Browse Source

Plane: Ensure that only one form of throttle nudging is active at once

c415-sdk
Michael du Breuil 5 years ago committed by Peter Barker
parent
commit
2909623057
  1. 5
      ArduPlane/radio.cpp

5
ArduPlane/radio.cpp

@ -186,6 +186,8 @@ void Plane::read_radio() @@ -186,6 +186,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()) {
@ -193,9 +195,6 @@ void Plane::read_radio() @@ -193,9 +195,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…
Cancel
Save