Path: blob/master/libraries/AP_Arming/AP_Arming.cpp
9441 views
/*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>61#include <AP_ICEngine/AP_ICEngine.h>6263#if HAL_MAX_CAN_PROTOCOL_DRIVERS64#include <AP_CANManager/AP_CANManager.h>65#include <AP_Common/AP_Common.h>66#include <AP_Vehicle/AP_Vehicle_Type.h>6768#include <AP_PiccoloCAN/AP_PiccoloCAN.h>69#include <AP_DroneCAN/AP_DroneCAN.h>70#endif7172#include <AP_Logger/AP_Logger.h>7374#define AP_ARMING_COMPASS_MAGFIELD_EXPECTED 53075#define AP_ARMING_COMPASS_MAGFIELD_MIN 185 // 0.35 * 530 milligauss76#define AP_ARMING_COMPASS_MAGFIELD_MAX 875 // 1.65 * 530 milligauss77#define AP_ARMING_BOARD_VOLTAGE_MAX 5.8f78#define AP_ARMING_ACCEL_ERROR_THRESHOLD 0.75f79#define AP_ARMING_MAGFIELD_ERROR_THRESHOLD 10080#define AP_ARMING_AHRS_GPS_ERROR_MAX 10 // accept up to 10m difference between AHRS and GPS8182#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)83#define ARMING_RUDDER_DEFAULT (uint8_t)RudderArming::ARMONLY84#else85#define ARMING_RUDDER_DEFAULT (uint8_t)RudderArming::ARMDISARM86#endif8788// find a default value for ARMING_NEED_POS parameter, and determine89// whether the parameter should be shown:90#ifndef AP_ARMING_NEED_LOC_PARAMETER_ENABLED91// determine whether ARMING_NEED_POS is shown:92#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_Rover)93#define AP_ARMING_NEED_LOC_PARAMETER_ENABLED 194#else95#define AP_ARMING_NEED_LOC_PARAMETER_ENABLED 096#endif // build types97#endif // AP_ARMING_NEED_LOC_PARAMETER_ENABLED9899// if ARMING_NEED_POS is shown, determine what its default should be:100#if AP_ARMING_NEED_LOC_PARAMETER_ENABLED101#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_Rover)102#define AP_ARMING_NEED_LOC_DEFAULT 0103#else104#error "Unable to find value for AP_ARMING_NEED_LOC_DEFAULT"105#endif // APM_BUILD_TYPE106#endif // AP_ARMING_NEED_LOC_PARAMETER_ENABLED107108#ifndef PREARM_DISPLAY_PERIOD109# define PREARM_DISPLAY_PERIOD 30110#endif111112extern const AP_HAL::HAL& hal;113114const AP_Param::GroupInfo AP_Arming::var_info[] = {115116// @Param{Plane, Rover}: REQUIRE117// @DisplayName: Require Arming Motors118// @Description{Plane}: 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 be blocked until all mandatory and non-ARMING_SKIPCHK items are satisfied; arming can then be accomplished via (eg.) rudder gesture or GCS command.119// @Description{Rover}: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, all checks not skipped by ARMING_SKIPCHK must pass before the vehicle can be armed (for example, via rudder stick or GCS command). If 3, Arm immediately once pre-arm/arm checks are satisfied, but only one time per boot up. Note that a reboot is NOT required when setting to 0 but IS require when setting to 3.120// @Values{Plane}: 0:Disabled,1:Yes(minimum PWM when disarmed),2:Yes(0 PWM when disarmed)121// @Values{Rover}: 0:No,1:Yes(minimum PWM when disarmed),3:No(AutoArmOnce after checks are passed)122// @User: Advanced123AP_GROUPINFO_FLAGS_FRAME("REQUIRE", 0, AP_Arming, require, float(Required::YES_MIN_PWM),124AP_PARAM_FLAG_NO_SHIFT,125AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_ROVER),126127// 2 was the CHECK paramter stored in a AP_Int16128129// @Param: ACCTHRESH130// @DisplayName: Accelerometer error threshold131// @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.132// @Units: m/s/s133// @Range: 0.25 3.0134// @User: Advanced135AP_GROUPINFO("ACCTHRESH", 3, AP_Arming, accel_error_threshold, AP_ARMING_ACCEL_ERROR_THRESHOLD),136137// index 4 was VOLT_MIN, moved to AP_BattMonitor138// index 5 was VOLT2_MIN, moved to AP_BattMonitor139140// @Param{Plane,Rover,Copter,Blimp}: RUDDER141// @DisplayName: Arming with Rudder enable/disable142// @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!143// @Values: 0:Disabled,1:ArmingOnly,2:ArmOrDisarm144// @User: Advanced145AP_GROUPINFO_FRAME("RUDDER", 6, AP_Arming, _rudder_arming, ARMING_RUDDER_DEFAULT, AP_PARAM_FRAME_PLANE |146AP_PARAM_FRAME_ROVER |147AP_PARAM_FRAME_COPTER |148AP_PARAM_FRAME_TRICOPTER |149AP_PARAM_FRAME_HELI |150AP_PARAM_FRAME_BLIMP),151152// @Param: MIS_ITEMS153// @DisplayName: Required mission items154// @Description: Bitmask of mission items that are required to be planned in order to arm the aircraft155// @Bitmask: 0:Land,1:VTOL Land,2:DO_LAND_START,3:Takeoff,4:VTOL Takeoff,5:Rallypoint,6:RTL156// @User: Advanced157AP_GROUPINFO("MIS_ITEMS", 7, AP_Arming, _required_mission_items, 0),158159// index 8 was CHECK stored as AP_Int32, became SKIPCHK160161// @Param: OPTIONS162// @DisplayName: Arming options163// @Description: Options that can be applied to change arming behaviour164// @Bitmask: 0:Disable prearm display,1:Do not send status text on state change,2:Skip IMU consistency checks when ICE motor running165// @User: Advanced166AP_GROUPINFO("OPTIONS", 9, AP_Arming, _arming_options, 0),167168// @Param: MAGTHRESH169// @DisplayName: Compass magnetic field strength error threshold vs earth magnetic model170// @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 check171// @Units: mGauss172// @Range: 0 500173// @User: Advanced174AP_GROUPINFO("MAGTHRESH", 10, AP_Arming, magfield_error_threshold, AP_ARMING_MAGFIELD_ERROR_THRESHOLD),175176#if AP_ARMING_CRASHDUMP_ACK_ENABLED177// @Param: CRSDP_IGN178// @DisplayName: Disable CrashDump Arming check179// @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.180// @Values: 0:Crash Dump arming check active, 1:Crash Dump arming check deactivated181// @User: Advanced182AP_GROUPINFO("CRSDP_IGN", 11, AP_Arming, crashdump_ack.acked, 0),183#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED184185#if AP_ARMING_NEED_LOC_PARAMETER_ENABLED186// @Param: NEED_LOC187// @DisplayName: Require vehicle location188// @Description: Require that the vehicle have an absolute position before it arms. This can help ensure that the vehicle can Return To Launch.189// @User: Advanced190// @Values{Copter,Rover}: 0:Do not require location,1:Require Location191AP_GROUPINFO("NEED_LOC", 12, AP_Arming, require_location, float(AP_ARMING_NEED_LOC_DEFAULT)),192#endif // AP_ARMING_NEED_LOC_PARAMETER_ENABLED193194// @Param: SKIPCHK195// @DisplayName: Arm Checks to Skip (bitmask)196// @Description: Checks to skip prior to arming motor. This is a bitmask of checks before allowing arming that will be skipped. For most users it is recommended to leave this at the default of 0 (no checks skipped). In extreme circumstances, a value of -1 can be used to skip all non-mandatory current and future checks.197// @Bitmask: 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:FFT198// @Bitmask{Plane}: 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:FFT199// @User: Standard200AP_GROUPINFO("SKIPCHK", 13, AP_Arming, checks_to_skip, 0),201202AP_GROUPEND203};204205#if HAL_WITH_IO_MCU206#include <AP_IOMCU/AP_IOMCU.h>207extern AP_IOMCU iomcu;208#endif209210#pragma GCC diagnostic push211#if defined(__clang_major__) && __clang_major__ >= 14212#pragma GCC diagnostic ignored "-Wbitwise-instead-of-logical"213#endif214215AP_Arming::AP_Arming()216{217if (_singleton) {218AP_HAL::panic("Too many AP_Arming instances");219}220_singleton = this;221222AP_Param::setup_object_defaults(this, var_info);223}224225__INITFUNC__ void AP_Arming::init(void)226{227// PARAM_CONVERSION - 4.7 CHECK -> SKIPCHK228229if (!checks_to_skip.configured()) {230// new parameter is not configured (though it may be set non-zero in a231// defaults table e.g. on Sub)232int32_t skipchk_new = checks_to_skip.get(); // get param default233234uint32_t idx = 8;235#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)236idx <<= 6; // the old index is shifted due to AP_NESTEDGROUPINFO in AP_Arming_Plane.cpp237#endif238239int32_t checks_old;240if (AP_Param::get_param_by_index(this, idx, AP_PARAM_INT32, &checks_old)) {241// the old parameter was customized242if (checks_old == 0) { // all checks disabled?243skipchk_new = -1; // skip all current and future checks244} else if (!(checks_old & 1)) { // ALL flag not set?245// mask of known checks at the time the conversion was written246uint32_t check_mask = ((1U << 21) - 1) & (~1); // remove ALL bit247// invert bits to get checks to skip248skipchk_new = (~checks_old) & check_mask;249} else {250skipchk_new = 0; // specifically enable all checks, ignoring param default251}252}253254checks_to_skip.set_and_save(skipchk_new); // set and save to finish migration255}256}257258// performs pre-arm checks. expects to be called at 1hz.259void AP_Arming::update(void)260{261#if AP_ARMING_CRASHDUMP_ACK_ENABLED262// if we boot with no crashdump data present, reset the "ignore"263// parameter so the user will need to acknowledge future crashes264// too:265crashdump_ack.check_reset();266#endif267268const uint32_t now_ms = AP_HAL::millis();269// perform pre-arm checks & display failures every 30 seconds270bool display_fail = false;271if ((report_immediately && (now_ms - last_prearm_display_ms > 4000)) ||272(now_ms - last_prearm_display_ms > PREARM_DISPLAY_PERIOD*1000)) {273report_immediately = false;274display_fail = true;275last_prearm_display_ms = now_ms;276}277// OTOH, the user may never want to display them:278if (option_enabled(Option::DISABLE_PREARM_DISPLAY)) {279display_fail = false;280}281282pre_arm_checks(display_fail);283}284285#if AP_ARMING_CRASHDUMP_ACK_ENABLED286void AP_Arming::CrashDump::check_reset()287{288// if there is no crash dump data then clear the crash dump ack.289// This means on subsequent crash-dumps appearing the user must290// re-acknowledge.291if (hal.util->last_crash_dump_size() == 0) {292// no crash dump data293acked.set_and_save_ifchanged(0);294}295}296#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED297298uint16_t AP_Arming::compass_magfield_expected() const299{300return AP_ARMING_COMPASS_MAGFIELD_EXPECTED;301}302303bool AP_Arming::is_armed() const304{305return armed || arming_required() == Required::NO;306}307308/*309true if armed and safety is off310*/311bool AP_Arming::is_armed_and_safety_off() const312{313return is_armed() && hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED;314}315316uint32_t AP_Arming::get_enabled_checks() const317{318// ignore unknown checks319uint32_t check_mask = (uint32_t(Check::CHECK_LAST)-1) & (~1); // remove former ALL bit320return (~checks_to_skip) & check_mask;321}322323bool AP_Arming::check_enabled(const AP_Arming::Check check) const324{325return (checks_to_skip & uint32_t(check)) == 0;326}327328bool AP_Arming::all_checks_enabled() const329{330// ignore unknown checks331uint32_t check_mask = (uint32_t(Check::CHECK_LAST)-1) & (~1); // remove former ALL bit332return (checks_to_skip & check_mask) == 0;333}334335void AP_Arming::check_failed(const AP_Arming::Check check, bool report, const char *fmt, ...) const336{337if (!report) {338return;339}340char taggedfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];341342// metafmt is wrapped around the passed-in format string to343// prepend "PreArm" or "Arm", depending on what sorts of checks344// we're currently doing.345const char *metafmt = "PreArm: %s"; // it's formats all the way down346if (running_arming_checks) {347metafmt = "Arm: %s";348}349hal.util->snprintf(taggedfmt, sizeof(taggedfmt), metafmt, fmt);350351#if HAL_GCS_ENABLED352MAV_SEVERITY severity = MAV_SEVERITY_CRITICAL;353if (!check_enabled(check)) {354// technically should be NOTICE, but will annoy users at that level:355severity = MAV_SEVERITY_DEBUG;356}357va_list arg_list;358va_start(arg_list, fmt);359gcs().send_textv(severity, taggedfmt, arg_list);360va_end(arg_list);361#endif // HAL_GCS_ENABLED362}363364void AP_Arming::check_failed(bool report, const char *fmt, ...) const365{366#if HAL_GCS_ENABLED367if (!report) {368return;369}370char taggedfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];371372// metafmt is wrapped around the passed-in format string to373// prepend "PreArm" or "Arm", depending on what sorts of checks374// we're currently doing.375const char *metafmt = "PreArm: %s"; // it's formats all the way down376if (running_arming_checks) {377metafmt = "Arm: %s";378}379hal.util->snprintf(taggedfmt, sizeof(taggedfmt), metafmt, fmt);380381va_list arg_list;382va_start(arg_list, fmt);383gcs().send_textv(MAV_SEVERITY_CRITICAL, taggedfmt, arg_list);384va_end(arg_list);385#endif // HAL_GCS_ENABLED386}387388bool AP_Arming::barometer_checks(bool report)389{390#ifdef HAL_BARO_ALLOW_INIT_NO_BARO391return true;392#endif393#if CONFIG_HAL_BOARD == HAL_BOARD_SITL394if (AP::sitl()->baro_count == 0) {395// simulate no baro boards396return true;397}398#endif399if (check_enabled(Check::BARO)) {400char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};401if (!AP::baro().arming_checks(sizeof(buffer), buffer)) {402check_failed(Check::BARO, report, "Baro: %s", buffer);403return false;404}405}406407return true;408}409410#if AP_AIRSPEED_ENABLED411bool AP_Arming::airspeed_checks(bool report)412{413if (check_enabled(Check::AIRSPEED)) {414const AP_Airspeed *airspeed = AP_Airspeed::get_singleton();415if (airspeed == nullptr) {416// not an airspeed capable vehicle417return true;418}419char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};420if (!airspeed->arming_checks(sizeof(buffer), buffer)) {421check_failed(Check::AIRSPEED, report, "Airspeed: %s", buffer);422return false;423}424}425426return true;427}428#endif // AP_AIRSPEED_ENABLED429430#if HAL_LOGGING_ENABLED431bool AP_Arming::logging_checks(bool report)432{433if (check_enabled(Check::LOGGING)) {434if (!AP::logger().logging_present()) {435// Logging is disabled, so nothing to check.436return true;437}438if (AP::logger().logging_failed()) {439check_failed(Check::LOGGING, report, "Logging failed");440return false;441}442if (!AP::logger().CardInserted()) {443check_failed(Check::LOGGING, report, "No SD card");444return false;445}446if (AP::logger().in_log_download()) {447check_failed(Check::LOGGING, report, "Downloading logs");448return false;449}450}451return true;452}453#endif // HAL_LOGGING_ENABLED454455#if AP_INERTIALSENSOR_ENABLED456bool AP_Arming::ins_accels_consistent(const AP_InertialSensor &ins)457{458const uint32_t now = AP_HAL::millis();459if (!ins.accels_consistent(accel_error_threshold)) {460// accels are inconsistent:461last_accel_pass_ms = 0;462return false;463}464465if (last_accel_pass_ms == 0) {466// we didn't return false above, so sensors are467// consistent right now:468last_accel_pass_ms = now;469}470471// if accels can in theory be inconsistent,472// must pass for at least 10 seconds before we're considered consistent:473if (ins.get_accel_count() > 1 && now - last_accel_pass_ms < 10000) {474return false;475}476477return true;478}479480bool AP_Arming::ins_gyros_consistent(const AP_InertialSensor &ins)481{482const uint32_t now = AP_HAL::millis();483// allow for up to 5 degrees/s difference484if (!ins.gyros_consistent(5)) {485// gyros are inconsistent:486last_gyro_pass_ms = 0;487return false;488}489490// we didn't return false above, so sensors are491// consistent right now:492if (last_gyro_pass_ms == 0) {493last_gyro_pass_ms = now;494}495496// if gyros can in theory be inconsistent,497// must pass for at least 10 seconds before we're considered consistent:498if (ins.get_gyro_count() > 1 && now - last_gyro_pass_ms < 10000) {499return false;500}501502return true;503}504505bool AP_Arming::ins_checks(bool report)506{507if (check_enabled(Check::INS)) {508const AP_InertialSensor &ins = AP::ins();509if (!ins.get_gyro_health_all()) {510check_failed(Check::INS, report, "Gyros not healthy");511return false;512}513if (!ins.gyro_calibrated_ok_all()) {514check_failed(Check::INS, report, "Gyros not calibrated");515return false;516}517if (!ins.get_accel_health_all()) {518check_failed(Check::INS, report, "Accels not healthy");519return false;520}521if (!ins.accel_calibrated_ok_all()) {522check_failed(Check::INS, report, "3D Accel calibration needed");523return false;524}525526//check if accelerometers have calibrated and require reboot527if (ins.accel_cal_requires_reboot()) {528check_failed(Check::INS, report, "Accels calibrated requires reboot");529return false;530}531532bool run_imu_consistency_check = true;533#if AP_ICENGINE_ENABLED534if (option_enabled(Option::SKIP_IMU_CONSISTENCY_ICE_RUNNING)) {535// ICE motors can greatly disturb the IMU, so we get arming failures536// due to gyro (and sometimes accel) inconsistency. Allow this check to be537// disabled while the motor is running538auto ice = AP::ice();539if (ice != nullptr) {540const auto ice_state = ice->get_state();541if (ice_state == AP_ICEngine::ICE_STARTING || ice_state == AP_ICEngine::ICE_RUNNING) {542run_imu_consistency_check = false;543}544}545}546#endif547548if (run_imu_consistency_check) {549// check all accelerometers point in roughly same direction550if (!ins_accels_consistent(ins)) {551check_failed(Check::INS, report, "Accels inconsistent");552return false;553}554555// check all gyros are giving consistent readings556if (!ins_gyros_consistent(ins)) {557check_failed(Check::INS, report, "Gyros inconsistent");558return false;559}560}561562// no arming while doing temp cal563if (ins.temperature_cal_running()) {564check_failed(Check::INS, report, "temperature cal running");565return false;566}567568#if AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED569// If Batch sampling enabled it must be initialized570if (ins.batchsampler.enabled() && !ins.batchsampler.is_initialised()) {571check_failed(Check::INS, report, "Batch sampling requires reboot");572return false;573}574#endif575576// check if IMU gyro updates are greater than or equal to Ardupilot Loop rate577char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];578if (!ins.pre_arm_check_gyro_backend_rate_hz(fail_msg, ARRAY_SIZE(fail_msg))) {579check_failed(Check::INS, report, "%s", fail_msg);580return false;581}582}583584#if HAL_GYROFFT_ENABLED585// gyros are healthy so check the FFT586if (check_enabled(Check::FFT)) {587// Check that the noise analyser works588AP_GyroFFT *fft = AP::fft();589590char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];591if (fft != nullptr && !fft->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {592check_failed(Check::INS, report, "%s", fail_msg);593return false;594}595}596#endif597598return true;599}600#endif // AP_INERTIALSENSOR_ENABLED601602bool AP_Arming::compass_checks(bool report)603{604Compass &_compass = AP::compass();605606#if COMPASS_CAL_ENABLED607// check if compass is calibrating608if (_compass.is_calibrating()) {609check_failed(report, "Compass calibration running");610return false;611}612613// check if compass has calibrated and requires reboot614if (_compass.compass_cal_requires_reboot()) {615check_failed(report, "Compass calibrated requires reboot");616return false;617}618#endif619620if (check_enabled(Check::COMPASS)) {621622// avoid Compass::use_for_yaw(void) as it implicitly calls healthy() which can623// incorrectly skip the remaining checks, pass the primary instance directly624if (!_compass.use_for_yaw(0)) {625// compass use is disabled626return true;627}628629if (!_compass.healthy()) {630check_failed(Check::COMPASS, report, "Compass %d not healthy", _compass.get_first_usable() + 1);631return false;632}633// check compass learning is on or offsets have been set634#if !APM_BUILD_COPTER_OR_HELI && !APM_BUILD_TYPE(APM_BUILD_Blimp)635// check compass offsets have been set if learning is off636// copter and blimp always require configured compasses637if (!_compass.learn_offsets_enabled())638#endif639{640char failure_msg[100] = {};641if (!_compass.configured(failure_msg, ARRAY_SIZE(failure_msg))) {642check_failed(Check::COMPASS, report, "%s", failure_msg);643return false;644}645}646647// check for unreasonable compass offsets648const Vector3f offsets = _compass.get_offsets();649if (offsets.length() > _compass.get_offsets_max()) {650check_failed(Check::COMPASS, report, "Compass offsets too high");651return false;652}653654// check for unreasonable mag field length655const float mag_field = _compass.get_field().length();656if (mag_field > AP_ARMING_COMPASS_MAGFIELD_MAX || mag_field < AP_ARMING_COMPASS_MAGFIELD_MIN) {657check_failed(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);658return false;659}660661// check all compasses point in roughly same direction662if (!_compass.consistent()) {663check_failed(Check::COMPASS, report, "Compasses inconsistent");664return false;665}666667#if AP_AHRS_ENABLED668// if ahrs is using compass and we have location, check mag field versus expected earth magnetic model669Location ahrs_loc;670AP_AHRS &ahrs = AP::ahrs();671if ((magfield_error_threshold > 0) && ahrs.use_compass() && ahrs.get_location(ahrs_loc)) {672const Vector3f veh_mag_field_ef = ahrs.get_rotation_body_to_ned() * _compass.get_field();673const Vector3f earth_field_mgauss = AP_Declination::get_earth_field_ga(ahrs_loc) * 1000.0;674const Vector3f diff_mgauss = veh_mag_field_ef - earth_field_mgauss;675if (MAX(fabsf(diff_mgauss.x), fabsf(diff_mgauss.y)) > magfield_error_threshold) {676check_failed(Check::COMPASS, report, "Check mag field (xy diff:%.0f>%d)",677(double)MAX(fabsf(diff_mgauss.x), (double)fabsf(diff_mgauss.y)), (int)magfield_error_threshold);678return false;679}680if (fabsf(diff_mgauss.z) > magfield_error_threshold*2.0) {681check_failed(Check::COMPASS, report, "Check mag field (z diff:%.0f>%d)",682(double)fabsf(diff_mgauss.z), (int)magfield_error_threshold*2);683return false;684}685}686#endif // AP_AHRS_ENABLED687}688689return true;690}691692#if AP_GPS_ENABLED693bool AP_Arming::gps_checks(bool report)694{695const AP_GPS &gps = AP::gps();696if (check_enabled(Check::GPS)) {697698// Any failure messages from GPS backends699char failure_msg[100] = {};700if (!AP::gps().pre_arm_checks(failure_msg, ARRAY_SIZE(failure_msg))) {701if (failure_msg[0] != '\0') {702check_failed(Check::GPS, report, "%s", failure_msg);703}704return false;705}706707for (uint8_t i = 0; i < gps.num_sensors(); i++) {708#if AP_GPS_BLENDED_ENABLED709if ((i != GPS_BLENDED_INSTANCE) &&710#else711if (712#endif713(gps.get_type(i) == AP_GPS::GPS_Type::GPS_TYPE_NONE)) {714if (gps.primary_sensor() == i) {715check_failed(Check::GPS, report, "GPS %i: primary but TYPE 0", i+1);716return false;717}718continue;719}720721//GPS OK?722if (gps.status(i) < AP_GPS::GPS_OK_FIX_3D) {723check_failed(Check::GPS, report, "GPS %i: Bad fix", i+1);724return false;725}726727//GPS update rate acceptable728if (!gps.is_healthy(i)) {729check_failed(Check::GPS, report, "GPS %i: not healthy", i+1);730return false;731}732}733734if (!AP::ahrs().home_is_set()) {735check_failed(Check::GPS, report, "AHRS: waiting for home");736return false;737}738739// check GPSs are within 50m of each other and that blending is healthy740float distance_m;741if (!gps.all_consistent(distance_m)) {742check_failed(Check::GPS, report, "GPS positions differ by %4.1fm",743(double)distance_m);744return false;745}746747// check AHRS and GPS are within 10m of each other748if (gps.num_sensors() > 0) {749const Location gps_loc = gps.location();750Location ahrs_loc;751if (AP::ahrs().get_location(ahrs_loc)) {752const float distance = gps_loc.get_distance(ahrs_loc);753if (distance > AP_ARMING_AHRS_GPS_ERROR_MAX) {754check_failed(Check::GPS, report, "GPS and AHRS differ by %4.1fm", (double)distance);755return false;756}757}758}759}760761if (check_enabled(Check::GPS_CONFIG)) {762uint8_t first_unconfigured;763if (gps.first_unconfigured_gps(first_unconfigured)) {764check_failed(Check::GPS_CONFIG,765report,766"GPS %d still configuring this GPS",767first_unconfigured + 1);768if (report) {769gps.broadcast_first_configuration_failure_reason();770}771return false;772}773}774775return true;776}777#endif // AP_GPS_ENABLED778779#if AP_BATTERY_ENABLED780bool AP_Arming::battery_checks(bool report)781{782if (check_enabled(Check::BATTERY)) {783784char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};785if (!AP::battery().arming_checks(sizeof(buffer), buffer)) {786check_failed(Check::BATTERY, report, "%s", buffer);787return false;788}789}790return true;791}792#endif // AP_BATTERY_ENABLED793794bool AP_Arming::hardware_safety_check(bool report)795{796if (check_enabled(Check::SWITCH)) {797798// check if safety switch has been pushed799if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {800check_failed(Check::SWITCH, report, "Hardware safety switch");801return false;802}803}804805return true;806}807808#if AP_RC_CHANNEL_ENABLED809bool AP_Arming::rc_arm_checks(AP_Arming::Method method)810{811// don't check the trims if we are in a failsafe812if (!rc().has_valid_input()) {813return true;814}815816// only check if we've received some form of input within the last second817// this is a protection against a vehicle having never enabled an input818uint32_t last_input_ms = rc().last_input_ms();819if ((last_input_ms == 0) || ((AP_HAL::millis() - last_input_ms) > 1000)) {820return true;821}822823bool check_passed = true;824// ensure all rc channels have different functions825if (rc().duplicate_options_exist()) {826check_failed(Check::PARAMETERS, true, "Duplicate Aux Switch Options");827check_passed = false;828}829if (rc().flight_mode_channel_conflicts_with_rc_option()) {830check_failed(Check::PARAMETERS, true, "Mode channel and RC%d_OPTION conflict", rc().flight_mode_channel_number());831check_passed = false;832}833{834if (!rc().option_is_enabled(RC_Channels::Option::ARMING_SKIP_CHECK_RPY)) {835const struct {836const char *name;837const RC_Channel *channel;838} channels_to_check[] {839{ "Roll", &rc().get_roll_channel(), },840{ "Pitch", &rc().get_pitch_channel(), },841{ "Yaw", &rc().get_yaw_channel(), },842};843for (const auto &channel_to_check : channels_to_check) {844const auto *c = channel_to_check.channel;845if (c->get_control_in() != 0) {846if ((method != Method::RUDDER) || (c != rc().get_arming_channel())) { // ignore the yaw input channel if rudder arming847check_failed(Check::RC, true, "%s (RC%d) is not neutral", channel_to_check.name, c->ch());848check_passed = false;849}850}851}852}853854// if throttle check is enabled, require zero input855if (rc().arming_check_throttle()) {856const RC_Channel *c = &rc().get_throttle_channel();857if (c->get_control_in() != 0) {858check_failed(Check::RC, true, "%s (RC%d) is not neutral", "Throttle", c->ch());859check_passed = false;860}861c = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FWD_THR);862if (c != nullptr) {863uint8_t fwd_thr = c->percent_input();864// require channel input within 2% of minimum865if (fwd_thr > 2) {866check_failed(Check::RC, true, "VTOL Fwd Throttle is not zero");867check_passed = false;868}869}870}871}872return check_passed;873}874875bool AP_Arming::rc_calibration_checks(bool report)876{877bool check_passed = true;878const uint8_t num_channels = RC_Channels::get_valid_channel_count();879for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {880const RC_Channel *c = rc().channel(i);881if (c == nullptr) {882continue;883}884if (i >= num_channels && !(c->has_override())) {885continue;886}887const uint16_t trim = c->get_radio_trim();888if (c->get_radio_min() > trim) {889check_failed(Check::RC, report, "RC%d_MIN is greater than RC%d_TRIM", i + 1, i + 1);890check_passed = false;891}892if (c->get_radio_max() < trim) {893check_failed(Check::RC, report, "RC%d_MAX is less than RC%d_TRIM", i + 1, i + 1);894check_passed = false;895}896}897898return check_passed;899}900901bool AP_Arming::rc_in_calibration_check(bool report)902{903if (rc().calibrating()) {904check_failed(Check::RC, report, "RC calibrating");905return false;906}907return true;908}909910bool AP_Arming::manual_transmitter_checks(bool report)911{912if (check_enabled(Check::RC)) {913914if (AP_Notify::flags.failsafe_radio) {915check_failed(Check::RC, report, "Radio failsafe on");916return false;917}918919if (!rc_calibration_checks(report)) {920return false;921}922}923924return rc_in_calibration_check(report);925}926#endif // AP_RC_CHANNEL_ENABLED927928#if AP_MISSION_ENABLED929bool AP_Arming::mission_checks(bool report)930{931AP_Mission *mission = AP::mission();932if (check_enabled(Check::MISSION) && _required_mission_items) {933if (mission == nullptr) {934check_failed(Check::MISSION, report, "No mission library present");935return false;936}937938const struct MisItemTable {939MIS_ITEM_CHECK check;940MAV_CMD mis_item_type;941const char *type;942} misChecks[] = {943{MIS_ITEM_CHECK_LAND, MAV_CMD_NAV_LAND, "land"},944{MIS_ITEM_CHECK_VTOL_LAND, MAV_CMD_NAV_VTOL_LAND, "vtol land"},945{MIS_ITEM_CHECK_DO_LAND_START, MAV_CMD_DO_LAND_START, "do land start"},946{MIS_ITEM_CHECK_TAKEOFF, MAV_CMD_NAV_TAKEOFF, "takeoff"},947{MIS_ITEM_CHECK_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_TAKEOFF, "vtol takeoff"},948{MIS_ITEM_CHECK_RETURN_TO_LAUNCH, MAV_CMD_NAV_RETURN_TO_LAUNCH, "RTL"},949};950for (uint8_t i = 0; i < ARRAY_SIZE(misChecks); i++) {951if (_required_mission_items & misChecks[i].check) {952if (!mission->contains_item(misChecks[i].mis_item_type)) {953check_failed(Check::MISSION, report, "Missing mission item: %s", misChecks[i].type);954return false;955}956}957}958if (_required_mission_items & MIS_ITEM_CHECK_RALLY) {959#if HAL_RALLY_ENABLED960AP_Rally *rally = AP::rally();961if (rally == nullptr) {962check_failed(Check::MISSION, report, "No rally library present");963return false;964}965Location ahrs_loc;966if (!AP::ahrs().get_location(ahrs_loc)) {967check_failed(Check::MISSION, report, "Can't check rally without position");968return false;969}970RallyLocation rally_loc = {};971if (!rally->find_nearest_rally_point(ahrs_loc, rally_loc)) {972check_failed(Check::MISSION, report, "No sufficiently close rally point located");973return false;974}975#else976check_failed(Check::MISSION, report, "No rally library present");977return false;978#endif979}980}981982#if AP_SDCARD_STORAGE_ENABLED983if (check_enabled(Check::MISSION) &&984mission != nullptr &&985(mission->failed_sdcard_storage() || StorageManager::storage_failed())) {986check_failed(Check::MISSION, report, "Failed to open %s", AP_MISSION_SDCARD_FILENAME);987return false;988}989#endif990991#if AP_VEHICLE_ENABLED992// do not allow arming if there are no mission items and we are in993// (e.g.) AUTO mode994if (AP::vehicle()->current_mode_requires_mission() &&995(mission == nullptr || !mission->present())) {996check_failed(Check::MISSION, report, "Mode requires mission");997return false;998}999#endif10001001return true;1002}1003#endif // AP_MISSION_ENABLED10041005bool AP_Arming::rangefinder_checks(bool report)1006{1007#if AP_RANGEFINDER_ENABLED1008if (check_enabled(Check::RANGEFINDER)) {1009RangeFinder *range = RangeFinder::get_singleton();1010if (range == nullptr) {1011return true;1012}10131014char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];1015if (!range->prearm_healthy(buffer, ARRAY_SIZE(buffer))) {1016check_failed(Check::RANGEFINDER, report, "%s", buffer);1017return false;1018}1019}1020#endif10211022return true;1023}10241025bool AP_Arming::servo_checks(bool report) const1026{1027#if NUM_SERVO_CHANNELS1028bool check_passed = true;1029for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {1030const SRV_Channel *c = SRV_Channels::srv_channel(i);1031if (c == nullptr || c->get_function() <= SRV_Channel::k_none) {1032continue;1033}10341035const uint16_t trim = c->get_trim();1036if (c->get_output_min() > trim) {1037check_failed(report, "SERVO%d_MIN is greater than SERVO%d_TRIM", i + 1, i + 1);1038check_passed = false;1039}1040if (c->get_output_max() < trim) {1041check_failed(report, "SERVO%d_MAX is less than SERVO%d_TRIM", i + 1, i + 1);1042check_passed = false;1043}10441045// check functions using PWM are enabled1046if (SRV_Channels::get_disabled_channel_mask() & 1U<<i) {1047const SRV_Channel::Function ch_function = c->get_function();10481049// motors, e-stoppable functions, neopixels and ProfiLEDs may be digital outputs and thus can be disabled1050// scripting can use its functions as labels for LED setup1051const bool disabled_ok = SRV_Channel::is_motor(ch_function) ||1052SRV_Channel::should_e_stop(ch_function) ||1053(ch_function >= SRV_Channel::k_LED_neopixel1 && ch_function <= SRV_Channel::k_LED_neopixel4) ||1054(ch_function >= SRV_Channel::k_ProfiLED_1 && ch_function <= SRV_Channel::k_ProfiLED_Clock) ||1055(ch_function >= SRV_Channel::k_scripting1 && ch_function <= SRV_Channel::k_scripting16);10561057// for all other functions raise a pre-arm failure1058if (!disabled_ok) {1059check_failed(report, "SERVO%u_FUNCTION=%u on disabled channel", i + 1, (unsigned)ch_function);1060check_passed = false;1061}1062}1063}10641065#if HAL_WITH_IO_MCU1066if (!iomcu.healthy() && AP_BoardConfig::io_enabled()) {1067check_failed(report, "IOMCU is unhealthy");1068check_passed = false;1069}1070#endif10711072return check_passed;1073#else1074return false;1075#endif1076}10771078bool AP_Arming::board_voltage_checks(bool report)1079{1080// check board voltage1081if (check_enabled(Check::VOLTAGE)) {1082#if HAL_HAVE_BOARD_VOLTAGE1083const float bus_voltage = hal.analogin->board_voltage();1084const float vbus_min = AP_BoardConfig::get_minimum_board_voltage();1085if(((bus_voltage < vbus_min) || (bus_voltage > AP_ARMING_BOARD_VOLTAGE_MAX))) {1086check_failed(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);1087return false;1088}1089#endif // HAL_HAVE_BOARD_VOLTAGE10901091#if HAL_HAVE_SERVO_VOLTAGE1092const float vservo_min = AP_BoardConfig::get_minimum_servo_voltage();1093if (is_positive(vservo_min)) {1094const float servo_voltage = hal.analogin->servorail_voltage();1095if (servo_voltage < vservo_min) {1096check_failed(Check::VOLTAGE, report, "Servo voltage to low (%1.2fv < %1.2fv)", (double)servo_voltage, (double)vservo_min);1097return false;1098}1099}1100#endif // HAL_HAVE_SERVO_VOLTAGE1101}11021103return true;1104}11051106#if HAL_HAVE_IMU_HEATER1107bool AP_Arming::heater_min_temperature_checks(bool report)1108{1109if (all_checks_enabled()) {1110AP_BoardConfig *board = AP::boardConfig();1111if (board) {1112float temperature;1113int8_t min_temperature;1114if (board->get_board_heater_temperature(temperature) &&1115board->get_board_heater_arming_temperature(min_temperature) &&1116(temperature < min_temperature)) {1117check_failed(Check::SYSTEM, report, "heater temp low (%0.1f < %i)", temperature, min_temperature);1118return false;1119}1120}1121}1122return true;1123}1124#endif // HAL_HAVE_IMU_HEATER11251126/*1127check base system operations1128*/1129bool AP_Arming::system_checks(bool report)1130{1131char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};11321133if (check_enabled(Check::SYSTEM)) {1134if (!hal.storage->healthy()) {1135check_failed(Check::SYSTEM, report, "Param storage failed");1136return false;1137}11381139if (AP_Param::get_eeprom_full()) {1140check_failed(Check::PARAMETERS, report, "parameter storage full");1141return false;1142}11431144// check main loop rate is at least 90% of expected value1145const float actual_loop_rate = AP::scheduler().get_filtered_loop_rate_hz();1146const uint16_t expected_loop_rate = AP::scheduler().get_loop_rate_hz();1147const float loop_rate_pct = actual_loop_rate / expected_loop_rate;1148if (loop_rate_pct < 0.90) {1149check_failed(Check::SYSTEM, report, "Main loop slow (%uHz < %uHz)", (unsigned)actual_loop_rate, (unsigned)expected_loop_rate);1150return false;1151}11521153#if AP_TERRAIN_AVAILABLE1154const AP_Terrain *terrain = AP_Terrain::get_singleton();1155if ((terrain != nullptr) && terrain->init_failed()) {1156check_failed(Check::SYSTEM, report, "Terrain out of memory");1157return false;1158}1159#endif1160#if AP_SCRIPTING_ENABLED1161const AP_Scripting *scripting = AP_Scripting::get_singleton();1162if ((scripting != nullptr) && !scripting->arming_checks(sizeof(buffer), buffer)) {1163check_failed(Check::SYSTEM, report, "%s", buffer);1164return false;1165}1166#endif1167#if HAL_ADSB_ENABLED1168AP_ADSB *adsb = AP::ADSB();1169if ((adsb != nullptr) && adsb->enabled() && adsb->init_failed()) {1170check_failed(Check::SYSTEM, report, "ADSB out of memory");1171return false;1172}1173#endif1174}1175if (AP::internalerror().errors() != 0) {1176AP::internalerror().errors_as_string((uint8_t*)buffer, ARRAY_SIZE(buffer));1177check_failed(report, "Internal errors 0x%x l:%u %s", (unsigned int)AP::internalerror().errors(), AP::internalerror().last_error_line(), buffer);1178return false;1179}11801181if (!hal.gpio->arming_checks(sizeof(buffer), buffer)) {1182check_failed(report, "%s", buffer);1183return false;1184}11851186if (check_enabled(Check::PARAMETERS)) {1187#if !AP_GPS_BLENDED_ENABLED1188if (!blending_auto_switch_checks(report)) {1189return false;1190}1191#endif1192#if AP_RPM_ENABLED1193auto *rpm = AP::rpm();1194if (rpm && !rpm->arming_checks(sizeof(buffer), buffer)) {1195check_failed(Check::PARAMETERS, report, "%s", buffer);1196return false;1197}1198#endif1199#if AP_RELAY_ENABLED1200auto *relay = AP::relay();1201if (relay && !relay->arming_checks(sizeof(buffer), buffer)) {1202check_failed(Check::PARAMETERS, report, "%s", buffer);1203return false;1204}1205#endif1206#if HAL_PARACHUTE_ENABLED1207auto *chute = AP::parachute();1208if (chute && !chute->arming_checks(sizeof(buffer), buffer)) {1209check_failed(Check::PARAMETERS, report, "%s", buffer);1210return false;1211}1212#endif1213#if HAL_BUTTON_ENABLED1214const auto &button = AP::button();1215if (!button.arming_checks(sizeof(buffer), buffer)) {1216check_failed(Check::PARAMETERS, report, "%s", buffer);1217return false;1218}1219#endif1220}12211222return true;1223}12241225bool AP_Arming::terrain_database_required() const1226{1227#if AP_MISSION_ENABLED1228AP_Mission *mission = AP::mission();1229if (mission == nullptr) {1230// no mission support?1231return false;1232}1233if (mission->contains_terrain_alt_items()) {1234return true;1235}1236#endif1237return false;1238}12391240// check terrain database is fit-for-purpose1241bool AP_Arming::terrain_checks(bool report) const1242{1243if (!check_enabled(Check::PARAMETERS)) {1244return true;1245}12461247if (!terrain_database_required()) {1248return true;1249}12501251#if AP_TERRAIN_AVAILABLE12521253const AP_Terrain *terrain = AP_Terrain::get_singleton();1254if (terrain == nullptr) {1255check_failed(Check::PARAMETERS, report, "terrain disabled");1256return false;1257}12581259if (!terrain->enabled()) {1260check_failed(Check::PARAMETERS, report, "terrain disabled");1261return false;1262}12631264char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];1265if (!terrain->pre_arm_checks(fail_msg, sizeof(fail_msg))) {1266check_failed(Check::PARAMETERS, report, "%s", fail_msg);1267return false;1268}12691270return true;12711272#else1273check_failed(Check::PARAMETERS, report, "terrain required but disabled");1274return false;1275#endif1276}127712781279#if HAL_PROXIMITY_ENABLED1280// check nothing is too close to vehicle1281bool AP_Arming::proximity_checks(bool report) const1282{1283const AP_Proximity *proximity = AP::proximity();1284// return true immediately if no sensor present1285if (proximity == nullptr) {1286return true;1287}1288char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];1289if (!proximity->prearm_healthy(buffer, ARRAY_SIZE(buffer))) {1290check_failed(report, "%s", buffer);1291return false;1292}1293return true;1294}1295#endif // HAL_PROXIMITY_ENABLED12961297#if HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED1298bool AP_Arming::can_checks(bool report)1299{1300if (check_enabled(Check::SYSTEM)) {1301char fail_msg[100] = {};1302(void)fail_msg; // might be left unused1303uint8_t num_drivers = AP::can().get_num_drivers();13041305for (uint8_t i = 0; i < num_drivers; i++) {1306switch (AP::can().get_driver_type(i)) {1307case AP_CAN::Protocol::PiccoloCAN: {1308#if AP_PICCOLOCAN_ENABLED1309AP_PiccoloCAN *ap_pcan = AP_PiccoloCAN::get_pcan(i);13101311if (ap_pcan != nullptr && !ap_pcan->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {1312check_failed(Check::SYSTEM, report, "PiccoloCAN: %s", fail_msg);1313return false;1314}13151316#else1317check_failed(Check::SYSTEM, report, "PiccoloCAN not enabled");1318return false;1319#endif1320break;1321}1322case AP_CAN::Protocol::DroneCAN:1323{1324#if HAL_ENABLE_DRONECAN_DRIVERS1325AP_DroneCAN *ap_dronecan = AP_DroneCAN::get_dronecan(i);1326if (ap_dronecan != nullptr && !ap_dronecan->prearm_check(fail_msg, ARRAY_SIZE(fail_msg))) {1327check_failed(Check::SYSTEM, report, "DroneCAN: %s", fail_msg);1328return false;1329}1330#endif1331break;1332}1333case AP_CAN::Protocol::USD1:1334case AP_CAN::Protocol::TOFSenseP:1335case AP_CAN::Protocol::RadarCAN:1336case AP_CAN::Protocol::Benewake:1337{1338for (uint8_t j = i; j; j--) {1339if (AP::can().get_driver_type(i) == AP::can().get_driver_type(j-1)) {1340check_failed(Check::SYSTEM, report, "Same rfnd on different CAN ports");1341return false;1342}1343}1344break;1345}1346case AP_CAN::Protocol::EFI_NWPMU:1347case AP_CAN::Protocol::None:1348case AP_CAN::Protocol::Scripting:1349case AP_CAN::Protocol::Scripting2:1350case AP_CAN::Protocol::KDECAN:13511352break;1353}1354}1355}1356return true;1357}1358#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED135913601361#if AP_FENCE_ENABLED1362bool AP_Arming::fence_checks(bool display_failure)1363{1364const AC_Fence *fence = AP::fence();1365if (fence == nullptr) {1366return true;1367}13681369// check fence is ready1370char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];1371if (fence->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {1372return true;1373}13741375check_failed(display_failure, "%s", fail_msg);13761377#if AP_SDCARD_STORAGE_ENABLED1378if (fence->failed_sdcard_storage() || StorageManager::storage_failed()) {1379check_failed(display_failure, "Failed to open fence storage");1380return false;1381}1382#endif13831384return false;1385}1386#endif // AP_FENCE_ENABLED13871388#if AP_CAMERA_RUNCAM_ENABLED1389bool AP_Arming::camera_checks(bool display_failure)1390{1391if (check_enabled(Check::CAMERA)) {1392AP_RunCam *runcam = AP::runcam();1393if (runcam == nullptr) {1394return true;1395}13961397// check camera is ready1398char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];1399if (!runcam->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {1400check_failed(Check::CAMERA, display_failure, "%s", fail_msg);1401return false;1402}1403}1404return true;1405}1406#endif // AP_CAMERA_RUNCAM_ENABLED14071408#if OSD_ENABLED1409bool AP_Arming::osd_checks(bool display_failure) const1410{1411if (check_enabled(Check::OSD)) {1412// if no OSD then pass1413const AP_OSD *osd = AP::osd();1414if (osd == nullptr) {1415return true;1416}1417// do osd checks for configuration1418char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];1419if (!osd->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {1420check_failed(Check::OSD, display_failure, "%s", fail_msg);1421return false;1422}1423}1424return true;1425}1426#endif // OSD_ENABLED14271428#if HAL_MOUNT_ENABLED1429bool AP_Arming::mount_checks(bool display_failure) const1430{1431if (check_enabled(Check::CAMERA)) {1432AP_Mount *mount = AP::mount();1433if (mount == nullptr) {1434return true;1435}1436char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] = {};1437if (!mount->pre_arm_checks(fail_msg, sizeof(fail_msg))) {1438check_failed(Check::CAMERA, display_failure, "Mount: %s", fail_msg);1439return false;1440}1441}1442return true;1443}1444#endif // HAL_MOUNT_ENABLED14451446#if AP_FETTEC_ONEWIRE_ENABLED1447bool AP_Arming::fettec_checks(bool display_failure) const1448{1449const AP_FETtecOneWire *f = AP_FETtecOneWire::get_singleton();1450if (f == nullptr) {1451return true;1452}14531454// check ESCs are ready1455char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];1456if (!f->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {1457check_failed(display_failure, "FETtec: %s", fail_msg);1458return false;1459}1460return true;1461}1462#endif // AP_FETTEC_ONEWIRE_ENABLED14631464#if AP_ARMING_AUX_AUTH_ENABLED1465// request an auxiliary authorisation id. This id should be used in subsequent calls to set_aux_auth_passed/failed1466// returns true on success1467bool AP_Arming::get_aux_auth_id(uint8_t& auth_id)1468{1469WITH_SEMAPHORE(aux_auth_sem);14701471// check we have enough room to allocate another id1472if (aux_auth_count >= aux_auth_count_max) {1473aux_auth_error = true;1474return false;1475}14761477// allocate buffer for failure message1478if (aux_auth_fail_msg == nullptr) {1479aux_auth_fail_msg = (char *)calloc(aux_auth_str_len, sizeof(char));1480if (aux_auth_fail_msg == nullptr) {1481aux_auth_error = true;1482return false;1483}1484}1485auth_id = aux_auth_count;1486aux_auth_count++;1487return true;1488}14891490// set auxiliary authorisation passed1491void AP_Arming::set_aux_auth_passed(uint8_t auth_id)1492{1493WITH_SEMAPHORE(aux_auth_sem);14941495// sanity check auth_id1496if (auth_id >= aux_auth_count) {1497return;1498}14991500aux_auth_state[auth_id] = AuxAuthStates::AUTH_PASSED;1501}15021503// set auxiliary authorisation failed and provide failure message1504void AP_Arming::set_aux_auth_failed(uint8_t auth_id, const char* fail_msg)1505{1506WITH_SEMAPHORE(aux_auth_sem);15071508// sanity check auth_id1509if (auth_id >= aux_auth_count) {1510return;1511}15121513// update state1514aux_auth_state[auth_id] = AuxAuthStates::AUTH_FAILED;15151516// store failure message if this authoriser has the lowest auth_id1517for (uint8_t i = 0; i < auth_id; i++) {1518if (aux_auth_state[i] == AuxAuthStates::AUTH_FAILED) {1519return;1520}1521}1522if (aux_auth_fail_msg != nullptr) {1523if (fail_msg == nullptr) {1524strncpy(aux_auth_fail_msg, "Auxiliary authorisation refused", aux_auth_str_len);1525} else {1526strncpy(aux_auth_fail_msg, fail_msg, aux_auth_str_len);1527}1528aux_auth_fail_msg_source = auth_id;1529}1530}15311532void AP_Arming::reset_all_aux_auths()1533{1534WITH_SEMAPHORE(aux_auth_sem);15351536// clear all auxiliary authorisation ids1537aux_auth_count = 0;1538// clear any previous allocation errors1539aux_auth_error = false;15401541// reset states for all auxiliary authorisation ids1542for (uint8_t i = 0; i < aux_auth_count_max; i++) {1543aux_auth_state[i] = AuxAuthStates::NO_RESPONSE;1544}15451546// free up the failure message buffer1547if (aux_auth_fail_msg != nullptr) {1548free(aux_auth_fail_msg);1549aux_auth_fail_msg = nullptr;1550}1551}15521553bool AP_Arming::aux_auth_checks(bool display_failure)1554{1555// handle error cases1556if (aux_auth_error) {1557if (aux_auth_fail_msg == nullptr) {1558check_failed(Check::AUX_AUTH, display_failure, "memory low for auxiliary authorisation");1559} else {1560check_failed(Check::AUX_AUTH, display_failure, "Too many auxiliary authorisers");1561}1562return false;1563}15641565WITH_SEMAPHORE(aux_auth_sem);15661567// check results for each auxiliary authorisation id1568bool some_failures = false;1569bool failure_msg_sent = false;1570bool waiting_for_responses = false;1571for (uint8_t i = 0; i < aux_auth_count; i++) {1572switch (aux_auth_state[i]) {1573case AuxAuthStates::NO_RESPONSE:1574waiting_for_responses = true;1575break;1576case AuxAuthStates::AUTH_FAILED:1577some_failures = true;1578if (i == aux_auth_fail_msg_source) {1579check_failed(Check::AUX_AUTH, display_failure, "%s", aux_auth_fail_msg);1580failure_msg_sent = true;1581}1582break;1583case AuxAuthStates::AUTH_PASSED:1584break;1585}1586}15871588// send failure or waiting message1589if (some_failures) {1590if (!failure_msg_sent) {1591check_failed(Check::AUX_AUTH, display_failure, "Auxiliary authorisation refused");1592}1593return false;1594} else if (waiting_for_responses) {1595check_failed(Check::AUX_AUTH, display_failure, "Waiting for auxiliary authorisation");1596return false;1597}15981599// if we got this far all auxiliary checks must have passed1600return true;1601}1602#endif // AP_ARMING_AUX_AUTH_ENABLED16031604#if HAL_GENERATOR_ENABLED1605bool AP_Arming::generator_checks(bool display_failure) const1606{1607const AP_Generator *generator = AP::generator();1608if (generator == nullptr) {1609return true;1610}1611char failure_msg[100] = {};1612if (!generator->pre_arm_check(failure_msg, sizeof(failure_msg))) {1613check_failed(display_failure, "Generator: %s", failure_msg);1614return false;1615}1616return true;1617}1618#endif // HAL_GENERATOR_ENABLED16191620#if AP_OPENDRONEID_ENABLED1621// OpenDroneID Checks1622bool AP_Arming::opendroneid_checks(bool display_failure)1623{1624auto &opendroneid = AP::opendroneid();16251626char failure_msg[100] {};1627if (!opendroneid.pre_arm_check(failure_msg, sizeof(failure_msg))) {1628check_failed(display_failure, "OpenDroneID: %s", failure_msg);1629return false;1630}1631return true;1632}1633#endif // AP_OPENDRONEID_ENABLED16341635//Check for multiple RC in serial protocols1636bool AP_Arming::serial_protocol_checks(bool display_failure)1637{1638if (AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_RCIN, 1)) {1639check_failed(display_failure, "Multiple SERIAL ports configured for RC input");1640return false;1641}1642char failure_msg[100] = {};1643if (!AP::serialmanager().pre_arm_checks(failure_msg, ARRAY_SIZE(failure_msg))) {1644check_failed(display_failure, "%s", failure_msg);1645return false;1646}1647return true;1648}16491650//Check for estop1651bool AP_Arming::estop_checks(bool display_failure)1652{1653if (!SRV_Channels::get_emergency_stop()) {1654// not emergency-stopped, so no prearm failure:1655return true;1656}1657#if AP_RC_CHANNEL_ENABLED1658// vehicle is emergency-stopped; if this *appears* to have been done via switch then we do not fail prearms:1659const RC_Channel *chan = rc().find_channel_for_option(RC_Channel::AUX_FUNC::ARM_EMERGENCY_STOP);1660if (chan != nullptr) {1661// an RC channel is configured for arm_emergency_stop option, so estop maybe activated via this switch1662if (chan->get_aux_switch_pos() == RC_Channel::AuxSwitchPos::LOW) {1663// switch is configured and is in estop position, so likely the reason we are estopped, so no prearm failure1664return true; // no prearm failure1665}1666}1667#endif // AP_RC_CHANNEL_ENABLED1668check_failed(display_failure,"Motors Emergency Stopped");1669return false;1670}16711672bool AP_Arming::pre_arm_checks(bool report)1673{1674#if !APM_BUILD_COPTER_OR_HELI1675if (armed || arming_required() == Required::NO) {1676// if we are already armed or don't need any arming checks1677// then skip the checks1678return true;1679}1680#endif16811682bool checks_result = hardware_safety_check(report)1683#if HAL_HAVE_IMU_HEATER1684& heater_min_temperature_checks(report)1685#endif1686#if AP_BARO_ENABLED1687& barometer_checks(report)1688#endif1689#if AP_INERTIALSENSOR_ENABLED1690& ins_checks(report)1691#endif1692#if AP_COMPASS_ENABLED1693& compass_checks(report)1694#endif1695#if AP_GPS_ENABLED1696& gps_checks(report)1697#endif1698#if AP_BATTERY_ENABLED1699& battery_checks(report)1700#endif1701#if HAL_LOGGING_ENABLED1702& logging_checks(report)1703#endif1704#if AP_RC_CHANNEL_ENABLED1705& manual_transmitter_checks(report)1706#endif1707#if AP_MISSION_ENABLED1708& mission_checks(report)1709#endif1710#if AP_RANGEFINDER_ENABLED1711& rangefinder_checks(report)1712#endif1713& servo_checks(report)1714& board_voltage_checks(report)1715& system_checks(report)1716& terrain_checks(report)1717#if HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED1718& can_checks(report)1719#endif1720#if HAL_GENERATOR_ENABLED1721& generator_checks(report)1722#endif1723#if HAL_PROXIMITY_ENABLED1724& proximity_checks(report)1725#endif1726#if AP_CAMERA_RUNCAM_ENABLED1727& camera_checks(report)1728#endif1729#if OSD_ENABLED1730& osd_checks(report)1731#endif1732#if HAL_MOUNT_ENABLED1733& mount_checks(report)1734#endif1735#if AP_FETTEC_ONEWIRE_ENABLED1736& fettec_checks(report)1737#endif1738#if HAL_VISUALODOM_ENABLED1739& visodom_checks(report)1740#endif1741#if AP_ARMING_AUX_AUTH_ENABLED1742& aux_auth_checks(report)1743#endif1744#if AP_RC_CHANNEL_ENABLED1745& disarm_switch_checks(report)1746#endif1747#if AP_FENCE_ENABLED1748& fence_checks(report)1749#endif1750#if AP_OPENDRONEID_ENABLED1751& opendroneid_checks(report)1752#endif1753#if AP_ARMING_CRASHDUMP_ACK_ENABLED1754& crashdump_checks(report)1755#endif1756& serial_protocol_checks(report)1757& estop_checks(report);17581759if (!checks_result && last_prearm_checks_result) { // check went from true to false1760report_immediately = true;1761}1762last_prearm_checks_result = checks_result;17631764return checks_result;1765}17661767bool AP_Arming::arm_checks(AP_Arming::Method method)1768{1769#if AP_RC_CHANNEL_ENABLED1770if (check_enabled(Check::RC)) {1771if (!rc_arm_checks(method)) {1772return false;1773}1774}1775#endif17761777// ensure the GPS drivers are ready on any final changes1778if (check_enabled(Check::GPS_CONFIG)) {1779if (!AP::gps().prepare_for_arming()) {1780return false;1781}1782}17831784// note that this will prepare AP_Logger to start logging1785// so should be the last check to be done before arming17861787// Note also that we need to PrepForArming() regardless of whether1788// the arming check flag is set - disabling the arming check1789// should not stop logging from working.17901791#if HAL_LOGGING_ENABLED1792AP_Logger *logger = AP_Logger::get_singleton();1793if (logger->logging_present()) {1794// If we're configured to log, prep it1795logger->PrepForArming();1796if (!logger->logging_started() &&1797check_enabled(Check::LOGGING)) {1798check_failed(Check::LOGGING, true, "Logging not started");1799return false;1800}1801}1802#endif // HAL_LOGGING_ENABLED18031804return true;1805}18061807#if !AP_GPS_BLENDED_ENABLED1808bool AP_Arming::blending_auto_switch_checks(bool report)1809{1810if (AP::gps().get_auto_switch_type() == 2) {1811if (report) {1812check_failed(Check::GPS, true, "GPS_AUTO_SWITCH==2 but no blending");1813}1814return false;1815}1816return true;1817}1818#endif18191820#if AP_ARMING_CRASHDUMP_ACK_ENABLED1821bool AP_Arming::crashdump_checks(bool report)1822{1823if (hal.util->last_crash_dump_size() == 0) {1824// no crash dump data1825return true;1826}18271828// see if the user has acknowledged the failure and wants to fly anyway:1829if (crashdump_ack.acked) {1830// they may have acked the problem, that doesn't mean we don't1831// continue to warn them they're on thin ice:1832if (report) {1833GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "CrashDump data detected");1834}1835return true;1836}18371838check_failed(Check::PARAMETERS, report, "CrashDump data detected");18391840return false;1841}1842#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED18431844bool AP_Arming::mandatory_checks(bool report)1845{1846bool ret = true;1847#if AP_OPENDRONEID_ENABLED1848ret &= opendroneid_checks(report);1849#endif1850ret &= rc_in_calibration_check(report);1851ret &= serial_protocol_checks(report);1852return ret;1853}18541855//returns true if arming occurred successfully1856bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks)1857{1858if (armed) { //already armed1859return false;1860}18611862if (method == Method::RUDDER) {1863switch (get_rudder_arming_type()) {1864case AP_Arming::RudderArming::IS_DISABLED:1865//parameter disallows rudder arming/disabling1866return false;1867case AP_Arming::RudderArming::ARMONLY:1868case AP_Arming::RudderArming::ARMDISARM:1869break;1870}1871}18721873running_arming_checks = true; // so we show Arm: rather than Disarm: in messages18741875if ((!do_arming_checks && mandatory_checks(true)) || (pre_arm_checks(true) && arm_checks(method))) {1876armed = true;1877last_arm_time_us = AP_HAL::micros64();18781879_last_arm_method = method;18801881#if HAL_LOGGING_ENABLED1882Log_Write_Arm(!do_arming_checks, method); // note Log_Write_Armed takes forced not do_arming_checks1883#endif18841885} else {1886#if HAL_LOGGING_ENABLED1887AP::logger().arming_failure();1888#endif1889armed = false;1890}18911892running_arming_checks = false;18931894if (armed && do_arming_checks && should_skip_all_checks()) {1895GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Warning: Arming Checks Disabled");1896}18971898#if HAL_GYROFFT_ENABLED1899// make sure the FFT subsystem is enabled if arming checks have been disabled1900AP_GyroFFT *fft = AP::fft();1901if (fft != nullptr) {1902fft->prepare_for_arming();1903}1904#endif19051906#if AP_TERRAIN_AVAILABLE1907if (armed) {1908// tell terrain we have just armed, so it can setup1909// a reference location for terrain adjustment1910auto *terrain = AP::terrain();1911if (terrain != nullptr) {1912terrain->set_reference_location();1913}1914}1915#endif19161917#if AP_FENCE_ENABLED1918if (armed) {1919auto *fence = AP::fence();1920if (fence != nullptr) {1921fence->auto_enable_fence_on_arming();1922}1923}1924#endif1925#if defined(HAL_ARM_GPIO_PIN)1926update_arm_gpio();1927#endif1928return armed;1929}19301931//returns true if disarming occurred successfully1932bool AP_Arming::disarm(const AP_Arming::Method method, bool do_disarm_checks)1933{1934if (!armed) { // already disarmed1935return false;1936}1937if (method == AP_Arming::Method::RUDDER) {1938// if throttle is not down, then pilot cannot rudder arm/disarm1939if (rc().get_throttle_channel().get_control_in() > 0) {1940return false;1941}1942// option must be enabled:1943if (get_rudder_arming_type() != AP_Arming::RudderArming::ARMDISARM) {1944gcs().send_text(MAV_SEVERITY_INFO, "Disarm: rudder disarm disabled");1945return false;1946}1947}1948armed = false;1949_last_disarm_method = method;19501951#if HAL_LOGGING_ENABLED1952Log_Write_Disarm(!do_disarm_checks, method); // Log_Write_Disarm takes "force"19531954check_forced_logging(method);1955#endif19561957#if HAL_HAVE_SAFETY_SWITCH1958AP_BoardConfig *board_cfg = AP_BoardConfig::get_singleton();1959if ((board_cfg != nullptr) &&1960(board_cfg->get_safety_button_options() & AP_BoardConfig::BOARD_SAFETY_OPTION_SAFETY_ON_DISARM)) {1961hal.rcout->force_safety_on();1962}1963#endif // HAL_HAVE_SAFETY_SWITCH19641965#if HAL_GYROFFT_ENABLED1966AP_GyroFFT *fft = AP::fft();1967if (fft != nullptr) {1968fft->save_params_on_disarm();1969}1970#endif19711972#if AP_FENCE_ENABLED1973AC_Fence *fence = AP::fence();1974if (fence != nullptr) {1975fence->auto_disable_fence_on_disarming();1976}1977#endif1978#if defined(HAL_ARM_GPIO_PIN)1979update_arm_gpio();1980#endif1981return true;1982}19831984#if defined(HAL_ARM_GPIO_PIN)1985void AP_Arming::update_arm_gpio()1986{1987if (!AP_BoardConfig::arming_gpio_disabled()) {1988hal.gpio->write(HAL_ARM_GPIO_PIN, HAL_ARM_GPIO_POL_INVERT ? !armed : armed);1989}1990}1991#endif19921993void AP_Arming::send_arm_disarm_statustext(const char *str) const1994{1995if (option_enabled(AP_Arming::Option::DISABLE_STATUSTEXT_ON_STATE_CHANGE)) {1996return;1997}1998GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s", str);1999}20002001AP_Arming::Required AP_Arming::arming_required() const2002{2003#if AP_OPENDRONEID_ENABLED2004// cannot be disabled if OpenDroneID is present2005if (AP_OpenDroneID::get_singleton() != nullptr && AP::opendroneid().enabled()) {2006if (require != Required::YES_MIN_PWM && require != Required::YES_ZERO_PWM) {2007return Required::YES_MIN_PWM;2008}2009}2010#endif2011return require;2012}20132014#if AP_RC_CHANNEL_ENABLED2015// Copter and sub share the same RC input limits2016// Copter checks that min and max have been configured by default, Sub does not2017bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channel *channels[4]) const2018{2019// set rc-checks to success if RC checks are disabled2020if (!check_enabled(Check::RC)) {2021return true;2022}20232024bool ret = true;20252026const char *channel_names[] = { "Roll", "Pitch", "Throttle", "Yaw" };20272028for (uint8_t i=0; i<ARRAY_SIZE(channel_names);i++) {2029const RC_Channel *channel = channels[i];2030const char *channel_name = channel_names[i];2031// check if radio has been calibrated2032if (channel->get_radio_min() > RC_Channel::RC_CALIB_MIN_LIMIT_PWM) {2033check_failed(Check::RC, display_failure, "%s radio min too high", channel_name);2034ret = false;2035}2036if (channel->get_radio_max() < RC_Channel::RC_CALIB_MAX_LIMIT_PWM) {2037check_failed(Check::RC, display_failure, "%s radio max too low", channel_name);2038ret = false;2039}2040}2041return ret;2042}2043#endif // AP_RC_CHANNEL_ENABLED20442045#if HAL_VISUALODOM_ENABLED2046// check visual odometry is working2047bool AP_Arming::visodom_checks(bool display_failure) const2048{2049if (!check_enabled(Check::VISION)) {2050return true;2051}20522053AP_VisualOdom *visual_odom = AP::visualodom();2054if (visual_odom != nullptr) {2055char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];2056if (!visual_odom->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {2057check_failed(Check::VISION, display_failure, "VisOdom: %s", fail_msg);2058return false;2059}2060}20612062return true;2063}2064#endif20652066#if AP_RC_CHANNEL_ENABLED2067// check disarm switch is asserted2068bool AP_Arming::disarm_switch_checks(bool display_failure) const2069{2070const RC_Channel *chan = rc().find_channel_for_option(RC_Channel::AUX_FUNC::DISARM);2071if (chan != nullptr &&2072chan->get_aux_switch_pos() == RC_Channel::AuxSwitchPos::HIGH) {2073check_failed(display_failure, "Disarm Switch on");2074return false;2075}20762077return true;2078}2079#endif // AP_RC_CHANNEL_ENABLED20802081#if HAL_LOGGING_ENABLED2082void AP_Arming::Log_Write_Arm(const bool forced, const AP_Arming::Method method)2083{2084const struct log_Arm_Disarm pkt {2085LOG_PACKET_HEADER_INIT(LOG_ARM_DISARM_MSG),2086time_us : AP_HAL::micros64(),2087arm_state : is_armed(),2088arm_checks : get_enabled_checks(),2089forced : forced,2090method : (uint8_t)method,2091};2092AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));2093AP::logger().Write_Event(LogEvent::ARMED);2094}20952096void AP_Arming::Log_Write_Disarm(const bool forced, const AP_Arming::Method method)2097{2098const struct log_Arm_Disarm pkt {2099LOG_PACKET_HEADER_INIT(LOG_ARM_DISARM_MSG),2100time_us : AP_HAL::micros64(),2101arm_state : is_armed(),2102arm_checks : 0,2103forced : forced,2104method : (uint8_t)method2105};2106AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));2107AP::logger().Write_Event(LogEvent::DISARMED);2108}21092110// check if we should keep logging after disarming2111void AP_Arming::check_forced_logging(const AP_Arming::Method method)2112{2113// keep logging if disarmed for a bad reason2114switch(method) {2115case Method::TERMINATION:2116case Method::CPUFAILSAFE:2117case Method::BATTERYFAILSAFE:2118case Method::AFS:2119case Method::ADSBCOLLISIONACTION:2120case Method::PARACHUTE_RELEASE:2121case Method::CRASH:2122case Method::FENCEBREACH:2123case Method::RADIOFAILSAFE:2124case Method::GCSFAILSAFE:2125case Method::TERRRAINFAILSAFE:2126case Method::FAILSAFE_ACTION_TERMINATE:2127case Method::TERRAINFAILSAFE:2128case Method::BADFLOWOFCONTROL:2129case Method::EKFFAILSAFE:2130case Method::GCS_FAILSAFE_SURFACEFAILED:2131case Method::GCS_FAILSAFE_HOLDFAILED:2132case Method::PILOT_INPUT_FAILSAFE:2133case Method::DEADRECKON_FAILSAFE:2134case Method::BLACKBOX:2135// keep logging for longer if disarmed for a bad reason2136AP::logger().set_long_log_persist(true);2137return;21382139case Method::RUDDER:2140case Method::TOYMODE:2141case Method::MAVLINK:2142case Method::AUXSWITCH:2143case Method::MOTORTEST:2144case Method::SCRIPTING:2145case Method::SOLOPAUSEWHENLANDED:2146case Method::LANDED:2147case Method::MISSIONEXIT:2148case Method::DISARMDELAY:2149case Method::MOTORDETECTDONE:2150case Method::TAKEOFFTIMEOUT:2151case Method::AUTOLANDED:2152case Method::TOYMODELANDTHROTTLE:2153case Method::TOYMODELANDFORCE:2154case Method::LANDING:2155case Method::DDS:2156case Method::AUTO_ARM_ONCE:2157case Method::TURTLE_MODE:2158case Method::UNKNOWN:2159AP::logger().set_long_log_persist(false);2160return;2161}2162}2163#endif // HAL_LOGGING_ENABLED21642165AP_Arming *AP_Arming::_singleton = nullptr;21662167/*2168* Get the AP_Arming singleton2169*/2170AP_Arming *AP_Arming::get_singleton()2171{2172return AP_Arming::_singleton;2173}21742175namespace AP {21762177AP_Arming &arming()2178{2179return *AP_Arming::get_singleton();2180}21812182};21832184#pragma GCC diagnostic pop21852186#endif // AP_ARMING_ENABLED218721882189