|
|
|
@ -1121,6 +1121,17 @@ void GCS_MAVLINK::send_scaled_pressure(AP_Baro &barometer)
@@ -1121,6 +1121,17 @@ void GCS_MAVLINK::send_scaled_pressure(AP_Baro &barometer)
|
|
|
|
|
barometer.get_temperature(1)*100); // 0.01 degrees C
|
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
#if BARO_MAX_INSTANCES > 2 |
|
|
|
|
if (barometer.num_instances() > 2) { |
|
|
|
|
pressure = barometer.get_pressure(2); |
|
|
|
|
mavlink_msg_scaled_pressure3_send( |
|
|
|
|
chan, |
|
|
|
|
now, |
|
|
|
|
pressure*0.01f, // hectopascal
|
|
|
|
|
(pressure - barometer.get_ground_pressure(2))*0.01f, // hectopascal
|
|
|
|
|
barometer.get_temperature(2)*100); // 0.01 degrees C
|
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void GCS_MAVLINK::send_sensor_offsets(const AP_InertialSensor &ins, const Compass &compass, AP_Baro &barometer) |
|
|
|
|