CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Arming/AP_Arming.h
Views: 1798
1
#pragma once
2
3
#include <AP_HAL/AP_HAL_Boards.h>
4
#include <AP_HAL/Semaphores.h>
5
#include <AP_Param/AP_Param.h>
6
#include <AP_GPS/AP_GPS_config.h>
7
#include <AP_BoardConfig/AP_BoardConfig_config.h>
8
9
#include "AP_Arming_config.h"
10
#include "AP_InertialSensor/AP_InertialSensor_config.h"
11
#include "AP_Proximity/AP_Proximity_config.h"
12
13
class AP_Arming {
14
public:
15
16
AP_Arming();
17
18
CLASS_NO_COPY(AP_Arming); /* Do not allow copies */
19
20
static AP_Arming *get_singleton();
21
22
void update();
23
24
enum ArmingChecks {
25
ARMING_CHECK_ALL = (1U << 0),
26
ARMING_CHECK_BARO = (1U << 1),
27
ARMING_CHECK_COMPASS = (1U << 2),
28
ARMING_CHECK_GPS = (1U << 3),
29
ARMING_CHECK_INS = (1U << 4),
30
ARMING_CHECK_PARAMETERS = (1U << 5),
31
ARMING_CHECK_RC = (1U << 6),
32
ARMING_CHECK_VOLTAGE = (1U << 7),
33
ARMING_CHECK_BATTERY = (1U << 8),
34
ARMING_CHECK_AIRSPEED = (1U << 9),
35
ARMING_CHECK_LOGGING = (1U << 10),
36
ARMING_CHECK_SWITCH = (1U << 11),
37
ARMING_CHECK_GPS_CONFIG = (1U << 12),
38
ARMING_CHECK_SYSTEM = (1U << 13),
39
ARMING_CHECK_MISSION = (1U << 14),
40
ARMING_CHECK_RANGEFINDER = (1U << 15),
41
ARMING_CHECK_CAMERA = (1U << 16),
42
ARMING_CHECK_AUX_AUTH = (1U << 17),
43
ARMING_CHECK_VISION = (1U << 18),
44
ARMING_CHECK_FFT = (1U << 19),
45
ARMING_CHECK_OSD = (1U << 20),
46
};
47
48
enum class Method {
49
RUDDER = 0,
50
MAVLINK = 1,
51
AUXSWITCH = 2,
52
MOTORTEST = 3,
53
SCRIPTING = 4,
54
TERMINATION = 5, // only disarm uses this...
55
CPUFAILSAFE = 6, // only disarm uses this...
56
BATTERYFAILSAFE = 7, // only disarm uses this...
57
SOLOPAUSEWHENLANDED = 8, // only disarm uses this...
58
AFS = 9, // only disarm uses this...
59
ADSBCOLLISIONACTION = 10, // only disarm uses this...
60
PARACHUTE_RELEASE = 11, // only disarm uses this...
61
CRASH = 12, // only disarm uses this...
62
LANDED = 13, // only disarm uses this...
63
MISSIONEXIT = 14, // only disarm uses this...
64
FENCEBREACH = 15, // only disarm uses this...
65
RADIOFAILSAFE = 16, // only disarm uses this...
66
DISARMDELAY = 17, // only disarm uses this...
67
GCSFAILSAFE = 18, // only disarm uses this...
68
TERRRAINFAILSAFE = 19, // only disarm uses this...
69
FAILSAFE_ACTION_TERMINATE = 20, // only disarm uses this...
70
TERRAINFAILSAFE = 21, // only disarm uses this...
71
MOTORDETECTDONE = 22, // only disarm uses this...
72
BADFLOWOFCONTROL = 23, // only disarm uses this...
73
EKFFAILSAFE = 24, // only disarm uses this...
74
GCS_FAILSAFE_SURFACEFAILED = 25, // only disarm uses this...
75
GCS_FAILSAFE_HOLDFAILED = 26, // only disarm uses this...
76
TAKEOFFTIMEOUT = 27, // only disarm uses this...
77
AUTOLANDED = 28, // only disarm uses this...
78
PILOT_INPUT_FAILSAFE = 29, // only disarm uses this...
79
TOYMODELANDTHROTTLE = 30, // only disarm uses this...
80
TOYMODELANDFORCE = 31, // only disarm uses this...
81
LANDING = 32, // only disarm uses this...
82
DEADRECKON_FAILSAFE = 33, // only disarm uses this...
83
BLACKBOX = 34,
84
DDS = 35,
85
UNKNOWN = 100,
86
};
87
88
enum class Required {
89
NO = 0,
90
YES_MIN_PWM = 1,
91
YES_ZERO_PWM = 2
92
};
93
94
void init(void);
95
96
// these functions should not be used by Copter which holds the armed state in the motors library
97
Required arming_required() const;
98
virtual bool arm(AP_Arming::Method method, bool do_arming_checks=true);
99
virtual bool arm_force(AP_Arming::Method method) { return arm(method, false); }
100
virtual bool disarm(AP_Arming::Method method, bool do_disarm_checks=true);
101
bool is_armed() const;
102
bool is_armed_and_safety_off() const;
103
104
// get bitmask of enabled checks
105
uint32_t get_enabled_checks() const;
106
107
// pre_arm_checks() is virtual so it can be modified in a vehicle specific subclass
108
virtual bool pre_arm_checks(bool report);
109
110
// some arming checks have side-effects, or require some form of state
111
// change to have occurred, and thus should not be done as pre-arm
112
// checks. Those go here:
113
virtual bool arm_checks(AP_Arming::Method method);
114
115
// get expected magnetic field strength
116
uint16_t compass_magfield_expected() const;
117
118
// rudder arming support
119
enum class RudderArming {
120
IS_DISABLED = 0, // DISABLED leaks in from vehicle defines.h
121
ARMONLY = 1,
122
ARMDISARM = 2
123
};
124
125
RudderArming get_rudder_arming_type() const { return (RudderArming)_rudder_arming.get(); }
126
127
#if AP_ARMING_AUX_AUTH_ENABLED
128
// auxiliary authorisation methods
129
bool get_aux_auth_id(uint8_t& auth_id);
130
void set_aux_auth_passed(uint8_t auth_id);
131
void set_aux_auth_failed(uint8_t auth_id, const char* fail_msg);
132
#endif
133
134
static const struct AP_Param::GroupInfo var_info[];
135
136
// method that was last used for disarm; invalid unless the
137
// vehicle has been disarmed at least once.
138
Method last_disarm_method() const { return _last_disarm_method; }
139
140
// method that was last used for arm; invalid unless the
141
// vehicle has been disarmed at least once.
142
Method last_arm_method() const { return _last_arm_method; }
143
144
// enum for ARMING_OPTIONS parameter
145
enum class Option : int32_t {
146
DISABLE_PREARM_DISPLAY = (1U << 0),
147
DISABLE_STATUSTEXT_ON_STATE_CHANGE = (1U << 1),
148
};
149
bool option_enabled(Option option) const {
150
return (_arming_options & uint32_t(option)) != 0;
151
}
152
153
void send_arm_disarm_statustext(const char *string) const;
154
155
static bool method_is_GCS(Method method) {
156
return (method == Method::MAVLINK || method == Method::DDS);
157
}
158
protected:
159
160
// Parameters
161
AP_Enum<Required> require;
162
AP_Int32 checks_to_perform; // bitmask for which checks are required
163
AP_Float accel_error_threshold;
164
AP_Int8 _rudder_arming;
165
AP_Int32 _required_mission_items;
166
AP_Int32 _arming_options;
167
AP_Int16 magfield_error_threshold;
168
169
// internal members
170
bool armed;
171
uint32_t last_accel_pass_ms;
172
uint32_t last_gyro_pass_ms;
173
174
virtual bool barometer_checks(bool report);
175
176
bool airspeed_checks(bool report);
177
178
bool logging_checks(bool report);
179
180
#if AP_INERTIALSENSOR_ENABLED
181
virtual bool ins_checks(bool report);
182
#endif
183
184
bool compass_checks(bool report);
185
186
virtual bool gps_checks(bool report);
187
188
bool battery_checks(bool report);
189
190
bool hardware_safety_check(bool report);
191
192
virtual bool board_voltage_checks(bool report);
193
194
virtual bool rc_calibration_checks(bool report);
195
196
bool rc_in_calibration_check(bool report);
197
198
bool rc_arm_checks(AP_Arming::Method method);
199
200
bool manual_transmitter_checks(bool report);
201
202
virtual bool mission_checks(bool report);
203
204
bool terrain_checks(bool report) const;
205
206
// expected to return true if the terrain database is required to have
207
// all data loaded
208
virtual bool terrain_database_required() const;
209
210
bool rangefinder_checks(bool report);
211
212
bool fence_checks(bool report);
213
214
#if HAL_HAVE_IMU_HEATER
215
bool heater_min_temperature_checks(bool report);
216
#endif
217
218
bool camera_checks(bool display_failure);
219
220
bool osd_checks(bool display_failure) const;
221
222
bool mount_checks(bool display_failure) const;
223
224
#if AP_ARMING_AUX_AUTH_ENABLED
225
bool aux_auth_checks(bool display_failure);
226
#endif
227
228
bool generator_checks(bool report) const;
229
230
bool opendroneid_checks(bool display_failure);
231
232
bool serial_protocol_checks(bool display_failure);
233
234
bool estop_checks(bool display_failure);
235
236
#if AP_ARMING_CRASHDUMP_ACK_ENABLED
237
bool crashdump_checks(bool report);
238
#endif
239
240
virtual bool system_checks(bool report);
241
242
bool can_checks(bool report);
243
244
bool fettec_checks(bool display_failure) const;
245
246
#if HAL_PROXIMITY_ENABLED
247
virtual bool proximity_checks(bool report) const;
248
#endif
249
250
bool servo_checks(bool report) const;
251
bool rc_checks_copter_sub(bool display_failure, const class RC_Channel *channels[4]) const;
252
253
bool visodom_checks(bool report) const;
254
bool disarm_switch_checks(bool report) const;
255
256
// mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced
257
virtual bool mandatory_checks(bool report);
258
259
// returns true if a particular check is enabled
260
bool check_enabled(const enum AP_Arming::ArmingChecks check) const;
261
// handle the case where a check fails
262
void check_failed(const enum AP_Arming::ArmingChecks check, bool report, const char *fmt, ...) const FMT_PRINTF(4, 5);
263
void check_failed(bool report, const char *fmt, ...) const FMT_PRINTF(3, 4);
264
265
void Log_Write_Arm(bool forced, AP_Arming::Method method);
266
void Log_Write_Disarm(bool forced, AP_Arming::Method method);
267
268
private:
269
270
static AP_Arming *_singleton;
271
272
#if AP_INERTIALSENSOR_ENABLED
273
bool ins_accels_consistent(const class AP_InertialSensor &ins);
274
bool ins_gyros_consistent(const class AP_InertialSensor &ins);
275
#endif
276
277
// check if we should keep logging after disarming
278
void check_forced_logging(const AP_Arming::Method method);
279
280
enum MIS_ITEM_CHECK {
281
MIS_ITEM_CHECK_LAND = (1 << 0),
282
MIS_ITEM_CHECK_VTOL_LAND = (1 << 1),
283
MIS_ITEM_CHECK_DO_LAND_START = (1 << 2),
284
MIS_ITEM_CHECK_TAKEOFF = (1 << 3),
285
MIS_ITEM_CHECK_VTOL_TAKEOFF = (1 << 4),
286
MIS_ITEM_CHECK_RALLY = (1 << 5),
287
MIS_ITEM_CHECK_RETURN_TO_LAUNCH = (1 << 6),
288
MIS_ITEM_CHECK_MAX
289
};
290
291
#if AP_ARMING_AUX_AUTH_ENABLED
292
// auxiliary authorisation
293
static const uint8_t aux_auth_count_max = 3; // maximum number of auxiliary authorisers
294
static const uint8_t aux_auth_str_len = 42; // maximum length of failure message (50-8 for "PreArm: ")
295
enum class AuxAuthStates : uint8_t {
296
NO_RESPONSE = 0,
297
AUTH_FAILED,
298
AUTH_PASSED
299
} aux_auth_state[aux_auth_count_max] = {}; // state of each auxiliary authorisation
300
uint8_t aux_auth_count; // number of auxiliary authorisers
301
uint8_t aux_auth_fail_msg_source; // authorisation id who set aux_auth_fail_msg
302
char* aux_auth_fail_msg; // buffer for holding failure messages
303
bool aux_auth_error; // true if too many auxiliary authorisers
304
HAL_Semaphore aux_auth_sem; // semaphore for accessing the aux_auth_state and aux_auth_fail_msg
305
#endif
306
307
// method that was last used for arm/disarm; invalid unless the
308
// vehicle has been disarmed at least once.
309
Method _last_disarm_method = Method::UNKNOWN;
310
Method _last_arm_method = Method::UNKNOWN;
311
312
uint32_t last_prearm_display_ms; // last time we send statustexts for prearm failures
313
bool running_arming_checks; // true if the arming checks currently being performed are being done because the vehicle is trying to arm the vehicle
314
315
bool last_prearm_checks_result; // result of last prearm check
316
bool report_immediately; // set to true when check goes from true to false, to trigger immediate report
317
318
void update_arm_gpio();
319
320
#if !AP_GPS_BLENDED_ENABLED
321
bool blending_auto_switch_checks(bool report);
322
#endif
323
324
#if AP_ARMING_CRASHDUMP_ACK_ENABLED
325
struct CrashDump {
326
void check_reset();
327
AP_Int8 acked;
328
} crashdump_ack;
329
#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED
330
331
};
332
333
namespace AP {
334
AP_Arming &arming();
335
};
336
337