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

This commit is contained in:
floaledm 2016-10-26 09:02:55 -05:00 committed by Andrew Tridgell
parent b2a6b93d30
commit 53fcbcb6c3
1 changed files with 1 additions and 1 deletions

View File

@ -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,