GCS_MAVLink: send SCALED_PRESSURE2 if available

This commit is contained in:
Andrew Tridgell 2015-01-05 22:30:00 +11:00
parent 19c717df2e
commit b1342c2d39

View File

@ -1044,13 +1044,25 @@ void GCS_MAVLINK::send_raw_imu(const AP_InertialSensor &ins, const Compass &comp
void GCS_MAVLINK::send_scaled_pressure(AP_Baro &barometer)
{
float pressure = barometer.get_pressure();
uint32_t now = hal.scheduler->millis();
float pressure = barometer.get_pressure(0);
mavlink_msg_scaled_pressure_send(
chan,
hal.scheduler->millis(),
now,
pressure*0.01f, // hectopascal
(pressure - barometer.get_ground_pressure())*0.01f, // hectopascal
barometer.get_temperature()*100); // 0.01 degrees C
(pressure - barometer.get_ground_pressure(0))*0.01f, // hectopascal
barometer.get_temperature(0)*100); // 0.01 degrees C
#if BARO_MAX_INSTANCES > 1
if (barometer.num_instances() > 1) {
pressure = barometer.get_pressure(1);
mavlink_msg_scaled_pressure2_send(
chan,
now,
pressure*0.01f, // hectopascal
(pressure - barometer.get_ground_pressure(1))*0.01f, // hectopascal
barometer.get_temperature(1)*100); // 0.01 degrees C
}
#endif
}
void GCS_MAVLINK::send_sensor_offsets(const AP_InertialSensor &ins, const Compass &compass, AP_Baro &barometer)