mirror of https://github.com/ArduPilot/ardupilot
Plane: deny reverse thrust in takeoff mode
This commit is contained in:
parent
d74d8fac95
commit
e983b94a2f
|
@ -71,7 +71,6 @@ bool Plane::allow_reverse_thrust(void) const
|
|||
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_RTL);
|
||||
break;
|
||||
case Mode::Number::CIRCLE:
|
||||
case Mode::Number::TAKEOFF:
|
||||
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_CIRCLE);
|
||||
break;
|
||||
case Mode::Number::CRUISE:
|
||||
|
@ -84,6 +83,9 @@ bool Plane::allow_reverse_thrust(void) const
|
|||
case Mode::Number::GUIDED:
|
||||
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_GUIDED);
|
||||
break;
|
||||
case Mode::Number::TAKEOFF:
|
||||
allow = false;
|
||||
break;
|
||||
default:
|
||||
// all other control_modes are auto_throttle_mode=false.
|
||||
// If we are not controlling throttle, don't limit it.
|
||||
|
@ -91,7 +93,8 @@ bool Plane::allow_reverse_thrust(void) const
|
|||
break;
|
||||
}
|
||||
|
||||
return allow;
|
||||
// cope with bitwise ops above
|
||||
return allow != false;
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue