From 31ba715616ec98f814dba7b7240555e17971b993 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 21 Jan 2023 13:30:08 +0000 Subject: [PATCH] Blimp: use check_enabked hepler to always check if all bit is set --- Blimp/AP_Arming.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Blimp/AP_Arming.cpp b/Blimp/AP_Arming.cpp index 17b12078a3..c72d250cc2 100644 --- a/Blimp/AP_Arming.cpp +++ b/Blimp/AP_Arming.cpp @@ -45,7 +45,7 @@ bool AP_Arming_Blimp::barometer_checks(bool display_failure) bool ret = true; // check Baro - if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_BARO)) { + if (check_enabled(ARMING_CHECK_BARO)) { // Check baro & inav alt are within 1m if EKF is operating in an absolute position mode. // Do not check if intending to operate in a ground relative height mode as EKF will output a ground relative height // that may differ from the baro height due to baro drift. @@ -65,7 +65,7 @@ bool AP_Arming_Blimp::ins_checks(bool display_failure) { bool ret = AP_Arming::ins_checks(display_failure); - if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_INS)) { + if (check_enabled(ARMING_CHECK_INS)) { // get ekf attitude (if bad, it's usually the gyro biases) if (!pre_arm_ekf_attitude_check()) { @@ -84,7 +84,7 @@ bool AP_Arming_Blimp::board_voltage_checks(bool display_failure) } // check battery voltage - if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_VOLTAGE)) { + if (check_enabled(ARMING_CHECK_VOLTAGE)) { if (blimp.battery.has_failsafed()) { check_failed(ARMING_CHECK_VOLTAGE, display_failure, "Battery failsafe"); return false; @@ -102,7 +102,7 @@ bool AP_Arming_Blimp::board_voltage_checks(bool display_failure) bool AP_Arming_Blimp::parameter_checks(bool display_failure) { // check various parameter values - if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_PARAMETERS)) { + if (check_enabled(ARMING_CHECK_PARAMETERS)) { // failsafe parameter checks if (blimp.g.failsafe_throttle) { @@ -159,7 +159,7 @@ bool AP_Arming_Blimp::gps_checks(bool display_failure) } // return true immediately if gps check is disabled - if (!(checks_to_perform == ARMING_CHECK_ALL || checks_to_perform & ARMING_CHECK_GPS)) { + if (!check_enabled(ARMING_CHECK_GPS)) { AP_Notify::flags.pre_arm_gps_check = true; return true; }