APM:Libraries
AP_Arming.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_AHRS/AP_AHRS.h>
5 #include <AP_HAL/AP_HAL.h>
6 #include <AP_Param/AP_Param.h>
9 
10 class AP_Arming {
11 public:
12  enum ArmingChecks {
14  ARMING_CHECK_ALL = 0x0001,
17  ARMING_CHECK_GPS = 0x0008,
18  ARMING_CHECK_INS = 0x0010,
20  ARMING_CHECK_RC = 0x0040,
27  };
28 
29  enum ArmingMethod {
30  NONE = 0,
33  };
34 
36  NO = 0,
39  };
40 
41  // these functions should not be used by Copter which holds the armed state in the motors library
43  virtual bool arm(uint8_t method);
44  bool disarm();
45  bool is_armed();
46 
47  // get bitmask of enabled checks
48  uint16_t get_enabled_checks();
49 
50  // pre_arm_checks() is virtual so it can be modified in a vehicle specific subclass
51  virtual bool pre_arm_checks(bool report);
52 
53  // some arming checks have side-effects, or require some form of state
54  // change to have occurred, and thus should not be done as pre-arm
55  // checks. Those go here:
56  bool arm_checks(uint8_t method);
57 
58  // get expected magnetic field strength
59  uint16_t compass_magfield_expected() const;
60 
61  static const struct AP_Param::GroupInfo var_info[];
62 
63 protected:
64  AP_Arming(const AP_AHRS &ahrs_ref, Compass &compass,
65  const AP_BattMonitor &battery);
66 
67  // Parameters
68  AP_Int8 require;
69  AP_Int16 checks_to_perform; // bitmask for which checks are required
72 
73  // references
74  const AP_AHRS &ahrs;
77 
78  // internal members
79  bool armed:1;
81  uint8_t arming_method; // how the vehicle was armed
84 
85  virtual bool barometer_checks(bool report);
86 
87  bool airspeed_checks(bool report);
88 
89  bool logging_checks(bool report);
90 
91  virtual bool ins_checks(bool report);
92 
93  virtual bool compass_checks(bool report);
94 
95  virtual bool gps_checks(bool report);
96 
97  bool battery_checks(bool report);
98 
99  bool hardware_safety_check(bool report);
100 
101  virtual bool board_voltage_checks(bool report);
102 
103  virtual bool rc_calibration_checks(bool report);
104 
105  bool manual_transmitter_checks(bool report);
106 
107  bool servo_checks(bool report) const;
108  bool rc_checks_copter_sub(bool display_failure, const RC_Channel *channels[4], const bool check_min_max = true) const;
109 
110 };
AP_Int8 require
Definition: AP_Arming.h:68
bool servo_checks(bool report) const
Definition: AP_Arming.cpp:503
virtual bool arm(uint8_t method)
Definition: AP_Arming.cpp:593
bool logging_checks(bool report)
Definition: AP_Arming.cpp:152
uint8_t arming_method
Definition: AP_Arming.h:81
bool logging_available
Definition: AP_Arming.h:80
virtual bool barometer_checks(bool report)
Definition: AP_Arming.cpp:115
static uint16_t channels[SRXL_MAX_CHANNELS]
Definition: srxl.cpp:59
uint32_t last_accel_pass_ms[INS_MAX_INSTANCES]
Definition: AP_Arming.h:82
virtual bool ins_checks(bool report)
Definition: AP_Arming.cpp:172
AP_Float accel_error_threshold
Definition: AP_Arming.h:70
AP_Float _min_voltage[AP_BATT_MONITOR_MAX_INSTANCES]
Definition: AP_Arming.h:71
A system for managing and storing variables that are of general interest to the system.
uint16_t get_enabled_checks()
Definition: AP_Arming.cpp:110
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Arming.h:61
RC_Channel manager, with EEPROM-backed storage of constants.
Object managing one RC channel.
Definition: RC_Channel.h:15
ArmingRequired
Definition: AP_Arming.h:35
bool manual_transmitter_checks(bool report)
Definition: AP_Arming.cpp:483
AP_Int16 checks_to_perform
Definition: AP_Arming.h:69
virtual bool pre_arm_checks(bool report)
Definition: AP_Arming.cpp:546
bool armed
Definition: AP_Arming.h:79
static Compass compass
Definition: AHRS_Test.cpp:20
uint16_t compass_magfield_expected() const
Definition: AP_Arming.cpp:100
bool is_armed()
Definition: AP_Arming.cpp:105
bool hardware_safety_check(bool report)
Definition: AP_Arming.cpp:440
virtual bool gps_checks(bool report)
Definition: AP_Arming.cpp:344
Compass & _compass
Definition: AP_Arming.h:75
AP_BattMonitor & battery()
bool battery_checks(bool report)
Definition: AP_Arming.cpp:413
bool disarm()
Definition: AP_Arming.cpp:630
virtual bool rc_calibration_checks(bool report)
Definition: AP_Arming.cpp:457
ArmingRequired arming_required()
Definition: AP_Arming.cpp:650
bool airspeed_checks(bool report)
Definition: AP_Arming.cpp:130
bool arm_checks(uint8_t method)
Definition: AP_Arming.cpp:568
virtual bool compass_checks(bool report)
Definition: AP_Arming.cpp:274
uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES]
Definition: AP_Arming.h:83
#define INS_MAX_INSTANCES
const AP_BattMonitor & _battery
Definition: AP_Arming.h:76
AP_Arming(const AP_AHRS &ahrs_ref, Compass &compass, const AP_BattMonitor &battery)
Definition: AP_Arming.cpp:81
#define AP_BATT_MONITOR_MAX_INSTANCES
virtual bool board_voltage_checks(bool report)
Definition: AP_Arming.cpp:530
bool rc_checks_copter_sub(bool display_failure, const RC_Channel *channels[4], const bool check_min_max=true) const
Definition: AP_Arming.cpp:657
const AP_AHRS & ahrs
Definition: AP_Arming.h:74