mirror of https://github.com/ArduPilot/ardupilot
Plane: Ensure that only one form of throttle nudging is active at once
This commit is contained in:
parent
5ffd40f973
commit
6c5d6330c3
|
@ -202,6 +202,8 @@ void Plane::read_radio()
|
|||
|
||||
control_failsafe();
|
||||
|
||||
airspeed_nudge_cm = 0;
|
||||
throttle_nudge = 0;
|
||||
if (g.throttle_nudge && channel_throttle->get_control_in() > 50 && geofence_stickmixing()) {
|
||||
float nudge = (channel_throttle->get_control_in() - 50) * 0.02f;
|
||||
if (ahrs.airspeed_sensor_enabled()) {
|
||||
|
@ -209,9 +211,6 @@ void Plane::read_radio()
|
|||
} else {
|
||||
throttle_nudge = (aparm.throttle_max - aparm.throttle_cruise) * nudge;
|
||||
}
|
||||
} else {
|
||||
airspeed_nudge_cm = 0;
|
||||
throttle_nudge = 0;
|
||||
}
|
||||
|
||||
rudder_arm_disarm_check();
|
||||
|
|
Loading…
Reference in New Issue