From 7bde4fa6342230ab37644f94d364cd6e9541773e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 4 Oct 2014 12:31:16 +0200 Subject: Revert "Use global position altitude to report HUD altitude, for consistency." --- src/modules/mavlink/mavlink_messages.cpp | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 941b45d88..a2f3828ff 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -820,11 +820,7 @@ 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; - /* - 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.alt = sensor_combined.baro_alt_meter; msg.climb = -pos.vel_d; _mavlink->send_message(MAVLINK_MSG_ID_VFR_HUD, &msg); -- cgit v1.2.3