ArduCopter: use check_enabked hepler to always check if all bit is set

This commit is contained in:
Iampete1 2023-01-21 13:30:08 +00:00 committed by Andrew Tridgell
parent fc7804f03a
commit e35b52c0be
1 changed files with 10 additions and 11 deletions

View File

@ -69,8 +69,7 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)
bool AP_Arming_Copter::rc_throttle_failsafe_checks(bool display_failure) const
{
if ((checks_to_perform != ARMING_CHECK_ALL) &&
(checks_to_perform & ARMING_CHECK_RC) == 0) {
if (!check_enabled(ARMING_CHECK_RC)) {
// this check has been disabled
return true;
}
@ -114,7 +113,7 @@ bool AP_Arming_Copter::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.
@ -134,7 +133,7 @@ bool AP_Arming_Copter::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()) {
@ -153,7 +152,7 @@ bool AP_Arming_Copter::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 (copter.battery.has_failsafed()) {
check_failed(ARMING_CHECK_VOLTAGE, display_failure, "Battery failsafe");
return false;
@ -183,7 +182,7 @@ bool AP_Arming_Copter::terrain_database_required() const
bool AP_Arming_Copter::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 (copter.g.failsafe_throttle) {
@ -379,7 +378,7 @@ bool AP_Arming_Copter::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;
}
@ -414,7 +413,7 @@ bool AP_Arming_Copter::proximity_checks(bool display_failure) const
return false;
}
if (!((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_PARAMETERS))) {
if (!check_enabled(ARMING_CHECK_PARAMETERS)) {
// check is disabled
return true;
}
@ -605,7 +604,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
}
// check lean angle
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_INS)) {
if (check_enabled(ARMING_CHECK_INS)) {
if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > copter.aparm.angle_max) {
check_failed(ARMING_CHECK_INS, true, "Leaning");
return false;
@ -614,7 +613,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
// check adsb
#if HAL_ADSB_ENABLED
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_PARAMETERS)) {
if (check_enabled(ARMING_CHECK_PARAMETERS)) {
if (copter.failsafe.adsb) {
check_failed(ARMING_CHECK_PARAMETERS, true, "ADSB threat detected");
return false;
@ -623,7 +622,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
#endif
// check throttle
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_RC)) {
if (check_enabled(ARMING_CHECK_RC)) {
#if FRAME_CONFIG == HELI_FRAME
const char *rc_item = "Collective";
#else