From a5dadd2694e0b53316c95a80409621c78ed25f87 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 4 Aug 2022 12:26:54 +1000 Subject: [PATCH] Copter: move motors check to be must-run prearm motors check would be run twice on arm without this. After this change, even if ARMING_CHECKS is 0 the user will be warned they need to set FRAME_CLASS and FRAME_TYPE, rather than just when they try to arm the vehicle. --- ArduCopter/AP_Arming.cpp | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 8845134bb0..0b3cfd8bf2 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -42,13 +42,17 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure) return false; } + // always check motors + if (!motor_checks(display_failure)) { + return false; + } + // if pre arm checks are disabled run only the mandatory checks if (checks_to_perform == 0) { return mandatory_checks(display_failure); } return parameter_checks(display_failure) - & motor_checks(display_failure) & oa_checks(display_failure) & gcs_failsafe_check(display_failure) & winch_checks(display_failure) @@ -576,11 +580,6 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) return false; } - // always check motors - if (!motor_checks(true)) { - return false; - } - // succeed if arming checks are disabled if (checks_to_perform == 0) { return true;