From 6652dd73e4c97f83325a85f3a8e321abf6eed2f2 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Sun, 4 Mar 2018 17:14:04 -0700 Subject: [PATCH] GCS_MAVLink: Correct sending SCALED_PRESSURE.press_diff Closes #6642 --- libraries/GCS_MAVLink/GCS_Common.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index b90d2ce5b7..8c8248b1ec 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include "GCS.h" @@ -1069,11 +1070,18 @@ void GCS_MAVLINK::send_scaled_pressure() uint32_t now = AP_HAL::millis(); const AP_Baro &barometer = AP::baro(); float pressure = barometer.get_pressure(0); + float diff_pressure = 0; // pascal + + AP_Airspeed *airspeed = AP_Airspeed::get_singleton(); + if (airspeed != nullptr) { + diff_pressure = airspeed->get_differential_pressure(); + } + mavlink_msg_scaled_pressure_send( chan, now, pressure*0.01f, // hectopascal - (pressure - barometer.get_ground_pressure(0))*0.01f, // hectopascal + diff_pressure*0.01f, // hectopascal barometer.get_temperature(0)*100); // 0.01 degrees C if (barometer.num_instances() > 1 &&