GCS_MAVLink: send abs throttle in VFR_HUD

This commit is contained in:
Andrew Tridgell 2019-12-24 12:36:30 +11:00
parent 6d4f4d7a3b
commit c6322c7c98
1 changed files with 1 additions and 1 deletions

View File

@ -2493,7 +2493,7 @@ void GCS_MAVLINK::send_vfr_hud()
vfr_hud_airspeed(), vfr_hud_airspeed(),
ahrs.groundspeed(), ahrs.groundspeed(),
(ahrs.yaw_sensor / 100) % 360, (ahrs.yaw_sensor / 100) % 360,
vfr_hud_throttle(), abs(vfr_hud_throttle()),
vfr_hud_alt(), vfr_hud_alt(),
vfr_hud_climbrate()); vfr_hud_climbrate());
} }