Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Blimp/AP_Arming.cpp
Views: 1798
#include "Blimp.h"12bool AP_Arming_Blimp::pre_arm_checks(bool display_failure)3{4const bool passed = run_pre_arm_checks(display_failure);5set_pre_arm_check(passed);6return passed;7}89// perform pre-arm checks10// return true if the checks pass successfully11bool AP_Arming_Blimp::run_pre_arm_checks(bool display_failure)12{13// exit immediately if already armed14if (blimp.motors->armed()) {15return true;16}1718// check if motor interlock and Emergency Stop aux switches are used19// at the same time. This cannot be allowed.20if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) &&21rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP)) {22check_failed(display_failure, "Interlock/E-Stop Conflict");23return false;24}2526// if pre arm checks are disabled run only the mandatory checks27if (checks_to_perform == 0) {28return mandatory_checks(display_failure);29}3031return parameter_checks(display_failure)32#if AP_FENCE_ENABLED33& fence_checks(display_failure)34#endif35& motor_checks(display_failure)36& gcs_failsafe_check(display_failure)37& alt_checks(display_failure)38& AP_Arming::pre_arm_checks(display_failure);39}4041bool AP_Arming_Blimp::barometer_checks(bool display_failure)42{43if (!AP_Arming::barometer_checks(display_failure)) {44return false;45}4647bool ret = true;48// check Baro49if (check_enabled(ARMING_CHECK_BARO)) {50// Check baro & inav alt are within 1m if EKF is operating in an absolute position mode.51// Do not check if intending to operate in a ground relative height mode as EKF will output a ground relative height52// that may differ from the baro height due to baro drift.53nav_filter_status filt_status = blimp.inertial_nav.get_filter_status();54bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs);55if (using_baro_ref) {56if (fabsf(blimp.inertial_nav.get_position_z_up_cm() - blimp.baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) {57check_failed(ARMING_CHECK_BARO, display_failure, "Altitude disparity");58ret = false;59}60}61}62return ret;63}6465bool AP_Arming_Blimp::ins_checks(bool display_failure)66{67bool ret = AP_Arming::ins_checks(display_failure);6869if (check_enabled(ARMING_CHECK_INS)) {7071// get ekf attitude (if bad, it's usually the gyro biases)72if (!pre_arm_ekf_attitude_check()) {73check_failed(ARMING_CHECK_INS, display_failure, "EKF attitude is bad");74ret = false;75}76}7778return ret;79}8081bool AP_Arming_Blimp::board_voltage_checks(bool display_failure)82{83if (!AP_Arming::board_voltage_checks(display_failure)) {84return false;85}8687// check battery voltage88if (check_enabled(ARMING_CHECK_VOLTAGE)) {89if (blimp.battery.has_failsafed()) {90check_failed(ARMING_CHECK_VOLTAGE, display_failure, "Battery failsafe");91return false;92}9394// call parent battery checks95if (!AP_Arming::battery_checks(display_failure)) {96return false;97}98}99100return true;101}102103bool AP_Arming_Blimp::parameter_checks(bool display_failure)104{105// check various parameter values106if (check_enabled(ARMING_CHECK_PARAMETERS)) {107108// failsafe parameter checks109if (blimp.g.failsafe_throttle) {110// check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900111if (blimp.channel_up->get_radio_min() <= blimp.g.failsafe_throttle_value+10 || blimp.g.failsafe_throttle_value < 910) {112check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check FS_THR_VALUE");113return false;114}115}116}117118return true;119}120121// check motor setup was successful122bool AP_Arming_Blimp::motor_checks(bool display_failure)123{124// check motors initialised correctly125if (!blimp.motors->initialised_ok()) {126check_failed(display_failure, "Check firmware or FRAME_CLASS");127return false;128}129130// further checks enabled with parameters131if (!check_enabled(ARMING_CHECK_PARAMETERS)) {132return true;133}134135return true;136}137138bool AP_Arming_Blimp::rc_calibration_checks(bool display_failure)139{140return true;141}142143// performs pre_arm gps related checks and returns true if passed144bool AP_Arming_Blimp::gps_checks(bool display_failure)145{146// run mandatory gps checks first147if (!mandatory_gps_checks(display_failure)) {148AP_Notify::flags.pre_arm_gps_check = false;149return false;150}151152// check if flight mode requires GPS153bool mode_requires_gps = blimp.flightmode->requires_GPS();154155156// return true if GPS is not required157if (!mode_requires_gps) {158AP_Notify::flags.pre_arm_gps_check = true;159return true;160}161162// return true immediately if gps check is disabled163if (!check_enabled(ARMING_CHECK_GPS)) {164AP_Notify::flags.pre_arm_gps_check = true;165return true;166}167168// warn about hdop separately - to prevent user confusion with no gps lock169if (blimp.gps.get_hdop() > blimp.g.gps_hdop_good) {170check_failed(ARMING_CHECK_GPS, display_failure, "High GPS HDOP");171AP_Notify::flags.pre_arm_gps_check = false;172return false;173}174175// call parent gps checks176if (!AP_Arming::gps_checks(display_failure)) {177AP_Notify::flags.pre_arm_gps_check = false;178return false;179}180181// if we got here all must be ok182AP_Notify::flags.pre_arm_gps_check = true;183return true;184}185186// check ekf attitude is acceptable187bool AP_Arming_Blimp::pre_arm_ekf_attitude_check()188{189// get ekf filter status190nav_filter_status filt_status = blimp.inertial_nav.get_filter_status();191192return filt_status.flags.attitude;193}194195// performs mandatory gps checks. returns true if passed196bool AP_Arming_Blimp::mandatory_gps_checks(bool display_failure)197{198// always check if inertial nav has started and is ready199const auto &ahrs = AP::ahrs();200char failure_msg[50] = {};201if (!ahrs.pre_arm_check(false, failure_msg, sizeof(failure_msg))) {202check_failed(display_failure, "AHRS: %s", failure_msg);203return false;204}205206// check if flight mode requires GPS207bool mode_requires_gps = blimp.flightmode->requires_GPS();208209if (mode_requires_gps) {210if (!blimp.position_ok()) {211// vehicle level position estimate checks212check_failed(display_failure, "Need Position Estimate");213return false;214}215} else {216// return true if GPS is not required217return true;218}219220// check for GPS glitch (as reported by EKF)221nav_filter_status filt_status;222if (ahrs.get_filter_status(filt_status)) {223if (filt_status.flags.gps_glitching) {224check_failed(display_failure, "GPS glitching");225return false;226}227}228229// if we got here all must be ok230return true;231}232233// Check GCS failsafe234bool AP_Arming_Blimp::gcs_failsafe_check(bool display_failure)235{236if (blimp.failsafe.gcs) {237check_failed(display_failure, "GCS failsafe on");238return false;239}240return true;241}242243// performs altitude checks. returns true if passed244bool AP_Arming_Blimp::alt_checks(bool display_failure)245{246// always EKF altitude estimate247if (!blimp.flightmode->has_manual_throttle() && !blimp.ekf_alt_ok()) {248check_failed(display_failure, "Need Alt Estimate");249return false;250}251252return true;253}254255// arm_checks - perform final checks before arming256// always called just before arming. Return true if ok to arm257// has side-effect that logging is started258bool AP_Arming_Blimp::arm_checks(AP_Arming::Method method)259{260return AP_Arming::arm_checks(method);261}262263// mandatory checks that will be run if ARMING_CHECK is zero or arming forced264bool AP_Arming_Blimp::mandatory_checks(bool display_failure)265{266// call mandatory gps checks and update notify status because regular gps checks will not run267bool result = mandatory_gps_checks(display_failure);268AP_Notify::flags.pre_arm_gps_check = result;269270// call mandatory alt check271if (!alt_checks(display_failure)) {272result = false;273}274275return result & AP_Arming::mandatory_checks(display_failure);276}277278void AP_Arming_Blimp::set_pre_arm_check(bool b)279{280blimp.ap.pre_arm_check = b;281AP_Notify::flags.pre_arm_check = b;282}283284bool AP_Arming_Blimp::arm(const AP_Arming::Method method, const bool do_arming_checks)285{286static bool in_arm_motors = false;287288// exit immediately if already in this function289if (in_arm_motors) {290return false;291}292in_arm_motors = true;293294// return true if already armed295if (blimp.motors->armed()) {296in_arm_motors = false;297return true;298}299300if (!AP_Arming::arm(method, do_arming_checks)) {301AP_Notify::events.arming_failed = true;302in_arm_motors = false;303return false;304}305306#if HAL_LOGGING_ENABLED307// let logger know that we're armed (it may open logs e.g.)308AP::logger().set_vehicle_armed(true);309#endif310311// notify that arming will occur (we do this early to give plenty of warning)312AP_Notify::flags.armed = true;313// call notify update a few times to ensure the message gets out314for (uint8_t i=0; i<=10; i++) {315AP::notify().update();316}317318send_arm_disarm_statustext("Arming motors"); //MIR kept in - usually only in SITL319320auto &ahrs = AP::ahrs();321322blimp.initial_armed_bearing = ahrs.yaw_sensor;323324if (!ahrs.home_is_set()) {325// Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home)326ahrs.resetHeightDatum();327LOGGER_WRITE_EVENT(LogEvent::EKF_ALT_RESET);328329// we have reset height, so arming height is zero330blimp.arming_altitude_m = 0;331} else if (!ahrs.home_is_locked()) {332// Reset home position if it has already been set before (but not locked)333if (!blimp.set_home_to_current_location(false)) {334// ignore failure335}336337// remember the height when we armed338blimp.arming_altitude_m = blimp.inertial_nav.get_position_z_up_cm() * 0.01;339}340341hal.util->set_soft_armed(true);342343// finally actually arm the motors344blimp.motors->armed(true);345346#if HAL_LOGGING_ENABLED347// log flight mode in case it was changed while vehicle was disarmed348AP::logger().Write_Mode((uint8_t)blimp.control_mode, blimp.control_mode_reason);349#endif350351// perf monitor ignores delay due to arming352AP::scheduler().perf_info.ignore_this_loop();353354// flag exiting this function355in_arm_motors = false;356357// Log time stamp of arming event358blimp.arm_time_ms = millis();359360// Start the arming delay361blimp.ap.in_arming_delay = true;362363// return success364return true;365}366367// arming.disarm - disarm motors368bool AP_Arming_Blimp::disarm(const AP_Arming::Method method, bool do_disarm_checks)369{370// return immediately if we are already disarmed371if (!blimp.motors->armed()) {372return true;373}374375if (!AP_Arming::disarm(method, do_disarm_checks)) {376return false;377}378379send_arm_disarm_statustext("Disarming motors"); //MIR keeping in - usually only in SITL380381auto &ahrs = AP::ahrs();382383// save compass offsets learned by the EKF if enabled384Compass &compass = AP::compass();385if (ahrs.use_compass() && compass.get_learn_type() == Compass::LEARN_EKF) {386for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {387Vector3f magOffsets;388if (ahrs.getMagOffsets(i, magOffsets)) {389compass.set_and_save_offsets(i, magOffsets);390}391}392}393394// send disarm command to motors395blimp.motors->armed(false);396397#if HAL_LOGGING_ENABLED398AP::logger().set_vehicle_armed(false);399#endif400401hal.util->set_soft_armed(false);402403blimp.ap.in_arming_delay = false;404405return true;406}407408409