mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: Make multiple decisions into a SWITCH statement
This commit is contained in:
parent
838fbc2b3b
commit
0e7a5ef520
@ -238,11 +238,15 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
|
|||||||
}
|
}
|
||||||
|
|
||||||
#else
|
#else
|
||||||
if (copter.g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI_QUAD ||
|
switch (copter.g2.frame_class.get()) {
|
||||||
copter.g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI_DUAL ||
|
case AP_Motors::MOTOR_FRAME_HELI_QUAD:
|
||||||
copter.g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI) {
|
case AP_Motors::MOTOR_FRAME_HELI_DUAL:
|
||||||
|
case AP_Motors::MOTOR_FRAME_HELI:
|
||||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Invalid MultiCopter FRAME_CLASS");
|
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Invalid MultiCopter FRAME_CLASS");
|
||||||
return false;
|
return false;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
#endif // HELI_FRAME
|
#endif // HELI_FRAME
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user