Skip to content

Commit

Permalink
Copter: Constant comparisons are made first
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed Apr 27, 2024
1 parent 338f492 commit 37b4a05
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -193,7 +193,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
// failsafe parameter checks
if (copter.g.failsafe_throttle) {
// check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900
if (copter.channel_throttle->get_radio_min() <= copter.g.failsafe_throttle_value+10 || copter.g.failsafe_throttle_value < 910) {
if (copter.g.failsafe_throttle_value < 910 || copter.channel_throttle->get_radio_min() <= copter.g.failsafe_throttle_value+10) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check FS_THR_VALUE");
return false;
}
Expand Down

0 comments on commit 37b4a05

Please sign in to comment.