From 5846f217d0e09ee4c1c64c0ebf0f2e621a14fa69 Mon Sep 17 00:00:00 2001 From: tstellanova Date: Fri, 3 Oct 2014 17:18:44 -0700 Subject: Use global position altitude to report HUD altitude, for consistency. Otherwise the HUD altitude jumps between two very different values. --- src/modules/mavlink/mavlink_messages.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index a2f3828ff..941b45d88 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -820,7 +820,11 @@ protected: msg.groundspeed = sqrtf(pos.vel_n * pos.vel_n + pos.vel_e * pos.vel_e); msg.heading = _wrap_2pi(att.yaw) * M_RAD_TO_DEG_F; msg.throttle = armed.armed ? act.control[3] * 100.0f : 0.0f; - msg.alt = sensor_combined.baro_alt_meter; + /* + Do not use sensor_combined.baro_alt_meter here because + it is mismatched with WSG84 AMSL used elsewhere for reporting altitude. + */ + msg.alt = pos.alt; msg.climb = -pos.vel_d; _mavlink->send_message(MAVLINK_MSG_ID_VFR_HUD, &msg); -- cgit v1.2.3