mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: manual throttle scaling fix
Scaling of bottom half of throttle was changed from THR_MIN ~ 500. Previously it was from 0 ~ 500.
This commit is contained in:
parent
dbbfba3686
commit
ac764642ca
@ -854,7 +854,7 @@ static int16_t get_pilot_desired_throttle(int16_t throttle_control)
|
|||||||
// check throttle is above, below or in the deadband
|
// check throttle is above, below or in the deadband
|
||||||
if (throttle_control < THROTTLE_IN_MIDDLE) {
|
if (throttle_control < THROTTLE_IN_MIDDLE) {
|
||||||
// below the deadband
|
// below the deadband
|
||||||
throttle_out = (float)throttle_control * (float)g.throttle_mid / 500.0f;
|
throttle_out = g.throttle_min + ((float)(throttle_control-g.throttle_min))*((float)(g.throttle_mid - g.throttle_min))/((float)(500-g.throttle_min));
|
||||||
}else if(throttle_control > THROTTLE_IN_MIDDLE) {
|
}else if(throttle_control > THROTTLE_IN_MIDDLE) {
|
||||||
// above the deadband
|
// above the deadband
|
||||||
throttle_out = g.throttle_mid + ((float)(throttle_control-500))*(float)(1000-g.throttle_mid)/500.0f;
|
throttle_out = g.throttle_mid + ((float)(throttle_control-500))*(float)(1000-g.throttle_mid)/500.0f;
|
||||||
|
Loading…
Reference in New Issue
Block a user