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/ArduCopter/AP_Arming.cpp
Views: 1798
#include "Copter.h"12#pragma GCC diagnostic push3#if defined(__clang_major__) && __clang_major__ >= 144#pragma GCC diagnostic ignored "-Wbitwise-instead-of-logical"5#endif67bool AP_Arming_Copter::pre_arm_checks(bool display_failure)8{9const bool passed = run_pre_arm_checks(display_failure);10set_pre_arm_check(passed);11return passed;12}1314// perform pre-arm checks15// return true if the checks pass successfully16bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)17{18// exit immediately if already armed19if (copter.motors->armed()) {20return true;21}2223// check if motor interlock and either Emergency Stop aux switches are used24// at the same time. This cannot be allowed.25bool passed = true;26if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) &&27(rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP) ||28rc().find_channel_for_option(RC_Channel::AUX_FUNC::ARM_EMERGENCY_STOP))){29check_failed(display_failure, "Interlock/E-Stop Conflict");30passed = false;31}3233// check if motor interlock aux switch is in use34// if it is, switch needs to be in disabled position to arm35// otherwise exit immediately.36if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) {37check_failed(display_failure, "Motor Interlock Enabled");38passed = false;39}4041if (!disarm_switch_checks(display_failure)) {42passed = false;43}4445// always check motors46char failure_msg[100] {};47if (!copter.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) {48check_failed(display_failure, "Motors: %s", failure_msg);49passed = false;50}5152// If not passed all checks return false53if (!passed) {54return false;55}5657// if pre arm checks are disabled run only the mandatory checks58if (checks_to_perform == 0) {59return mandatory_checks(display_failure);60}6162// bitwise & ensures all checks are run63return parameter_checks(display_failure)64& oa_checks(display_failure)65& gcs_failsafe_check(display_failure)66& winch_checks(display_failure)67& rc_throttle_failsafe_checks(display_failure)68& alt_checks(display_failure)69#if AP_AIRSPEED_ENABLED70& AP_Arming::airspeed_checks(display_failure)71#endif72& AP_Arming::pre_arm_checks(display_failure);73}7475bool AP_Arming_Copter::rc_throttle_failsafe_checks(bool display_failure) const76{77if (!check_enabled(ARMING_CHECK_RC)) {78// this check has been disabled79return true;80}8182// throttle failsafe. In this case the parameter also gates the83// no-pulses RC failure case - the radio-in value can be zero due84// to not having received any RC pulses at all. Note that if we85// have ever seen RC and then we *lose* RC then these checks are86// likely to pass if the user is relying on no-pulses to detect RC87// failure. However, arming is precluded in that case by being in88// RC failsafe.89if (copter.g.failsafe_throttle == FS_THR_DISABLED) {90return true;91}9293#if FRAME_CONFIG == HELI_FRAME94const char *rc_item = "Collective";95#else96const char *rc_item = "Throttle";97#endif9899if (!rc().has_had_rc_receiver() && !rc().has_had_rc_override()) {100check_failed(ARMING_CHECK_RC, display_failure, "RC not found");101return false;102}103104// check throttle is not too low - must be above failsafe throttle105if (copter.channel_throttle->get_radio_in() < copter.g.failsafe_throttle_value) {106check_failed(ARMING_CHECK_RC, display_failure, "%s below failsafe", rc_item);107return false;108}109110return true;111}112113bool AP_Arming_Copter::barometer_checks(bool display_failure)114{115if (!AP_Arming::barometer_checks(display_failure)) {116return false;117}118119bool ret = true;120// check Baro121if (check_enabled(ARMING_CHECK_BARO)) {122// Check baro & inav alt are within 1m if EKF is operating in an absolute position mode.123// Do not check if intending to operate in a ground relative height mode as EKF will output a ground relative height124// that may differ from the baro height due to baro drift.125nav_filter_status filt_status = copter.inertial_nav.get_filter_status();126bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs);127if (using_baro_ref) {128if (fabsf(copter.inertial_nav.get_position_z_up_cm() - copter.baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) {129check_failed(ARMING_CHECK_BARO, display_failure, "Altitude disparity");130ret = false;131}132}133}134return ret;135}136137bool AP_Arming_Copter::ins_checks(bool display_failure)138{139bool ret = AP_Arming::ins_checks(display_failure);140141if (check_enabled(ARMING_CHECK_INS)) {142143// get ekf attitude (if bad, it's usually the gyro biases)144if (!pre_arm_ekf_attitude_check()) {145check_failed(ARMING_CHECK_INS, display_failure, "EKF attitude is bad");146ret = false;147}148}149150return ret;151}152153bool AP_Arming_Copter::board_voltage_checks(bool display_failure)154{155if (!AP_Arming::board_voltage_checks(display_failure)) {156return false;157}158159// check battery voltage160if (check_enabled(ARMING_CHECK_VOLTAGE)) {161if (copter.battery.has_failsafed()) {162check_failed(ARMING_CHECK_VOLTAGE, display_failure, "Battery failsafe");163return false;164}165}166167return true;168}169170// expected to return true if the terrain database is required to have171// all data loaded172bool AP_Arming_Copter::terrain_database_required() const173{174175if (copter.wp_nav->get_terrain_source() == AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER) {176// primary terrain source is from rangefinder, allow arming without terrain database177return false;178}179180if (copter.wp_nav->get_terrain_source() == AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE &&181copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::TERRAIN) {182return true;183}184return AP_Arming::terrain_database_required();185}186187bool AP_Arming_Copter::parameter_checks(bool display_failure)188{189// check various parameter values190if (check_enabled(ARMING_CHECK_PARAMETERS)) {191192// failsafe parameter checks193if (copter.g.failsafe_throttle) {194// check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900195if (copter.channel_throttle->get_radio_min() <= copter.g.failsafe_throttle_value+10 || copter.g.failsafe_throttle_value < 910) {196check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check FS_THR_VALUE");197return false;198}199}200if (copter.g.failsafe_gcs == FS_GCS_ENABLED_CONTINUE_MISSION) {201// FS_GCS_ENABLE == 2 has been removed202check_failed(ARMING_CHECK_PARAMETERS, display_failure, "FS_GCS_ENABLE=2 removed, see FS_OPTIONS");203}204205// lean angle parameter check206if (copter.aparm.angle_max < 1000 || copter.aparm.angle_max > 8000) {207check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check ANGLE_MAX");208return false;209}210211// acro balance parameter check212#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED213if ((copter.g.acro_balance_roll > copter.attitude_control->get_angle_roll_p().kP()) || (copter.g.acro_balance_pitch > copter.attitude_control->get_angle_pitch_p().kP())) {214check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check ACRO_BAL_ROLL/PITCH");215return false;216}217#endif218219// pilot-speed-up parameter check220if (copter.g.pilot_speed_up <= 0) {221check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check PILOT_SPEED_UP");222return false;223}224225#if FRAME_CONFIG == HELI_FRAME226char fail_msg[100]{};227// check input manager parameters228if (!copter.input_manager.parameter_check(fail_msg, ARRAY_SIZE(fail_msg))) {229check_failed(ARMING_CHECK_PARAMETERS, display_failure, "%s", fail_msg);230return false;231}232233// Ensure an Aux Channel is configured for motor interlock234if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) == nullptr) {235check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Motor Interlock not configured");236return false;237}238239#else240switch (copter.g2.frame_class.get()) {241case AP_Motors::MOTOR_FRAME_HELI_QUAD:242case AP_Motors::MOTOR_FRAME_HELI_DUAL:243case AP_Motors::MOTOR_FRAME_HELI:244check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Invalid MultiCopter FRAME_CLASS");245return false;246247default:248break;249}250#endif // HELI_FRAME251252// checks when using range finder for RTL253#if MODE_RTL_ENABLED254if (copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::TERRAIN) {255// get terrain source from wpnav256const char *failure_template = "RTL_ALT_TYPE is above-terrain but %s";257switch (copter.wp_nav->get_terrain_source()) {258case AC_WPNav::TerrainSource::TERRAIN_UNAVAILABLE:259check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "no terrain data");260return false;261break;262case AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER:263#if AP_RANGEFINDER_ENABLED264if (!copter.rangefinder_state.enabled || !copter.rangefinder.has_orientation(ROTATION_PITCH_270)) {265check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "no rangefinder");266return false;267}268// check if RTL_ALT is higher than rangefinder's max range269if (copter.g.rtl_altitude > copter.rangefinder.max_distance_cm_orient(ROTATION_PITCH_270)) {270check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "RTL_ALT>RNGFND_MAX_CM");271return false;272}273#else274check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "rangefinder not in firmware");275#endif276break;277case AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE:278// these checks are done in AP_Arming279break;280}281}282#endif283284// check adsb avoidance failsafe285#if HAL_ADSB_ENABLED286if (copter.failsafe.adsb) {287check_failed(ARMING_CHECK_PARAMETERS, display_failure, "ADSB threat detected");288return false;289}290#endif291292// ensure controllers are OK with us arming:293char failure_msg[100] = {};294if (!copter.pos_control->pre_arm_checks("PSC", failure_msg, ARRAY_SIZE(failure_msg))) {295check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);296return false;297}298if (!copter.attitude_control->pre_arm_checks("ATC", failure_msg, ARRAY_SIZE(failure_msg))) {299check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);300return false;301}302}303304return true;305}306307bool AP_Arming_Copter::oa_checks(bool display_failure)308{309#if AP_OAPATHPLANNER_ENABLED310char failure_msg[100] = {};311if (copter.g2.oa.pre_arm_check(failure_msg, ARRAY_SIZE(failure_msg))) {312return true;313}314// display failure315if (strlen(failure_msg) == 0) {316check_failed(display_failure, "%s", "Check Object Avoidance");317} else {318check_failed(display_failure, "%s", failure_msg);319}320return false;321#else322return true;323#endif324}325326bool AP_Arming_Copter::rc_calibration_checks(bool display_failure)327{328const RC_Channel *channels[] = {329copter.channel_roll,330copter.channel_pitch,331copter.channel_throttle,332copter.channel_yaw333};334335// bitwise & ensures all checks are run336copter.ap.pre_arm_rc_check = rc_checks_copter_sub(display_failure, channels)337& AP_Arming::rc_calibration_checks(display_failure);338339return copter.ap.pre_arm_rc_check;340}341342// performs pre_arm gps related checks and returns true if passed343bool AP_Arming_Copter::gps_checks(bool display_failure)344{345// check if fence requires GPS346bool fence_requires_gps = false;347#if AP_FENCE_ENABLED348// if circular or polygon fence is enabled we need GPS349fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;350#endif351352// check if flight mode requires GPS353bool mode_requires_gps = copter.flightmode->requires_GPS() || fence_requires_gps || (copter.simple_mode == Copter::SimpleMode::SUPERSIMPLE);354355// call parent gps checks356if (mode_requires_gps) {357if (!AP_Arming::gps_checks(display_failure)) {358AP_Notify::flags.pre_arm_gps_check = false;359return false;360}361}362363// run mandatory gps checks first364if (!mandatory_gps_checks(display_failure)) {365AP_Notify::flags.pre_arm_gps_check = false;366return false;367}368369// return true if GPS is not required370if (!mode_requires_gps) {371AP_Notify::flags.pre_arm_gps_check = true;372return true;373}374375// return true immediately if gps check is disabled376if (!check_enabled(ARMING_CHECK_GPS)) {377AP_Notify::flags.pre_arm_gps_check = true;378return true;379}380381// warn about hdop separately - to prevent user confusion with no gps lock382if ((copter.gps.num_sensors() > 0) && (copter.gps.get_hdop() > copter.g.gps_hdop_good)) {383check_failed(ARMING_CHECK_GPS, display_failure, "High GPS HDOP");384AP_Notify::flags.pre_arm_gps_check = false;385return false;386}387388// if we got here all must be ok389AP_Notify::flags.pre_arm_gps_check = true;390return true;391}392393// check ekf attitude is acceptable394bool AP_Arming_Copter::pre_arm_ekf_attitude_check()395{396// get ekf filter status397nav_filter_status filt_status = copter.inertial_nav.get_filter_status();398399return filt_status.flags.attitude;400}401402#if HAL_PROXIMITY_ENABLED403// check nothing is too close to vehicle404bool AP_Arming_Copter::proximity_checks(bool display_failure) const405{406407if (!AP_Arming::proximity_checks(display_failure)) {408return false;409}410411if (!check_enabled(ARMING_CHECK_PARAMETERS)) {412// check is disabled413return true;414}415416// get closest object if we might use it for avoidance417#if AP_AVOIDANCE_ENABLED418float angle_deg, distance;419if (copter.avoid.proximity_avoidance_enabled() && copter.g2.proximity.get_closest_object(angle_deg, distance)) {420// display error if something is within 60cm421const float tolerance = 0.6f;422if (distance <= tolerance) {423check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Proximity %d deg, %4.2fm (want > %0.1fm)", (int)angle_deg, (double)distance, (double)tolerance);424return false;425}426}427#endif428429return true;430}431#endif // HAL_PROXIMITY_ENABLED432433// performs mandatory gps checks. returns true if passed434bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)435{436// check if flight mode requires GPS437bool mode_requires_gps = copter.flightmode->requires_GPS();438439// always check if inertial nav has started and is ready440const auto &ahrs = AP::ahrs();441char failure_msg[100] = {};442if (!ahrs.pre_arm_check(mode_requires_gps, failure_msg, sizeof(failure_msg))) {443check_failed(display_failure, "AHRS: %s", failure_msg);444return false;445}446447// check if fence requires GPS448bool fence_requires_gps = false;449#if AP_FENCE_ENABLED450// if circular or polygon fence is enabled we need GPS451fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;452#endif453454if (mode_requires_gps || copter.option_is_enabled(Copter::FlightOption::REQUIRE_POSITION_FOR_ARMING)) {455if (!copter.position_ok()) {456// vehicle level position estimate checks457check_failed(display_failure, "Need Position Estimate");458return false;459}460} else if (fence_requires_gps) {461if (!copter.position_ok()) {462// clarify to user why they need GPS in non-GPS flight mode463check_failed(display_failure, "Fence enabled, need position estimate");464return false;465}466} else {467// return true if GPS is not required468return true;469}470471// check for GPS glitch (as reported by EKF)472nav_filter_status filt_status;473if (ahrs.get_filter_status(filt_status)) {474if (filt_status.flags.gps_glitching) {475check_failed(display_failure, "GPS glitching");476return false;477}478}479480// check EKF's compass, position, height and velocity variances are below failsafe threshold481if (copter.g.fs_ekf_thresh > 0.0f) {482float vel_variance, pos_variance, hgt_variance, tas_variance;483Vector3f mag_variance;484ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance);485if (mag_variance.length() >= copter.g.fs_ekf_thresh) {486check_failed(display_failure, "EKF compass variance");487return false;488}489if (pos_variance >= copter.g.fs_ekf_thresh) {490check_failed(display_failure, "EKF position variance");491return false;492}493if (vel_variance >= copter.g.fs_ekf_thresh) {494check_failed(display_failure, "EKF velocity variance");495return false;496}497if (hgt_variance >= copter.g.fs_ekf_thresh) {498check_failed(display_failure, "EKF height variance");499return false;500}501}502503// if we got here all must be ok504return true;505}506507// Check GCS failsafe508bool AP_Arming_Copter::gcs_failsafe_check(bool display_failure)509{510if (copter.failsafe.gcs) {511check_failed(display_failure, "GCS failsafe on");512return false;513}514return true;515}516517// check winch518bool AP_Arming_Copter::winch_checks(bool display_failure) const519{520#if AP_WINCH_ENABLED521// pass if parameter or all arming checks disabled522if (!check_enabled(ARMING_CHECK_PARAMETERS)) {523return true;524}525526const AP_Winch *winch = AP::winch();527if (winch == nullptr) {528return true;529}530char failure_msg[100] = {};531if (!winch->pre_arm_check(failure_msg, sizeof(failure_msg))) {532check_failed(display_failure, "%s", failure_msg);533return false;534}535#endif536return true;537}538539// performs altitude checks. returns true if passed540bool AP_Arming_Copter::alt_checks(bool display_failure)541{542// always EKF altitude estimate543if (!copter.flightmode->has_manual_throttle() && !copter.ekf_alt_ok()) {544check_failed(display_failure, "Need Alt Estimate");545return false;546}547548return true;549}550551// arm_checks - perform final checks before arming552// always called just before arming. Return true if ok to arm553// has side-effect that logging is started554bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)555{556const auto &ahrs = AP::ahrs();557558// always check if inertial nav has started and is ready559if (!ahrs.healthy()) {560check_failed(true, "AHRS not healthy");561return false;562}563564#ifndef ALLOW_ARM_NO_COMPASS565// if non-compass is source of heading we can skip compass health check566if (!ahrs.using_noncompass_for_yaw()) {567const Compass &_compass = AP::compass();568// check compass health569if (!_compass.healthy()) {570check_failed(true, "Compass not healthy");571return false;572}573}574#endif575576// always check if the current mode allows arming577if (!copter.flightmode->allows_arming(method)) {578check_failed(true, "%s mode not armable", copter.flightmode->name());579return false;580}581582// succeed if arming checks are disabled583if (checks_to_perform == 0) {584return true;585}586587// check lean angle588if (check_enabled(ARMING_CHECK_INS)) {589if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > copter.aparm.angle_max) {590check_failed(ARMING_CHECK_INS, true, "Leaning");591return false;592}593}594595// check adsb596#if HAL_ADSB_ENABLED597if (check_enabled(ARMING_CHECK_PARAMETERS)) {598if (copter.failsafe.adsb) {599check_failed(ARMING_CHECK_PARAMETERS, true, "ADSB threat detected");600return false;601}602}603#endif604605// check throttle606if (check_enabled(ARMING_CHECK_RC)) {607#if FRAME_CONFIG == HELI_FRAME608const char *rc_item = "Collective";609#else610const char *rc_item = "Throttle";611#endif612// check throttle is not too high - skips checks if arming from GCS/scripting in Guided,Guided_NoGPS or Auto613if (!((AP_Arming::method_is_GCS(method) || method == AP_Arming::Method::SCRIPTING) && copter.flightmode->allows_GCS_or_SCR_arming_with_throttle_high())) {614// above top of deadband is too always high615if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) {616check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);617return false;618}619// in manual modes throttle must be at zero620#if FRAME_CONFIG != HELI_FRAME621if ((copter.flightmode->has_manual_throttle() || copter.flightmode->mode_number() == Mode::Number::DRIFT) && copter.channel_throttle->get_control_in() > 0) {622check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);623return false;624}625#endif626}627}628629// check if safety switch has been pushed630if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {631check_failed(true, "Safety Switch");632return false;633}634635// superclass method should always be the last thing called; it636// has side-effects which would need to be cleaned up if one of637// our arm checks failed638return AP_Arming::arm_checks(method);639}640641// mandatory checks that will be run if ARMING_CHECK is zero or arming forced642bool AP_Arming_Copter::mandatory_checks(bool display_failure)643{644// call mandatory gps checks and update notify status because regular gps checks will not run645bool result = mandatory_gps_checks(display_failure);646AP_Notify::flags.pre_arm_gps_check = result;647648// call mandatory alt check649if (!alt_checks(display_failure)) {650result = false;651}652653return result & AP_Arming::mandatory_checks(display_failure);654}655656void AP_Arming_Copter::set_pre_arm_check(bool b)657{658copter.ap.pre_arm_check = b;659AP_Notify::flags.pre_arm_check = b;660}661662bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_checks)663{664static bool in_arm_motors = false;665666// exit immediately if already in this function667if (in_arm_motors) {668return false;669}670in_arm_motors = true;671672// return true if already armed673if (copter.motors->armed()) {674in_arm_motors = false;675return true;676}677678if (!AP_Arming::arm(method, do_arming_checks)) {679AP_Notify::events.arming_failed = true;680in_arm_motors = false;681return false;682}683684#if HAL_LOGGING_ENABLED685// let logger know that we're armed (it may open logs e.g.)686AP::logger().set_vehicle_armed(true);687#endif688689// disable cpu failsafe because initialising everything takes a while690copter.failsafe_disable();691692// notify that arming will occur (we do this early to give plenty of warning)693AP_Notify::flags.armed = true;694// call notify update a few times to ensure the message gets out695for (uint8_t i=0; i<=10; i++) {696AP::notify().update();697}698699#if CONFIG_HAL_BOARD == HAL_BOARD_SITL700send_arm_disarm_statustext("Arming motors");701#endif702703// Remember Orientation704// --------------------705copter.init_simple_bearing();706707auto &ahrs = AP::ahrs();708709copter.initial_armed_bearing = ahrs.yaw_sensor;710711if (!ahrs.home_is_set()) {712// Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home)713ahrs.resetHeightDatum();714LOGGER_WRITE_EVENT(LogEvent::EKF_ALT_RESET);715716// we have reset height, so arming height is zero717copter.arming_altitude_m = 0;718} else if (!ahrs.home_is_locked()) {719// Reset home position if it has already been set before (but not locked)720if (!copter.set_home_to_current_location(false)) {721// ignore failure722}723724// remember the height when we armed725copter.arming_altitude_m = copter.inertial_nav.get_position_z_up_cm() * 0.01;726}727copter.update_super_simple_bearing(false);728729// Reset SmartRTL return location. If activated, SmartRTL will ultimately try to land at this point730#if MODE_SMARTRTL_ENABLED731copter.g2.smart_rtl.set_home(copter.position_ok());732#endif733734hal.util->set_soft_armed(true);735736#if HAL_SPRAYER_ENABLED737// turn off sprayer's test if on738copter.sprayer.test_pump(false);739#endif740741// output lowest possible value to motors742copter.motors->output_min();743744// finally actually arm the motors745copter.motors->armed(true);746747#if HAL_LOGGING_ENABLED748// log flight mode in case it was changed while vehicle was disarmed749AP::logger().Write_Mode((uint8_t)copter.flightmode->mode_number(), copter.control_mode_reason);750#endif751752// re-enable failsafe753copter.failsafe_enable();754755// perf monitor ignores delay due to arming756AP::scheduler().perf_info.ignore_this_loop();757758// flag exiting this function759in_arm_motors = false;760761// Log time stamp of arming event762copter.arm_time_ms = millis();763764// Start the arming delay765copter.ap.in_arming_delay = true;766767// assumed armed without a arming, switch. Overridden in switches.cpp768copter.ap.armed_with_airmode_switch = false;769770// return success771return true;772}773774// arming.disarm - disarm motors775bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_checks)776{777// return immediately if we are already disarmed778if (!copter.motors->armed()) {779return true;780}781782// do not allow disarm via mavlink if we think we are flying:783if (do_disarm_checks &&784AP_Arming::method_is_GCS(method) &&785!copter.ap.land_complete) {786return false;787}788789if (!AP_Arming::disarm(method, do_disarm_checks)) {790return false;791}792793#if CONFIG_HAL_BOARD == HAL_BOARD_SITL794send_arm_disarm_statustext("Disarming motors");795#endif796797auto &ahrs = AP::ahrs();798799// save compass offsets learned by the EKF if enabled800Compass &compass = AP::compass();801if (ahrs.use_compass() && compass.get_learn_type() == Compass::LEARN_EKF) {802for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {803Vector3f magOffsets;804if (ahrs.getMagOffsets(i, magOffsets)) {805compass.set_and_save_offsets(i, magOffsets);806}807}808}809810// we are not in the air811copter.set_land_complete(true);812copter.set_land_complete_maybe(true);813814// send disarm command to motors815copter.motors->armed(false);816817#if MODE_AUTO_ENABLED818// reset the mission819copter.mode_auto.mission.reset();820#endif821822#if HAL_LOGGING_ENABLED823AP::logger().set_vehicle_armed(false);824#endif825826hal.util->set_soft_armed(false);827828copter.ap.in_arming_delay = false;829830#if AUTOTUNE_ENABLED831// Possibly save auto tuned parameters832copter.mode_autotune.autotune.disarmed(copter.flightmode == &copter.mode_autotune);833#endif834835return true;836}837838#pragma GCC diagnostic pop839840841