From a62d72893363e1b6e17ecbc723d59e89860bc01f Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Tue, 28 Feb 2017 23:05:51 -0500 Subject: [PATCH] Sub: Move arming checks under AP_Arming_Sub --- ArduSub/AP_Arming_Sub.cpp | 46 +++ ArduSub/AP_Arming_Sub.h | 3 + ArduSub/AP_State.cpp | 7 - ArduSub/ArduSub.cpp | 4 +- ArduSub/Sub.h | 54 ++- ArduSub/arming_checks.cpp | 657 ------------------------------------ ArduSub/compassmot.cpp | 4 +- ArduSub/defines.h | 11 - ArduSub/esc_calibration.cpp | 3 +- ArduSub/motor_test.cpp | 4 +- ArduSub/motors.cpp | 4 +- ArduSub/radio.cpp | 3 +- 12 files changed, 78 insertions(+), 722 deletions(-) delete mode 100644 ArduSub/arming_checks.cpp diff --git a/ArduSub/AP_Arming_Sub.cpp b/ArduSub/AP_Arming_Sub.cpp index 530c3b60ee..af307f6596 100644 --- a/ArduSub/AP_Arming_Sub.cpp +++ b/ArduSub/AP_Arming_Sub.cpp @@ -5,3 +5,49 @@ enum HomeState AP_Arming_Sub::home_status() const { return sub.ap.home_state; } + +bool AP_Arming_Sub::rc_check(bool report) +{ + // set rc-checks to success if RC checks are disabled + if ((checks_to_perform != ARMING_CHECK_ALL) && !(checks_to_perform & ARMING_CHECK_RC)) { + return true; + } + + static const char* message_fail = "PreArm: Check RC min/max parameters"; + bool ret = true; + + // check channels 1 & 2 have min <= 1300 and max >= 1700 + if (sub.channel_roll->get_radio_min() > 1300 || sub.channel_roll->get_radio_max() < 1700 || sub.channel_pitch->get_radio_min() > 1300 || sub.channel_pitch->get_radio_max() < 1700) { + ret = false; + } + + // check channels 3 & 4 have min <= 1300 and max >= 1700 + if (sub.channel_throttle->get_radio_min() > 1300 || sub.channel_throttle->get_radio_max() < 1700 || sub.channel_yaw->get_radio_min() > 1300 || sub.channel_yaw->get_radio_max() < 1700) { + ret = false; + } + + // check channels 1 & 2 have trim >= 1300 and <= 1700 + if (sub.channel_roll->get_radio_trim() < 1300 || sub.channel_roll->get_radio_trim() > 1700 || sub.channel_pitch->get_radio_trim() < 1300 || sub.channel_pitch->get_radio_trim() > 1700) { + ret = false; + } + + // check channel 4 has trim >= 1300 and <= 1700 + if (sub.channel_yaw->get_radio_trim() < 1300 || sub.channel_yaw->get_radio_trim() > 1700) { + ret = false; + } + + if (report && !ret) { + sub.gcs_send_text(MAV_SEVERITY_CRITICAL, message_fail); + } + + return ret; +} + +bool AP_Arming_Sub::pre_arm_checks(bool report) +{ + if (armed) { + return true; + } + + return AP_Arming::pre_arm_checks(report) & rc_check(report); +} diff --git a/ArduSub/AP_Arming_Sub.h b/ArduSub/AP_Arming_Sub.h index d990512a52..47a20078c1 100644 --- a/ArduSub/AP_Arming_Sub.h +++ b/ArduSub/AP_Arming_Sub.h @@ -10,6 +10,9 @@ public: AP_Param::setup_object_defaults(this, var_info); } + bool rc_check(bool report=true); + bool pre_arm_checks(bool report) override; + protected: enum HomeState home_status() const override; }; diff --git a/ArduSub/AP_State.cpp b/ArduSub/AP_State.cpp index 595dc1a54b..cf5f0f3253 100644 --- a/ArduSub/AP_State.cpp +++ b/ArduSub/AP_State.cpp @@ -74,13 +74,6 @@ void Sub::set_pre_arm_check(bool b) } } -void Sub::set_pre_arm_rc_check(bool b) -{ - if (ap.pre_arm_rc_check != b) { - ap.pre_arm_rc_check = b; - } -} - void Sub::update_using_interlock() { // check if we are using motor interlock control on an aux switch diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 3d39fce59c..285fd01951 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -372,12 +372,12 @@ void Sub::three_hz_loop() // one_hz_loop - runs at 1Hz void Sub::one_hz_loop() { + AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false); + if (should_log(MASK_LOG_ANY)) { Log_Write_Data(DATA_AP_STATE, ap.value); } - update_arming_checks(); - if (!motors.armed()) { // make it possible to change ahrs orientation at runtime during initial config ahrs.set_orientation(); diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 46f26c7d38..fff656e74a 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -230,31 +230,29 @@ private: # include USERHOOK_VARIABLES #endif - // Documentation of GLobals: + // Documentation of Globals: union { struct { - uint8_t unused1 : 1; // 0 - uint8_t simple_mode : 2; // 1,2 // This is the state of simple mode : 0 = disabled ; 1 = SIMPLE ; 2 = SUPERSIMPLE - uint8_t pre_arm_rc_check : 1; // 3 // true if rc input pre-arm checks have been completed successfully - uint8_t pre_arm_check : 1; // 4 // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed - uint8_t auto_armed : 1; // 5 // stops auto missions from beginning until throttle is raised - uint8_t logging_started : 1; // 6 // true if dataflash logging has started - uint8_t new_radio_frame : 1; // 8 // Set true if we have new PWM data to act on from the Radio - uint8_t usb_connected : 1; // 9 // true if APM is powered from USB connection - uint8_t rc_receiver_present : 1; // 10 // true if we have an rc receiver present (i.e. if we've ever received an update - uint8_t compass_mot : 1; // 11 // true if we are currently performing compassmot calibration - uint8_t motor_test : 1; // 12 // true if we are currently performing the motors test - uint8_t initialised : 1; // 13 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes - uint8_t throttle_zero : 1; // 15 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock - uint8_t system_time_set : 1; // 16 // true if the system time has been set from the GPS - uint8_t gps_base_pos_set : 1; // 17 // true when the gps base position has been set (used for RTK gps only) - enum HomeState home_state : 2; // 18,19 // home status (unset, set, locked) - uint8_t using_interlock : 1; // 20 // aux switch motor interlock function is in use - uint8_t motor_emergency_stop: 1; // 21 // motor estop switch, shuts off motors when enabled - uint8_t land_repo_active : 1; // 22 // true if the pilot is overriding the landing position - uint8_t at_bottom : 1; // true if we are at the bottom - uint8_t at_surface : 1; // true if we are at the surface - uint8_t depth_sensor_present: 1; // true if we have an external baro connected + uint8_t simple_mode : 2; // This is the state of simple mode : 0 = disabled ; 1 = SIMPLE ; 2 = SUPERSIMPLE + uint8_t pre_arm_check : 1; // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed + uint8_t auto_armed : 1; // stops auto missions from beginning until throttle is raised + uint8_t logging_started : 1; // true if dataflash logging has started + uint8_t new_radio_frame : 1; // Set true if we have new PWM data to act on from the Radio + uint8_t usb_connected : 1; // true if APM is powered from USB connection + uint8_t rc_receiver_present : 1; // true if we have an rc receiver present (i.e. if we've ever received an update + uint8_t compass_mot : 1; // true if we are currently performing compassmot calibration + uint8_t motor_test : 1; // true if we are currently performing the motors test + uint8_t initialised : 1; // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes + uint8_t throttle_zero : 1; // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock + uint8_t system_time_set : 1; // true if the system time has been set from the GPS + uint8_t gps_base_pos_set : 1; // true when the gps base position has been set (used for RTK gps only) + enum HomeState home_state : 2; // home status (unset, set, locked) + uint8_t using_interlock : 1; // aux switch motor interlock function is in use + uint8_t motor_emergency_stop: 1; // motor estop switch, shuts off motors when enabled + uint8_t land_repo_active : 1; // true if the pilot is overriding the landing position + uint8_t at_bottom : 1; // true if we are at the bottom + uint8_t at_surface : 1; // true if we are at the surface + uint8_t depth_sensor_present: 1; // true if we have an external baro connected }; uint32_t value; } ap; @@ -510,7 +508,6 @@ private: void set_simple_mode(uint8_t b); void set_failsafe_battery(bool b); void set_pre_arm_check(bool b); - void set_pre_arm_rc_check(bool b); void update_using_interlock(); void set_motor_emergency_stop(bool b); float get_smoothing_gain(); @@ -727,15 +724,6 @@ private: void motor_test_stop(); void auto_disarm_check(); bool init_arm_motors(bool arming_from_gcs); - void update_arming_checks(void); - bool all_arming_checks_passing(bool arming_from_gcs); - bool pre_arm_checks(bool display_failure); - void pre_arm_rc_checks(); - bool pre_arm_gps_checks(bool display_failure); - bool pre_arm_ekf_attitude_check(); - bool pre_arm_rallypoint_check(); - bool pre_arm_terrain_check(bool display_failure); - bool arm_checks(bool display_failure, bool arming_from_gcs); void init_disarm_motors(); void motors_output(); void lost_vehicle_check(); diff --git a/ArduSub/arming_checks.cpp b/ArduSub/arming_checks.cpp deleted file mode 100644 index db34900c55..0000000000 --- a/ArduSub/arming_checks.cpp +++ /dev/null @@ -1,657 +0,0 @@ -#include "Sub.h" - -// performs pre-arm checks. expects to be called at 1hz. -void Sub::update_arming_checks(void) -{ - // perform pre-arm checks & display failures every 30 seconds - static uint8_t pre_arm_display_counter = PREARM_DISPLAY_PERIOD/2; - pre_arm_display_counter++; - bool display_fail = false; - if (pre_arm_display_counter >= PREARM_DISPLAY_PERIOD) { - display_fail = true; - pre_arm_display_counter = 0; - } - - if (pre_arm_checks(display_fail)) { - set_pre_arm_check(true); - } -} - -// performs pre-arm checks and arming checks -bool Sub::all_arming_checks_passing(bool arming_from_gcs) -{ -#if CONFIG_HAL_BOARD != HAL_BOARD_SITL - if (failsafe.manual_control) { - gcs_send_text(MAV_SEVERITY_WARNING, "Arming requires manual control"); - return false; - } -#endif - - if (pre_arm_checks(true)) { - set_pre_arm_check(true); - } - - return ap.pre_arm_check && arm_checks(true, arming_from_gcs); -} - -// perform pre-arm checks and set ap.pre_arm_check flag -// return true if the checks pass successfully -bool Sub::pre_arm_checks(bool display_failure) -{ - // exit immediately if already armed - if (motors.armed()) { - return true; - } - - // check if motor interlock and Emergency Stop aux switches are used - // at the same time. This cannot be allowed. - if (check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK) && check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP)) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Interlock/E-Stop Conflict"); - } - return false; - } - - // check if motor interlock aux switch is in use - // if it is, switch needs to be in disabled position to arm - // otherwise exit immediately. This check to be repeated, - // as state can change at any time. - if (ap.using_interlock && motors.get_interlock()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Motor Interlock Enabled"); - } - return false; - } - - // exit immediately if we've already successfully performed the pre-arm check - if (ap.pre_arm_check) { - // run gps checks because results may change and affect LED colour - // no need to display failures because arm_checks will do that if the pilot tries to arm - pre_arm_gps_checks(false); - return true; - } - - // succeed if pre arm checks are disabled - if (g.arming_check == ARMING_CHECK_NONE) { - set_pre_arm_check(true); - set_pre_arm_rc_check(true); - return true; - } - - // pre-arm rc checks a prerequisite - pre_arm_rc_checks(); - if (!ap.pre_arm_rc_check) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: RC not calibrated"); - } - return false; - } - // check Baro - if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_BARO)) { - // barometer health check - if (!barometer.all_healthy()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Barometer not healthy"); - } - return false; - } - // 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. - nav_filter_status filt_status = inertial_nav.get_filter_status(); - bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs); - if (using_baro_ref) { - if (fabsf(inertial_nav.get_altitude() - baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Altitude disparity"); - } - return false; - } - } - } - - // check Compass - if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_COMPASS)) { - // check the primary compass is healthy - if (!compass.healthy()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Compass not healthy"); - } - return false; - } - - // check compass learning is on or offsets have been set - if (!compass.configured()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Compass not calibrated"); - } - return false; - } - - // check for unreasonable compass offsets - Vector3f offsets = compass.get_offsets(); - if (offsets.length() > COMPASS_OFFSETS_MAX) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Compass offsets too high"); - } - return false; - } - - // check for unreasonable mag field length - float mag_field = compass.get_field().length(); - if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.65f || mag_field < COMPASS_MAGFIELD_EXPECTED*0.35f) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check mag field"); - } - return false; - } - - // check all compasses point in roughly same direction - if (!compass.consistent()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent compasses"); - } - return false; - } - - } - - // check GPS - if (!pre_arm_gps_checks(display_failure)) { - return false; - } - -#if AC_FENCE == ENABLED - // check fence is initialised - if (!fence.pre_arm_check()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: check fence"); - } - return false; - } -#endif - - // check INS - if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) { - // check accelerometers have been calibrated - if (!ins.accel_calibrated_ok_all()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Accels not calibrated"); - } - return false; - } - - // check accels are healthy - if (!ins.get_accel_health_all()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Accelerometers not healthy"); - } - return false; - } - - //check if accelerometers have calibrated and require reboot - if (ins.accel_cal_requires_reboot()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL, "PreArm: Accelerometers calibrated requires reboot"); - } - return false; - } - - // check all accelerometers point in roughly same direction - if (ins.get_accel_count() > 1) { - const Vector3f &prime_accel_vec = ins.get_accel(); - for (uint8_t i=0; i= 2) { - /* - * for boards with 3 IMUs we only use the first two - * in the EKF. Allow for larger accel discrepancy - * for IMU3 as it may be running at a different temperature - */ - threshold *= 2; - } - if (vec_diff.length() > threshold) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent Accelerometers"); - } - return false; - } - } - } - - // check gyros are healthy - if (!ins.get_gyro_health_all()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Gyros not healthy"); - } - return false; - } - - // check all gyros are consistent - if (ins.get_gyro_count() > 1) { - for (uint8_t i=0; i PREARM_MAX_GYRO_VECTOR_DIFF) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent Gyros"); - } - return false; - } - } - } - - // get ekf attitude (if bad, it's usually the gyro biases) - if (!pre_arm_ekf_attitude_check()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: gyros still settling"); - } - return false; - } - } -#if CONFIG_HAL_BOARD != HAL_BOARD_VRBRAIN -#ifndef CONFIG_ARCH_BOARD_PX4FMU_V1 - // check board voltage - if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_VOLTAGE)) { - if (hal.analogin->board_voltage() < BOARD_VOLTAGE_MIN || hal.analogin->board_voltage() > BOARD_VOLTAGE_MAX) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check Board Voltage"); - } - return false; - } - } -#endif -#endif - - // check battery voltage - if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_VOLTAGE)) { - if (failsafe.battery || (!ap.usb_connected && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah))) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check Battery"); - } - return false; - } - } - - // check various parameter values - if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_PARAMETERS)) { - - // ensure ch7 and ch8 have different functions - if (check_duplicate_auxsw()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Duplicate Aux Switch Options"); - } - return false; - } - - // lean angle parameter check - if (aparm.angle_max < 1000 || aparm.angle_max > 8000) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check ANGLE_MAX"); - } - return false; - } - - // acro balance parameter check - if ((g.acro_balance_roll > attitude_control.get_angle_roll_p().kP()) || (g.acro_balance_pitch > attitude_control.get_angle_pitch_p().kP())) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: ACRO_BAL_ROLL/PITCH"); - } - return false; - } - -#if RANGEFINDER_ENABLED == ENABLED && OPTFLOW == ENABLED - // check range finder if optflow enabled - if (optflow.enabled() && !rangefinder.pre_arm_check()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: check range finder"); - } - return false; - } -#endif - - // check for missing terrain data - if (!pre_arm_terrain_check(display_failure)) { - return false; - } - } - - return true; -} - -// perform pre_arm_rc_checks checks and set ap.pre_arm_rc_check flag -void Sub::pre_arm_rc_checks() -{ - // exit immediately if we've already successfully performed the pre-arm rc check - if (ap.pre_arm_rc_check) { - return; - } - - // set rc-checks to success if RC checks are disabled - if ((g.arming_check != ARMING_CHECK_ALL) && !(g.arming_check & ARMING_CHECK_RC)) { - set_pre_arm_rc_check(true); - return; - } - - // check if radio has been calibrated - if (!channel_throttle->min_max_configured()) { - return; - } - - // check channels 1 & 2 have min <= 1300 and max >= 1700 - if (channel_roll->get_radio_min() > 1300 || channel_roll->get_radio_max() < 1700 || channel_pitch->get_radio_min() > 1300 || channel_pitch->get_radio_max() < 1700) { - return; - } - - // check channels 3 & 4 have min <= 1300 and max >= 1700 - if (channel_throttle->get_radio_min() > 1300 || channel_throttle->get_radio_max() < 1700 || channel_yaw->get_radio_min() > 1300 || channel_yaw->get_radio_max() < 1700) { - return; - } - - // check channels 1 & 2 have trim >= 1300 and <= 1700 - if (channel_roll->get_radio_trim() < 1300 || channel_roll->get_radio_trim() > 1700 || channel_pitch->get_radio_trim() < 1300 || channel_pitch->get_radio_trim() > 1700) { - return; - } - - // check channel 4 has trim >= 1300 and <= 1700 - if (channel_yaw->get_radio_trim() < 1300 || channel_yaw->get_radio_trim() > 1700) { - return; - } - - // if we've gotten this far rc is ok - set_pre_arm_rc_check(true); -} - -// performs pre_arm gps related checks and returns true if passed -bool Sub::pre_arm_gps_checks(bool display_failure) -{ - // always check if inertial nav has started and is ready - if (!ahrs.healthy()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Waiting for Nav Checks"); - } - return false; - } - - // check if flight mode requires GPS - bool gps_required = mode_requires_GPS(control_mode); - -#if AC_FENCE == ENABLED - // if circular fence is enabled we need GPS - if ((fence.get_enabled_fences() & AC_FENCE_TYPE_CIRCLE) != 0) { - gps_required = true; - } -#endif - - // return true if GPS is not required - if (!gps_required) { - AP_Notify::flags.pre_arm_gps_check = true; - return true; - } - - // ensure GPS is ok - if (!position_ok()) { - if (display_failure) { - const char *reason = ahrs.prearm_failure_reason(); - if (reason) { - GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: %s", reason); - } else { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Need 3D Fix"); - } - } - AP_Notify::flags.pre_arm_gps_check = false; - return false; - } - - // check EKF compass variance is below failsafe threshold - float vel_variance, pos_variance, hgt_variance, tas_variance; - Vector3f mag_variance; - Vector2f offset; - ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance, offset); - if (mag_variance.length() >= g.fs_ekf_thresh) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: EKF compass variance"); - } - return false; - } - - // check home and EKF origin are not too far - if (far_from_EKF_origin(ahrs.get_home())) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: EKF-home variance"); - } - AP_Notify::flags.pre_arm_gps_check = false; - return false; - } - - // return true immediately if gps check is disabled - if (!(g.arming_check == ARMING_CHECK_ALL || g.arming_check & ARMING_CHECK_GPS)) { - AP_Notify::flags.pre_arm_gps_check = true; - return true; - } - - // warn about hdop separately - to prevent user confusion with no gps lock - if (gps.get_hdop() > g.gps_hdop_good) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: High GPS HDOP"); - } - AP_Notify::flags.pre_arm_gps_check = false; - return false; - } - - // if we got here all must be ok - AP_Notify::flags.pre_arm_gps_check = true; - return true; -} - -// check ekf attitude is acceptable -bool Sub::pre_arm_ekf_attitude_check() -{ - // get ekf filter status - nav_filter_status filt_status = inertial_nav.get_filter_status(); - - return filt_status.flags.attitude; -} - -// check we have required terrain data -bool Sub::pre_arm_terrain_check(bool display_failure) -{ -#if AP_TERRAIN_AVAILABLE && AC_TERRAIN - // succeed if not using terrain data - if (!terrain_use()) { - return true; - } - - // show terrain statistics - uint16_t terr_pending, terr_loaded; - terrain.get_statistics(terr_pending, terr_loaded); - bool have_all_data = (terr_pending <= 0); - if (!have_all_data && display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Waiting for Terrain data"); - } - return have_all_data; -#else - return true; -#endif -} - -// arm_checks - perform final checks before arming -// always called just before arming. Return true if ok to arm -// has side-effect that logging is started -bool Sub::arm_checks(bool display_failure, bool arming_from_gcs) -{ -#if LOGGING_ENABLED == ENABLED - // start dataflash - start_logging(); -#endif - - // check accels and gyro are healthy - if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) { - //check if accelerometers have calibrated and require reboot - if (ins.accel_cal_requires_reboot()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL, "PreArm: Accelerometers calibrated requires reboot"); - } - return false; - } - - if (!ins.get_accel_health_all()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Accelerometers not healthy"); - } - return false; - } - if (!ins.get_gyro_health_all()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Gyros not healthy"); - } - return false; - } - // get ekf attitude (if bad, it's usually the gyro biases) - if (!pre_arm_ekf_attitude_check()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: gyros still settling"); - } - return false; - } - } - - // always check if inertial nav has started and is ready - if (!ahrs.healthy()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Waiting for Nav Checks"); - } - ahrs.reset(); // This will fix the altitude hang; ToDo: figure out what is actually causing the hang - return false; - } - - if (compass.is_calibrating()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Compass calibration running"); - } - return false; - } - - // always check if the current mode allows arming - if (!mode_allows_arming(control_mode, arming_from_gcs)) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Mode not armable"); - } - return false; - } - - // always check gps - if (!pre_arm_gps_checks(display_failure)) { - return false; - } - - // if we are using motor interlock switch and it's enabled, fail to arm - if (ap.using_interlock && motors.get_interlock()) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Motor Interlock Enabled"); - return false; - } - - // if we are not using Emergency Stop switch option, force Estop false to ensure motors - // can run normally - if (!check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP)) { - set_motor_emergency_stop(false); - // if we are using motor Estop switch, it must not be in Estop position - } else if (check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP) && ap.motor_emergency_stop) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Motor Emergency Stopped"); - return false; - } - - // succeed if arming checks are disabled - if (g.arming_check == ARMING_CHECK_NONE) { - return true; - } - - // baro checks - if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_BARO)) { - // baro health check - if (!barometer.all_healthy()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Barometer not healthy"); - } - return false; - } - // 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. - nav_filter_status filt_status = inertial_nav.get_filter_status(); - bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs); - if (using_baro_ref && (fabsf(inertial_nav.get_altitude() - baro_alt) > PREARM_MAX_ALT_DISPARITY_CM)) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Altitude disparity"); - } - return false; - } - } - -#if AC_FENCE == ENABLED - // check vehicle is within fence - if (!fence.pre_arm_check()) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: check fence"); - } - return false; - } -#endif - - // check lean angle - if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) { - if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > aparm.angle_max) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Leaning"); - } - return false; - } - } - - // check battery voltage - if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_VOLTAGE)) { - if (failsafe.battery || (!ap.usb_connected && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah))) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Check Battery"); - } - return false; - } - } - - // check for missing terrain data - if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_PARAMETERS)) { - if (!pre_arm_terrain_check(display_failure)) { - return false; - } - } - - // check throttle - if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_RC)) { - // check throttle is not too low - must be above failsafe throttle - - // check throttle is not too high - skips checks if arming from GCS in Guided - if (!(arming_from_gcs && control_mode == GUIDED)) { - // in manual modes throttle must be at zero - if ((mode_has_manual_throttle(control_mode)) && channel_throttle->get_control_in() > 0) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Throttle too high"); - } - return false; - } - } - } - - // check if safety switch has been pushed - if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) { - if (display_failure) { - gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Safety Switch"); - } - return false; - } - - // if we've gotten this far all is ok - return true; -} diff --git a/ArduSub/compassmot.cpp b/ArduSub/compassmot.cpp index a7d2203851..9c418ef940 100644 --- a/ArduSub/compassmot.cpp +++ b/ArduSub/compassmot.cpp @@ -52,9 +52,7 @@ uint8_t Sub::mavlink_compassmot(mavlink_channel_t chan) } // check if radio is calibrated - pre_arm_rc_checks(); - if (!ap.pre_arm_rc_check) { - gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "RC not calibrated"); + if (!arming.rc_check()) { ap.compass_mot = false; return 1; } diff --git a/ArduSub/defines.h b/ArduSub/defines.h index abb1e99acb..0b4b91ef34 100644 --- a/ArduSub/defines.h +++ b/ArduSub/defines.h @@ -393,17 +393,6 @@ enum LoiterModeState { // Baro specific error codes #define ERROR_CODE_BARO_GLITCH 2 -// Arming Check Enable/Disable bits -#define ARMING_CHECK_NONE 0x00 -#define ARMING_CHECK_ALL 0x01 -#define ARMING_CHECK_BARO 0x02 -#define ARMING_CHECK_COMPASS 0x04 -#define ARMING_CHECK_GPS 0x08 -#define ARMING_CHECK_INS 0x10 -#define ARMING_CHECK_PARAMETERS 0x20 -#define ARMING_CHECK_RC 0x40 -#define ARMING_CHECK_VOLTAGE 0x80 - // Radio failsafe definitions (FS_THR parameter) #define FS_THR_DISABLED 0 #define FS_THR_ENABLED_ALWAYS_RTL 1 diff --git a/ArduSub/esc_calibration.cpp b/ArduSub/esc_calibration.cpp index 529a77ec02..bb378c88f2 100644 --- a/ArduSub/esc_calibration.cpp +++ b/ArduSub/esc_calibration.cpp @@ -19,8 +19,7 @@ enum ESCCalibrationModes { void Sub::esc_calibration_startup_check() { // exit immediately if pre-arm rc checks fail - pre_arm_rc_checks(); - if (!ap.pre_arm_rc_check) { + if (!arming.rc_check()) { // clear esc flag for next time if ((g.esc_calibrate != ESCCAL_NONE) && (g.esc_calibrate != ESCCAL_DISABLED)) { g.esc_calibrate.set_and_save(ESCCAL_NONE); diff --git a/ArduSub/motor_test.cpp b/ArduSub/motor_test.cpp index a34fe54fa3..c57a1e45f8 100644 --- a/ArduSub/motor_test.cpp +++ b/ArduSub/motor_test.cpp @@ -67,9 +67,7 @@ void Sub::motor_test_output() bool Sub::mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc) { // check rc has been calibrated - pre_arm_rc_checks(); - if (check_rc && !ap.pre_arm_rc_check) { - gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL,"Motor Test: RC not calibrated"); + if (check_rc && !arming.rc_check()) { return false; } diff --git a/ArduSub/motors.cpp b/ArduSub/motors.cpp index 9ddb9ad267..ea87394a90 100644 --- a/ArduSub/motors.cpp +++ b/ArduSub/motors.cpp @@ -44,10 +44,10 @@ bool Sub::init_arm_motors(bool arming_from_gcs) if (in_arm_motors) { return false; } + in_arm_motors = true; - // run pre-arm-checks and display failures - if (!all_arming_checks_passing(arming_from_gcs)) { + if (!arming.pre_arm_checks(true)) { AP_Notify::events.arming_failed = true; in_arm_motors = false; return false; diff --git a/ArduSub/radio.cpp b/ArduSub/radio.cpp index e5ef7c5f02..e871d78af8 100644 --- a/ArduSub/radio.cpp +++ b/ArduSub/radio.cpp @@ -76,8 +76,7 @@ void Sub::init_rc_out() esc_calibration_startup_check(); // enable output to motors - pre_arm_rc_checks(); - if (ap.pre_arm_rc_check) { + if (arming.rc_check()) { enable_motor_output(); }