Plane: allow control_mode enum to be in arbitrary order

never use control_mode >= BLAH. This requires the order to be important which greatly increases chance for unexpected behavior
Closes https://github.com/ArduPilot/ardupilot/issues/4656
This commit is contained in:
Tom Pittenger 2018-01-02 20:45:41 -08:00 committed by Tom Pittenger
parent 39a200b83f
commit 1ef0f27786

View File

@ -127,7 +127,9 @@ void Plane::calc_airspeed_errors()
// Set target to current airspeed + ground speed undershoot,
// but only when this is faster than the target airspeed commanded
// above.
if (control_mode >= FLY_BY_WIRE_B && (aparm.min_gndspeed_cm > 0)) {
if (auto_throttle_mode &&
aparm.min_gndspeed_cm > 0 &&
control_mode != CIRCLE) {
int32_t min_gnd_target_airspeed = airspeed_measured*100 + groundspeed_undershoot;
if (min_gnd_target_airspeed > target_airspeed_cm) {
target_airspeed_cm = min_gnd_target_airspeed;