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/libraries/AP_Arming/AP_Arming.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "AP_Arming_config.h"1617#if AP_ARMING_ENABLED1819#include "AP_Arming.h"20#include <AP_HAL/AP_HAL.h>21#include <AP_BoardConfig/AP_BoardConfig.h>22#include <AP_BattMonitor/AP_BattMonitor.h>23#include <AP_Compass/AP_Compass.h>24#include <AP_Notify/AP_Notify.h>25#include <GCS_MAVLink/GCS.h>26#include <GCS_MAVLink/GCS_MAVLink.h>27#include <AP_Mission/AP_Mission.h>28#include <AP_Proximity/AP_Proximity.h>29#include <AP_Rally/AP_Rally.h>30#include <SRV_Channel/SRV_Channel.h>31#include <AC_Fence/AC_Fence.h>32#include <AP_InertialSensor/AP_InertialSensor.h>33#include <AP_InternalError/AP_InternalError.h>34#include <AP_GPS/AP_GPS.h>35#include <AP_Declination/AP_Declination.h>36#include <AP_Airspeed/AP_Airspeed.h>37#include <AP_AHRS/AP_AHRS.h>38#include <AP_Baro/AP_Baro.h>39#include <AP_RangeFinder/AP_RangeFinder.h>40#include <AP_Generator/AP_Generator.h>41#include <AP_Terrain/AP_Terrain.h>42#include <AP_ADSB/AP_ADSB.h>43#include <AP_Scripting/AP_Scripting.h>44#include <AP_Camera/AP_RunCam.h>45#include <AP_GyroFFT/AP_GyroFFT.h>46#include <AP_VisualOdom/AP_VisualOdom.h>47#include <AP_Parachute/AP_Parachute.h>48#include <AP_OSD/AP_OSD.h>49#include <AP_Relay/AP_Relay.h>50#include <RC_Channel/RC_Channel.h>51#include <AP_Button/AP_Button.h>52#include <AP_FETtecOneWire/AP_FETtecOneWire.h>53#include <AP_RPM/AP_RPM.h>54#include <AP_Mount/AP_Mount.h>55#include <AP_OpenDroneID/AP_OpenDroneID.h>56#include <AP_SerialManager/AP_SerialManager.h>57#include <AP_Vehicle/AP_Vehicle_Type.h>58#include <AP_Scheduler/AP_Scheduler.h>59#include <AP_KDECAN/AP_KDECAN.h>60#include <AP_Vehicle/AP_Vehicle.h>6162#if HAL_MAX_CAN_PROTOCOL_DRIVERS63#include <AP_CANManager/AP_CANManager.h>64#include <AP_Common/AP_Common.h>65#include <AP_Vehicle/AP_Vehicle_Type.h>6667#include <AP_PiccoloCAN/AP_PiccoloCAN.h>68#include <AP_DroneCAN/AP_DroneCAN.h>69#endif7071#include <AP_Logger/AP_Logger.h>7273#define AP_ARMING_COMPASS_MAGFIELD_EXPECTED 53074#define AP_ARMING_COMPASS_MAGFIELD_MIN 185 // 0.35 * 530 milligauss75#define AP_ARMING_COMPASS_MAGFIELD_MAX 875 // 1.65 * 530 milligauss76#define AP_ARMING_BOARD_VOLTAGE_MAX 5.8f77#define AP_ARMING_ACCEL_ERROR_THRESHOLD 0.75f78#define AP_ARMING_MAGFIELD_ERROR_THRESHOLD 10079#define AP_ARMING_AHRS_GPS_ERROR_MAX 10 // accept up to 10m difference between AHRS and GPS8081#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)82#define ARMING_RUDDER_DEFAULT (uint8_t)RudderArming::ARMONLY83#else84#define ARMING_RUDDER_DEFAULT (uint8_t)RudderArming::ARMDISARM85#endif8687#ifndef PREARM_DISPLAY_PERIOD88# define PREARM_DISPLAY_PERIOD 3089#endif9091extern const AP_HAL::HAL& hal;9293const AP_Param::GroupInfo AP_Arming::var_info[] = {9495// @Param{Plane, Rover}: REQUIRE96// @DisplayName: Require Arming Motors97// @Description: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, sends the minimum throttle PWM value to the throttle channel when disarmed. If 2, send 0 PWM (no signal) to throttle channel when disarmed. On planes with ICE enabled and the throttle while disarmed option set in ICE_OPTIONS, the motor will always get THR_MIN when disarmed. Arming will occur using either rudder stick arming (if enabled) or GCS command when all mandatory and ARMING_CHECK items are satisfied. Note, when setting this parameter to 0, a reboot is required to immediately arm the plane.98// @Values: 0:Disabled,1:minimum PWM when disarmed,2:0 PWM when disarmed99// @User: Advanced100AP_GROUPINFO_FLAGS_FRAME("REQUIRE", 0, AP_Arming, require, float(Required::YES_MIN_PWM),101AP_PARAM_FLAG_NO_SHIFT,102AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_ROVER),103104// 2 was the CHECK paramter stored in a AP_Int16105106// @Param: ACCTHRESH107// @DisplayName: Accelerometer error threshold108// @Description: Accelerometer error threshold used to determine inconsistent accelerometers. Compares this error range to other accelerometers to detect a hardware or calibration error. Lower value means tighter check and harder to pass arming check. Not all accelerometers are created equal.109// @Units: m/s/s110// @Range: 0.25 3.0111// @User: Advanced112AP_GROUPINFO("ACCTHRESH", 3, AP_Arming, accel_error_threshold, AP_ARMING_ACCEL_ERROR_THRESHOLD),113114// index 4 was VOLT_MIN, moved to AP_BattMonitor115// index 5 was VOLT2_MIN, moved to AP_BattMonitor116117// @Param{Plane,Rover,Copter,Blimp}: RUDDER118// @DisplayName: Arming with Rudder enable/disable119// @Description: Allow arm/disarm by rudder input. When enabled arming can be done with right rudder, disarming with left rudder. Rudder arming only works with throttle at zero +- deadzone (RCx_DZ). Depending on vehicle type, arming in certain modes is prevented. See the wiki for each vehicle. Caution is recommended when arming if it is allowed in an auto-throttle mode!120// @Values: 0:Disabled,1:ArmingOnly,2:ArmOrDisarm121// @User: Advanced122AP_GROUPINFO_FRAME("RUDDER", 6, AP_Arming, _rudder_arming, ARMING_RUDDER_DEFAULT, AP_PARAM_FRAME_PLANE |123AP_PARAM_FRAME_ROVER |124AP_PARAM_FRAME_COPTER |125AP_PARAM_FRAME_TRICOPTER |126AP_PARAM_FRAME_HELI |127AP_PARAM_FRAME_BLIMP),128129// @Param: MIS_ITEMS130// @DisplayName: Required mission items131// @Description: Bitmask of mission items that are required to be planned in order to arm the aircraft132// @Bitmask: 0:Land,1:VTOL Land,2:DO_LAND_START,3:Takeoff,4:VTOL Takeoff,5:Rallypoint,6:RTL133// @User: Advanced134AP_GROUPINFO("MIS_ITEMS", 7, AP_Arming, _required_mission_items, 0),135136// @Param: CHECK137// @DisplayName: Arm Checks to Perform (bitmask)138// @Description: Checks prior to arming motor. This is a bitmask of checks that will be performed before allowing arming. For most users it is recommended to leave this at the default of 1 (all checks enabled). You can select whatever checks you prefer by adding together the values of each check type to set this parameter. For example, to only allow arming when you have GPS lock and no RC failsafe you would set ARMING_CHECK to 72.139// @Bitmask: 0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,10:Logging Available,11:Hardware safety switch,12:GPS Configuration,13:System,14:Mission,15:Rangefinder,16:Camera,17:AuxAuth,18:VisualOdometry,19:FFT140// @Bitmask{Plane}: 0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch,12:GPS Configuration,13:System,14:Mission,15:Rangefinder,16:Camera,17:AuxAuth,19:FFT141// @User: Standard142AP_GROUPINFO("CHECK", 8, AP_Arming, checks_to_perform, ARMING_CHECK_ALL),143144// @Param: OPTIONS145// @DisplayName: Arming options146// @Description: Options that can be applied to change arming behaviour147// @Bitmask: 0:Disable prearm display,1:Do not send status text on state change148// @User: Advanced149AP_GROUPINFO("OPTIONS", 9, AP_Arming, _arming_options, 0),150151// @Param: MAGTHRESH152// @DisplayName: Compass magnetic field strength error threshold vs earth magnetic model153// @Description: Compass magnetic field strength error threshold vs earth magnetic model. X and y axis are compared using this threhold, Z axis uses 2x this threshold. 0 to disable check154// @Units: mGauss155// @Range: 0 500156// @User: Advanced157AP_GROUPINFO("MAGTHRESH", 10, AP_Arming, magfield_error_threshold, AP_ARMING_MAGFIELD_ERROR_THRESHOLD),158159#if AP_ARMING_CRASHDUMP_ACK_ENABLED160// @Param: CRSDP_IGN161// @DisplayName: Disable CrashDump Arming check162// @Description: Must have value "1" if crashdump data is present on the system, or a prearm failure will be raised. Do not set this parameter unless the risks of doing so are fully understood. The presence of a crash dump means that the firmware currently installed has suffered a critical software failure which resulted in the autopilot immediately rebooting. The crashdump file gives diagnostic information which can help in finding the issue, please contact the ArduPIlot support team. If this crashdump data is present, the vehicle is likely unsafe to fly. Check the ArduPilot documentation for more details.163// @Values: 0:Crash Dump arming check active, 1:Crash Dump arming check deactivated164// @User: Advanced165AP_GROUPINFO("CRSDP_IGN", 11, AP_Arming, crashdump_ack.acked, 0),166#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED167168AP_GROUPEND169};170171#if HAL_WITH_IO_MCU172#include <AP_IOMCU/AP_IOMCU.h>173extern AP_IOMCU iomcu;174#endif175176#pragma GCC diagnostic push177#if defined(__clang_major__) && __clang_major__ >= 14178#pragma GCC diagnostic ignored "-Wbitwise-instead-of-logical"179#endif180181AP_Arming::AP_Arming()182{183if (_singleton) {184AP_HAL::panic("Too many AP_Arming instances");185}186_singleton = this;187188AP_Param::setup_object_defaults(this, var_info);189}190191// performs pre-arm checks. expects to be called at 1hz.192void AP_Arming::update(void)193{194#if AP_ARMING_CRASHDUMP_ACK_ENABLED195// if we boot with no crashdump data present, reset the "ignore"196// parameter so the user will need to acknowledge future crashes197// too:198crashdump_ack.check_reset();199#endif200201const uint32_t now_ms = AP_HAL::millis();202// perform pre-arm checks & display failures every 30 seconds203bool display_fail = false;204if ((report_immediately && (now_ms - last_prearm_display_ms > 4000)) ||205(now_ms - last_prearm_display_ms > PREARM_DISPLAY_PERIOD*1000)) {206report_immediately = false;207display_fail = true;208last_prearm_display_ms = now_ms;209}210// OTOH, the user may never want to display them:211if (option_enabled(Option::DISABLE_PREARM_DISPLAY)) {212display_fail = false;213}214215pre_arm_checks(display_fail);216}217218#if AP_ARMING_CRASHDUMP_ACK_ENABLED219void AP_Arming::CrashDump::check_reset()220{221// if there is no crash dump data then clear the crash dump ack.222// This means on subsequent crash-dumps appearing the user must223// re-acknowledge.224if (hal.util->last_crash_dump_size() == 0) {225// no crash dump data226acked.set_and_save_ifchanged(0);227}228}229#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED230231uint16_t AP_Arming::compass_magfield_expected() const232{233return AP_ARMING_COMPASS_MAGFIELD_EXPECTED;234}235236bool AP_Arming::is_armed() const237{238return armed || arming_required() == Required::NO;239}240241/*242true if armed and safety is off243*/244bool AP_Arming::is_armed_and_safety_off() const245{246return is_armed() && hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED;247}248249uint32_t AP_Arming::get_enabled_checks() const250{251return checks_to_perform;252}253254bool AP_Arming::check_enabled(const enum AP_Arming::ArmingChecks check) const255{256if (checks_to_perform & ARMING_CHECK_ALL) {257return true;258}259return (checks_to_perform & check);260}261262void AP_Arming::check_failed(const enum AP_Arming::ArmingChecks check, bool report, const char *fmt, ...) const263{264if (!report) {265return;266}267char taggedfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];268269// metafmt is wrapped around the passed-in format string to270// prepend "PreArm" or "Arm", depending on what sorts of checks271// we're currently doing.272const char *metafmt = "PreArm: %s"; // it's formats all the way down273if (running_arming_checks) {274metafmt = "Arm: %s";275}276hal.util->snprintf(taggedfmt, sizeof(taggedfmt), metafmt, fmt);277278#if HAL_GCS_ENABLED279MAV_SEVERITY severity = MAV_SEVERITY_CRITICAL;280if (!check_enabled(check)) {281// technically should be NOTICE, but will annoy users at that level:282severity = MAV_SEVERITY_DEBUG;283}284va_list arg_list;285va_start(arg_list, fmt);286gcs().send_textv(severity, taggedfmt, arg_list);287va_end(arg_list);288#endif // HAL_GCS_ENABLED289}290291void AP_Arming::check_failed(bool report, const char *fmt, ...) const292{293#if HAL_GCS_ENABLED294if (!report) {295return;296}297char taggedfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];298299// metafmt is wrapped around the passed-in format string to300// prepend "PreArm" or "Arm", depending on what sorts of checks301// we're currently doing.302const char *metafmt = "PreArm: %s"; // it's formats all the way down303if (running_arming_checks) {304metafmt = "Arm: %s";305}306hal.util->snprintf(taggedfmt, sizeof(taggedfmt), metafmt, fmt);307308va_list arg_list;309va_start(arg_list, fmt);310gcs().send_textv(MAV_SEVERITY_CRITICAL, taggedfmt, arg_list);311va_end(arg_list);312#endif // HAL_GCS_ENABLED313}314315bool AP_Arming::barometer_checks(bool report)316{317#ifdef HAL_BARO_ALLOW_INIT_NO_BARO318return true;319#endif320#if CONFIG_HAL_BOARD == HAL_BOARD_SITL321if (AP::sitl()->baro_count == 0) {322// simulate no baro boards323return true;324}325#endif326if (check_enabled(ARMING_CHECK_BARO)) {327char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};328if (!AP::baro().arming_checks(sizeof(buffer), buffer)) {329check_failed(ARMING_CHECK_BARO, report, "Baro: %s", buffer);330return false;331}332}333334return true;335}336337#if AP_AIRSPEED_ENABLED338bool AP_Arming::airspeed_checks(bool report)339{340if (check_enabled(ARMING_CHECK_AIRSPEED)) {341const AP_Airspeed *airspeed = AP_Airspeed::get_singleton();342if (airspeed == nullptr) {343// not an airspeed capable vehicle344return true;345}346for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {347if (airspeed->enabled(i) && airspeed->use(i) && !airspeed->healthy(i)) {348check_failed(ARMING_CHECK_AIRSPEED, report, "Airspeed %d not healthy", i + 1);349return false;350}351}352}353354return true;355}356#endif // AP_AIRSPEED_ENABLED357358#if HAL_LOGGING_ENABLED359bool AP_Arming::logging_checks(bool report)360{361if (check_enabled(ARMING_CHECK_LOGGING)) {362if (!AP::logger().logging_present()) {363// Logging is disabled, so nothing to check.364return true;365}366if (AP::logger().logging_failed()) {367check_failed(ARMING_CHECK_LOGGING, report, "Logging failed");368return false;369}370if (!AP::logger().CardInserted()) {371check_failed(ARMING_CHECK_LOGGING, report, "No SD card");372return false;373}374if (AP::logger().in_log_download()) {375check_failed(ARMING_CHECK_LOGGING, report, "Downloading logs");376return false;377}378}379return true;380}381#endif // HAL_LOGGING_ENABLED382383#if AP_INERTIALSENSOR_ENABLED384bool AP_Arming::ins_accels_consistent(const AP_InertialSensor &ins)385{386const uint32_t now = AP_HAL::millis();387if (!ins.accels_consistent(accel_error_threshold)) {388// accels are inconsistent:389last_accel_pass_ms = 0;390return false;391}392393if (last_accel_pass_ms == 0) {394// we didn't return false above, so sensors are395// consistent right now:396last_accel_pass_ms = now;397}398399// if accels can in theory be inconsistent,400// must pass for at least 10 seconds before we're considered consistent:401if (ins.get_accel_count() > 1 && now - last_accel_pass_ms < 10000) {402return false;403}404405return true;406}407408bool AP_Arming::ins_gyros_consistent(const AP_InertialSensor &ins)409{410const uint32_t now = AP_HAL::millis();411// allow for up to 5 degrees/s difference412if (!ins.gyros_consistent(5)) {413// gyros are inconsistent:414last_gyro_pass_ms = 0;415return false;416}417418// we didn't return false above, so sensors are419// consistent right now:420if (last_gyro_pass_ms == 0) {421last_gyro_pass_ms = now;422}423424// if gyros can in theory be inconsistent,425// must pass for at least 10 seconds before we're considered consistent:426if (ins.get_gyro_count() > 1 && now - last_gyro_pass_ms < 10000) {427return false;428}429430return true;431}432433bool AP_Arming::ins_checks(bool report)434{435if (check_enabled(ARMING_CHECK_INS)) {436const AP_InertialSensor &ins = AP::ins();437if (!ins.get_gyro_health_all()) {438check_failed(ARMING_CHECK_INS, report, "Gyros not healthy");439return false;440}441if (!ins.gyro_calibrated_ok_all()) {442check_failed(ARMING_CHECK_INS, report, "Gyros not calibrated");443return false;444}445if (!ins.get_accel_health_all()) {446check_failed(ARMING_CHECK_INS, report, "Accels not healthy");447return false;448}449if (!ins.accel_calibrated_ok_all()) {450check_failed(ARMING_CHECK_INS, report, "3D Accel calibration needed");451return false;452}453454//check if accelerometers have calibrated and require reboot455if (ins.accel_cal_requires_reboot()) {456check_failed(ARMING_CHECK_INS, report, "Accels calibrated requires reboot");457return false;458}459460// check all accelerometers point in roughly same direction461if (!ins_accels_consistent(ins)) {462check_failed(ARMING_CHECK_INS, report, "Accels inconsistent");463return false;464}465466// check all gyros are giving consistent readings467if (!ins_gyros_consistent(ins)) {468check_failed(ARMING_CHECK_INS, report, "Gyros inconsistent");469return false;470}471472// no arming while doing temp cal473if (ins.temperature_cal_running()) {474check_failed(ARMING_CHECK_INS, report, "temperature cal running");475return false;476}477478#if AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED479// If Batch sampling enabled it must be initialized480if (ins.batchsampler.enabled() && !ins.batchsampler.is_initialised()) {481check_failed(ARMING_CHECK_INS, report, "Batch sampling requires reboot");482return false;483}484#endif485486}487488#if HAL_GYROFFT_ENABLED489// gyros are healthy so check the FFT490if (check_enabled(ARMING_CHECK_FFT)) {491// Check that the noise analyser works492AP_GyroFFT *fft = AP::fft();493494char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];495if (fft != nullptr && !fft->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {496check_failed(ARMING_CHECK_INS, report, "%s", fail_msg);497return false;498}499}500#endif501502return true;503}504#endif // AP_INERTIALSENSOR_ENABLED505506bool AP_Arming::compass_checks(bool report)507{508Compass &_compass = AP::compass();509510#if COMPASS_CAL_ENABLED511// check if compass is calibrating512if (_compass.is_calibrating()) {513check_failed(report, "Compass calibration running");514return false;515}516517// check if compass has calibrated and requires reboot518if (_compass.compass_cal_requires_reboot()) {519check_failed(report, "Compass calibrated requires reboot");520return false;521}522#endif523524if (check_enabled(ARMING_CHECK_COMPASS)) {525526// avoid Compass::use_for_yaw(void) as it implicitly calls healthy() which can527// incorrectly skip the remaining checks, pass the primary instance directly528if (!_compass.use_for_yaw(0)) {529// compass use is disabled530return true;531}532533if (!_compass.healthy()) {534check_failed(ARMING_CHECK_COMPASS, report, "Compass not healthy");535return false;536}537// check compass learning is on or offsets have been set538#if !APM_BUILD_COPTER_OR_HELI && !APM_BUILD_TYPE(APM_BUILD_Blimp)539// check compass offsets have been set if learning is off540// copter and blimp always require configured compasses541if (!_compass.learn_offsets_enabled())542#endif543{544char failure_msg[100] = {};545if (!_compass.configured(failure_msg, ARRAY_SIZE(failure_msg))) {546check_failed(ARMING_CHECK_COMPASS, report, "%s", failure_msg);547return false;548}549}550551// check for unreasonable compass offsets552const Vector3f offsets = _compass.get_offsets();553if (offsets.length() > _compass.get_offsets_max()) {554check_failed(ARMING_CHECK_COMPASS, report, "Compass offsets too high");555return false;556}557558// check for unreasonable mag field length559const float mag_field = _compass.get_field().length();560if (mag_field > AP_ARMING_COMPASS_MAGFIELD_MAX || mag_field < AP_ARMING_COMPASS_MAGFIELD_MIN) {561check_failed(ARMING_CHECK_COMPASS, report, "Check mag field: %4.0f, max %d, min %d", (double)mag_field, AP_ARMING_COMPASS_MAGFIELD_MAX, AP_ARMING_COMPASS_MAGFIELD_MIN);562return false;563}564565// check all compasses point in roughly same direction566if (!_compass.consistent()) {567check_failed(ARMING_CHECK_COMPASS, report, "Compasses inconsistent");568return false;569}570571#if AP_AHRS_ENABLED572// if ahrs is using compass and we have location, check mag field versus expected earth magnetic model573Location ahrs_loc;574AP_AHRS &ahrs = AP::ahrs();575if ((magfield_error_threshold > 0) && ahrs.use_compass() && ahrs.get_location(ahrs_loc)) {576const Vector3f veh_mag_field_ef = ahrs.get_rotation_body_to_ned() * _compass.get_field();577const Vector3f earth_field_mgauss = AP_Declination::get_earth_field_ga(ahrs_loc) * 1000.0;578const Vector3f diff_mgauss = veh_mag_field_ef - earth_field_mgauss;579if (MAX(fabsf(diff_mgauss.x), fabsf(diff_mgauss.y)) > magfield_error_threshold) {580check_failed(ARMING_CHECK_COMPASS, report, "Check mag field (xy diff:%.0f>%d)",581(double)MAX(fabsf(diff_mgauss.x), (double)fabsf(diff_mgauss.y)), (int)magfield_error_threshold);582return false;583}584if (fabsf(diff_mgauss.z) > magfield_error_threshold*2.0) {585check_failed(ARMING_CHECK_COMPASS, report, "Check mag field (z diff:%.0f>%d)",586(double)fabsf(diff_mgauss.z), (int)magfield_error_threshold*2);587return false;588}589}590#endif // AP_AHRS_ENABLED591}592593return true;594}595596#if AP_GPS_ENABLED597bool AP_Arming::gps_checks(bool report)598{599const AP_GPS &gps = AP::gps();600if (check_enabled(ARMING_CHECK_GPS)) {601602// Any failure messages from GPS backends603char failure_msg[100] = {};604if (!AP::gps().pre_arm_checks(failure_msg, ARRAY_SIZE(failure_msg))) {605if (failure_msg[0] != '\0') {606check_failed(ARMING_CHECK_GPS, report, "%s", failure_msg);607}608return false;609}610611for (uint8_t i = 0; i < gps.num_sensors(); i++) {612#if AP_GPS_BLENDED_ENABLED613if ((i != GPS_BLENDED_INSTANCE) &&614#else615if (616#endif617(gps.get_type(i) == AP_GPS::GPS_Type::GPS_TYPE_NONE)) {618if (gps.primary_sensor() == i) {619check_failed(ARMING_CHECK_GPS, report, "GPS %i: primary but TYPE 0", i+1);620return false;621}622continue;623}624625//GPS OK?626if (gps.status(i) < AP_GPS::GPS_OK_FIX_3D) {627check_failed(ARMING_CHECK_GPS, report, "GPS %i: Bad fix", i+1);628return false;629}630631//GPS update rate acceptable632if (!gps.is_healthy(i)) {633check_failed(ARMING_CHECK_GPS, report, "GPS %i: not healthy", i+1);634return false;635}636}637638if (!AP::ahrs().home_is_set()) {639check_failed(ARMING_CHECK_GPS, report, "AHRS: waiting for home");640return false;641}642643// check GPSs are within 50m of each other and that blending is healthy644float distance_m;645if (!gps.all_consistent(distance_m)) {646check_failed(ARMING_CHECK_GPS, report, "GPS positions differ by %4.1fm",647(double)distance_m);648return false;649}650651// check AHRS and GPS are within 10m of each other652if (gps.num_sensors() > 0) {653const Location gps_loc = gps.location();654Location ahrs_loc;655if (AP::ahrs().get_location(ahrs_loc)) {656const float distance = gps_loc.get_distance(ahrs_loc);657if (distance > AP_ARMING_AHRS_GPS_ERROR_MAX) {658check_failed(ARMING_CHECK_GPS, report, "GPS and AHRS differ by %4.1fm", (double)distance);659return false;660}661}662}663}664665if (check_enabled(ARMING_CHECK_GPS_CONFIG)) {666uint8_t first_unconfigured;667if (gps.first_unconfigured_gps(first_unconfigured)) {668check_failed(ARMING_CHECK_GPS_CONFIG,669report,670"GPS %d still configuring this GPS",671first_unconfigured + 1);672if (report) {673gps.broadcast_first_configuration_failure_reason();674}675return false;676}677}678679return true;680}681#endif // AP_GPS_ENABLED682683#if AP_BATTERY_ENABLED684bool AP_Arming::battery_checks(bool report)685{686if (check_enabled(ARMING_CHECK_BATTERY)) {687688char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};689if (!AP::battery().arming_checks(sizeof(buffer), buffer)) {690check_failed(ARMING_CHECK_BATTERY, report, "%s", buffer);691return false;692}693}694return true;695}696#endif // AP_BATTERY_ENABLED697698bool AP_Arming::hardware_safety_check(bool report)699{700if (check_enabled(ARMING_CHECK_SWITCH)) {701702// check if safety switch has been pushed703if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {704check_failed(ARMING_CHECK_SWITCH, report, "Hardware safety switch");705return false;706}707}708709return true;710}711712#if AP_RC_CHANNEL_ENABLED713bool AP_Arming::rc_arm_checks(AP_Arming::Method method)714{715// don't check the trims if we are in a failsafe716if (!rc().has_valid_input()) {717return true;718}719720// only check if we've received some form of input within the last second721// this is a protection against a vehicle having never enabled an input722uint32_t last_input_ms = rc().last_input_ms();723if ((last_input_ms == 0) || ((AP_HAL::millis() - last_input_ms) > 1000)) {724return true;725}726727bool check_passed = true;728// ensure all rc channels have different functions729if (rc().duplicate_options_exist()) {730check_failed(ARMING_CHECK_PARAMETERS, true, "Duplicate Aux Switch Options");731check_passed = false;732}733if (rc().flight_mode_channel_conflicts_with_rc_option()) {734check_failed(ARMING_CHECK_PARAMETERS, true, "Mode channel and RC%d_OPTION conflict", rc().flight_mode_channel_number());735check_passed = false;736}737{738if (!rc().option_is_enabled(RC_Channels::Option::ARMING_SKIP_CHECK_RPY)) {739const struct {740const char *name;741const RC_Channel *channel;742} channels_to_check[] {743{ "Roll", &rc().get_roll_channel(), },744{ "Pitch", &rc().get_pitch_channel(), },745{ "Yaw", &rc().get_yaw_channel(), },746};747for (const auto &channel_to_check : channels_to_check) {748const auto *c = channel_to_check.channel;749if (c->get_control_in() != 0) {750if ((method != Method::RUDDER) || (c != rc().get_arming_channel())) { // ignore the yaw input channel if rudder arming751check_failed(ARMING_CHECK_RC, true, "%s (RC%d) is not neutral", channel_to_check.name, c->ch());752check_passed = false;753}754}755}756}757758// if throttle check is enabled, require zero input759if (rc().arming_check_throttle()) {760const RC_Channel *c = &rc().get_throttle_channel();761if (c->get_control_in() != 0) {762check_failed(ARMING_CHECK_RC, true, "%s (RC%d) is not neutral", "Throttle", c->ch());763check_passed = false;764}765c = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FWD_THR);766if (c != nullptr) {767uint8_t fwd_thr = c->percent_input();768// require channel input within 2% of minimum769if (fwd_thr > 2) {770check_failed(ARMING_CHECK_RC, true, "VTOL Fwd Throttle is not zero");771check_passed = false;772}773}774}775}776return check_passed;777}778779bool AP_Arming::rc_calibration_checks(bool report)780{781bool check_passed = true;782const uint8_t num_channels = RC_Channels::get_valid_channel_count();783for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {784const RC_Channel *c = rc().channel(i);785if (c == nullptr) {786continue;787}788if (i >= num_channels && !(c->has_override())) {789continue;790}791const uint16_t trim = c->get_radio_trim();792if (c->get_radio_min() > trim) {793check_failed(ARMING_CHECK_RC, report, "RC%d_MIN is greater than RC%d_TRIM", i + 1, i + 1);794check_passed = false;795}796if (c->get_radio_max() < trim) {797check_failed(ARMING_CHECK_RC, report, "RC%d_MAX is less than RC%d_TRIM", i + 1, i + 1);798check_passed = false;799}800}801802return check_passed;803}804805bool AP_Arming::rc_in_calibration_check(bool report)806{807if (rc().calibrating()) {808check_failed(ARMING_CHECK_RC, report, "RC calibrating");809return false;810}811return true;812}813814bool AP_Arming::manual_transmitter_checks(bool report)815{816if (check_enabled(ARMING_CHECK_RC)) {817818if (AP_Notify::flags.failsafe_radio) {819check_failed(ARMING_CHECK_RC, report, "Radio failsafe on");820return false;821}822823if (!rc_calibration_checks(report)) {824return false;825}826}827828return rc_in_calibration_check(report);829}830#endif // AP_RC_CHANNEL_ENABLED831832#if AP_MISSION_ENABLED833bool AP_Arming::mission_checks(bool report)834{835AP_Mission *mission = AP::mission();836if (check_enabled(ARMING_CHECK_MISSION) && _required_mission_items) {837if (mission == nullptr) {838check_failed(ARMING_CHECK_MISSION, report, "No mission library present");839return false;840}841842const struct MisItemTable {843MIS_ITEM_CHECK check;844MAV_CMD mis_item_type;845const char *type;846} misChecks[] = {847{MIS_ITEM_CHECK_LAND, MAV_CMD_NAV_LAND, "land"},848{MIS_ITEM_CHECK_VTOL_LAND, MAV_CMD_NAV_VTOL_LAND, "vtol land"},849{MIS_ITEM_CHECK_DO_LAND_START, MAV_CMD_DO_LAND_START, "do land start"},850{MIS_ITEM_CHECK_TAKEOFF, MAV_CMD_NAV_TAKEOFF, "takeoff"},851{MIS_ITEM_CHECK_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_TAKEOFF, "vtol takeoff"},852{MIS_ITEM_CHECK_RETURN_TO_LAUNCH, MAV_CMD_NAV_RETURN_TO_LAUNCH, "RTL"},853};854for (uint8_t i = 0; i < ARRAY_SIZE(misChecks); i++) {855if (_required_mission_items & misChecks[i].check) {856if (!mission->contains_item(misChecks[i].mis_item_type)) {857check_failed(ARMING_CHECK_MISSION, report, "Missing mission item: %s", misChecks[i].type);858return false;859}860}861}862if (_required_mission_items & MIS_ITEM_CHECK_RALLY) {863#if HAL_RALLY_ENABLED864AP_Rally *rally = AP::rally();865if (rally == nullptr) {866check_failed(ARMING_CHECK_MISSION, report, "No rally library present");867return false;868}869Location ahrs_loc;870if (!AP::ahrs().get_location(ahrs_loc)) {871check_failed(ARMING_CHECK_MISSION, report, "Can't check rally without position");872return false;873}874RallyLocation rally_loc = {};875if (!rally->find_nearest_rally_point(ahrs_loc, rally_loc)) {876check_failed(ARMING_CHECK_MISSION, report, "No sufficiently close rally point located");877return false;878}879#else880check_failed(ARMING_CHECK_MISSION, report, "No rally library present");881return false;882#endif883}884}885886#if AP_SDCARD_STORAGE_ENABLED887if (check_enabled(ARMING_CHECK_MISSION) &&888mission != nullptr &&889(mission->failed_sdcard_storage() || StorageManager::storage_failed())) {890check_failed(ARMING_CHECK_MISSION, report, "Failed to open %s", AP_MISSION_SDCARD_FILENAME);891return false;892}893#endif894895#if AP_VEHICLE_ENABLED896// do not allow arming if there are no mission items and we are in897// (e.g.) AUTO mode898if (AP::vehicle()->current_mode_requires_mission() &&899(mission == nullptr || mission->num_commands() <= 1)) {900check_failed(ARMING_CHECK_MISSION, report, "Mode requires mission");901return false;902}903#endif904905return true;906}907#endif // AP_MISSION_ENABLED908909bool AP_Arming::rangefinder_checks(bool report)910{911#if AP_RANGEFINDER_ENABLED912if (check_enabled(ARMING_CHECK_RANGEFINDER)) {913RangeFinder *range = RangeFinder::get_singleton();914if (range == nullptr) {915return true;916}917918char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];919if (!range->prearm_healthy(buffer, ARRAY_SIZE(buffer))) {920check_failed(ARMING_CHECK_RANGEFINDER, report, "%s", buffer);921return false;922}923}924#endif925926return true;927}928929bool AP_Arming::servo_checks(bool report) const930{931#if NUM_SERVO_CHANNELS932bool check_passed = true;933for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {934const SRV_Channel *c = SRV_Channels::srv_channel(i);935if (c == nullptr || c->get_function() <= SRV_Channel::k_none) {936continue;937}938939const uint16_t trim = c->get_trim();940if (c->get_output_min() > trim) {941check_failed(report, "SERVO%d_MIN is greater than SERVO%d_TRIM", i + 1, i + 1);942check_passed = false;943}944if (c->get_output_max() < trim) {945check_failed(report, "SERVO%d_MAX is less than SERVO%d_TRIM", i + 1, i + 1);946check_passed = false;947}948949// check functions using PWM are enabled950if (SRV_Channels::get_disabled_channel_mask() & 1U<<i) {951const SRV_Channel::Aux_servo_function_t ch_function = c->get_function();952953// motors, e-stoppable functions, neopixels and ProfiLEDs may be digital outputs and thus can be disabled954// scripting can use its functions as labels for LED setup955const bool disabled_ok = SRV_Channel::is_motor(ch_function) ||956SRV_Channel::should_e_stop(ch_function) ||957(ch_function >= SRV_Channel::k_LED_neopixel1 && ch_function <= SRV_Channel::k_LED_neopixel4) ||958(ch_function >= SRV_Channel::k_ProfiLED_1 && ch_function <= SRV_Channel::k_ProfiLED_Clock) ||959(ch_function >= SRV_Channel::k_scripting1 && ch_function <= SRV_Channel::k_scripting16);960961// for all other functions raise a pre-arm failure962if (!disabled_ok) {963check_failed(report, "SERVO%u_FUNCTION=%u on disabled channel", i + 1, (unsigned)ch_function);964check_passed = false;965}966}967}968969#if HAL_WITH_IO_MCU970if (!iomcu.healthy() && AP_BoardConfig::io_enabled()) {971check_failed(report, "IOMCU is unhealthy");972check_passed = false;973}974#endif975976return check_passed;977#else978return false;979#endif980}981982bool AP_Arming::board_voltage_checks(bool report)983{984// check board voltage985if (check_enabled(ARMING_CHECK_VOLTAGE)) {986#if HAL_HAVE_BOARD_VOLTAGE987const float bus_voltage = hal.analogin->board_voltage();988const float vbus_min = AP_BoardConfig::get_minimum_board_voltage();989if(((bus_voltage < vbus_min) || (bus_voltage > AP_ARMING_BOARD_VOLTAGE_MAX))) {990check_failed(ARMING_CHECK_VOLTAGE, report, "Board (%1.1fv) out of range %1.1f-%1.1fv", (double)bus_voltage, (double)vbus_min, (double)AP_ARMING_BOARD_VOLTAGE_MAX);991return false;992}993#endif // HAL_HAVE_BOARD_VOLTAGE994995#if HAL_HAVE_SERVO_VOLTAGE996const float vservo_min = AP_BoardConfig::get_minimum_servo_voltage();997if (is_positive(vservo_min)) {998const float servo_voltage = hal.analogin->servorail_voltage();999if (servo_voltage < vservo_min) {1000check_failed(ARMING_CHECK_VOLTAGE, report, "Servo voltage to low (%1.2fv < %1.2fv)", (double)servo_voltage, (double)vservo_min);1001return false;1002}1003}1004#endif // HAL_HAVE_SERVO_VOLTAGE1005}10061007return true;1008}10091010#if HAL_HAVE_IMU_HEATER1011bool AP_Arming::heater_min_temperature_checks(bool report)1012{1013if (checks_to_perform & ARMING_CHECK_ALL) {1014AP_BoardConfig *board = AP::boardConfig();1015if (board) {1016float temperature;1017int8_t min_temperature;1018if (board->get_board_heater_temperature(temperature) &&1019board->get_board_heater_arming_temperature(min_temperature) &&1020(temperature < min_temperature)) {1021check_failed(ARMING_CHECK_SYSTEM, report, "heater temp low (%0.1f < %i)", temperature, min_temperature);1022return false;1023}1024}1025}1026return true;1027}1028#endif // HAL_HAVE_IMU_HEATER10291030/*1031check base system operations1032*/1033bool AP_Arming::system_checks(bool report)1034{1035char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};10361037if (check_enabled(ARMING_CHECK_SYSTEM)) {1038if (!hal.storage->healthy()) {1039check_failed(ARMING_CHECK_SYSTEM, report, "Param storage failed");1040return false;1041}10421043if (AP_Param::get_eeprom_full()) {1044check_failed(ARMING_CHECK_PARAMETERS, report, "parameter storage full");1045return false;1046}10471048// check main loop rate is at least 90% of expected value1049const float actual_loop_rate = AP::scheduler().get_filtered_loop_rate_hz();1050const uint16_t expected_loop_rate = AP::scheduler().get_loop_rate_hz();1051const float loop_rate_pct = actual_loop_rate / expected_loop_rate;1052if (loop_rate_pct < 0.90) {1053check_failed(ARMING_CHECK_SYSTEM, report, "Main loop slow (%uHz < %uHz)", (unsigned)actual_loop_rate, (unsigned)expected_loop_rate);1054return false;1055}10561057#if AP_TERRAIN_AVAILABLE1058const AP_Terrain *terrain = AP_Terrain::get_singleton();1059if ((terrain != nullptr) && terrain->init_failed()) {1060check_failed(ARMING_CHECK_SYSTEM, report, "Terrain out of memory");1061return false;1062}1063#endif1064#if AP_SCRIPTING_ENABLED1065const AP_Scripting *scripting = AP_Scripting::get_singleton();1066if ((scripting != nullptr) && !scripting->arming_checks(sizeof(buffer), buffer)) {1067check_failed(ARMING_CHECK_SYSTEM, report, "%s", buffer);1068return false;1069}1070#endif1071#if HAL_ADSB_ENABLED1072AP_ADSB *adsb = AP::ADSB();1073if ((adsb != nullptr) && adsb->enabled() && adsb->init_failed()) {1074check_failed(ARMING_CHECK_SYSTEM, report, "ADSB out of memory");1075return false;1076}1077#endif1078}1079if (AP::internalerror().errors() != 0) {1080AP::internalerror().errors_as_string((uint8_t*)buffer, ARRAY_SIZE(buffer));1081check_failed(report, "Internal errors 0x%x l:%u %s", (unsigned int)AP::internalerror().errors(), AP::internalerror().last_error_line(), buffer);1082return false;1083}10841085if (!hal.gpio->arming_checks(sizeof(buffer), buffer)) {1086check_failed(report, "%s", buffer);1087return false;1088}10891090if (check_enabled(ARMING_CHECK_PARAMETERS)) {1091#if !AP_GPS_BLENDED_ENABLED1092if (!blending_auto_switch_checks(report)) {1093return false;1094}1095#endif1096#if AP_RPM_ENABLED1097auto *rpm = AP::rpm();1098if (rpm && !rpm->arming_checks(sizeof(buffer), buffer)) {1099check_failed(ARMING_CHECK_PARAMETERS, report, "%s", buffer);1100return false;1101}1102#endif1103#if AP_RELAY_ENABLED1104auto *relay = AP::relay();1105if (relay && !relay->arming_checks(sizeof(buffer), buffer)) {1106check_failed(ARMING_CHECK_PARAMETERS, report, "%s", buffer);1107return false;1108}1109#endif1110#if HAL_PARACHUTE_ENABLED1111auto *chute = AP::parachute();1112if (chute && !chute->arming_checks(sizeof(buffer), buffer)) {1113check_failed(ARMING_CHECK_PARAMETERS, report, "%s", buffer);1114return false;1115}1116#endif1117#if HAL_BUTTON_ENABLED1118const auto &button = AP::button();1119if (!button.arming_checks(sizeof(buffer), buffer)) {1120check_failed(ARMING_CHECK_PARAMETERS, report, "%s", buffer);1121return false;1122}1123#endif1124}11251126return true;1127}11281129bool AP_Arming::terrain_database_required() const1130{1131#if AP_MISSION_ENABLED1132AP_Mission *mission = AP::mission();1133if (mission == nullptr) {1134// no mission support?1135return false;1136}1137if (mission->contains_terrain_alt_items()) {1138return true;1139}1140#endif1141return false;1142}11431144// check terrain database is fit-for-purpose1145bool AP_Arming::terrain_checks(bool report) const1146{1147if (!check_enabled(ARMING_CHECK_PARAMETERS)) {1148return true;1149}11501151if (!terrain_database_required()) {1152return true;1153}11541155#if AP_TERRAIN_AVAILABLE11561157const AP_Terrain *terrain = AP_Terrain::get_singleton();1158if (terrain == nullptr) {1159// this is also a system error, and it is already complaining1160// about it.1161return false;1162}11631164if (!terrain->enabled()) {1165check_failed(ARMING_CHECK_PARAMETERS, report, "terrain disabled");1166return false;1167}11681169char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];1170if (!terrain->pre_arm_checks(fail_msg, sizeof(fail_msg))) {1171check_failed(ARMING_CHECK_PARAMETERS, report, "%s", fail_msg);1172return false;1173}11741175return true;11761177#else1178check_failed(ARMING_CHECK_PARAMETERS, report, "terrain required but disabled");1179return false;1180#endif1181}118211831184#if HAL_PROXIMITY_ENABLED1185// check nothing is too close to vehicle1186bool AP_Arming::proximity_checks(bool report) const1187{1188const AP_Proximity *proximity = AP::proximity();1189// return true immediately if no sensor present1190if (proximity == nullptr) {1191return true;1192}1193char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];1194if (!proximity->prearm_healthy(buffer, ARRAY_SIZE(buffer))) {1195check_failed(report, "%s", buffer);1196return false;1197}1198return true;1199}1200#endif // HAL_PROXIMITY_ENABLED12011202#if HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED1203bool AP_Arming::can_checks(bool report)1204{1205if (check_enabled(ARMING_CHECK_SYSTEM)) {1206char fail_msg[100] = {};1207(void)fail_msg; // might be left unused1208uint8_t num_drivers = AP::can().get_num_drivers();12091210for (uint8_t i = 0; i < num_drivers; i++) {1211switch (AP::can().get_driver_type(i)) {1212case AP_CAN::Protocol::PiccoloCAN: {1213#if HAL_PICCOLO_CAN_ENABLE1214AP_PiccoloCAN *ap_pcan = AP_PiccoloCAN::get_pcan(i);12151216if (ap_pcan != nullptr && !ap_pcan->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {1217check_failed(ARMING_CHECK_SYSTEM, report, "PiccoloCAN: %s", fail_msg);1218return false;1219}12201221#else1222check_failed(ARMING_CHECK_SYSTEM, report, "PiccoloCAN not enabled");1223return false;1224#endif1225break;1226}1227case AP_CAN::Protocol::DroneCAN:1228{1229#if HAL_ENABLE_DRONECAN_DRIVERS1230AP_DroneCAN *ap_dronecan = AP_DroneCAN::get_dronecan(i);1231if (ap_dronecan != nullptr && !ap_dronecan->prearm_check(fail_msg, ARRAY_SIZE(fail_msg))) {1232check_failed(ARMING_CHECK_SYSTEM, report, "DroneCAN: %s", fail_msg);1233return false;1234}1235#endif1236break;1237}1238case AP_CAN::Protocol::USD1:1239case AP_CAN::Protocol::TOFSenseP:1240case AP_CAN::Protocol::NanoRadar:1241case AP_CAN::Protocol::Benewake:1242{1243for (uint8_t j = i; j; j--) {1244if (AP::can().get_driver_type(i) == AP::can().get_driver_type(j-1)) {1245check_failed(ARMING_CHECK_SYSTEM, report, "Same rfnd on different CAN ports");1246return false;1247}1248}1249break;1250}1251case AP_CAN::Protocol::EFI_NWPMU:1252case AP_CAN::Protocol::None:1253case AP_CAN::Protocol::Scripting:1254case AP_CAN::Protocol::Scripting2:1255case AP_CAN::Protocol::KDECAN:12561257break;1258}1259}1260}1261return true;1262}1263#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED126412651266#if AP_FENCE_ENABLED1267bool AP_Arming::fence_checks(bool display_failure)1268{1269const AC_Fence *fence = AP::fence();1270if (fence == nullptr) {1271return true;1272}12731274// check fence is ready1275char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];1276if (fence->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {1277return true;1278}12791280check_failed(display_failure, "%s", fail_msg);12811282#if AP_SDCARD_STORAGE_ENABLED1283if (fence->failed_sdcard_storage() || StorageManager::storage_failed()) {1284check_failed(display_failure, "Failed to open fence storage");1285return false;1286}1287#endif12881289return false;1290}1291#endif // AP_FENCE_ENABLED12921293#if AP_CAMERA_RUNCAM_ENABLED1294bool AP_Arming::camera_checks(bool display_failure)1295{1296if (check_enabled(ARMING_CHECK_CAMERA)) {1297AP_RunCam *runcam = AP::runcam();1298if (runcam == nullptr) {1299return true;1300}13011302// check camera is ready1303char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];1304if (!runcam->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {1305check_failed(ARMING_CHECK_CAMERA, display_failure, "%s", fail_msg);1306return false;1307}1308}1309return true;1310}1311#endif // AP_CAMERA_RUNCAM_ENABLED13121313#if OSD_ENABLED1314bool AP_Arming::osd_checks(bool display_failure) const1315{1316if (check_enabled(ARMING_CHECK_OSD)) {1317// if no OSD then pass1318const AP_OSD *osd = AP::osd();1319if (osd == nullptr) {1320return true;1321}1322// do osd checks for configuration1323char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];1324if (!osd->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {1325check_failed(ARMING_CHECK_OSD, display_failure, "%s", fail_msg);1326return false;1327}1328}1329return true;1330}1331#endif // OSD_ENABLED13321333#if HAL_MOUNT_ENABLED1334bool AP_Arming::mount_checks(bool display_failure) const1335{1336if (check_enabled(ARMING_CHECK_CAMERA)) {1337AP_Mount *mount = AP::mount();1338if (mount == nullptr) {1339return true;1340}1341char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] = {};1342if (!mount->pre_arm_checks(fail_msg, sizeof(fail_msg))) {1343check_failed(ARMING_CHECK_CAMERA, display_failure, "Mount: %s", fail_msg);1344return false;1345}1346}1347return true;1348}1349#endif // HAL_MOUNT_ENABLED13501351#if AP_FETTEC_ONEWIRE_ENABLED1352bool AP_Arming::fettec_checks(bool display_failure) const1353{1354const AP_FETtecOneWire *f = AP_FETtecOneWire::get_singleton();1355if (f == nullptr) {1356return true;1357}13581359// check ESCs are ready1360char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];1361if (!f->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {1362check_failed(ARMING_CHECK_ALL, display_failure, "FETtec: %s", fail_msg);1363return false;1364}1365return true;1366}1367#endif // AP_FETTEC_ONEWIRE_ENABLED13681369#if AP_ARMING_AUX_AUTH_ENABLED1370// request an auxiliary authorisation id. This id should be used in subsequent calls to set_aux_auth_passed/failed1371// returns true on success1372bool AP_Arming::get_aux_auth_id(uint8_t& auth_id)1373{1374WITH_SEMAPHORE(aux_auth_sem);13751376// check we have enough room to allocate another id1377if (aux_auth_count >= aux_auth_count_max) {1378aux_auth_error = true;1379return false;1380}13811382// allocate buffer for failure message1383if (aux_auth_fail_msg == nullptr) {1384aux_auth_fail_msg = (char *)calloc(aux_auth_str_len, sizeof(char));1385if (aux_auth_fail_msg == nullptr) {1386aux_auth_error = true;1387return false;1388}1389}1390auth_id = aux_auth_count;1391aux_auth_count++;1392return true;1393}13941395// set auxiliary authorisation passed1396void AP_Arming::set_aux_auth_passed(uint8_t auth_id)1397{1398WITH_SEMAPHORE(aux_auth_sem);13991400// sanity check auth_id1401if (auth_id >= aux_auth_count) {1402return;1403}14041405aux_auth_state[auth_id] = AuxAuthStates::AUTH_PASSED;1406}14071408// set auxiliary authorisation failed and provide failure message1409void AP_Arming::set_aux_auth_failed(uint8_t auth_id, const char* fail_msg)1410{1411WITH_SEMAPHORE(aux_auth_sem);14121413// sanity check auth_id1414if (auth_id >= aux_auth_count) {1415return;1416}14171418// update state1419aux_auth_state[auth_id] = AuxAuthStates::AUTH_FAILED;14201421// store failure message if this authoriser has the lowest auth_id1422for (uint8_t i = 0; i < auth_id; i++) {1423if (aux_auth_state[i] == AuxAuthStates::AUTH_FAILED) {1424return;1425}1426}1427if (aux_auth_fail_msg != nullptr) {1428if (fail_msg == nullptr) {1429strncpy(aux_auth_fail_msg, "Auxiliary authorisation refused", aux_auth_str_len);1430} else {1431strncpy(aux_auth_fail_msg, fail_msg, aux_auth_str_len);1432}1433aux_auth_fail_msg_source = auth_id;1434}1435}14361437bool AP_Arming::aux_auth_checks(bool display_failure)1438{1439// handle error cases1440if (aux_auth_error) {1441if (aux_auth_fail_msg == nullptr) {1442check_failed(ARMING_CHECK_AUX_AUTH, display_failure, "memory low for auxiliary authorisation");1443} else {1444check_failed(ARMING_CHECK_AUX_AUTH, display_failure, "Too many auxiliary authorisers");1445}1446return false;1447}14481449WITH_SEMAPHORE(aux_auth_sem);14501451// check results for each auxiliary authorisation id1452bool some_failures = false;1453bool failure_msg_sent = false;1454bool waiting_for_responses = false;1455for (uint8_t i = 0; i < aux_auth_count; i++) {1456switch (aux_auth_state[i]) {1457case AuxAuthStates::NO_RESPONSE:1458waiting_for_responses = true;1459break;1460case AuxAuthStates::AUTH_FAILED:1461some_failures = true;1462if (i == aux_auth_fail_msg_source) {1463check_failed(ARMING_CHECK_AUX_AUTH, display_failure, "%s", aux_auth_fail_msg);1464failure_msg_sent = true;1465}1466break;1467case AuxAuthStates::AUTH_PASSED:1468break;1469}1470}14711472// send failure or waiting message1473if (some_failures) {1474if (!failure_msg_sent) {1475check_failed(ARMING_CHECK_AUX_AUTH, display_failure, "Auxiliary authorisation refused");1476}1477return false;1478} else if (waiting_for_responses) {1479check_failed(ARMING_CHECK_AUX_AUTH, display_failure, "Waiting for auxiliary authorisation");1480return false;1481}14821483// if we got this far all auxiliary checks must have passed1484return true;1485}1486#endif // AP_ARMING_AUX_AUTH_ENABLED14871488#if HAL_GENERATOR_ENABLED1489bool AP_Arming::generator_checks(bool display_failure) const1490{1491const AP_Generator *generator = AP::generator();1492if (generator == nullptr) {1493return true;1494}1495char failure_msg[100] = {};1496if (!generator->pre_arm_check(failure_msg, sizeof(failure_msg))) {1497check_failed(display_failure, "Generator: %s", failure_msg);1498return false;1499}1500return true;1501}1502#endif // HAL_GENERATOR_ENABLED15031504#if AP_OPENDRONEID_ENABLED1505// OpenDroneID Checks1506bool AP_Arming::opendroneid_checks(bool display_failure)1507{1508auto &opendroneid = AP::opendroneid();15091510char failure_msg[100] {};1511if (!opendroneid.pre_arm_check(failure_msg, sizeof(failure_msg))) {1512check_failed(display_failure, "OpenDroneID: %s", failure_msg);1513return false;1514}1515return true;1516}1517#endif // AP_OPENDRONEID_ENABLED15181519//Check for multiple RC in serial protocols1520bool AP_Arming::serial_protocol_checks(bool display_failure)1521{1522if (AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_RCIN, 1)) {1523check_failed(display_failure, "Multiple SERIAL ports configured for RC input");1524return false;1525}1526return true;1527}15281529//Check for estop1530bool AP_Arming::estop_checks(bool display_failure)1531{1532if (!SRV_Channels::get_emergency_stop()) {1533// not emergency-stopped, so no prearm failure:1534return true;1535}1536#if AP_RC_CHANNEL_ENABLED1537// vehicle is emergency-stopped; if this *appears* to have been done via switch then we do not fail prearms:1538const RC_Channel *chan = rc().find_channel_for_option(RC_Channel::AUX_FUNC::ARM_EMERGENCY_STOP);1539if (chan != nullptr) {1540// an RC channel is configured for arm_emergency_stop option, so estop maybe activated via this switch1541if (chan->get_aux_switch_pos() == RC_Channel::AuxSwitchPos::LOW) {1542// switch is configured and is in estop position, so likely the reason we are estopped, so no prearm failure1543return true; // no prearm failure1544}1545}1546#endif // AP_RC_CHANNEL_ENABLED1547check_failed(display_failure,"Motors Emergency Stopped");1548return false;1549}15501551bool AP_Arming::pre_arm_checks(bool report)1552{1553#if !APM_BUILD_COPTER_OR_HELI1554if (armed || arming_required() == Required::NO) {1555// if we are already armed or don't need any arming checks1556// then skip the checks1557return true;1558}1559#endif15601561bool checks_result = hardware_safety_check(report)1562#if HAL_HAVE_IMU_HEATER1563& heater_min_temperature_checks(report)1564#endif1565#if AP_BARO_ENABLED1566& barometer_checks(report)1567#endif1568#if AP_INERTIALSENSOR_ENABLED1569& ins_checks(report)1570#endif1571#if AP_COMPASS_ENABLED1572& compass_checks(report)1573#endif1574#if AP_GPS_ENABLED1575& gps_checks(report)1576#endif1577#if AP_BATTERY_ENABLED1578& battery_checks(report)1579#endif1580#if HAL_LOGGING_ENABLED1581& logging_checks(report)1582#endif1583#if AP_RC_CHANNEL_ENABLED1584& manual_transmitter_checks(report)1585#endif1586#if AP_MISSION_ENABLED1587& mission_checks(report)1588#endif1589#if AP_RANGEFINDER_ENABLED1590& rangefinder_checks(report)1591#endif1592& servo_checks(report)1593& board_voltage_checks(report)1594& system_checks(report)1595& terrain_checks(report)1596#if HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED1597& can_checks(report)1598#endif1599#if HAL_GENERATOR_ENABLED1600& generator_checks(report)1601#endif1602#if HAL_PROXIMITY_ENABLED1603& proximity_checks(report)1604#endif1605#if AP_CAMERA_RUNCAM_ENABLED1606& camera_checks(report)1607#endif1608#if OSD_ENABLED1609& osd_checks(report)1610#endif1611#if HAL_MOUNT_ENABLED1612& mount_checks(report)1613#endif1614#if AP_FETTEC_ONEWIRE_ENABLED1615& fettec_checks(report)1616#endif1617#if HAL_VISUALODOM_ENABLED1618& visodom_checks(report)1619#endif1620#if AP_ARMING_AUX_AUTH_ENABLED1621& aux_auth_checks(report)1622#endif1623#if AP_RC_CHANNEL_ENABLED1624& disarm_switch_checks(report)1625#endif1626#if AP_FENCE_ENABLED1627& fence_checks(report)1628#endif1629#if AP_OPENDRONEID_ENABLED1630& opendroneid_checks(report)1631#endif1632#if AP_ARMING_CRASHDUMP_ACK_ENABLED1633& crashdump_checks(report)1634#endif1635& serial_protocol_checks(report)1636& estop_checks(report);16371638if (!checks_result && last_prearm_checks_result) { // check went from true to false1639report_immediately = true;1640}1641last_prearm_checks_result = checks_result;16421643return checks_result;1644}16451646bool AP_Arming::arm_checks(AP_Arming::Method method)1647{1648#if AP_RC_CHANNEL_ENABLED1649if (check_enabled(ARMING_CHECK_RC)) {1650if (!rc_arm_checks(method)) {1651return false;1652}1653}1654#endif16551656// ensure the GPS drivers are ready on any final changes1657if (check_enabled(ARMING_CHECK_GPS_CONFIG)) {1658if (!AP::gps().prepare_for_arming()) {1659return false;1660}1661}16621663// note that this will prepare AP_Logger to start logging1664// so should be the last check to be done before arming16651666// Note also that we need to PrepForArming() regardless of whether1667// the arming check flag is set - disabling the arming check1668// should not stop logging from working.16691670#if HAL_LOGGING_ENABLED1671AP_Logger *logger = AP_Logger::get_singleton();1672if (logger->logging_present()) {1673// If we're configured to log, prep it1674logger->PrepForArming();1675if (!logger->logging_started() &&1676check_enabled(ARMING_CHECK_LOGGING)) {1677check_failed(ARMING_CHECK_LOGGING, true, "Logging not started");1678return false;1679}1680}1681#endif // HAL_LOGGING_ENABLED16821683return true;1684}16851686#if !AP_GPS_BLENDED_ENABLED1687bool AP_Arming::blending_auto_switch_checks(bool report)1688{1689if (AP::gps().get_auto_switch_type() == 2) {1690if (report) {1691check_failed(ARMING_CHECK_GPS, true, "GPS_AUTO_SWITCH==2 but no blending");1692}1693return false;1694}1695return true;1696}1697#endif16981699#if AP_ARMING_CRASHDUMP_ACK_ENABLED1700bool AP_Arming::crashdump_checks(bool report)1701{1702if (hal.util->last_crash_dump_size() == 0) {1703// no crash dump data1704return true;1705}17061707// see if the user has acknowledged the failure and wants to fly anyway:1708if (crashdump_ack.acked) {1709// they may have acked the problem, that doesn't mean we don't1710// continue to warn them they're on thin ice:1711if (report) {1712GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "CrashDump data detected");1713}1714return true;1715}17161717check_failed(ARMING_CHECK_PARAMETERS, true, "CrashDump data detected");17181719return false;1720}1721#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED17221723bool AP_Arming::mandatory_checks(bool report)1724{1725bool ret = true;1726#if AP_OPENDRONEID_ENABLED1727ret &= opendroneid_checks(report);1728#endif1729ret &= rc_in_calibration_check(report);1730ret &= serial_protocol_checks(report);1731return ret;1732}17331734//returns true if arming occurred successfully1735bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks)1736{1737if (armed) { //already armed1738return false;1739}17401741running_arming_checks = true; // so we show Arm: rather than Disarm: in messages17421743if ((!do_arming_checks && mandatory_checks(true)) || (pre_arm_checks(true) && arm_checks(method))) {1744armed = true;17451746_last_arm_method = method;17471748#if HAL_LOGGING_ENABLED1749Log_Write_Arm(!do_arming_checks, method); // note Log_Write_Armed takes forced not do_arming_checks1750#endif17511752} else {1753#if HAL_LOGGING_ENABLED1754AP::logger().arming_failure();1755#endif1756armed = false;1757}17581759running_arming_checks = false;17601761if (armed && do_arming_checks && checks_to_perform == 0) {1762GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Warning: Arming Checks Disabled");1763}17641765#if HAL_GYROFFT_ENABLED1766// make sure the FFT subsystem is enabled if arming checks have been disabled1767AP_GyroFFT *fft = AP::fft();1768if (fft != nullptr) {1769fft->prepare_for_arming();1770}1771#endif17721773#if AP_TERRAIN_AVAILABLE1774if (armed) {1775// tell terrain we have just armed, so it can setup1776// a reference location for terrain adjustment1777auto *terrain = AP::terrain();1778if (terrain != nullptr) {1779terrain->set_reference_location();1780}1781}1782#endif17831784#if AP_FENCE_ENABLED1785if (armed) {1786auto *fence = AP::fence();1787if (fence != nullptr) {1788fence->auto_enable_fence_on_arming();1789}1790}1791#endif1792#if defined(HAL_ARM_GPIO_PIN)1793update_arm_gpio();1794#endif1795return armed;1796}17971798//returns true if disarming occurred successfully1799bool AP_Arming::disarm(const AP_Arming::Method method, bool do_disarm_checks)1800{1801if (!armed) { // already disarmed1802return false;1803}1804armed = false;1805_last_disarm_method = method;18061807#if HAL_LOGGING_ENABLED1808Log_Write_Disarm(!do_disarm_checks, method); // Log_Write_Disarm takes "force"18091810check_forced_logging(method);1811#endif18121813#if HAL_HAVE_SAFETY_SWITCH1814AP_BoardConfig *board_cfg = AP_BoardConfig::get_singleton();1815if ((board_cfg != nullptr) &&1816(board_cfg->get_safety_button_options() & AP_BoardConfig::BOARD_SAFETY_OPTION_SAFETY_ON_DISARM)) {1817hal.rcout->force_safety_on();1818}1819#endif // HAL_HAVE_SAFETY_SWITCH18201821#if HAL_GYROFFT_ENABLED1822AP_GyroFFT *fft = AP::fft();1823if (fft != nullptr) {1824fft->save_params_on_disarm();1825}1826#endif18271828#if AP_FENCE_ENABLED1829AC_Fence *fence = AP::fence();1830if (fence != nullptr) {1831fence->auto_disable_fence_on_disarming();1832}1833#endif1834#if defined(HAL_ARM_GPIO_PIN)1835update_arm_gpio();1836#endif1837return true;1838}18391840#if defined(HAL_ARM_GPIO_PIN)1841void AP_Arming::update_arm_gpio()1842{1843if (!AP_BoardConfig::arming_gpio_disabled()) {1844hal.gpio->write(HAL_ARM_GPIO_PIN, HAL_ARM_GPIO_POL_INVERT ? !armed : armed);1845}1846}1847#endif18481849void AP_Arming::send_arm_disarm_statustext(const char *str) const1850{1851if (option_enabled(AP_Arming::Option::DISABLE_STATUSTEXT_ON_STATE_CHANGE)) {1852return;1853}1854GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s", str);1855}18561857AP_Arming::Required AP_Arming::arming_required() const1858{1859#if AP_OPENDRONEID_ENABLED1860// cannot be disabled if OpenDroneID is present1861if (AP_OpenDroneID::get_singleton() != nullptr && AP::opendroneid().enabled()) {1862if (require != Required::YES_MIN_PWM && require != Required::YES_ZERO_PWM) {1863return Required::YES_MIN_PWM;1864}1865}1866#endif1867return require;1868}18691870#if AP_RC_CHANNEL_ENABLED1871// Copter and sub share the same RC input limits1872// Copter checks that min and max have been configured by default, Sub does not1873bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channel *channels[4]) const1874{1875// set rc-checks to success if RC checks are disabled1876if (!check_enabled(ARMING_CHECK_RC)) {1877return true;1878}18791880bool ret = true;18811882const char *channel_names[] = { "Roll", "Pitch", "Throttle", "Yaw" };18831884for (uint8_t i=0; i<ARRAY_SIZE(channel_names);i++) {1885const RC_Channel *channel = channels[i];1886const char *channel_name = channel_names[i];1887// check if radio has been calibrated1888if (channel->get_radio_min() > RC_Channel::RC_CALIB_MIN_LIMIT_PWM) {1889check_failed(ARMING_CHECK_RC, display_failure, "%s radio min too high", channel_name);1890ret = false;1891}1892if (channel->get_radio_max() < RC_Channel::RC_CALIB_MAX_LIMIT_PWM) {1893check_failed(ARMING_CHECK_RC, display_failure, "%s radio max too low", channel_name);1894ret = false;1895}1896}1897return ret;1898}1899#endif // AP_RC_CHANNEL_ENABLED19001901#if HAL_VISUALODOM_ENABLED1902// check visual odometry is working1903bool AP_Arming::visodom_checks(bool display_failure) const1904{1905if (!check_enabled(ARMING_CHECK_VISION)) {1906return true;1907}19081909AP_VisualOdom *visual_odom = AP::visualodom();1910if (visual_odom != nullptr) {1911char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];1912if (!visual_odom->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {1913check_failed(ARMING_CHECK_VISION, display_failure, "VisOdom: %s", fail_msg);1914return false;1915}1916}19171918return true;1919}1920#endif19211922#if AP_RC_CHANNEL_ENABLED1923// check disarm switch is asserted1924bool AP_Arming::disarm_switch_checks(bool display_failure) const1925{1926const RC_Channel *chan = rc().find_channel_for_option(RC_Channel::AUX_FUNC::DISARM);1927if (chan != nullptr &&1928chan->get_aux_switch_pos() == RC_Channel::AuxSwitchPos::HIGH) {1929check_failed(display_failure, "Disarm Switch on");1930return false;1931}19321933return true;1934}1935#endif // AP_RC_CHANNEL_ENABLED19361937#if HAL_LOGGING_ENABLED1938void AP_Arming::Log_Write_Arm(const bool forced, const AP_Arming::Method method)1939{1940const struct log_Arm_Disarm pkt {1941LOG_PACKET_HEADER_INIT(LOG_ARM_DISARM_MSG),1942time_us : AP_HAL::micros64(),1943arm_state : is_armed(),1944arm_checks : get_enabled_checks(),1945forced : forced,1946method : (uint8_t)method,1947};1948AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));1949AP::logger().Write_Event(LogEvent::ARMED);1950}19511952void AP_Arming::Log_Write_Disarm(const bool forced, const AP_Arming::Method method)1953{1954const struct log_Arm_Disarm pkt {1955LOG_PACKET_HEADER_INIT(LOG_ARM_DISARM_MSG),1956time_us : AP_HAL::micros64(),1957arm_state : is_armed(),1958arm_checks : 0,1959forced : forced,1960method : (uint8_t)method1961};1962AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));1963AP::logger().Write_Event(LogEvent::DISARMED);1964}19651966// check if we should keep logging after disarming1967void AP_Arming::check_forced_logging(const AP_Arming::Method method)1968{1969// keep logging if disarmed for a bad reason1970switch(method) {1971case Method::TERMINATION:1972case Method::CPUFAILSAFE:1973case Method::BATTERYFAILSAFE:1974case Method::AFS:1975case Method::ADSBCOLLISIONACTION:1976case Method::PARACHUTE_RELEASE:1977case Method::CRASH:1978case Method::FENCEBREACH:1979case Method::RADIOFAILSAFE:1980case Method::GCSFAILSAFE:1981case Method::TERRRAINFAILSAFE:1982case Method::FAILSAFE_ACTION_TERMINATE:1983case Method::TERRAINFAILSAFE:1984case Method::BADFLOWOFCONTROL:1985case Method::EKFFAILSAFE:1986case Method::GCS_FAILSAFE_SURFACEFAILED:1987case Method::GCS_FAILSAFE_HOLDFAILED:1988case Method::PILOT_INPUT_FAILSAFE:1989case Method::DEADRECKON_FAILSAFE:1990case Method::BLACKBOX:1991// keep logging for longer if disarmed for a bad reason1992AP::logger().set_long_log_persist(true);1993return;19941995case Method::RUDDER:1996case Method::MAVLINK:1997case Method::AUXSWITCH:1998case Method::MOTORTEST:1999case Method::SCRIPTING:2000case Method::SOLOPAUSEWHENLANDED:2001case Method::LANDED:2002case Method::MISSIONEXIT:2003case Method::DISARMDELAY:2004case Method::MOTORDETECTDONE:2005case Method::TAKEOFFTIMEOUT:2006case Method::AUTOLANDED:2007case Method::TOYMODELANDTHROTTLE:2008case Method::TOYMODELANDFORCE:2009case Method::LANDING:2010case Method::DDS:2011case Method::UNKNOWN:2012AP::logger().set_long_log_persist(false);2013return;2014}2015}2016#endif // HAL_LOGGING_ENABLED20172018AP_Arming *AP_Arming::_singleton = nullptr;20192020/*2021* Get the AP_Arming singleton2022*/2023AP_Arming *AP_Arming::get_singleton()2024{2025return AP_Arming::_singleton;2026}20272028namespace AP {20292030AP_Arming &arming()2031{2032return *AP_Arming::get_singleton();2033}20342035};20362037#pragma GCC diagnostic pop20382039#endif // AP_ARMING_ENABLED204020412042