Skip to content

Commit

Permalink
GCS_Mavlink: temporarily remove SCALED_PRESSURE2
Browse files Browse the repository at this point in the history
  • Loading branch information
jschall committed Jan 27, 2015
1 parent 06fcc91 commit ada9dbe
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1052,7 +1052,7 @@ void GCS_MAVLINK::send_scaled_pressure(AP_Baro &barometer)
pressure*0.01f, // hectopascal
(pressure - barometer.get_ground_pressure(0))*0.01f, // hectopascal
barometer.get_temperature(0)*100); // 0.01 degrees C
#if BARO_MAX_INSTANCES > 1
/*#if BARO_MAX_INSTANCES > 1
if (barometer.num_instances() > 1) {
pressure = barometer.get_pressure(1);
mavlink_msg_scaled_pressure2_send(
Expand All @@ -1062,7 +1062,7 @@ void GCS_MAVLINK::send_scaled_pressure(AP_Baro &barometer)
(pressure - barometer.get_ground_pressure(1))*0.01f, // hectopascal
barometer.get_temperature(1)*100); // 0.01 degrees C
}
#endif
#endif*/
}

void GCS_MAVLINK::send_sensor_offsets(const AP_InertialSensor &ins, const Compass &compass, AP_Baro &barometer)
Expand Down

0 comments on commit ada9dbe

Please sign in to comment.