mirror of https://github.com/ArduPilot/ardupilot
Rover: fixed VFR_HUD.throttle for reverse
This commit is contained in:
parent
14a0f8f46d
commit
41cf8d91c3
|
@ -338,7 +338,7 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
|
|||
(float)g_gps->ground_speed_cm / 100.0,
|
||||
(float)g_gps->ground_speed_cm / 100.0,
|
||||
(ahrs.yaw_sensor / 100) % 360,
|
||||
(uint16_t)(100 * channel_throttle->norm_output()),
|
||||
(uint16_t)(100 * fabsf(channel_throttle->norm_output())),
|
||||
current_loc.alt / 100.0,
|
||||
0);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue