2016-02-17 21:25:15 -04:00
|
|
|
#pragma once
|
2013-11-27 22:18:14 -04:00
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
2018-12-20 04:22:10 -04:00
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
2017-08-09 20:11:22 -03:00
|
|
|
#include <RC_Channel/RC_Channel.h>
|
2013-11-27 22:18:14 -04:00
|
|
|
|
|
|
|
class AP_Arming {
|
|
|
|
public:
|
2018-06-25 00:42:39 -03:00
|
|
|
|
|
|
|
AP_Arming();
|
|
|
|
|
|
|
|
/* Do not allow copies */
|
|
|
|
AP_Arming(const AP_Arming &other) = delete;
|
|
|
|
AP_Arming &operator=(const AP_Arming&) = delete;
|
|
|
|
|
2013-11-27 22:18:14 -04:00
|
|
|
enum ArmingChecks {
|
|
|
|
ARMING_CHECK_NONE = 0x0000,
|
|
|
|
ARMING_CHECK_ALL = 0x0001,
|
|
|
|
ARMING_CHECK_BARO = 0x0002,
|
|
|
|
ARMING_CHECK_COMPASS = 0x0004,
|
|
|
|
ARMING_CHECK_GPS = 0x0008,
|
|
|
|
ARMING_CHECK_INS = 0x0010,
|
|
|
|
ARMING_CHECK_PARAMETERS = 0x0020,
|
|
|
|
ARMING_CHECK_RC = 0x0040,
|
|
|
|
ARMING_CHECK_VOLTAGE = 0x0080,
|
|
|
|
ARMING_CHECK_BATTERY = 0x0100,
|
2015-01-19 20:27:13 -04:00
|
|
|
ARMING_CHECK_AIRSPEED = 0x0200,
|
2015-02-06 03:38:53 -04:00
|
|
|
ARMING_CHECK_LOGGING = 0x0400,
|
2015-12-21 02:34:00 -04:00
|
|
|
ARMING_CHECK_SWITCH = 0x0800,
|
2016-02-19 16:28:29 -04:00
|
|
|
ARMING_CHECK_GPS_CONFIG = 0x1000,
|
2018-06-29 20:23:08 -03:00
|
|
|
ARMING_CHECK_SYSTEM = 0x2000,
|
2018-12-25 01:19:02 -04:00
|
|
|
ARMING_CHECK_MISSION = 0x4000,
|
2013-11-27 22:18:14 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
enum ArmingMethod {
|
|
|
|
RUDDER,
|
2018-06-24 23:05:56 -03:00
|
|
|
MAVLINK,
|
|
|
|
AUXSWITCH,
|
|
|
|
MOTORTEST,
|
2013-11-27 22:18:14 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
enum ArmingRequired {
|
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
|
|
|
};
|
|
|
|
|
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
|
2013-12-11 02:02:25 -04:00
|
|
|
ArmingRequired arming_required();
|
2018-06-24 23:05:56 -03:00
|
|
|
virtual bool arm(ArmingMethod method, bool do_arming_checks=true);
|
2013-12-11 01:09:11 -04:00
|
|
|
bool disarm();
|
|
|
|
bool is_armed();
|
2016-12-28 01:43:31 -04:00
|
|
|
|
|
|
|
// get bitmask of enabled checks
|
2013-12-11 01:09:11 -04:00
|
|
|
uint16_t get_enabled_checks();
|
|
|
|
|
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:
|
2018-06-24 23:05:56 -03:00
|
|
|
bool arm_checks(ArmingMethod 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
|
|
|
|
enum ArmingRudder {
|
|
|
|
ARMING_RUDDER_DISABLED = 0,
|
|
|
|
ARMING_RUDDER_ARMONLY = 1,
|
|
|
|
ARMING_RUDDER_ARMDISARM = 2
|
|
|
|
};
|
2018-09-11 01:48:09 -03:00
|
|
|
ArmingRudder get_rudder_arming_type() const { return (ArmingRudder)_rudder_arming.get(); }
|
2018-09-08 00:30:21 -03:00
|
|
|
|
2016-12-28 01:43:31 -04:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
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
|
|
|
|
AP_Int8 require;
|
|
|
|
AP_Int16 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;
|
2018-12-25 01:19:02 -04:00
|
|
|
AP_Int32 _required_mission_items;
|
2015-10-12 02:29:27 -03:00
|
|
|
|
|
|
|
// internal members
|
|
|
|
bool armed:1;
|
|
|
|
uint32_t last_accel_pass_ms[INS_MAX_INSTANCES];
|
|
|
|
uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES];
|
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
|
|
|
|
2016-08-17 05:15:38 -03:00
|
|
|
virtual 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);
|
|
|
|
|
2014-01-23 06:39:55 -04:00
|
|
|
bool manual_transmitter_checks(bool report);
|
2016-08-15 00:37:03 -03:00
|
|
|
|
2018-12-25 01:19:02 -04:00
|
|
|
bool mission_checks(bool report);
|
|
|
|
|
2018-06-29 20:23:08 -03:00
|
|
|
virtual bool system_checks(bool report);
|
|
|
|
|
2018-04-19 17:10:39 -03:00
|
|
|
bool servo_checks(bool report) const;
|
2018-12-20 04:23:02 -04:00
|
|
|
bool rc_checks_copter_sub(bool display_failure, const RC_Channel *channels[4]) const;
|
2017-08-09 20:11:22 -03: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;
|
|
|
|
// returns a mavlink severity which should be used if a specific check fails
|
|
|
|
MAV_SEVERITY check_severity(const enum AP_Arming::ArmingChecks check) const;
|
|
|
|
// handle the case where a check fails
|
|
|
|
void check_failed(const enum AP_Arming::ArmingChecks check, bool report, const char *fmt, ...) const;
|
|
|
|
|
2017-07-27 01:16:38 -03:00
|
|
|
private:
|
|
|
|
|
|
|
|
bool ins_accels_consistent(const AP_InertialSensor &ins);
|
2017-07-27 01:25:06 -03:00
|
|
|
bool ins_gyros_consistent(const AP_InertialSensor &ins);
|
2017-07-27 01:16:38 -03:00
|
|
|
|
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),
|
|
|
|
MIS_ITEM_CHECK_MAX
|
|
|
|
};
|
2013-11-27 22:18:14 -04:00
|
|
|
};
|