2016-02-17 21:25:15 -04:00
|
|
|
#pragma once
|
2013-11-27 22:18:14 -04:00
|
|
|
|
2022-02-28 21:19:07 -04:00
|
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
|
|
|
#include <AP_HAL/Semaphores.h>
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_Param/AP_Param.h>
|
2013-11-27 22:18:14 -04:00
|
|
|
|
2023-03-24 00:24:31 -03:00
|
|
|
#include "AP_Arming_config.h"
|
|
|
|
|
2013-11-27 22:18:14 -04:00
|
|
|
class AP_Arming {
|
|
|
|
public:
|
2018-06-25 00:42:39 -03:00
|
|
|
|
|
|
|
AP_Arming();
|
|
|
|
|
2022-02-28 21:19:07 -04:00
|
|
|
CLASS_NO_COPY(AP_Arming); /* Do not allow copies */
|
2018-06-25 00:42:39 -03:00
|
|
|
|
2019-05-06 00:33:15 -03:00
|
|
|
static AP_Arming *get_singleton();
|
|
|
|
|
2022-05-10 04:53:31 -03:00
|
|
|
void update();
|
|
|
|
|
2013-11-27 22:18:14 -04:00
|
|
|
enum ArmingChecks {
|
2019-04-10 04:32:30 -03:00
|
|
|
ARMING_CHECK_ALL = (1U << 0),
|
|
|
|
ARMING_CHECK_BARO = (1U << 1),
|
|
|
|
ARMING_CHECK_COMPASS = (1U << 2),
|
|
|
|
ARMING_CHECK_GPS = (1U << 3),
|
|
|
|
ARMING_CHECK_INS = (1U << 4),
|
|
|
|
ARMING_CHECK_PARAMETERS = (1U << 5),
|
|
|
|
ARMING_CHECK_RC = (1U << 6),
|
|
|
|
ARMING_CHECK_VOLTAGE = (1U << 7),
|
|
|
|
ARMING_CHECK_BATTERY = (1U << 8),
|
|
|
|
ARMING_CHECK_AIRSPEED = (1U << 9),
|
|
|
|
ARMING_CHECK_LOGGING = (1U << 10),
|
|
|
|
ARMING_CHECK_SWITCH = (1U << 11),
|
|
|
|
ARMING_CHECK_GPS_CONFIG = (1U << 12),
|
|
|
|
ARMING_CHECK_SYSTEM = (1U << 13),
|
|
|
|
ARMING_CHECK_MISSION = (1U << 14),
|
|
|
|
ARMING_CHECK_RANGEFINDER = (1U << 15),
|
2019-12-06 13:52:12 -04:00
|
|
|
ARMING_CHECK_CAMERA = (1U << 16),
|
2020-02-12 00:50:07 -04:00
|
|
|
ARMING_CHECK_AUX_AUTH = (1U << 17),
|
2020-03-30 00:30:20 -03:00
|
|
|
ARMING_CHECK_VISION = (1U << 18),
|
2020-03-27 19:06:43 -03:00
|
|
|
ARMING_CHECK_FFT = (1U << 19),
|
2013-11-27 22:18:14 -04:00
|
|
|
};
|
|
|
|
|
2019-03-06 23:12:39 -04:00
|
|
|
enum class Method {
|
2020-01-07 01:04:01 -04:00
|
|
|
RUDDER = 0,
|
|
|
|
MAVLINK = 1,
|
|
|
|
AUXSWITCH = 2,
|
|
|
|
MOTORTEST = 3,
|
|
|
|
SCRIPTING = 4,
|
2020-02-21 09:09:57 -04:00
|
|
|
TERMINATION = 5, // only disarm uses this...
|
|
|
|
CPUFAILSAFE = 6, // only disarm uses this...
|
|
|
|
BATTERYFAILSAFE = 7, // only disarm uses this...
|
|
|
|
SOLOPAUSEWHENLANDED = 8, // only disarm uses this...
|
|
|
|
AFS = 9, // only disarm uses this...
|
|
|
|
ADSBCOLLISIONACTION = 10, // only disarm uses this...
|
|
|
|
PARACHUTE_RELEASE = 11, // only disarm uses this...
|
|
|
|
CRASH = 12, // only disarm uses this...
|
|
|
|
LANDED = 13, // only disarm uses this...
|
|
|
|
MISSIONEXIT = 14, // only disarm uses this...
|
|
|
|
FENCEBREACH = 15, // only disarm uses this...
|
|
|
|
RADIOFAILSAFE = 16, // only disarm uses this...
|
|
|
|
DISARMDELAY = 17, // only disarm uses this...
|
|
|
|
GCSFAILSAFE = 18, // only disarm uses this...
|
|
|
|
TERRRAINFAILSAFE = 19, // only disarm uses this...
|
|
|
|
FAILSAFE_ACTION_TERMINATE = 20, // only disarm uses this...
|
|
|
|
TERRAINFAILSAFE = 21, // only disarm uses this...
|
|
|
|
MOTORDETECTDONE = 22, // only disarm uses this...
|
|
|
|
BADFLOWOFCONTROL = 23, // only disarm uses this...
|
|
|
|
EKFFAILSAFE = 24, // only disarm uses this...
|
|
|
|
GCS_FAILSAFE_SURFACEFAILED = 25, // only disarm uses this...
|
|
|
|
GCS_FAILSAFE_HOLDFAILED = 26, // only disarm uses this...
|
|
|
|
TAKEOFFTIMEOUT = 27, // only disarm uses this...
|
|
|
|
AUTOLANDED = 28, // only disarm uses this...
|
2020-02-21 09:09:58 -04:00
|
|
|
PILOT_INPUT_FAILSAFE = 29, // only disarm uses this...
|
2020-02-27 05:02:23 -04:00
|
|
|
TOYMODELANDTHROTTLE = 30, // only disarm uses this...
|
|
|
|
TOYMODELANDFORCE = 31, // only disarm uses this...
|
2021-03-24 00:45:13 -03:00
|
|
|
LANDING = 32, // only disarm uses this...
|
2022-05-11 00:53:33 -03:00
|
|
|
DEADRECKON_FAILSAFE = 33, // only disarm uses this...
|
2023-05-10 22:04:15 -03:00
|
|
|
BLACKBOX = 34,
|
2020-07-15 23:52:11 -03:00
|
|
|
UNKNOWN = 100,
|
2013-11-27 22:18:14 -04:00
|
|
|
};
|
|
|
|
|
2019-03-06 23:12:39 -04:00
|
|
|
enum class Required {
|
2013-12-19 20:59:05 -04:00
|
|
|
NO = 0,
|
|
|
|
YES_MIN_PWM = 1,
|
|
|
|
YES_ZERO_PWM = 2
|
2013-11-27 22:18:14 -04:00
|
|
|
};
|
|
|
|
|
2019-04-10 04:32:30 -03:00
|
|
|
void init(void);
|
|
|
|
|
2016-12-28 01:41:21 -04:00
|
|
|
// these functions should not be used by Copter which holds the armed state in the motors library
|
2023-02-10 22:35:16 -04:00
|
|
|
Required arming_required() const;
|
2019-03-06 23:12:39 -04:00
|
|
|
virtual bool arm(AP_Arming::Method method, bool do_arming_checks=true);
|
2021-01-05 20:15:47 -04:00
|
|
|
virtual bool disarm(AP_Arming::Method method, bool do_disarm_checks=true);
|
2023-02-10 22:35:16 -04:00
|
|
|
bool is_armed() const;
|
|
|
|
bool is_armed_and_safety_off() const;
|
2016-12-28 01:43:31 -04:00
|
|
|
|
|
|
|
// get bitmask of enabled checks
|
2020-02-11 21:24:36 -04:00
|
|
|
uint32_t get_enabled_checks() const;
|
2013-12-11 01:09:11 -04:00
|
|
|
|
2016-12-28 01:43:31 -04:00
|
|
|
// pre_arm_checks() is virtual so it can be modified in a vehicle specific subclass
|
2015-06-04 00:13:03 -03:00
|
|
|
virtual bool pre_arm_checks(bool report);
|
2016-12-28 01:43:31 -04:00
|
|
|
|
2016-11-05 20:23:14 -03:00
|
|
|
// some arming checks have side-effects, or require some form of state
|
2016-12-28 01:43:31 -04:00
|
|
|
// change to have occurred, and thus should not be done as pre-arm
|
2016-11-05 20:23:14 -03:00
|
|
|
// checks. Those go here:
|
2019-04-21 22:13:23 -03:00
|
|
|
virtual bool arm_checks(AP_Arming::Method method);
|
2014-01-23 06:39:55 -04:00
|
|
|
|
2016-12-28 01:43:31 -04:00
|
|
|
// get expected magnetic field strength
|
2016-08-17 05:15:38 -03:00
|
|
|
uint16_t compass_magfield_expected() const;
|
|
|
|
|
2018-09-08 00:30:21 -03:00
|
|
|
// rudder arming support
|
2019-03-06 23:12:39 -04:00
|
|
|
enum class RudderArming {
|
|
|
|
IS_DISABLED = 0, // DISABLED leaks in from vehicle defines.h
|
|
|
|
ARMONLY = 1,
|
|
|
|
ARMDISARM = 2
|
2018-09-08 00:30:21 -03:00
|
|
|
};
|
2019-03-06 23:12:39 -04:00
|
|
|
|
|
|
|
RudderArming get_rudder_arming_type() const { return (RudderArming)_rudder_arming.get(); }
|
2018-09-08 00:30:21 -03:00
|
|
|
|
2023-03-24 00:24:31 -03:00
|
|
|
#if AP_ARMING_AUX_AUTH_ENABLED
|
2020-02-12 00:50:07 -04:00
|
|
|
// auxiliary authorisation methods
|
|
|
|
bool get_aux_auth_id(uint8_t& auth_id);
|
|
|
|
void set_aux_auth_passed(uint8_t auth_id);
|
|
|
|
void set_aux_auth_failed(uint8_t auth_id, const char* fail_msg);
|
2023-03-24 00:24:31 -03:00
|
|
|
#endif
|
2020-02-12 00:50:07 -04:00
|
|
|
|
2016-12-28 01:43:31 -04:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
2020-07-15 23:52:11 -03:00
|
|
|
// method that was last used for disarm; invalid unless the
|
|
|
|
// vehicle has been disarmed at least once.
|
2022-01-26 20:51:02 -04:00
|
|
|
Method last_disarm_method() const { return _last_disarm_method; }
|
|
|
|
|
2023-01-16 01:45:08 -04:00
|
|
|
// method that was last used for arm; invalid unless the
|
|
|
|
// vehicle has been disarmed at least once.
|
|
|
|
Method last_arm_method() const { return _last_arm_method; }
|
|
|
|
|
2022-01-26 20:51:02 -04:00
|
|
|
// enum for ARMING_OPTIONS parameter
|
2022-08-03 02:14:08 -03:00
|
|
|
enum class Option : int32_t {
|
2022-01-26 20:51:02 -04:00
|
|
|
DISABLE_PREARM_DISPLAY = (1U << 0),
|
|
|
|
};
|
2022-08-03 02:14:08 -03:00
|
|
|
bool option_enabled(Option option) const {
|
|
|
|
return (_arming_options & uint32_t(option)) != 0;
|
|
|
|
}
|
2020-07-15 23:52:11 -03:00
|
|
|
|
2015-06-04 00:13:03 -03:00
|
|
|
protected:
|
2017-08-30 17:09:05 -03:00
|
|
|
|
2015-10-12 02:29:27 -03:00
|
|
|
// Parameters
|
2022-07-17 16:37:33 -03:00
|
|
|
AP_Enum<Required> require;
|
2019-04-10 04:32:30 -03:00
|
|
|
AP_Int32 checks_to_perform; // bitmask for which checks are required
|
2015-12-21 17:51:12 -04:00
|
|
|
AP_Float accel_error_threshold;
|
2018-09-08 00:30:21 -03:00
|
|
|
AP_Int8 _rudder_arming;
|
2022-01-26 20:51:02 -04:00
|
|
|
AP_Int32 _required_mission_items;
|
|
|
|
AP_Int32 _arming_options;
|
2015-10-12 02:29:27 -03:00
|
|
|
|
|
|
|
// internal members
|
2019-01-24 01:54:50 -04:00
|
|
|
bool armed;
|
2022-07-16 01:44:33 -03:00
|
|
|
uint32_t last_accel_pass_ms;
|
|
|
|
uint32_t last_gyro_pass_ms;
|
2013-11-27 22:18:14 -04:00
|
|
|
|
2017-09-04 00:23:42 -03:00
|
|
|
virtual bool barometer_checks(bool report);
|
2013-11-27 22:18:14 -04:00
|
|
|
|
2015-01-19 20:27:13 -04:00
|
|
|
bool airspeed_checks(bool report);
|
|
|
|
|
2015-02-06 03:38:53 -04:00
|
|
|
bool logging_checks(bool report);
|
|
|
|
|
2015-10-16 00:51:46 -03:00
|
|
|
virtual bool ins_checks(bool report);
|
2015-01-19 20:27:13 -04:00
|
|
|
|
2021-08-15 20:09:15 -03:00
|
|
|
bool compass_checks(bool report);
|
2013-11-27 22:18:14 -04:00
|
|
|
|
2017-03-08 21:58:25 -04:00
|
|
|
virtual bool gps_checks(bool report);
|
2013-11-27 22:18:14 -04:00
|
|
|
|
2014-01-23 06:39:55 -04:00
|
|
|
bool battery_checks(bool report);
|
2013-11-27 22:18:14 -04:00
|
|
|
|
2014-01-23 06:39:55 -04:00
|
|
|
bool hardware_safety_check(bool report);
|
2013-11-27 22:18:14 -04:00
|
|
|
|
2017-09-04 00:48:30 -03:00
|
|
|
virtual bool board_voltage_checks(bool report);
|
2015-10-16 00:13:53 -03:00
|
|
|
|
2017-09-04 01:16:12 -03:00
|
|
|
virtual bool rc_calibration_checks(bool report);
|
|
|
|
|
2021-08-30 12:53:22 -03:00
|
|
|
bool rc_in_calibration_check(bool report);
|
|
|
|
|
2020-03-30 19:24:07 -03:00
|
|
|
bool rc_arm_checks(AP_Arming::Method method);
|
|
|
|
|
2014-01-23 06:39:55 -04:00
|
|
|
bool manual_transmitter_checks(bool report);
|
2016-08-15 00:37:03 -03:00
|
|
|
|
2022-03-12 02:53:33 -04:00
|
|
|
virtual bool mission_checks(bool report);
|
2018-12-25 01:19:02 -04:00
|
|
|
|
2022-08-03 09:59:38 -03:00
|
|
|
bool terrain_checks(bool report) const;
|
|
|
|
|
|
|
|
// expected to return true if the terrain database is required to have
|
|
|
|
// all data loaded
|
|
|
|
virtual bool terrain_database_required() const;
|
|
|
|
|
2019-04-10 04:32:30 -03:00
|
|
|
bool rangefinder_checks(bool report);
|
|
|
|
|
2019-03-05 19:09:55 -04:00
|
|
|
bool fence_checks(bool report);
|
|
|
|
|
2021-10-15 18:21:31 -03:00
|
|
|
#if HAL_HAVE_IMU_HEATER
|
|
|
|
bool heater_min_temperature_checks(bool report);
|
|
|
|
#endif
|
|
|
|
|
2019-12-06 13:52:12 -04:00
|
|
|
bool camera_checks(bool display_failure);
|
|
|
|
|
2020-04-26 11:37:49 -03:00
|
|
|
bool osd_checks(bool display_failure) const;
|
2022-06-16 05:13:47 -03:00
|
|
|
|
|
|
|
bool mount_checks(bool display_failure) const;
|
2020-04-26 11:37:49 -03:00
|
|
|
|
2023-03-24 00:24:31 -03:00
|
|
|
#if AP_ARMING_AUX_AUTH_ENABLED
|
2020-02-12 00:50:07 -04:00
|
|
|
bool aux_auth_checks(bool display_failure);
|
2023-03-24 00:24:31 -03:00
|
|
|
#endif
|
2020-02-12 00:50:07 -04:00
|
|
|
|
2019-11-27 03:44:03 -04:00
|
|
|
bool generator_checks(bool report) const;
|
|
|
|
|
2022-07-17 16:37:33 -03:00
|
|
|
bool opendroneid_checks(bool display_failure);
|
2022-10-21 15:50:45 -03:00
|
|
|
|
|
|
|
bool serial_protocol_checks(bool display_failure);
|
2023-04-10 09:08:01 -03:00
|
|
|
|
|
|
|
bool estop_checks(bool display_failure);
|
2022-07-17 16:37:33 -03:00
|
|
|
|
2018-06-29 20:23:08 -03:00
|
|
|
virtual bool system_checks(bool report);
|
2018-08-11 11:09:57 -03:00
|
|
|
|
|
|
|
bool can_checks(bool report);
|
2019-05-29 23:28:33 -03:00
|
|
|
|
2021-07-03 21:47:46 -03:00
|
|
|
bool fettec_checks(bool display_failure) const;
|
2023-04-16 01:23:03 -03:00
|
|
|
|
|
|
|
bool kdecan_checks(bool display_failure) const;
|
2021-07-03 21:47:46 -03:00
|
|
|
|
2019-05-29 23:28:33 -03:00
|
|
|
virtual bool proximity_checks(bool report) const;
|
|
|
|
|
2018-04-19 17:10:39 -03:00
|
|
|
bool servo_checks(bool report) const;
|
2022-02-28 21:19:07 -04:00
|
|
|
bool rc_checks_copter_sub(bool display_failure, const class RC_Channel *channels[4]) const;
|
2017-08-09 20:11:22 -03:00
|
|
|
|
2020-03-30 00:30:20 -03:00
|
|
|
bool visodom_checks(bool report) const;
|
2020-04-30 11:57:44 -03:00
|
|
|
bool disarm_switch_checks(bool report) const;
|
2020-03-30 00:30:20 -03:00
|
|
|
|
2019-11-29 02:18:19 -04:00
|
|
|
// mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced
|
2021-08-30 12:53:22 -03:00
|
|
|
virtual bool mandatory_checks(bool report);
|
2019-11-29 02:18:19 -04:00
|
|
|
|
2017-08-01 00:09:27 -03:00
|
|
|
// returns true if a particular check is enabled
|
|
|
|
bool check_enabled(const enum AP_Arming::ArmingChecks check) const;
|
|
|
|
// handle the case where a check fails
|
2019-08-04 22:39:00 -03:00
|
|
|
void check_failed(const enum AP_Arming::ArmingChecks check, bool report, const char *fmt, ...) const FMT_PRINTF(4, 5);
|
2019-10-04 18:49:20 -03:00
|
|
|
void check_failed(bool report, const char *fmt, ...) const FMT_PRINTF(3, 4);
|
2017-08-01 00:09:27 -03:00
|
|
|
|
2020-01-07 01:04:01 -04:00
|
|
|
void Log_Write_Arm(bool forced, AP_Arming::Method method);
|
2021-10-18 23:36:26 -03:00
|
|
|
void Log_Write_Disarm(bool forced, AP_Arming::Method method);
|
2019-05-03 08:15:46 -03:00
|
|
|
|
2017-07-27 01:16:38 -03:00
|
|
|
private:
|
|
|
|
|
2019-05-06 00:33:15 -03:00
|
|
|
static AP_Arming *_singleton;
|
|
|
|
|
2022-02-28 21:19:07 -04:00
|
|
|
bool ins_accels_consistent(const class AP_InertialSensor &ins);
|
|
|
|
bool ins_gyros_consistent(const class AP_InertialSensor &ins);
|
2017-07-27 01:16:38 -03:00
|
|
|
|
2021-09-03 15:00:45 -03:00
|
|
|
// check if we should keep logging after disarming
|
|
|
|
void check_forced_logging(const AP_Arming::Method method);
|
|
|
|
|
2018-12-25 01:19:02 -04:00
|
|
|
enum MIS_ITEM_CHECK {
|
|
|
|
MIS_ITEM_CHECK_LAND = (1 << 0),
|
|
|
|
MIS_ITEM_CHECK_VTOL_LAND = (1 << 1),
|
|
|
|
MIS_ITEM_CHECK_DO_LAND_START = (1 << 2),
|
|
|
|
MIS_ITEM_CHECK_TAKEOFF = (1 << 3),
|
|
|
|
MIS_ITEM_CHECK_VTOL_TAKEOFF = (1 << 4),
|
|
|
|
MIS_ITEM_CHECK_RALLY = (1 << 5),
|
2022-07-25 18:58:45 -03:00
|
|
|
MIS_ITEM_CHECK_RETURN_TO_LAUNCH = (1 << 6),
|
2018-12-25 01:19:02 -04:00
|
|
|
MIS_ITEM_CHECK_MAX
|
|
|
|
};
|
2020-02-12 00:50:07 -04:00
|
|
|
|
2023-03-24 00:24:31 -03:00
|
|
|
#if AP_ARMING_AUX_AUTH_ENABLED
|
2020-02-12 00:50:07 -04:00
|
|
|
// auxiliary authorisation
|
|
|
|
static const uint8_t aux_auth_count_max = 3; // maximum number of auxiliary authorisers
|
|
|
|
static const uint8_t aux_auth_str_len = 42; // maximum length of failure message (50-8 for "PreArm: ")
|
|
|
|
enum class AuxAuthStates : uint8_t {
|
|
|
|
NO_RESPONSE = 0,
|
|
|
|
AUTH_FAILED,
|
|
|
|
AUTH_PASSED
|
|
|
|
} aux_auth_state[aux_auth_count_max] = {}; // state of each auxiliary authorisation
|
|
|
|
uint8_t aux_auth_count; // number of auxiliary authorisers
|
|
|
|
uint8_t aux_auth_fail_msg_source; // authorisation id who set aux_auth_fail_msg
|
|
|
|
char* aux_auth_fail_msg; // buffer for holding failure messages
|
|
|
|
bool aux_auth_error; // true if too many auxiliary authorisers
|
|
|
|
HAL_Semaphore aux_auth_sem; // semaphore for accessing the aux_auth_state and aux_auth_fail_msg
|
2023-03-24 00:24:31 -03:00
|
|
|
#endif
|
2020-07-15 23:52:11 -03:00
|
|
|
|
2023-01-16 01:45:08 -04:00
|
|
|
// method that was last used for arm/disarm; invalid unless the
|
2020-07-15 23:52:11 -03:00
|
|
|
// vehicle has been disarmed at least once.
|
|
|
|
Method _last_disarm_method = Method::UNKNOWN;
|
2023-01-16 01:45:08 -04:00
|
|
|
Method _last_arm_method = Method::UNKNOWN;
|
2022-08-03 02:14:08 -03:00
|
|
|
|
|
|
|
uint32_t last_prearm_display_ms; // last time we send statustexts for prearm failures
|
2022-08-03 02:15:43 -03:00
|
|
|
bool running_arming_checks; // true if the arming checks currently being performed are being done because the vehicle is trying to arm the vehicle
|
2013-11-27 22:18:14 -04:00
|
|
|
};
|
2019-05-06 00:33:15 -03:00
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
AP_Arming &arming();
|
|
|
|
};
|