Copter: Make multiple decisions into a SWITCH statement

This commit is contained in:
muramura 2024-04-27 21:07:35 +09:00 committed by Randy Mackay
parent 838fbc2b3b
commit 0e7a5ef520
1 changed files with 7 additions and 3 deletions

View File

@ -238,11 +238,15 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
}
#else
if (copter.g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI_QUAD ||
copter.g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI_DUAL ||
copter.g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI) {
switch (copter.g2.frame_class.get()) {
case AP_Motors::MOTOR_FRAME_HELI_QUAD:
case AP_Motors::MOTOR_FRAME_HELI_DUAL:
case AP_Motors::MOTOR_FRAME_HELI:
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Invalid MultiCopter FRAME_CLASS");
return false;
default:
break;
}
#endif // HELI_FRAME