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.h
Views: 1798
#pragma once12#include <AP_HAL/AP_HAL_Boards.h>3#include <AP_HAL/Semaphores.h>4#include <AP_Param/AP_Param.h>5#include <AP_GPS/AP_GPS_config.h>6#include <AP_BoardConfig/AP_BoardConfig_config.h>78#include "AP_Arming_config.h"9#include "AP_InertialSensor/AP_InertialSensor_config.h"10#include "AP_Proximity/AP_Proximity_config.h"1112class AP_Arming {13public:1415AP_Arming();1617CLASS_NO_COPY(AP_Arming); /* Do not allow copies */1819static AP_Arming *get_singleton();2021void update();2223enum ArmingChecks {24ARMING_CHECK_ALL = (1U << 0),25ARMING_CHECK_BARO = (1U << 1),26ARMING_CHECK_COMPASS = (1U << 2),27ARMING_CHECK_GPS = (1U << 3),28ARMING_CHECK_INS = (1U << 4),29ARMING_CHECK_PARAMETERS = (1U << 5),30ARMING_CHECK_RC = (1U << 6),31ARMING_CHECK_VOLTAGE = (1U << 7),32ARMING_CHECK_BATTERY = (1U << 8),33ARMING_CHECK_AIRSPEED = (1U << 9),34ARMING_CHECK_LOGGING = (1U << 10),35ARMING_CHECK_SWITCH = (1U << 11),36ARMING_CHECK_GPS_CONFIG = (1U << 12),37ARMING_CHECK_SYSTEM = (1U << 13),38ARMING_CHECK_MISSION = (1U << 14),39ARMING_CHECK_RANGEFINDER = (1U << 15),40ARMING_CHECK_CAMERA = (1U << 16),41ARMING_CHECK_AUX_AUTH = (1U << 17),42ARMING_CHECK_VISION = (1U << 18),43ARMING_CHECK_FFT = (1U << 19),44ARMING_CHECK_OSD = (1U << 20),45};4647enum class Method {48RUDDER = 0,49MAVLINK = 1,50AUXSWITCH = 2,51MOTORTEST = 3,52SCRIPTING = 4,53TERMINATION = 5, // only disarm uses this...54CPUFAILSAFE = 6, // only disarm uses this...55BATTERYFAILSAFE = 7, // only disarm uses this...56SOLOPAUSEWHENLANDED = 8, // only disarm uses this...57AFS = 9, // only disarm uses this...58ADSBCOLLISIONACTION = 10, // only disarm uses this...59PARACHUTE_RELEASE = 11, // only disarm uses this...60CRASH = 12, // only disarm uses this...61LANDED = 13, // only disarm uses this...62MISSIONEXIT = 14, // only disarm uses this...63FENCEBREACH = 15, // only disarm uses this...64RADIOFAILSAFE = 16, // only disarm uses this...65DISARMDELAY = 17, // only disarm uses this...66GCSFAILSAFE = 18, // only disarm uses this...67TERRRAINFAILSAFE = 19, // only disarm uses this...68FAILSAFE_ACTION_TERMINATE = 20, // only disarm uses this...69TERRAINFAILSAFE = 21, // only disarm uses this...70MOTORDETECTDONE = 22, // only disarm uses this...71BADFLOWOFCONTROL = 23, // only disarm uses this...72EKFFAILSAFE = 24, // only disarm uses this...73GCS_FAILSAFE_SURFACEFAILED = 25, // only disarm uses this...74GCS_FAILSAFE_HOLDFAILED = 26, // only disarm uses this...75TAKEOFFTIMEOUT = 27, // only disarm uses this...76AUTOLANDED = 28, // only disarm uses this...77PILOT_INPUT_FAILSAFE = 29, // only disarm uses this...78TOYMODELANDTHROTTLE = 30, // only disarm uses this...79TOYMODELANDFORCE = 31, // only disarm uses this...80LANDING = 32, // only disarm uses this...81DEADRECKON_FAILSAFE = 33, // only disarm uses this...82BLACKBOX = 34,83DDS = 35,84UNKNOWN = 100,85};8687enum class Required {88NO = 0,89YES_MIN_PWM = 1,90YES_ZERO_PWM = 291};9293void init(void);9495// these functions should not be used by Copter which holds the armed state in the motors library96Required arming_required() const;97virtual bool arm(AP_Arming::Method method, bool do_arming_checks=true);98virtual bool arm_force(AP_Arming::Method method) { return arm(method, false); }99virtual bool disarm(AP_Arming::Method method, bool do_disarm_checks=true);100bool is_armed() const;101bool is_armed_and_safety_off() const;102103// get bitmask of enabled checks104uint32_t get_enabled_checks() const;105106// pre_arm_checks() is virtual so it can be modified in a vehicle specific subclass107virtual bool pre_arm_checks(bool report);108109// some arming checks have side-effects, or require some form of state110// change to have occurred, and thus should not be done as pre-arm111// checks. Those go here:112virtual bool arm_checks(AP_Arming::Method method);113114// get expected magnetic field strength115uint16_t compass_magfield_expected() const;116117// rudder arming support118enum class RudderArming {119IS_DISABLED = 0, // DISABLED leaks in from vehicle defines.h120ARMONLY = 1,121ARMDISARM = 2122};123124RudderArming get_rudder_arming_type() const { return (RudderArming)_rudder_arming.get(); }125126#if AP_ARMING_AUX_AUTH_ENABLED127// auxiliary authorisation methods128bool get_aux_auth_id(uint8_t& auth_id);129void set_aux_auth_passed(uint8_t auth_id);130void set_aux_auth_failed(uint8_t auth_id, const char* fail_msg);131#endif132133static const struct AP_Param::GroupInfo var_info[];134135// method that was last used for disarm; invalid unless the136// vehicle has been disarmed at least once.137Method last_disarm_method() const { return _last_disarm_method; }138139// method that was last used for arm; invalid unless the140// vehicle has been disarmed at least once.141Method last_arm_method() const { return _last_arm_method; }142143// enum for ARMING_OPTIONS parameter144enum class Option : int32_t {145DISABLE_PREARM_DISPLAY = (1U << 0),146DISABLE_STATUSTEXT_ON_STATE_CHANGE = (1U << 1),147};148bool option_enabled(Option option) const {149return (_arming_options & uint32_t(option)) != 0;150}151152void send_arm_disarm_statustext(const char *string) const;153154static bool method_is_GCS(Method method) {155return (method == Method::MAVLINK || method == Method::DDS);156}157protected:158159// Parameters160AP_Enum<Required> require;161AP_Int32 checks_to_perform; // bitmask for which checks are required162AP_Float accel_error_threshold;163AP_Int8 _rudder_arming;164AP_Int32 _required_mission_items;165AP_Int32 _arming_options;166AP_Int16 magfield_error_threshold;167168// internal members169bool armed;170uint32_t last_accel_pass_ms;171uint32_t last_gyro_pass_ms;172173virtual bool barometer_checks(bool report);174175bool airspeed_checks(bool report);176177bool logging_checks(bool report);178179#if AP_INERTIALSENSOR_ENABLED180virtual bool ins_checks(bool report);181#endif182183bool compass_checks(bool report);184185virtual bool gps_checks(bool report);186187bool battery_checks(bool report);188189bool hardware_safety_check(bool report);190191virtual bool board_voltage_checks(bool report);192193virtual bool rc_calibration_checks(bool report);194195bool rc_in_calibration_check(bool report);196197bool rc_arm_checks(AP_Arming::Method method);198199bool manual_transmitter_checks(bool report);200201virtual bool mission_checks(bool report);202203bool terrain_checks(bool report) const;204205// expected to return true if the terrain database is required to have206// all data loaded207virtual bool terrain_database_required() const;208209bool rangefinder_checks(bool report);210211bool fence_checks(bool report);212213#if HAL_HAVE_IMU_HEATER214bool heater_min_temperature_checks(bool report);215#endif216217bool camera_checks(bool display_failure);218219bool osd_checks(bool display_failure) const;220221bool mount_checks(bool display_failure) const;222223#if AP_ARMING_AUX_AUTH_ENABLED224bool aux_auth_checks(bool display_failure);225#endif226227bool generator_checks(bool report) const;228229bool opendroneid_checks(bool display_failure);230231bool serial_protocol_checks(bool display_failure);232233bool estop_checks(bool display_failure);234235#if AP_ARMING_CRASHDUMP_ACK_ENABLED236bool crashdump_checks(bool report);237#endif238239virtual bool system_checks(bool report);240241bool can_checks(bool report);242243bool fettec_checks(bool display_failure) const;244245#if HAL_PROXIMITY_ENABLED246virtual bool proximity_checks(bool report) const;247#endif248249bool servo_checks(bool report) const;250bool rc_checks_copter_sub(bool display_failure, const class RC_Channel *channels[4]) const;251252bool visodom_checks(bool report) const;253bool disarm_switch_checks(bool report) const;254255// mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced256virtual bool mandatory_checks(bool report);257258// returns true if a particular check is enabled259bool check_enabled(const enum AP_Arming::ArmingChecks check) const;260// handle the case where a check fails261void check_failed(const enum AP_Arming::ArmingChecks check, bool report, const char *fmt, ...) const FMT_PRINTF(4, 5);262void check_failed(bool report, const char *fmt, ...) const FMT_PRINTF(3, 4);263264void Log_Write_Arm(bool forced, AP_Arming::Method method);265void Log_Write_Disarm(bool forced, AP_Arming::Method method);266267private:268269static AP_Arming *_singleton;270271#if AP_INERTIALSENSOR_ENABLED272bool ins_accels_consistent(const class AP_InertialSensor &ins);273bool ins_gyros_consistent(const class AP_InertialSensor &ins);274#endif275276// check if we should keep logging after disarming277void check_forced_logging(const AP_Arming::Method method);278279enum MIS_ITEM_CHECK {280MIS_ITEM_CHECK_LAND = (1 << 0),281MIS_ITEM_CHECK_VTOL_LAND = (1 << 1),282MIS_ITEM_CHECK_DO_LAND_START = (1 << 2),283MIS_ITEM_CHECK_TAKEOFF = (1 << 3),284MIS_ITEM_CHECK_VTOL_TAKEOFF = (1 << 4),285MIS_ITEM_CHECK_RALLY = (1 << 5),286MIS_ITEM_CHECK_RETURN_TO_LAUNCH = (1 << 6),287MIS_ITEM_CHECK_MAX288};289290#if AP_ARMING_AUX_AUTH_ENABLED291// auxiliary authorisation292static const uint8_t aux_auth_count_max = 3; // maximum number of auxiliary authorisers293static const uint8_t aux_auth_str_len = 42; // maximum length of failure message (50-8 for "PreArm: ")294enum class AuxAuthStates : uint8_t {295NO_RESPONSE = 0,296AUTH_FAILED,297AUTH_PASSED298} aux_auth_state[aux_auth_count_max] = {}; // state of each auxiliary authorisation299uint8_t aux_auth_count; // number of auxiliary authorisers300uint8_t aux_auth_fail_msg_source; // authorisation id who set aux_auth_fail_msg301char* aux_auth_fail_msg; // buffer for holding failure messages302bool aux_auth_error; // true if too many auxiliary authorisers303HAL_Semaphore aux_auth_sem; // semaphore for accessing the aux_auth_state and aux_auth_fail_msg304#endif305306// method that was last used for arm/disarm; invalid unless the307// vehicle has been disarmed at least once.308Method _last_disarm_method = Method::UNKNOWN;309Method _last_arm_method = Method::UNKNOWN;310311uint32_t last_prearm_display_ms; // last time we send statustexts for prearm failures312bool running_arming_checks; // true if the arming checks currently being performed are being done because the vehicle is trying to arm the vehicle313314bool last_prearm_checks_result; // result of last prearm check315bool report_immediately; // set to true when check goes from true to false, to trigger immediate report316317void update_arm_gpio();318319#if !AP_GPS_BLENDED_ENABLED320bool blending_auto_switch_checks(bool report);321#endif322323#if AP_ARMING_CRASHDUMP_ACK_ENABLED324struct CrashDump {325void check_reset();326AP_Int8 acked;327} crashdump_ack;328#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED329330};331332namespace AP {333AP_Arming &arming();334};335336337