aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp5
-rw-r--r--src/modules/mavlink/orb_listener.c2
2 files changed, 4 insertions, 3 deletions
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 5b2fa392d..33ac14860 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -416,7 +416,8 @@ handle_message(mavlink_message_t *msg)
airspeed.timestamp = hrt_absolute_time();
float ias = calc_indicated_airspeed(imu.diff_pressure);
- float tas = calc_true_airspeed_from_indicated(ias, imu.abs_pressure, imu.temperature);
+ // XXX need to fix this
+ float tas = ias;
airspeed.indicated_airspeed_m_s = ias;
airspeed.true_airspeed_m_s = tas;
@@ -426,7 +427,7 @@ handle_message(mavlink_message_t *msg)
} else {
orb_publish(ORB_ID(airspeed), pub_hil_airspeed, &airspeed);
}
- warnx("SENSOR: IAS: %6.2f TAS: %6.2f", airspeed.indicated_airspeed_m_s, airspeed.true_airspeed_m_s);
+ //warnx("SENSOR: IAS: %6.2f TAS: %6.2f", airspeed.indicated_airspeed_m_s, airspeed.true_airspeed_m_s);
/* publish */
if (pub_hil_sensors > 0) {
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index 7c5441842..0597555ab 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -196,7 +196,7 @@ l_sensor_combined(const struct listener *l)
raw.gyro_rad_s[1], raw.gyro_rad_s[2],
raw.magnetometer_ga[0],
raw.magnetometer_ga[1], raw.magnetometer_ga[2],
- raw.baro_pres_mbar, 0 /* no diff pressure yet */,
+ raw.baro_pres_mbar, raw.differential_pressure_pa,
raw.baro_alt_meter, raw.baro_temp_celcius,
fields_updated);