mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
MAVLink: fixed throttle display in VFR_HUD
This commit is contained in:
parent
4933c5bcdd
commit
8ef364657b
@ -409,7 +409,7 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
|
||||
(float)airspeed / 100.0,
|
||||
(float)g_gps->ground_speed / 100.0,
|
||||
(dcm.yaw_sensor / 100) % 360,
|
||||
(int)g.channel_throttle.servo_out,
|
||||
(uint16_t)(100 * g.channel_throttle.norm_output()),
|
||||
current_loc.alt / 100.0,
|
||||
0);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user