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