Skip to content

Commit

Permalink
Copter: Make multiple decisions into a SWITCH statement
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed Apr 27, 2024
1 parent 54bfaa4 commit 548c7bb
Showing 1 changed file with 7 additions and 3 deletions.
10 changes: 7 additions & 3 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down

0 comments on commit 548c7bb

Please sign in to comment.