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