From 548c7bbd163ede7f93694e7432b070d1cab005a5 Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 27 Apr 2024 21:07:35 +0900 Subject: [PATCH] Copter: Make multiple decisions into a SWITCH statement --- ArduCopter/AP_Arming.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 4fbfe125ccd30..dc30b2fefa1b4 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -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