From 53fcbcb6c3d415831e004e8a97b393b2fb42f7f1 Mon Sep 17 00:00:00 2001 From: floaledm Date: Wed, 26 Oct 2016 09:02:55 -0500 Subject: [PATCH] Copter: send ahrs groundspeed estimate instead of GPS groundspeed in VFR_HUD message --- ArduCopter/GCS_Mavlink.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 4c334ccc88..97e8617d4f 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -233,7 +233,7 @@ void NOINLINE Copter::send_vfr_hud(mavlink_channel_t chan) mavlink_msg_vfr_hud_send( chan, gps.ground_speed(), - gps.ground_speed(), + ahrs.groundspeed(), (ahrs.yaw_sensor / 100) % 360, (int16_t)(motors.get_throttle() * 100), current_loc.alt / 100.0f,