Browse Source

GCS_MAVLink: send abs throttle in VFR_HUD

c415-sdk
Andrew Tridgell 5 years ago
parent
commit
c6322c7c98
  1. 2
      libraries/GCS_MAVLink/GCS_Common.cpp

2
libraries/GCS_MAVLink/GCS_Common.cpp

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

Loading…
Cancel
Save