Browse Source

Plane: don't do throttle nudge while in geofence failsafe

user stick inputs should not apply when outside fence
mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
eeda1b56de
  1. 2
      ArduPlane/radio.cpp

2
ArduPlane/radio.cpp

@ -188,7 +188,7 @@ void Plane::read_radio() @@ -188,7 +188,7 @@ void Plane::read_radio()
channel_throttle->servo_out = channel_throttle->control_in;
if (g.throttle_nudge && channel_throttle->servo_out > 50) {
if (g.throttle_nudge && channel_throttle->servo_out > 50 && geofence_stickmixing()) {
float nudge = (channel_throttle->servo_out - 50) * 0.02f;
if (ahrs.airspeed_sensor_enabled()) {
airspeed_nudge_cm = (aparm.airspeed_max * 100 - g.airspeed_cruise_cm) * nudge;

Loading…
Cancel
Save