Plane: send ahrs groundspeed estimate instead of GPS groundspeed in VFR_HUD message

This commit is contained in:
floaledm 2016-10-25 20:52:26 -05:00 committed by Andrew Tridgell
parent e8fc5b9552
commit b2a6b93d30

View File

@ -238,7 +238,7 @@ void Plane::send_vfr_hud(mavlink_channel_t chan)
mavlink_msg_vfr_hud_send(
chan,
aspeed,
gps.ground_speed(),
ahrs.groundspeed(),
(ahrs.yaw_sensor / 100) % 360,
abs(throttle_percentage()),
current_loc.alt / 100.0f,