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,