AP_Arming: use check_enabled helper

This commit is contained in:
Iampete1 2023-01-21 13:23:07 +00:00 committed by Randy Mackay
parent c440d98897
commit 6c8064da96
1 changed files with 20 additions and 33 deletions

View File

@ -266,8 +266,7 @@ bool AP_Arming::barometer_checks(bool report)
return true; return true;
} }
#endif #endif
if ((checks_to_perform & ARMING_CHECK_ALL) || if (check_enabled(ARMING_CHECK_BARO)) {
(checks_to_perform & ARMING_CHECK_BARO)) {
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {}; char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
if (!AP::baro().arming_checks(sizeof(buffer), buffer)) { if (!AP::baro().arming_checks(sizeof(buffer), buffer)) {
check_failed(ARMING_CHECK_BARO, report, "Baro: %s", buffer); check_failed(ARMING_CHECK_BARO, report, "Baro: %s", buffer);
@ -281,8 +280,7 @@ bool AP_Arming::barometer_checks(bool report)
bool AP_Arming::airspeed_checks(bool report) bool AP_Arming::airspeed_checks(bool report)
{ {
#if AP_AIRSPEED_ENABLED #if AP_AIRSPEED_ENABLED
if ((checks_to_perform & ARMING_CHECK_ALL) || if (check_enabled(ARMING_CHECK_AIRSPEED)) {
(checks_to_perform & ARMING_CHECK_AIRSPEED)) {
const AP_Airspeed *airspeed = AP_Airspeed::get_singleton(); const AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
if (airspeed == nullptr) { if (airspeed == nullptr) {
// not an airspeed capable vehicle // not an airspeed capable vehicle
@ -302,8 +300,7 @@ bool AP_Arming::airspeed_checks(bool report)
bool AP_Arming::logging_checks(bool report) bool AP_Arming::logging_checks(bool report)
{ {
if ((checks_to_perform & ARMING_CHECK_ALL) || if (check_enabled(ARMING_CHECK_LOGGING)) {
(checks_to_perform & ARMING_CHECK_LOGGING)) {
if (!AP::logger().logging_present()) { if (!AP::logger().logging_present()) {
// Logging is disabled, so nothing to check. // Logging is disabled, so nothing to check.
return true; return true;
@ -411,8 +408,7 @@ bool AP_Arming::ins_gyros_consistent(const AP_InertialSensor &ins)
bool AP_Arming::ins_checks(bool report) bool AP_Arming::ins_checks(bool report)
{ {
if ((checks_to_perform & ARMING_CHECK_ALL) || if (check_enabled(ARMING_CHECK_INS)) {
(checks_to_perform & ARMING_CHECK_INS)) {
const AP_InertialSensor &ins = AP::ins(); const AP_InertialSensor &ins = AP::ins();
if (!ins.get_gyro_health_all()) { if (!ins.get_gyro_health_all()) {
check_failed(ARMING_CHECK_INS, report, "Gyros not healthy"); check_failed(ARMING_CHECK_INS, report, "Gyros not healthy");
@ -458,8 +454,7 @@ bool AP_Arming::ins_checks(bool report)
#if HAL_GYROFFT_ENABLED #if HAL_GYROFFT_ENABLED
// gyros are healthy so check the FFT // gyros are healthy so check the FFT
if ((checks_to_perform & ARMING_CHECK_ALL) || if (check_enabled(ARMING_CHECK_FFT)) {
(checks_to_perform & ARMING_CHECK_FFT)) {
// Check that the noise analyser works // Check that the noise analyser works
AP_GyroFFT *fft = AP::fft(); AP_GyroFFT *fft = AP::fft();
@ -492,8 +487,7 @@ bool AP_Arming::compass_checks(bool report)
} }
#endif #endif
if ((checks_to_perform) & ARMING_CHECK_ALL || if (check_enabled(ARMING_CHECK_COMPASS)) {
(checks_to_perform) & ARMING_CHECK_COMPASS) {
// avoid Compass::use_for_yaw(void) as it implicitly calls healthy() which can // avoid Compass::use_for_yaw(void) as it implicitly calls healthy() which can
// incorrectly skip the remaining checks, pass the primary instance directly // incorrectly skip the remaining checks, pass the primary instance directly
@ -547,7 +541,7 @@ bool AP_Arming::compass_checks(bool report)
bool AP_Arming::gps_checks(bool report) bool AP_Arming::gps_checks(bool report)
{ {
const AP_GPS &gps = AP::gps(); const AP_GPS &gps = AP::gps();
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS)) { if (check_enabled(ARMING_CHECK_GPS)) {
// Any failure messages from GPS backends // Any failure messages from GPS backends
char failure_msg[50] = {}; char failure_msg[50] = {};
@ -616,7 +610,7 @@ bool AP_Arming::gps_checks(bool report)
} }
} }
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS_CONFIG)) { if (check_enabled(ARMING_CHECK_GPS_CONFIG)) {
uint8_t first_unconfigured; uint8_t first_unconfigured;
if (gps.first_unconfigured_gps(first_unconfigured)) { if (gps.first_unconfigured_gps(first_unconfigured)) {
check_failed(ARMING_CHECK_GPS_CONFIG, check_failed(ARMING_CHECK_GPS_CONFIG,
@ -635,8 +629,7 @@ bool AP_Arming::gps_checks(bool report)
bool AP_Arming::battery_checks(bool report) bool AP_Arming::battery_checks(bool report)
{ {
if ((checks_to_perform & ARMING_CHECK_ALL) || if (check_enabled(ARMING_CHECK_BATTERY)) {
(checks_to_perform & ARMING_CHECK_BATTERY)) {
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {}; char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
if (!AP::battery().arming_checks(sizeof(buffer), buffer)) { if (!AP::battery().arming_checks(sizeof(buffer), buffer)) {
@ -649,8 +642,7 @@ bool AP_Arming::battery_checks(bool report)
bool AP_Arming::hardware_safety_check(bool report) bool AP_Arming::hardware_safety_check(bool report)
{ {
if ((checks_to_perform & ARMING_CHECK_ALL) || if (check_enabled(ARMING_CHECK_SWITCH)) {
(checks_to_perform & ARMING_CHECK_SWITCH)) {
// check if safety switch has been pushed // check if safety switch has been pushed
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) { if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
@ -765,8 +757,7 @@ bool AP_Arming::rc_in_calibration_check(bool report)
bool AP_Arming::manual_transmitter_checks(bool report) bool AP_Arming::manual_transmitter_checks(bool report)
{ {
if ((checks_to_perform & ARMING_CHECK_ALL) || if (check_enabled(ARMING_CHECK_RC)) {
(checks_to_perform & ARMING_CHECK_RC)) {
if (AP_Notify::flags.failsafe_radio) { if (AP_Notify::flags.failsafe_radio) {
check_failed(ARMING_CHECK_RC, report, "Radio failsafe on"); check_failed(ARMING_CHECK_RC, report, "Radio failsafe on");
@ -783,8 +774,7 @@ bool AP_Arming::manual_transmitter_checks(bool report)
bool AP_Arming::mission_checks(bool report) bool AP_Arming::mission_checks(bool report)
{ {
if (((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_MISSION)) && if (check_enabled(ARMING_CHECK_MISSION) && _required_mission_items) {
_required_mission_items) {
AP_Mission *mission = AP::mission(); AP_Mission *mission = AP::mission();
if (mission == nullptr) { if (mission == nullptr) {
check_failed(ARMING_CHECK_MISSION, report, "No mission library present"); check_failed(ARMING_CHECK_MISSION, report, "No mission library present");
@ -840,7 +830,7 @@ bool AP_Arming::mission_checks(bool report)
bool AP_Arming::rangefinder_checks(bool report) bool AP_Arming::rangefinder_checks(bool report)
{ {
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_RANGEFINDER)) { if (check_enabled(ARMING_CHECK_RANGEFINDER)) {
RangeFinder *range = RangeFinder::get_singleton(); RangeFinder *range = RangeFinder::get_singleton();
if (range == nullptr) { if (range == nullptr) {
return true; return true;
@ -912,7 +902,7 @@ bool AP_Arming::servo_checks(bool report) const
bool AP_Arming::board_voltage_checks(bool report) bool AP_Arming::board_voltage_checks(bool report)
{ {
// check board voltage // check board voltage
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_VOLTAGE)) { if (check_enabled(ARMING_CHECK_VOLTAGE)) {
#if HAL_HAVE_BOARD_VOLTAGE #if HAL_HAVE_BOARD_VOLTAGE
const float bus_voltage = hal.analogin->board_voltage(); const float bus_voltage = hal.analogin->board_voltage();
const float vbus_min = AP_BoardConfig::get_minimum_board_voltage(); const float vbus_min = AP_BoardConfig::get_minimum_board_voltage();
@ -1207,7 +1197,7 @@ bool AP_Arming::fence_checks(bool display_failure)
bool AP_Arming::camera_checks(bool display_failure) bool AP_Arming::camera_checks(bool display_failure)
{ {
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_CAMERA)) { if (check_enabled(ARMING_CHECK_CAMERA)) {
#if HAL_RUNCAM_ENABLED #if HAL_RUNCAM_ENABLED
AP_RunCam *runcam = AP::runcam(); AP_RunCam *runcam = AP::runcam();
if (runcam == nullptr) { if (runcam == nullptr) {
@ -1228,7 +1218,7 @@ bool AP_Arming::camera_checks(bool display_failure)
bool AP_Arming::osd_checks(bool display_failure) const bool AP_Arming::osd_checks(bool display_failure) const
{ {
#if OSD_PARAM_ENABLED && OSD_ENABLED #if OSD_PARAM_ENABLED && OSD_ENABLED
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_CAMERA)) { if (check_enabled(ARMING_CHECK_CAMERA)) {
const AP_OSD *osd = AP::osd(); const AP_OSD *osd = AP::osd();
if (osd == nullptr) { if (osd == nullptr) {
return true; return true;
@ -1248,7 +1238,7 @@ bool AP_Arming::osd_checks(bool display_failure) const
bool AP_Arming::mount_checks(bool display_failure) const bool AP_Arming::mount_checks(bool display_failure) const
{ {
#if HAL_MOUNT_ENABLED #if HAL_MOUNT_ENABLED
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_CAMERA)) { if (check_enabled(ARMING_CHECK_CAMERA)) {
AP_Mount *mount = AP::mount(); AP_Mount *mount = AP::mount();
if (mount == nullptr) { if (mount == nullptr) {
return true; return true;
@ -1483,16 +1473,14 @@ bool AP_Arming::pre_arm_checks(bool report)
bool AP_Arming::arm_checks(AP_Arming::Method method) bool AP_Arming::arm_checks(AP_Arming::Method method)
{ {
if ((checks_to_perform & ARMING_CHECK_ALL) || if (check_enabled(ARMING_CHECK_RC)) {
(checks_to_perform & ARMING_CHECK_RC)) {
if (!rc_arm_checks(method)) { if (!rc_arm_checks(method)) {
return false; return false;
} }
} }
// ensure the GPS drivers are ready on any final changes // ensure the GPS drivers are ready on any final changes
if ((checks_to_perform & ARMING_CHECK_ALL) || if (check_enabled(ARMING_CHECK_GPS_CONFIG)) {
(checks_to_perform & ARMING_CHECK_GPS_CONFIG)) {
if (!AP::gps().prepare_for_arming()) { if (!AP::gps().prepare_for_arming()) {
return false; return false;
} }
@ -1520,8 +1508,7 @@ bool AP_Arming::arm_checks(AP_Arming::Method method)
// If we're configured to log, prep it // If we're configured to log, prep it
logger->PrepForArming(); logger->PrepForArming();
if (!logger->logging_started() && if (!logger->logging_started() &&
((checks_to_perform & ARMING_CHECK_ALL) || check_enabled(ARMING_CHECK_LOGGING)) {
(checks_to_perform & ARMING_CHECK_LOGGING))) {
check_failed(ARMING_CHECK_LOGGING, true, "Logging not started"); check_failed(ARMING_CHECK_LOGGING, true, "Logging not started");
return false; return false;
} }