mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
APM: fixed throttle display to always be between 0 and 100
when rc3 is below RC3_MIN, don't give an invalid value
This commit is contained in:
parent
8ccac5da3d
commit
f80783665f
@ -358,12 +358,15 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
|
||||
} else if (!ahrs.airspeed_estimate(&aspeed)) {
|
||||
aspeed = 0;
|
||||
}
|
||||
float throttle_norm = g.channel_throttle.norm_output() * 100;
|
||||
throttle_norm = constrain(throttle_norm, -100, 100);
|
||||
uint16_t throttle = ((uint16_t)(throttle_norm + 100)) / 2;
|
||||
mavlink_msg_vfr_hud_send(
|
||||
chan,
|
||||
aspeed,
|
||||
(float)g_gps->ground_speed * 0.01,
|
||||
(ahrs.yaw_sensor / 100) % 360,
|
||||
(uint16_t)(100 * (g.channel_throttle.norm_output() / 2.0 + 0.5)), // scale -1,1 to 0-100
|
||||
throttle,
|
||||
current_loc.alt / 100.0,
|
||||
barometer.get_climb_rate());
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user