Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Arming/AP_Arming.cpp
9441 views
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
#include "AP_Arming_config.h"
17
18
#if AP_ARMING_ENABLED
19
20
#include "AP_Arming.h"
21
#include <AP_HAL/AP_HAL.h>
22
#include <AP_BoardConfig/AP_BoardConfig.h>
23
#include <AP_BattMonitor/AP_BattMonitor.h>
24
#include <AP_Compass/AP_Compass.h>
25
#include <AP_Notify/AP_Notify.h>
26
#include <GCS_MAVLink/GCS.h>
27
#include <GCS_MAVLink/GCS_MAVLink.h>
28
#include <AP_Mission/AP_Mission.h>
29
#include <AP_Proximity/AP_Proximity.h>
30
#include <AP_Rally/AP_Rally.h>
31
#include <SRV_Channel/SRV_Channel.h>
32
#include <AC_Fence/AC_Fence.h>
33
#include <AP_InertialSensor/AP_InertialSensor.h>
34
#include <AP_InternalError/AP_InternalError.h>
35
#include <AP_GPS/AP_GPS.h>
36
#include <AP_Declination/AP_Declination.h>
37
#include <AP_Airspeed/AP_Airspeed.h>
38
#include <AP_AHRS/AP_AHRS.h>
39
#include <AP_Baro/AP_Baro.h>
40
#include <AP_RangeFinder/AP_RangeFinder.h>
41
#include <AP_Generator/AP_Generator.h>
42
#include <AP_Terrain/AP_Terrain.h>
43
#include <AP_ADSB/AP_ADSB.h>
44
#include <AP_Scripting/AP_Scripting.h>
45
#include <AP_Camera/AP_RunCam.h>
46
#include <AP_GyroFFT/AP_GyroFFT.h>
47
#include <AP_VisualOdom/AP_VisualOdom.h>
48
#include <AP_Parachute/AP_Parachute.h>
49
#include <AP_OSD/AP_OSD.h>
50
#include <AP_Relay/AP_Relay.h>
51
#include <RC_Channel/RC_Channel.h>
52
#include <AP_Button/AP_Button.h>
53
#include <AP_FETtecOneWire/AP_FETtecOneWire.h>
54
#include <AP_RPM/AP_RPM.h>
55
#include <AP_Mount/AP_Mount.h>
56
#include <AP_OpenDroneID/AP_OpenDroneID.h>
57
#include <AP_SerialManager/AP_SerialManager.h>
58
#include <AP_Vehicle/AP_Vehicle_Type.h>
59
#include <AP_Scheduler/AP_Scheduler.h>
60
#include <AP_KDECAN/AP_KDECAN.h>
61
#include <AP_Vehicle/AP_Vehicle.h>
62
#include <AP_ICEngine/AP_ICEngine.h>
63
64
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
65
#include <AP_CANManager/AP_CANManager.h>
66
#include <AP_Common/AP_Common.h>
67
#include <AP_Vehicle/AP_Vehicle_Type.h>
68
69
#include <AP_PiccoloCAN/AP_PiccoloCAN.h>
70
#include <AP_DroneCAN/AP_DroneCAN.h>
71
#endif
72
73
#include <AP_Logger/AP_Logger.h>
74
75
#define AP_ARMING_COMPASS_MAGFIELD_EXPECTED 530
76
#define AP_ARMING_COMPASS_MAGFIELD_MIN 185 // 0.35 * 530 milligauss
77
#define AP_ARMING_COMPASS_MAGFIELD_MAX 875 // 1.65 * 530 milligauss
78
#define AP_ARMING_BOARD_VOLTAGE_MAX 5.8f
79
#define AP_ARMING_ACCEL_ERROR_THRESHOLD 0.75f
80
#define AP_ARMING_MAGFIELD_ERROR_THRESHOLD 100
81
#define AP_ARMING_AHRS_GPS_ERROR_MAX 10 // accept up to 10m difference between AHRS and GPS
82
83
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
84
#define ARMING_RUDDER_DEFAULT (uint8_t)RudderArming::ARMONLY
85
#else
86
#define ARMING_RUDDER_DEFAULT (uint8_t)RudderArming::ARMDISARM
87
#endif
88
89
// find a default value for ARMING_NEED_POS parameter, and determine
90
// whether the parameter should be shown:
91
#ifndef AP_ARMING_NEED_LOC_PARAMETER_ENABLED
92
// determine whether ARMING_NEED_POS is shown:
93
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_Rover)
94
#define AP_ARMING_NEED_LOC_PARAMETER_ENABLED 1
95
#else
96
#define AP_ARMING_NEED_LOC_PARAMETER_ENABLED 0
97
#endif // build types
98
#endif // AP_ARMING_NEED_LOC_PARAMETER_ENABLED
99
100
// if ARMING_NEED_POS is shown, determine what its default should be:
101
#if AP_ARMING_NEED_LOC_PARAMETER_ENABLED
102
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_Rover)
103
#define AP_ARMING_NEED_LOC_DEFAULT 0
104
#else
105
#error "Unable to find value for AP_ARMING_NEED_LOC_DEFAULT"
106
#endif // APM_BUILD_TYPE
107
#endif // AP_ARMING_NEED_LOC_PARAMETER_ENABLED
108
109
#ifndef PREARM_DISPLAY_PERIOD
110
# define PREARM_DISPLAY_PERIOD 30
111
#endif
112
113
extern const AP_HAL::HAL& hal;
114
115
const AP_Param::GroupInfo AP_Arming::var_info[] = {
116
117
// @Param{Plane, Rover}: REQUIRE
118
// @DisplayName: Require Arming Motors
119
// @Description{Plane}: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, sends the minimum throttle PWM value to the throttle channel when disarmed. If 2, send 0 PWM (no signal) to throttle channel when disarmed. On planes with ICE enabled and the throttle while disarmed option set in ICE_OPTIONS, the motor will always get THR_MIN when disarmed. Arming will be blocked until all mandatory and non-ARMING_SKIPCHK items are satisfied; arming can then be accomplished via (eg.) rudder gesture or GCS command.
120
// @Description{Rover}: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, all checks not skipped by ARMING_SKIPCHK must pass before the vehicle can be armed (for example, via rudder stick or GCS command). If 3, Arm immediately once pre-arm/arm checks are satisfied, but only one time per boot up. Note that a reboot is NOT required when setting to 0 but IS require when setting to 3.
121
// @Values{Plane}: 0:Disabled,1:Yes(minimum PWM when disarmed),2:Yes(0 PWM when disarmed)
122
// @Values{Rover}: 0:No,1:Yes(minimum PWM when disarmed),3:No(AutoArmOnce after checks are passed)
123
// @User: Advanced
124
AP_GROUPINFO_FLAGS_FRAME("REQUIRE", 0, AP_Arming, require, float(Required::YES_MIN_PWM),
125
AP_PARAM_FLAG_NO_SHIFT,
126
AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_ROVER),
127
128
// 2 was the CHECK paramter stored in a AP_Int16
129
130
// @Param: ACCTHRESH
131
// @DisplayName: Accelerometer error threshold
132
// @Description: Accelerometer error threshold used to determine inconsistent accelerometers. Compares this error range to other accelerometers to detect a hardware or calibration error. Lower value means tighter check and harder to pass arming check. Not all accelerometers are created equal.
133
// @Units: m/s/s
134
// @Range: 0.25 3.0
135
// @User: Advanced
136
AP_GROUPINFO("ACCTHRESH", 3, AP_Arming, accel_error_threshold, AP_ARMING_ACCEL_ERROR_THRESHOLD),
137
138
// index 4 was VOLT_MIN, moved to AP_BattMonitor
139
// index 5 was VOLT2_MIN, moved to AP_BattMonitor
140
141
// @Param{Plane,Rover,Copter,Blimp}: RUDDER
142
// @DisplayName: Arming with Rudder enable/disable
143
// @Description: Allow arm/disarm by rudder input. When enabled arming can be done with right rudder, disarming with left rudder. Rudder arming only works with throttle at zero +- deadzone (RCx_DZ). Depending on vehicle type, arming in certain modes is prevented. See the wiki for each vehicle. Caution is recommended when arming if it is allowed in an auto-throttle mode!
144
// @Values: 0:Disabled,1:ArmingOnly,2:ArmOrDisarm
145
// @User: Advanced
146
AP_GROUPINFO_FRAME("RUDDER", 6, AP_Arming, _rudder_arming, ARMING_RUDDER_DEFAULT, AP_PARAM_FRAME_PLANE |
147
AP_PARAM_FRAME_ROVER |
148
AP_PARAM_FRAME_COPTER |
149
AP_PARAM_FRAME_TRICOPTER |
150
AP_PARAM_FRAME_HELI |
151
AP_PARAM_FRAME_BLIMP),
152
153
// @Param: MIS_ITEMS
154
// @DisplayName: Required mission items
155
// @Description: Bitmask of mission items that are required to be planned in order to arm the aircraft
156
// @Bitmask: 0:Land,1:VTOL Land,2:DO_LAND_START,3:Takeoff,4:VTOL Takeoff,5:Rallypoint,6:RTL
157
// @User: Advanced
158
AP_GROUPINFO("MIS_ITEMS", 7, AP_Arming, _required_mission_items, 0),
159
160
// index 8 was CHECK stored as AP_Int32, became SKIPCHK
161
162
// @Param: OPTIONS
163
// @DisplayName: Arming options
164
// @Description: Options that can be applied to change arming behaviour
165
// @Bitmask: 0:Disable prearm display,1:Do not send status text on state change,2:Skip IMU consistency checks when ICE motor running
166
// @User: Advanced
167
AP_GROUPINFO("OPTIONS", 9, AP_Arming, _arming_options, 0),
168
169
// @Param: MAGTHRESH
170
// @DisplayName: Compass magnetic field strength error threshold vs earth magnetic model
171
// @Description: Compass magnetic field strength error threshold vs earth magnetic model. X and y axis are compared using this threhold, Z axis uses 2x this threshold. 0 to disable check
172
// @Units: mGauss
173
// @Range: 0 500
174
// @User: Advanced
175
AP_GROUPINFO("MAGTHRESH", 10, AP_Arming, magfield_error_threshold, AP_ARMING_MAGFIELD_ERROR_THRESHOLD),
176
177
#if AP_ARMING_CRASHDUMP_ACK_ENABLED
178
// @Param: CRSDP_IGN
179
// @DisplayName: Disable CrashDump Arming check
180
// @Description: Must have value "1" if crashdump data is present on the system, or a prearm failure will be raised. Do not set this parameter unless the risks of doing so are fully understood. The presence of a crash dump means that the firmware currently installed has suffered a critical software failure which resulted in the autopilot immediately rebooting. The crashdump file gives diagnostic information which can help in finding the issue, please contact the ArduPIlot support team. If this crashdump data is present, the vehicle is likely unsafe to fly. Check the ArduPilot documentation for more details.
181
// @Values: 0:Crash Dump arming check active, 1:Crash Dump arming check deactivated
182
// @User: Advanced
183
AP_GROUPINFO("CRSDP_IGN", 11, AP_Arming, crashdump_ack.acked, 0),
184
#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED
185
186
#if AP_ARMING_NEED_LOC_PARAMETER_ENABLED
187
// @Param: NEED_LOC
188
// @DisplayName: Require vehicle location
189
// @Description: Require that the vehicle have an absolute position before it arms. This can help ensure that the vehicle can Return To Launch.
190
// @User: Advanced
191
// @Values{Copter,Rover}: 0:Do not require location,1:Require Location
192
AP_GROUPINFO("NEED_LOC", 12, AP_Arming, require_location, float(AP_ARMING_NEED_LOC_DEFAULT)),
193
#endif // AP_ARMING_NEED_LOC_PARAMETER_ENABLED
194
195
// @Param: SKIPCHK
196
// @DisplayName: Arm Checks to Skip (bitmask)
197
// @Description: Checks to skip prior to arming motor. This is a bitmask of checks before allowing arming that will be skipped. For most users it is recommended to leave this at the default of 0 (no checks skipped). In extreme circumstances, a value of -1 can be used to skip all non-mandatory current and future checks.
198
// @Bitmask: 1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,10:Logging Available,11:Hardware safety switch,12:GPS Configuration,13:System,14:Mission,15:Rangefinder,16:Camera,17:AuxAuth,18:VisualOdometry,19:FFT
199
// @Bitmask{Plane}: 1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch,12:GPS Configuration,13:System,14:Mission,15:Rangefinder,16:Camera,17:AuxAuth,19:FFT
200
// @User: Standard
201
AP_GROUPINFO("SKIPCHK", 13, AP_Arming, checks_to_skip, 0),
202
203
AP_GROUPEND
204
};
205
206
#if HAL_WITH_IO_MCU
207
#include <AP_IOMCU/AP_IOMCU.h>
208
extern AP_IOMCU iomcu;
209
#endif
210
211
#pragma GCC diagnostic push
212
#if defined(__clang_major__) && __clang_major__ >= 14
213
#pragma GCC diagnostic ignored "-Wbitwise-instead-of-logical"
214
#endif
215
216
AP_Arming::AP_Arming()
217
{
218
if (_singleton) {
219
AP_HAL::panic("Too many AP_Arming instances");
220
}
221
_singleton = this;
222
223
AP_Param::setup_object_defaults(this, var_info);
224
}
225
226
__INITFUNC__ void AP_Arming::init(void)
227
{
228
// PARAM_CONVERSION - 4.7 CHECK -> SKIPCHK
229
230
if (!checks_to_skip.configured()) {
231
// new parameter is not configured (though it may be set non-zero in a
232
// defaults table e.g. on Sub)
233
int32_t skipchk_new = checks_to_skip.get(); // get param default
234
235
uint32_t idx = 8;
236
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
237
idx <<= 6; // the old index is shifted due to AP_NESTEDGROUPINFO in AP_Arming_Plane.cpp
238
#endif
239
240
int32_t checks_old;
241
if (AP_Param::get_param_by_index(this, idx, AP_PARAM_INT32, &checks_old)) {
242
// the old parameter was customized
243
if (checks_old == 0) { // all checks disabled?
244
skipchk_new = -1; // skip all current and future checks
245
} else if (!(checks_old & 1)) { // ALL flag not set?
246
// mask of known checks at the time the conversion was written
247
uint32_t check_mask = ((1U << 21) - 1) & (~1); // remove ALL bit
248
// invert bits to get checks to skip
249
skipchk_new = (~checks_old) & check_mask;
250
} else {
251
skipchk_new = 0; // specifically enable all checks, ignoring param default
252
}
253
}
254
255
checks_to_skip.set_and_save(skipchk_new); // set and save to finish migration
256
}
257
}
258
259
// performs pre-arm checks. expects to be called at 1hz.
260
void AP_Arming::update(void)
261
{
262
#if AP_ARMING_CRASHDUMP_ACK_ENABLED
263
// if we boot with no crashdump data present, reset the "ignore"
264
// parameter so the user will need to acknowledge future crashes
265
// too:
266
crashdump_ack.check_reset();
267
#endif
268
269
const uint32_t now_ms = AP_HAL::millis();
270
// perform pre-arm checks & display failures every 30 seconds
271
bool display_fail = false;
272
if ((report_immediately && (now_ms - last_prearm_display_ms > 4000)) ||
273
(now_ms - last_prearm_display_ms > PREARM_DISPLAY_PERIOD*1000)) {
274
report_immediately = false;
275
display_fail = true;
276
last_prearm_display_ms = now_ms;
277
}
278
// OTOH, the user may never want to display them:
279
if (option_enabled(Option::DISABLE_PREARM_DISPLAY)) {
280
display_fail = false;
281
}
282
283
pre_arm_checks(display_fail);
284
}
285
286
#if AP_ARMING_CRASHDUMP_ACK_ENABLED
287
void AP_Arming::CrashDump::check_reset()
288
{
289
// if there is no crash dump data then clear the crash dump ack.
290
// This means on subsequent crash-dumps appearing the user must
291
// re-acknowledge.
292
if (hal.util->last_crash_dump_size() == 0) {
293
// no crash dump data
294
acked.set_and_save_ifchanged(0);
295
}
296
}
297
#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED
298
299
uint16_t AP_Arming::compass_magfield_expected() const
300
{
301
return AP_ARMING_COMPASS_MAGFIELD_EXPECTED;
302
}
303
304
bool AP_Arming::is_armed() const
305
{
306
return armed || arming_required() == Required::NO;
307
}
308
309
/*
310
true if armed and safety is off
311
*/
312
bool AP_Arming::is_armed_and_safety_off() const
313
{
314
return is_armed() && hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED;
315
}
316
317
uint32_t AP_Arming::get_enabled_checks() const
318
{
319
// ignore unknown checks
320
uint32_t check_mask = (uint32_t(Check::CHECK_LAST)-1) & (~1); // remove former ALL bit
321
return (~checks_to_skip) & check_mask;
322
}
323
324
bool AP_Arming::check_enabled(const AP_Arming::Check check) const
325
{
326
return (checks_to_skip & uint32_t(check)) == 0;
327
}
328
329
bool AP_Arming::all_checks_enabled() const
330
{
331
// ignore unknown checks
332
uint32_t check_mask = (uint32_t(Check::CHECK_LAST)-1) & (~1); // remove former ALL bit
333
return (checks_to_skip & check_mask) == 0;
334
}
335
336
void AP_Arming::check_failed(const AP_Arming::Check check, bool report, const char *fmt, ...) const
337
{
338
if (!report) {
339
return;
340
}
341
char taggedfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
342
343
// metafmt is wrapped around the passed-in format string to
344
// prepend "PreArm" or "Arm", depending on what sorts of checks
345
// we're currently doing.
346
const char *metafmt = "PreArm: %s"; // it's formats all the way down
347
if (running_arming_checks) {
348
metafmt = "Arm: %s";
349
}
350
hal.util->snprintf(taggedfmt, sizeof(taggedfmt), metafmt, fmt);
351
352
#if HAL_GCS_ENABLED
353
MAV_SEVERITY severity = MAV_SEVERITY_CRITICAL;
354
if (!check_enabled(check)) {
355
// technically should be NOTICE, but will annoy users at that level:
356
severity = MAV_SEVERITY_DEBUG;
357
}
358
va_list arg_list;
359
va_start(arg_list, fmt);
360
gcs().send_textv(severity, taggedfmt, arg_list);
361
va_end(arg_list);
362
#endif // HAL_GCS_ENABLED
363
}
364
365
void AP_Arming::check_failed(bool report, const char *fmt, ...) const
366
{
367
#if HAL_GCS_ENABLED
368
if (!report) {
369
return;
370
}
371
char taggedfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
372
373
// metafmt is wrapped around the passed-in format string to
374
// prepend "PreArm" or "Arm", depending on what sorts of checks
375
// we're currently doing.
376
const char *metafmt = "PreArm: %s"; // it's formats all the way down
377
if (running_arming_checks) {
378
metafmt = "Arm: %s";
379
}
380
hal.util->snprintf(taggedfmt, sizeof(taggedfmt), metafmt, fmt);
381
382
va_list arg_list;
383
va_start(arg_list, fmt);
384
gcs().send_textv(MAV_SEVERITY_CRITICAL, taggedfmt, arg_list);
385
va_end(arg_list);
386
#endif // HAL_GCS_ENABLED
387
}
388
389
bool AP_Arming::barometer_checks(bool report)
390
{
391
#ifdef HAL_BARO_ALLOW_INIT_NO_BARO
392
return true;
393
#endif
394
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
395
if (AP::sitl()->baro_count == 0) {
396
// simulate no baro boards
397
return true;
398
}
399
#endif
400
if (check_enabled(Check::BARO)) {
401
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
402
if (!AP::baro().arming_checks(sizeof(buffer), buffer)) {
403
check_failed(Check::BARO, report, "Baro: %s", buffer);
404
return false;
405
}
406
}
407
408
return true;
409
}
410
411
#if AP_AIRSPEED_ENABLED
412
bool AP_Arming::airspeed_checks(bool report)
413
{
414
if (check_enabled(Check::AIRSPEED)) {
415
const AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
416
if (airspeed == nullptr) {
417
// not an airspeed capable vehicle
418
return true;
419
}
420
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
421
if (!airspeed->arming_checks(sizeof(buffer), buffer)) {
422
check_failed(Check::AIRSPEED, report, "Airspeed: %s", buffer);
423
return false;
424
}
425
}
426
427
return true;
428
}
429
#endif // AP_AIRSPEED_ENABLED
430
431
#if HAL_LOGGING_ENABLED
432
bool AP_Arming::logging_checks(bool report)
433
{
434
if (check_enabled(Check::LOGGING)) {
435
if (!AP::logger().logging_present()) {
436
// Logging is disabled, so nothing to check.
437
return true;
438
}
439
if (AP::logger().logging_failed()) {
440
check_failed(Check::LOGGING, report, "Logging failed");
441
return false;
442
}
443
if (!AP::logger().CardInserted()) {
444
check_failed(Check::LOGGING, report, "No SD card");
445
return false;
446
}
447
if (AP::logger().in_log_download()) {
448
check_failed(Check::LOGGING, report, "Downloading logs");
449
return false;
450
}
451
}
452
return true;
453
}
454
#endif // HAL_LOGGING_ENABLED
455
456
#if AP_INERTIALSENSOR_ENABLED
457
bool AP_Arming::ins_accels_consistent(const AP_InertialSensor &ins)
458
{
459
const uint32_t now = AP_HAL::millis();
460
if (!ins.accels_consistent(accel_error_threshold)) {
461
// accels are inconsistent:
462
last_accel_pass_ms = 0;
463
return false;
464
}
465
466
if (last_accel_pass_ms == 0) {
467
// we didn't return false above, so sensors are
468
// consistent right now:
469
last_accel_pass_ms = now;
470
}
471
472
// if accels can in theory be inconsistent,
473
// must pass for at least 10 seconds before we're considered consistent:
474
if (ins.get_accel_count() > 1 && now - last_accel_pass_ms < 10000) {
475
return false;
476
}
477
478
return true;
479
}
480
481
bool AP_Arming::ins_gyros_consistent(const AP_InertialSensor &ins)
482
{
483
const uint32_t now = AP_HAL::millis();
484
// allow for up to 5 degrees/s difference
485
if (!ins.gyros_consistent(5)) {
486
// gyros are inconsistent:
487
last_gyro_pass_ms = 0;
488
return false;
489
}
490
491
// we didn't return false above, so sensors are
492
// consistent right now:
493
if (last_gyro_pass_ms == 0) {
494
last_gyro_pass_ms = now;
495
}
496
497
// if gyros can in theory be inconsistent,
498
// must pass for at least 10 seconds before we're considered consistent:
499
if (ins.get_gyro_count() > 1 && now - last_gyro_pass_ms < 10000) {
500
return false;
501
}
502
503
return true;
504
}
505
506
bool AP_Arming::ins_checks(bool report)
507
{
508
if (check_enabled(Check::INS)) {
509
const AP_InertialSensor &ins = AP::ins();
510
if (!ins.get_gyro_health_all()) {
511
check_failed(Check::INS, report, "Gyros not healthy");
512
return false;
513
}
514
if (!ins.gyro_calibrated_ok_all()) {
515
check_failed(Check::INS, report, "Gyros not calibrated");
516
return false;
517
}
518
if (!ins.get_accel_health_all()) {
519
check_failed(Check::INS, report, "Accels not healthy");
520
return false;
521
}
522
if (!ins.accel_calibrated_ok_all()) {
523
check_failed(Check::INS, report, "3D Accel calibration needed");
524
return false;
525
}
526
527
//check if accelerometers have calibrated and require reboot
528
if (ins.accel_cal_requires_reboot()) {
529
check_failed(Check::INS, report, "Accels calibrated requires reboot");
530
return false;
531
}
532
533
bool run_imu_consistency_check = true;
534
#if AP_ICENGINE_ENABLED
535
if (option_enabled(Option::SKIP_IMU_CONSISTENCY_ICE_RUNNING)) {
536
// ICE motors can greatly disturb the IMU, so we get arming failures
537
// due to gyro (and sometimes accel) inconsistency. Allow this check to be
538
// disabled while the motor is running
539
auto ice = AP::ice();
540
if (ice != nullptr) {
541
const auto ice_state = ice->get_state();
542
if (ice_state == AP_ICEngine::ICE_STARTING || ice_state == AP_ICEngine::ICE_RUNNING) {
543
run_imu_consistency_check = false;
544
}
545
}
546
}
547
#endif
548
549
if (run_imu_consistency_check) {
550
// check all accelerometers point in roughly same direction
551
if (!ins_accels_consistent(ins)) {
552
check_failed(Check::INS, report, "Accels inconsistent");
553
return false;
554
}
555
556
// check all gyros are giving consistent readings
557
if (!ins_gyros_consistent(ins)) {
558
check_failed(Check::INS, report, "Gyros inconsistent");
559
return false;
560
}
561
}
562
563
// no arming while doing temp cal
564
if (ins.temperature_cal_running()) {
565
check_failed(Check::INS, report, "temperature cal running");
566
return false;
567
}
568
569
#if AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED
570
// If Batch sampling enabled it must be initialized
571
if (ins.batchsampler.enabled() && !ins.batchsampler.is_initialised()) {
572
check_failed(Check::INS, report, "Batch sampling requires reboot");
573
return false;
574
}
575
#endif
576
577
// check if IMU gyro updates are greater than or equal to Ardupilot Loop rate
578
char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
579
if (!ins.pre_arm_check_gyro_backend_rate_hz(fail_msg, ARRAY_SIZE(fail_msg))) {
580
check_failed(Check::INS, report, "%s", fail_msg);
581
return false;
582
}
583
}
584
585
#if HAL_GYROFFT_ENABLED
586
// gyros are healthy so check the FFT
587
if (check_enabled(Check::FFT)) {
588
// Check that the noise analyser works
589
AP_GyroFFT *fft = AP::fft();
590
591
char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
592
if (fft != nullptr && !fft->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
593
check_failed(Check::INS, report, "%s", fail_msg);
594
return false;
595
}
596
}
597
#endif
598
599
return true;
600
}
601
#endif // AP_INERTIALSENSOR_ENABLED
602
603
bool AP_Arming::compass_checks(bool report)
604
{
605
Compass &_compass = AP::compass();
606
607
#if COMPASS_CAL_ENABLED
608
// check if compass is calibrating
609
if (_compass.is_calibrating()) {
610
check_failed(report, "Compass calibration running");
611
return false;
612
}
613
614
// check if compass has calibrated and requires reboot
615
if (_compass.compass_cal_requires_reboot()) {
616
check_failed(report, "Compass calibrated requires reboot");
617
return false;
618
}
619
#endif
620
621
if (check_enabled(Check::COMPASS)) {
622
623
// avoid Compass::use_for_yaw(void) as it implicitly calls healthy() which can
624
// incorrectly skip the remaining checks, pass the primary instance directly
625
if (!_compass.use_for_yaw(0)) {
626
// compass use is disabled
627
return true;
628
}
629
630
if (!_compass.healthy()) {
631
check_failed(Check::COMPASS, report, "Compass %d not healthy", _compass.get_first_usable() + 1);
632
return false;
633
}
634
// check compass learning is on or offsets have been set
635
#if !APM_BUILD_COPTER_OR_HELI && !APM_BUILD_TYPE(APM_BUILD_Blimp)
636
// check compass offsets have been set if learning is off
637
// copter and blimp always require configured compasses
638
if (!_compass.learn_offsets_enabled())
639
#endif
640
{
641
char failure_msg[100] = {};
642
if (!_compass.configured(failure_msg, ARRAY_SIZE(failure_msg))) {
643
check_failed(Check::COMPASS, report, "%s", failure_msg);
644
return false;
645
}
646
}
647
648
// check for unreasonable compass offsets
649
const Vector3f offsets = _compass.get_offsets();
650
if (offsets.length() > _compass.get_offsets_max()) {
651
check_failed(Check::COMPASS, report, "Compass offsets too high");
652
return false;
653
}
654
655
// check for unreasonable mag field length
656
const float mag_field = _compass.get_field().length();
657
if (mag_field > AP_ARMING_COMPASS_MAGFIELD_MAX || mag_field < AP_ARMING_COMPASS_MAGFIELD_MIN) {
658
check_failed(Check::COMPASS, report, "Check mag field: %4.0f, max %d, min %d", (double)mag_field, AP_ARMING_COMPASS_MAGFIELD_MAX, AP_ARMING_COMPASS_MAGFIELD_MIN);
659
return false;
660
}
661
662
// check all compasses point in roughly same direction
663
if (!_compass.consistent()) {
664
check_failed(Check::COMPASS, report, "Compasses inconsistent");
665
return false;
666
}
667
668
#if AP_AHRS_ENABLED
669
// if ahrs is using compass and we have location, check mag field versus expected earth magnetic model
670
Location ahrs_loc;
671
AP_AHRS &ahrs = AP::ahrs();
672
if ((magfield_error_threshold > 0) && ahrs.use_compass() && ahrs.get_location(ahrs_loc)) {
673
const Vector3f veh_mag_field_ef = ahrs.get_rotation_body_to_ned() * _compass.get_field();
674
const Vector3f earth_field_mgauss = AP_Declination::get_earth_field_ga(ahrs_loc) * 1000.0;
675
const Vector3f diff_mgauss = veh_mag_field_ef - earth_field_mgauss;
676
if (MAX(fabsf(diff_mgauss.x), fabsf(diff_mgauss.y)) > magfield_error_threshold) {
677
check_failed(Check::COMPASS, report, "Check mag field (xy diff:%.0f>%d)",
678
(double)MAX(fabsf(diff_mgauss.x), (double)fabsf(diff_mgauss.y)), (int)magfield_error_threshold);
679
return false;
680
}
681
if (fabsf(diff_mgauss.z) > magfield_error_threshold*2.0) {
682
check_failed(Check::COMPASS, report, "Check mag field (z diff:%.0f>%d)",
683
(double)fabsf(diff_mgauss.z), (int)magfield_error_threshold*2);
684
return false;
685
}
686
}
687
#endif // AP_AHRS_ENABLED
688
}
689
690
return true;
691
}
692
693
#if AP_GPS_ENABLED
694
bool AP_Arming::gps_checks(bool report)
695
{
696
const AP_GPS &gps = AP::gps();
697
if (check_enabled(Check::GPS)) {
698
699
// Any failure messages from GPS backends
700
char failure_msg[100] = {};
701
if (!AP::gps().pre_arm_checks(failure_msg, ARRAY_SIZE(failure_msg))) {
702
if (failure_msg[0] != '\0') {
703
check_failed(Check::GPS, report, "%s", failure_msg);
704
}
705
return false;
706
}
707
708
for (uint8_t i = 0; i < gps.num_sensors(); i++) {
709
#if AP_GPS_BLENDED_ENABLED
710
if ((i != GPS_BLENDED_INSTANCE) &&
711
#else
712
if (
713
#endif
714
(gps.get_type(i) == AP_GPS::GPS_Type::GPS_TYPE_NONE)) {
715
if (gps.primary_sensor() == i) {
716
check_failed(Check::GPS, report, "GPS %i: primary but TYPE 0", i+1);
717
return false;
718
}
719
continue;
720
}
721
722
//GPS OK?
723
if (gps.status(i) < AP_GPS::GPS_OK_FIX_3D) {
724
check_failed(Check::GPS, report, "GPS %i: Bad fix", i+1);
725
return false;
726
}
727
728
//GPS update rate acceptable
729
if (!gps.is_healthy(i)) {
730
check_failed(Check::GPS, report, "GPS %i: not healthy", i+1);
731
return false;
732
}
733
}
734
735
if (!AP::ahrs().home_is_set()) {
736
check_failed(Check::GPS, report, "AHRS: waiting for home");
737
return false;
738
}
739
740
// check GPSs are within 50m of each other and that blending is healthy
741
float distance_m;
742
if (!gps.all_consistent(distance_m)) {
743
check_failed(Check::GPS, report, "GPS positions differ by %4.1fm",
744
(double)distance_m);
745
return false;
746
}
747
748
// check AHRS and GPS are within 10m of each other
749
if (gps.num_sensors() > 0) {
750
const Location gps_loc = gps.location();
751
Location ahrs_loc;
752
if (AP::ahrs().get_location(ahrs_loc)) {
753
const float distance = gps_loc.get_distance(ahrs_loc);
754
if (distance > AP_ARMING_AHRS_GPS_ERROR_MAX) {
755
check_failed(Check::GPS, report, "GPS and AHRS differ by %4.1fm", (double)distance);
756
return false;
757
}
758
}
759
}
760
}
761
762
if (check_enabled(Check::GPS_CONFIG)) {
763
uint8_t first_unconfigured;
764
if (gps.first_unconfigured_gps(first_unconfigured)) {
765
check_failed(Check::GPS_CONFIG,
766
report,
767
"GPS %d still configuring this GPS",
768
first_unconfigured + 1);
769
if (report) {
770
gps.broadcast_first_configuration_failure_reason();
771
}
772
return false;
773
}
774
}
775
776
return true;
777
}
778
#endif // AP_GPS_ENABLED
779
780
#if AP_BATTERY_ENABLED
781
bool AP_Arming::battery_checks(bool report)
782
{
783
if (check_enabled(Check::BATTERY)) {
784
785
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
786
if (!AP::battery().arming_checks(sizeof(buffer), buffer)) {
787
check_failed(Check::BATTERY, report, "%s", buffer);
788
return false;
789
}
790
}
791
return true;
792
}
793
#endif // AP_BATTERY_ENABLED
794
795
bool AP_Arming::hardware_safety_check(bool report)
796
{
797
if (check_enabled(Check::SWITCH)) {
798
799
// check if safety switch has been pushed
800
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
801
check_failed(Check::SWITCH, report, "Hardware safety switch");
802
return false;
803
}
804
}
805
806
return true;
807
}
808
809
#if AP_RC_CHANNEL_ENABLED
810
bool AP_Arming::rc_arm_checks(AP_Arming::Method method)
811
{
812
// don't check the trims if we are in a failsafe
813
if (!rc().has_valid_input()) {
814
return true;
815
}
816
817
// only check if we've received some form of input within the last second
818
// this is a protection against a vehicle having never enabled an input
819
uint32_t last_input_ms = rc().last_input_ms();
820
if ((last_input_ms == 0) || ((AP_HAL::millis() - last_input_ms) > 1000)) {
821
return true;
822
}
823
824
bool check_passed = true;
825
// ensure all rc channels have different functions
826
if (rc().duplicate_options_exist()) {
827
check_failed(Check::PARAMETERS, true, "Duplicate Aux Switch Options");
828
check_passed = false;
829
}
830
if (rc().flight_mode_channel_conflicts_with_rc_option()) {
831
check_failed(Check::PARAMETERS, true, "Mode channel and RC%d_OPTION conflict", rc().flight_mode_channel_number());
832
check_passed = false;
833
}
834
{
835
if (!rc().option_is_enabled(RC_Channels::Option::ARMING_SKIP_CHECK_RPY)) {
836
const struct {
837
const char *name;
838
const RC_Channel *channel;
839
} channels_to_check[] {
840
{ "Roll", &rc().get_roll_channel(), },
841
{ "Pitch", &rc().get_pitch_channel(), },
842
{ "Yaw", &rc().get_yaw_channel(), },
843
};
844
for (const auto &channel_to_check : channels_to_check) {
845
const auto *c = channel_to_check.channel;
846
if (c->get_control_in() != 0) {
847
if ((method != Method::RUDDER) || (c != rc().get_arming_channel())) { // ignore the yaw input channel if rudder arming
848
check_failed(Check::RC, true, "%s (RC%d) is not neutral", channel_to_check.name, c->ch());
849
check_passed = false;
850
}
851
}
852
}
853
}
854
855
// if throttle check is enabled, require zero input
856
if (rc().arming_check_throttle()) {
857
const RC_Channel *c = &rc().get_throttle_channel();
858
if (c->get_control_in() != 0) {
859
check_failed(Check::RC, true, "%s (RC%d) is not neutral", "Throttle", c->ch());
860
check_passed = false;
861
}
862
c = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FWD_THR);
863
if (c != nullptr) {
864
uint8_t fwd_thr = c->percent_input();
865
// require channel input within 2% of minimum
866
if (fwd_thr > 2) {
867
check_failed(Check::RC, true, "VTOL Fwd Throttle is not zero");
868
check_passed = false;
869
}
870
}
871
}
872
}
873
return check_passed;
874
}
875
876
bool AP_Arming::rc_calibration_checks(bool report)
877
{
878
bool check_passed = true;
879
const uint8_t num_channels = RC_Channels::get_valid_channel_count();
880
for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
881
const RC_Channel *c = rc().channel(i);
882
if (c == nullptr) {
883
continue;
884
}
885
if (i >= num_channels && !(c->has_override())) {
886
continue;
887
}
888
const uint16_t trim = c->get_radio_trim();
889
if (c->get_radio_min() > trim) {
890
check_failed(Check::RC, report, "RC%d_MIN is greater than RC%d_TRIM", i + 1, i + 1);
891
check_passed = false;
892
}
893
if (c->get_radio_max() < trim) {
894
check_failed(Check::RC, report, "RC%d_MAX is less than RC%d_TRIM", i + 1, i + 1);
895
check_passed = false;
896
}
897
}
898
899
return check_passed;
900
}
901
902
bool AP_Arming::rc_in_calibration_check(bool report)
903
{
904
if (rc().calibrating()) {
905
check_failed(Check::RC, report, "RC calibrating");
906
return false;
907
}
908
return true;
909
}
910
911
bool AP_Arming::manual_transmitter_checks(bool report)
912
{
913
if (check_enabled(Check::RC)) {
914
915
if (AP_Notify::flags.failsafe_radio) {
916
check_failed(Check::RC, report, "Radio failsafe on");
917
return false;
918
}
919
920
if (!rc_calibration_checks(report)) {
921
return false;
922
}
923
}
924
925
return rc_in_calibration_check(report);
926
}
927
#endif // AP_RC_CHANNEL_ENABLED
928
929
#if AP_MISSION_ENABLED
930
bool AP_Arming::mission_checks(bool report)
931
{
932
AP_Mission *mission = AP::mission();
933
if (check_enabled(Check::MISSION) && _required_mission_items) {
934
if (mission == nullptr) {
935
check_failed(Check::MISSION, report, "No mission library present");
936
return false;
937
}
938
939
const struct MisItemTable {
940
MIS_ITEM_CHECK check;
941
MAV_CMD mis_item_type;
942
const char *type;
943
} misChecks[] = {
944
{MIS_ITEM_CHECK_LAND, MAV_CMD_NAV_LAND, "land"},
945
{MIS_ITEM_CHECK_VTOL_LAND, MAV_CMD_NAV_VTOL_LAND, "vtol land"},
946
{MIS_ITEM_CHECK_DO_LAND_START, MAV_CMD_DO_LAND_START, "do land start"},
947
{MIS_ITEM_CHECK_TAKEOFF, MAV_CMD_NAV_TAKEOFF, "takeoff"},
948
{MIS_ITEM_CHECK_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_TAKEOFF, "vtol takeoff"},
949
{MIS_ITEM_CHECK_RETURN_TO_LAUNCH, MAV_CMD_NAV_RETURN_TO_LAUNCH, "RTL"},
950
};
951
for (uint8_t i = 0; i < ARRAY_SIZE(misChecks); i++) {
952
if (_required_mission_items & misChecks[i].check) {
953
if (!mission->contains_item(misChecks[i].mis_item_type)) {
954
check_failed(Check::MISSION, report, "Missing mission item: %s", misChecks[i].type);
955
return false;
956
}
957
}
958
}
959
if (_required_mission_items & MIS_ITEM_CHECK_RALLY) {
960
#if HAL_RALLY_ENABLED
961
AP_Rally *rally = AP::rally();
962
if (rally == nullptr) {
963
check_failed(Check::MISSION, report, "No rally library present");
964
return false;
965
}
966
Location ahrs_loc;
967
if (!AP::ahrs().get_location(ahrs_loc)) {
968
check_failed(Check::MISSION, report, "Can't check rally without position");
969
return false;
970
}
971
RallyLocation rally_loc = {};
972
if (!rally->find_nearest_rally_point(ahrs_loc, rally_loc)) {
973
check_failed(Check::MISSION, report, "No sufficiently close rally point located");
974
return false;
975
}
976
#else
977
check_failed(Check::MISSION, report, "No rally library present");
978
return false;
979
#endif
980
}
981
}
982
983
#if AP_SDCARD_STORAGE_ENABLED
984
if (check_enabled(Check::MISSION) &&
985
mission != nullptr &&
986
(mission->failed_sdcard_storage() || StorageManager::storage_failed())) {
987
check_failed(Check::MISSION, report, "Failed to open %s", AP_MISSION_SDCARD_FILENAME);
988
return false;
989
}
990
#endif
991
992
#if AP_VEHICLE_ENABLED
993
// do not allow arming if there are no mission items and we are in
994
// (e.g.) AUTO mode
995
if (AP::vehicle()->current_mode_requires_mission() &&
996
(mission == nullptr || !mission->present())) {
997
check_failed(Check::MISSION, report, "Mode requires mission");
998
return false;
999
}
1000
#endif
1001
1002
return true;
1003
}
1004
#endif // AP_MISSION_ENABLED
1005
1006
bool AP_Arming::rangefinder_checks(bool report)
1007
{
1008
#if AP_RANGEFINDER_ENABLED
1009
if (check_enabled(Check::RANGEFINDER)) {
1010
RangeFinder *range = RangeFinder::get_singleton();
1011
if (range == nullptr) {
1012
return true;
1013
}
1014
1015
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
1016
if (!range->prearm_healthy(buffer, ARRAY_SIZE(buffer))) {
1017
check_failed(Check::RANGEFINDER, report, "%s", buffer);
1018
return false;
1019
}
1020
}
1021
#endif
1022
1023
return true;
1024
}
1025
1026
bool AP_Arming::servo_checks(bool report) const
1027
{
1028
#if NUM_SERVO_CHANNELS
1029
bool check_passed = true;
1030
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
1031
const SRV_Channel *c = SRV_Channels::srv_channel(i);
1032
if (c == nullptr || c->get_function() <= SRV_Channel::k_none) {
1033
continue;
1034
}
1035
1036
const uint16_t trim = c->get_trim();
1037
if (c->get_output_min() > trim) {
1038
check_failed(report, "SERVO%d_MIN is greater than SERVO%d_TRIM", i + 1, i + 1);
1039
check_passed = false;
1040
}
1041
if (c->get_output_max() < trim) {
1042
check_failed(report, "SERVO%d_MAX is less than SERVO%d_TRIM", i + 1, i + 1);
1043
check_passed = false;
1044
}
1045
1046
// check functions using PWM are enabled
1047
if (SRV_Channels::get_disabled_channel_mask() & 1U<<i) {
1048
const SRV_Channel::Function ch_function = c->get_function();
1049
1050
// motors, e-stoppable functions, neopixels and ProfiLEDs may be digital outputs and thus can be disabled
1051
// scripting can use its functions as labels for LED setup
1052
const bool disabled_ok = SRV_Channel::is_motor(ch_function) ||
1053
SRV_Channel::should_e_stop(ch_function) ||
1054
(ch_function >= SRV_Channel::k_LED_neopixel1 && ch_function <= SRV_Channel::k_LED_neopixel4) ||
1055
(ch_function >= SRV_Channel::k_ProfiLED_1 && ch_function <= SRV_Channel::k_ProfiLED_Clock) ||
1056
(ch_function >= SRV_Channel::k_scripting1 && ch_function <= SRV_Channel::k_scripting16);
1057
1058
// for all other functions raise a pre-arm failure
1059
if (!disabled_ok) {
1060
check_failed(report, "SERVO%u_FUNCTION=%u on disabled channel", i + 1, (unsigned)ch_function);
1061
check_passed = false;
1062
}
1063
}
1064
}
1065
1066
#if HAL_WITH_IO_MCU
1067
if (!iomcu.healthy() && AP_BoardConfig::io_enabled()) {
1068
check_failed(report, "IOMCU is unhealthy");
1069
check_passed = false;
1070
}
1071
#endif
1072
1073
return check_passed;
1074
#else
1075
return false;
1076
#endif
1077
}
1078
1079
bool AP_Arming::board_voltage_checks(bool report)
1080
{
1081
// check board voltage
1082
if (check_enabled(Check::VOLTAGE)) {
1083
#if HAL_HAVE_BOARD_VOLTAGE
1084
const float bus_voltage = hal.analogin->board_voltage();
1085
const float vbus_min = AP_BoardConfig::get_minimum_board_voltage();
1086
if(((bus_voltage < vbus_min) || (bus_voltage > AP_ARMING_BOARD_VOLTAGE_MAX))) {
1087
check_failed(Check::VOLTAGE, report, "Board (%1.1fv) out of range %1.1f-%1.1fv", (double)bus_voltage, (double)vbus_min, (double)AP_ARMING_BOARD_VOLTAGE_MAX);
1088
return false;
1089
}
1090
#endif // HAL_HAVE_BOARD_VOLTAGE
1091
1092
#if HAL_HAVE_SERVO_VOLTAGE
1093
const float vservo_min = AP_BoardConfig::get_minimum_servo_voltage();
1094
if (is_positive(vservo_min)) {
1095
const float servo_voltage = hal.analogin->servorail_voltage();
1096
if (servo_voltage < vservo_min) {
1097
check_failed(Check::VOLTAGE, report, "Servo voltage to low (%1.2fv < %1.2fv)", (double)servo_voltage, (double)vservo_min);
1098
return false;
1099
}
1100
}
1101
#endif // HAL_HAVE_SERVO_VOLTAGE
1102
}
1103
1104
return true;
1105
}
1106
1107
#if HAL_HAVE_IMU_HEATER
1108
bool AP_Arming::heater_min_temperature_checks(bool report)
1109
{
1110
if (all_checks_enabled()) {
1111
AP_BoardConfig *board = AP::boardConfig();
1112
if (board) {
1113
float temperature;
1114
int8_t min_temperature;
1115
if (board->get_board_heater_temperature(temperature) &&
1116
board->get_board_heater_arming_temperature(min_temperature) &&
1117
(temperature < min_temperature)) {
1118
check_failed(Check::SYSTEM, report, "heater temp low (%0.1f < %i)", temperature, min_temperature);
1119
return false;
1120
}
1121
}
1122
}
1123
return true;
1124
}
1125
#endif // HAL_HAVE_IMU_HEATER
1126
1127
/*
1128
check base system operations
1129
*/
1130
bool AP_Arming::system_checks(bool report)
1131
{
1132
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
1133
1134
if (check_enabled(Check::SYSTEM)) {
1135
if (!hal.storage->healthy()) {
1136
check_failed(Check::SYSTEM, report, "Param storage failed");
1137
return false;
1138
}
1139
1140
if (AP_Param::get_eeprom_full()) {
1141
check_failed(Check::PARAMETERS, report, "parameter storage full");
1142
return false;
1143
}
1144
1145
// check main loop rate is at least 90% of expected value
1146
const float actual_loop_rate = AP::scheduler().get_filtered_loop_rate_hz();
1147
const uint16_t expected_loop_rate = AP::scheduler().get_loop_rate_hz();
1148
const float loop_rate_pct = actual_loop_rate / expected_loop_rate;
1149
if (loop_rate_pct < 0.90) {
1150
check_failed(Check::SYSTEM, report, "Main loop slow (%uHz < %uHz)", (unsigned)actual_loop_rate, (unsigned)expected_loop_rate);
1151
return false;
1152
}
1153
1154
#if AP_TERRAIN_AVAILABLE
1155
const AP_Terrain *terrain = AP_Terrain::get_singleton();
1156
if ((terrain != nullptr) && terrain->init_failed()) {
1157
check_failed(Check::SYSTEM, report, "Terrain out of memory");
1158
return false;
1159
}
1160
#endif
1161
#if AP_SCRIPTING_ENABLED
1162
const AP_Scripting *scripting = AP_Scripting::get_singleton();
1163
if ((scripting != nullptr) && !scripting->arming_checks(sizeof(buffer), buffer)) {
1164
check_failed(Check::SYSTEM, report, "%s", buffer);
1165
return false;
1166
}
1167
#endif
1168
#if HAL_ADSB_ENABLED
1169
AP_ADSB *adsb = AP::ADSB();
1170
if ((adsb != nullptr) && adsb->enabled() && adsb->init_failed()) {
1171
check_failed(Check::SYSTEM, report, "ADSB out of memory");
1172
return false;
1173
}
1174
#endif
1175
}
1176
if (AP::internalerror().errors() != 0) {
1177
AP::internalerror().errors_as_string((uint8_t*)buffer, ARRAY_SIZE(buffer));
1178
check_failed(report, "Internal errors 0x%x l:%u %s", (unsigned int)AP::internalerror().errors(), AP::internalerror().last_error_line(), buffer);
1179
return false;
1180
}
1181
1182
if (!hal.gpio->arming_checks(sizeof(buffer), buffer)) {
1183
check_failed(report, "%s", buffer);
1184
return false;
1185
}
1186
1187
if (check_enabled(Check::PARAMETERS)) {
1188
#if !AP_GPS_BLENDED_ENABLED
1189
if (!blending_auto_switch_checks(report)) {
1190
return false;
1191
}
1192
#endif
1193
#if AP_RPM_ENABLED
1194
auto *rpm = AP::rpm();
1195
if (rpm && !rpm->arming_checks(sizeof(buffer), buffer)) {
1196
check_failed(Check::PARAMETERS, report, "%s", buffer);
1197
return false;
1198
}
1199
#endif
1200
#if AP_RELAY_ENABLED
1201
auto *relay = AP::relay();
1202
if (relay && !relay->arming_checks(sizeof(buffer), buffer)) {
1203
check_failed(Check::PARAMETERS, report, "%s", buffer);
1204
return false;
1205
}
1206
#endif
1207
#if HAL_PARACHUTE_ENABLED
1208
auto *chute = AP::parachute();
1209
if (chute && !chute->arming_checks(sizeof(buffer), buffer)) {
1210
check_failed(Check::PARAMETERS, report, "%s", buffer);
1211
return false;
1212
}
1213
#endif
1214
#if HAL_BUTTON_ENABLED
1215
const auto &button = AP::button();
1216
if (!button.arming_checks(sizeof(buffer), buffer)) {
1217
check_failed(Check::PARAMETERS, report, "%s", buffer);
1218
return false;
1219
}
1220
#endif
1221
}
1222
1223
return true;
1224
}
1225
1226
bool AP_Arming::terrain_database_required() const
1227
{
1228
#if AP_MISSION_ENABLED
1229
AP_Mission *mission = AP::mission();
1230
if (mission == nullptr) {
1231
// no mission support?
1232
return false;
1233
}
1234
if (mission->contains_terrain_alt_items()) {
1235
return true;
1236
}
1237
#endif
1238
return false;
1239
}
1240
1241
// check terrain database is fit-for-purpose
1242
bool AP_Arming::terrain_checks(bool report) const
1243
{
1244
if (!check_enabled(Check::PARAMETERS)) {
1245
return true;
1246
}
1247
1248
if (!terrain_database_required()) {
1249
return true;
1250
}
1251
1252
#if AP_TERRAIN_AVAILABLE
1253
1254
const AP_Terrain *terrain = AP_Terrain::get_singleton();
1255
if (terrain == nullptr) {
1256
check_failed(Check::PARAMETERS, report, "terrain disabled");
1257
return false;
1258
}
1259
1260
if (!terrain->enabled()) {
1261
check_failed(Check::PARAMETERS, report, "terrain disabled");
1262
return false;
1263
}
1264
1265
char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
1266
if (!terrain->pre_arm_checks(fail_msg, sizeof(fail_msg))) {
1267
check_failed(Check::PARAMETERS, report, "%s", fail_msg);
1268
return false;
1269
}
1270
1271
return true;
1272
1273
#else
1274
check_failed(Check::PARAMETERS, report, "terrain required but disabled");
1275
return false;
1276
#endif
1277
}
1278
1279
1280
#if HAL_PROXIMITY_ENABLED
1281
// check nothing is too close to vehicle
1282
bool AP_Arming::proximity_checks(bool report) const
1283
{
1284
const AP_Proximity *proximity = AP::proximity();
1285
// return true immediately if no sensor present
1286
if (proximity == nullptr) {
1287
return true;
1288
}
1289
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
1290
if (!proximity->prearm_healthy(buffer, ARRAY_SIZE(buffer))) {
1291
check_failed(report, "%s", buffer);
1292
return false;
1293
}
1294
return true;
1295
}
1296
#endif // HAL_PROXIMITY_ENABLED
1297
1298
#if HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED
1299
bool AP_Arming::can_checks(bool report)
1300
{
1301
if (check_enabled(Check::SYSTEM)) {
1302
char fail_msg[100] = {};
1303
(void)fail_msg; // might be left unused
1304
uint8_t num_drivers = AP::can().get_num_drivers();
1305
1306
for (uint8_t i = 0; i < num_drivers; i++) {
1307
switch (AP::can().get_driver_type(i)) {
1308
case AP_CAN::Protocol::PiccoloCAN: {
1309
#if AP_PICCOLOCAN_ENABLED
1310
AP_PiccoloCAN *ap_pcan = AP_PiccoloCAN::get_pcan(i);
1311
1312
if (ap_pcan != nullptr && !ap_pcan->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
1313
check_failed(Check::SYSTEM, report, "PiccoloCAN: %s", fail_msg);
1314
return false;
1315
}
1316
1317
#else
1318
check_failed(Check::SYSTEM, report, "PiccoloCAN not enabled");
1319
return false;
1320
#endif
1321
break;
1322
}
1323
case AP_CAN::Protocol::DroneCAN:
1324
{
1325
#if HAL_ENABLE_DRONECAN_DRIVERS
1326
AP_DroneCAN *ap_dronecan = AP_DroneCAN::get_dronecan(i);
1327
if (ap_dronecan != nullptr && !ap_dronecan->prearm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
1328
check_failed(Check::SYSTEM, report, "DroneCAN: %s", fail_msg);
1329
return false;
1330
}
1331
#endif
1332
break;
1333
}
1334
case AP_CAN::Protocol::USD1:
1335
case AP_CAN::Protocol::TOFSenseP:
1336
case AP_CAN::Protocol::RadarCAN:
1337
case AP_CAN::Protocol::Benewake:
1338
{
1339
for (uint8_t j = i; j; j--) {
1340
if (AP::can().get_driver_type(i) == AP::can().get_driver_type(j-1)) {
1341
check_failed(Check::SYSTEM, report, "Same rfnd on different CAN ports");
1342
return false;
1343
}
1344
}
1345
break;
1346
}
1347
case AP_CAN::Protocol::EFI_NWPMU:
1348
case AP_CAN::Protocol::None:
1349
case AP_CAN::Protocol::Scripting:
1350
case AP_CAN::Protocol::Scripting2:
1351
case AP_CAN::Protocol::KDECAN:
1352
1353
break;
1354
}
1355
}
1356
}
1357
return true;
1358
}
1359
#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED
1360
1361
1362
#if AP_FENCE_ENABLED
1363
bool AP_Arming::fence_checks(bool display_failure)
1364
{
1365
const AC_Fence *fence = AP::fence();
1366
if (fence == nullptr) {
1367
return true;
1368
}
1369
1370
// check fence is ready
1371
char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
1372
if (fence->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
1373
return true;
1374
}
1375
1376
check_failed(display_failure, "%s", fail_msg);
1377
1378
#if AP_SDCARD_STORAGE_ENABLED
1379
if (fence->failed_sdcard_storage() || StorageManager::storage_failed()) {
1380
check_failed(display_failure, "Failed to open fence storage");
1381
return false;
1382
}
1383
#endif
1384
1385
return false;
1386
}
1387
#endif // AP_FENCE_ENABLED
1388
1389
#if AP_CAMERA_RUNCAM_ENABLED
1390
bool AP_Arming::camera_checks(bool display_failure)
1391
{
1392
if (check_enabled(Check::CAMERA)) {
1393
AP_RunCam *runcam = AP::runcam();
1394
if (runcam == nullptr) {
1395
return true;
1396
}
1397
1398
// check camera is ready
1399
char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
1400
if (!runcam->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
1401
check_failed(Check::CAMERA, display_failure, "%s", fail_msg);
1402
return false;
1403
}
1404
}
1405
return true;
1406
}
1407
#endif // AP_CAMERA_RUNCAM_ENABLED
1408
1409
#if OSD_ENABLED
1410
bool AP_Arming::osd_checks(bool display_failure) const
1411
{
1412
if (check_enabled(Check::OSD)) {
1413
// if no OSD then pass
1414
const AP_OSD *osd = AP::osd();
1415
if (osd == nullptr) {
1416
return true;
1417
}
1418
// do osd checks for configuration
1419
char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
1420
if (!osd->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
1421
check_failed(Check::OSD, display_failure, "%s", fail_msg);
1422
return false;
1423
}
1424
}
1425
return true;
1426
}
1427
#endif // OSD_ENABLED
1428
1429
#if HAL_MOUNT_ENABLED
1430
bool AP_Arming::mount_checks(bool display_failure) const
1431
{
1432
if (check_enabled(Check::CAMERA)) {
1433
AP_Mount *mount = AP::mount();
1434
if (mount == nullptr) {
1435
return true;
1436
}
1437
char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] = {};
1438
if (!mount->pre_arm_checks(fail_msg, sizeof(fail_msg))) {
1439
check_failed(Check::CAMERA, display_failure, "Mount: %s", fail_msg);
1440
return false;
1441
}
1442
}
1443
return true;
1444
}
1445
#endif // HAL_MOUNT_ENABLED
1446
1447
#if AP_FETTEC_ONEWIRE_ENABLED
1448
bool AP_Arming::fettec_checks(bool display_failure) const
1449
{
1450
const AP_FETtecOneWire *f = AP_FETtecOneWire::get_singleton();
1451
if (f == nullptr) {
1452
return true;
1453
}
1454
1455
// check ESCs are ready
1456
char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
1457
if (!f->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
1458
check_failed(display_failure, "FETtec: %s", fail_msg);
1459
return false;
1460
}
1461
return true;
1462
}
1463
#endif // AP_FETTEC_ONEWIRE_ENABLED
1464
1465
#if AP_ARMING_AUX_AUTH_ENABLED
1466
// request an auxiliary authorisation id. This id should be used in subsequent calls to set_aux_auth_passed/failed
1467
// returns true on success
1468
bool AP_Arming::get_aux_auth_id(uint8_t& auth_id)
1469
{
1470
WITH_SEMAPHORE(aux_auth_sem);
1471
1472
// check we have enough room to allocate another id
1473
if (aux_auth_count >= aux_auth_count_max) {
1474
aux_auth_error = true;
1475
return false;
1476
}
1477
1478
// allocate buffer for failure message
1479
if (aux_auth_fail_msg == nullptr) {
1480
aux_auth_fail_msg = (char *)calloc(aux_auth_str_len, sizeof(char));
1481
if (aux_auth_fail_msg == nullptr) {
1482
aux_auth_error = true;
1483
return false;
1484
}
1485
}
1486
auth_id = aux_auth_count;
1487
aux_auth_count++;
1488
return true;
1489
}
1490
1491
// set auxiliary authorisation passed
1492
void AP_Arming::set_aux_auth_passed(uint8_t auth_id)
1493
{
1494
WITH_SEMAPHORE(aux_auth_sem);
1495
1496
// sanity check auth_id
1497
if (auth_id >= aux_auth_count) {
1498
return;
1499
}
1500
1501
aux_auth_state[auth_id] = AuxAuthStates::AUTH_PASSED;
1502
}
1503
1504
// set auxiliary authorisation failed and provide failure message
1505
void AP_Arming::set_aux_auth_failed(uint8_t auth_id, const char* fail_msg)
1506
{
1507
WITH_SEMAPHORE(aux_auth_sem);
1508
1509
// sanity check auth_id
1510
if (auth_id >= aux_auth_count) {
1511
return;
1512
}
1513
1514
// update state
1515
aux_auth_state[auth_id] = AuxAuthStates::AUTH_FAILED;
1516
1517
// store failure message if this authoriser has the lowest auth_id
1518
for (uint8_t i = 0; i < auth_id; i++) {
1519
if (aux_auth_state[i] == AuxAuthStates::AUTH_FAILED) {
1520
return;
1521
}
1522
}
1523
if (aux_auth_fail_msg != nullptr) {
1524
if (fail_msg == nullptr) {
1525
strncpy(aux_auth_fail_msg, "Auxiliary authorisation refused", aux_auth_str_len);
1526
} else {
1527
strncpy(aux_auth_fail_msg, fail_msg, aux_auth_str_len);
1528
}
1529
aux_auth_fail_msg_source = auth_id;
1530
}
1531
}
1532
1533
void AP_Arming::reset_all_aux_auths()
1534
{
1535
WITH_SEMAPHORE(aux_auth_sem);
1536
1537
// clear all auxiliary authorisation ids
1538
aux_auth_count = 0;
1539
// clear any previous allocation errors
1540
aux_auth_error = false;
1541
1542
// reset states for all auxiliary authorisation ids
1543
for (uint8_t i = 0; i < aux_auth_count_max; i++) {
1544
aux_auth_state[i] = AuxAuthStates::NO_RESPONSE;
1545
}
1546
1547
// free up the failure message buffer
1548
if (aux_auth_fail_msg != nullptr) {
1549
free(aux_auth_fail_msg);
1550
aux_auth_fail_msg = nullptr;
1551
}
1552
}
1553
1554
bool AP_Arming::aux_auth_checks(bool display_failure)
1555
{
1556
// handle error cases
1557
if (aux_auth_error) {
1558
if (aux_auth_fail_msg == nullptr) {
1559
check_failed(Check::AUX_AUTH, display_failure, "memory low for auxiliary authorisation");
1560
} else {
1561
check_failed(Check::AUX_AUTH, display_failure, "Too many auxiliary authorisers");
1562
}
1563
return false;
1564
}
1565
1566
WITH_SEMAPHORE(aux_auth_sem);
1567
1568
// check results for each auxiliary authorisation id
1569
bool some_failures = false;
1570
bool failure_msg_sent = false;
1571
bool waiting_for_responses = false;
1572
for (uint8_t i = 0; i < aux_auth_count; i++) {
1573
switch (aux_auth_state[i]) {
1574
case AuxAuthStates::NO_RESPONSE:
1575
waiting_for_responses = true;
1576
break;
1577
case AuxAuthStates::AUTH_FAILED:
1578
some_failures = true;
1579
if (i == aux_auth_fail_msg_source) {
1580
check_failed(Check::AUX_AUTH, display_failure, "%s", aux_auth_fail_msg);
1581
failure_msg_sent = true;
1582
}
1583
break;
1584
case AuxAuthStates::AUTH_PASSED:
1585
break;
1586
}
1587
}
1588
1589
// send failure or waiting message
1590
if (some_failures) {
1591
if (!failure_msg_sent) {
1592
check_failed(Check::AUX_AUTH, display_failure, "Auxiliary authorisation refused");
1593
}
1594
return false;
1595
} else if (waiting_for_responses) {
1596
check_failed(Check::AUX_AUTH, display_failure, "Waiting for auxiliary authorisation");
1597
return false;
1598
}
1599
1600
// if we got this far all auxiliary checks must have passed
1601
return true;
1602
}
1603
#endif // AP_ARMING_AUX_AUTH_ENABLED
1604
1605
#if HAL_GENERATOR_ENABLED
1606
bool AP_Arming::generator_checks(bool display_failure) const
1607
{
1608
const AP_Generator *generator = AP::generator();
1609
if (generator == nullptr) {
1610
return true;
1611
}
1612
char failure_msg[100] = {};
1613
if (!generator->pre_arm_check(failure_msg, sizeof(failure_msg))) {
1614
check_failed(display_failure, "Generator: %s", failure_msg);
1615
return false;
1616
}
1617
return true;
1618
}
1619
#endif // HAL_GENERATOR_ENABLED
1620
1621
#if AP_OPENDRONEID_ENABLED
1622
// OpenDroneID Checks
1623
bool AP_Arming::opendroneid_checks(bool display_failure)
1624
{
1625
auto &opendroneid = AP::opendroneid();
1626
1627
char failure_msg[100] {};
1628
if (!opendroneid.pre_arm_check(failure_msg, sizeof(failure_msg))) {
1629
check_failed(display_failure, "OpenDroneID: %s", failure_msg);
1630
return false;
1631
}
1632
return true;
1633
}
1634
#endif // AP_OPENDRONEID_ENABLED
1635
1636
//Check for multiple RC in serial protocols
1637
bool AP_Arming::serial_protocol_checks(bool display_failure)
1638
{
1639
if (AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_RCIN, 1)) {
1640
check_failed(display_failure, "Multiple SERIAL ports configured for RC input");
1641
return false;
1642
}
1643
char failure_msg[100] = {};
1644
if (!AP::serialmanager().pre_arm_checks(failure_msg, ARRAY_SIZE(failure_msg))) {
1645
check_failed(display_failure, "%s", failure_msg);
1646
return false;
1647
}
1648
return true;
1649
}
1650
1651
//Check for estop
1652
bool AP_Arming::estop_checks(bool display_failure)
1653
{
1654
if (!SRV_Channels::get_emergency_stop()) {
1655
// not emergency-stopped, so no prearm failure:
1656
return true;
1657
}
1658
#if AP_RC_CHANNEL_ENABLED
1659
// vehicle is emergency-stopped; if this *appears* to have been done via switch then we do not fail prearms:
1660
const RC_Channel *chan = rc().find_channel_for_option(RC_Channel::AUX_FUNC::ARM_EMERGENCY_STOP);
1661
if (chan != nullptr) {
1662
// an RC channel is configured for arm_emergency_stop option, so estop maybe activated via this switch
1663
if (chan->get_aux_switch_pos() == RC_Channel::AuxSwitchPos::LOW) {
1664
// switch is configured and is in estop position, so likely the reason we are estopped, so no prearm failure
1665
return true; // no prearm failure
1666
}
1667
}
1668
#endif // AP_RC_CHANNEL_ENABLED
1669
check_failed(display_failure,"Motors Emergency Stopped");
1670
return false;
1671
}
1672
1673
bool AP_Arming::pre_arm_checks(bool report)
1674
{
1675
#if !APM_BUILD_COPTER_OR_HELI
1676
if (armed || arming_required() == Required::NO) {
1677
// if we are already armed or don't need any arming checks
1678
// then skip the checks
1679
return true;
1680
}
1681
#endif
1682
1683
bool checks_result = hardware_safety_check(report)
1684
#if HAL_HAVE_IMU_HEATER
1685
& heater_min_temperature_checks(report)
1686
#endif
1687
#if AP_BARO_ENABLED
1688
& barometer_checks(report)
1689
#endif
1690
#if AP_INERTIALSENSOR_ENABLED
1691
& ins_checks(report)
1692
#endif
1693
#if AP_COMPASS_ENABLED
1694
& compass_checks(report)
1695
#endif
1696
#if AP_GPS_ENABLED
1697
& gps_checks(report)
1698
#endif
1699
#if AP_BATTERY_ENABLED
1700
& battery_checks(report)
1701
#endif
1702
#if HAL_LOGGING_ENABLED
1703
& logging_checks(report)
1704
#endif
1705
#if AP_RC_CHANNEL_ENABLED
1706
& manual_transmitter_checks(report)
1707
#endif
1708
#if AP_MISSION_ENABLED
1709
& mission_checks(report)
1710
#endif
1711
#if AP_RANGEFINDER_ENABLED
1712
& rangefinder_checks(report)
1713
#endif
1714
& servo_checks(report)
1715
& board_voltage_checks(report)
1716
& system_checks(report)
1717
& terrain_checks(report)
1718
#if HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED
1719
& can_checks(report)
1720
#endif
1721
#if HAL_GENERATOR_ENABLED
1722
& generator_checks(report)
1723
#endif
1724
#if HAL_PROXIMITY_ENABLED
1725
& proximity_checks(report)
1726
#endif
1727
#if AP_CAMERA_RUNCAM_ENABLED
1728
& camera_checks(report)
1729
#endif
1730
#if OSD_ENABLED
1731
& osd_checks(report)
1732
#endif
1733
#if HAL_MOUNT_ENABLED
1734
& mount_checks(report)
1735
#endif
1736
#if AP_FETTEC_ONEWIRE_ENABLED
1737
& fettec_checks(report)
1738
#endif
1739
#if HAL_VISUALODOM_ENABLED
1740
& visodom_checks(report)
1741
#endif
1742
#if AP_ARMING_AUX_AUTH_ENABLED
1743
& aux_auth_checks(report)
1744
#endif
1745
#if AP_RC_CHANNEL_ENABLED
1746
& disarm_switch_checks(report)
1747
#endif
1748
#if AP_FENCE_ENABLED
1749
& fence_checks(report)
1750
#endif
1751
#if AP_OPENDRONEID_ENABLED
1752
& opendroneid_checks(report)
1753
#endif
1754
#if AP_ARMING_CRASHDUMP_ACK_ENABLED
1755
& crashdump_checks(report)
1756
#endif
1757
& serial_protocol_checks(report)
1758
& estop_checks(report);
1759
1760
if (!checks_result && last_prearm_checks_result) { // check went from true to false
1761
report_immediately = true;
1762
}
1763
last_prearm_checks_result = checks_result;
1764
1765
return checks_result;
1766
}
1767
1768
bool AP_Arming::arm_checks(AP_Arming::Method method)
1769
{
1770
#if AP_RC_CHANNEL_ENABLED
1771
if (check_enabled(Check::RC)) {
1772
if (!rc_arm_checks(method)) {
1773
return false;
1774
}
1775
}
1776
#endif
1777
1778
// ensure the GPS drivers are ready on any final changes
1779
if (check_enabled(Check::GPS_CONFIG)) {
1780
if (!AP::gps().prepare_for_arming()) {
1781
return false;
1782
}
1783
}
1784
1785
// note that this will prepare AP_Logger to start logging
1786
// so should be the last check to be done before arming
1787
1788
// Note also that we need to PrepForArming() regardless of whether
1789
// the arming check flag is set - disabling the arming check
1790
// should not stop logging from working.
1791
1792
#if HAL_LOGGING_ENABLED
1793
AP_Logger *logger = AP_Logger::get_singleton();
1794
if (logger->logging_present()) {
1795
// If we're configured to log, prep it
1796
logger->PrepForArming();
1797
if (!logger->logging_started() &&
1798
check_enabled(Check::LOGGING)) {
1799
check_failed(Check::LOGGING, true, "Logging not started");
1800
return false;
1801
}
1802
}
1803
#endif // HAL_LOGGING_ENABLED
1804
1805
return true;
1806
}
1807
1808
#if !AP_GPS_BLENDED_ENABLED
1809
bool AP_Arming::blending_auto_switch_checks(bool report)
1810
{
1811
if (AP::gps().get_auto_switch_type() == 2) {
1812
if (report) {
1813
check_failed(Check::GPS, true, "GPS_AUTO_SWITCH==2 but no blending");
1814
}
1815
return false;
1816
}
1817
return true;
1818
}
1819
#endif
1820
1821
#if AP_ARMING_CRASHDUMP_ACK_ENABLED
1822
bool AP_Arming::crashdump_checks(bool report)
1823
{
1824
if (hal.util->last_crash_dump_size() == 0) {
1825
// no crash dump data
1826
return true;
1827
}
1828
1829
// see if the user has acknowledged the failure and wants to fly anyway:
1830
if (crashdump_ack.acked) {
1831
// they may have acked the problem, that doesn't mean we don't
1832
// continue to warn them they're on thin ice:
1833
if (report) {
1834
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "CrashDump data detected");
1835
}
1836
return true;
1837
}
1838
1839
check_failed(Check::PARAMETERS, report, "CrashDump data detected");
1840
1841
return false;
1842
}
1843
#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED
1844
1845
bool AP_Arming::mandatory_checks(bool report)
1846
{
1847
bool ret = true;
1848
#if AP_OPENDRONEID_ENABLED
1849
ret &= opendroneid_checks(report);
1850
#endif
1851
ret &= rc_in_calibration_check(report);
1852
ret &= serial_protocol_checks(report);
1853
return ret;
1854
}
1855
1856
//returns true if arming occurred successfully
1857
bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks)
1858
{
1859
if (armed) { //already armed
1860
return false;
1861
}
1862
1863
if (method == Method::RUDDER) {
1864
switch (get_rudder_arming_type()) {
1865
case AP_Arming::RudderArming::IS_DISABLED:
1866
//parameter disallows rudder arming/disabling
1867
return false;
1868
case AP_Arming::RudderArming::ARMONLY:
1869
case AP_Arming::RudderArming::ARMDISARM:
1870
break;
1871
}
1872
}
1873
1874
running_arming_checks = true; // so we show Arm: rather than Disarm: in messages
1875
1876
if ((!do_arming_checks && mandatory_checks(true)) || (pre_arm_checks(true) && arm_checks(method))) {
1877
armed = true;
1878
last_arm_time_us = AP_HAL::micros64();
1879
1880
_last_arm_method = method;
1881
1882
#if HAL_LOGGING_ENABLED
1883
Log_Write_Arm(!do_arming_checks, method); // note Log_Write_Armed takes forced not do_arming_checks
1884
#endif
1885
1886
} else {
1887
#if HAL_LOGGING_ENABLED
1888
AP::logger().arming_failure();
1889
#endif
1890
armed = false;
1891
}
1892
1893
running_arming_checks = false;
1894
1895
if (armed && do_arming_checks && should_skip_all_checks()) {
1896
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Warning: Arming Checks Disabled");
1897
}
1898
1899
#if HAL_GYROFFT_ENABLED
1900
// make sure the FFT subsystem is enabled if arming checks have been disabled
1901
AP_GyroFFT *fft = AP::fft();
1902
if (fft != nullptr) {
1903
fft->prepare_for_arming();
1904
}
1905
#endif
1906
1907
#if AP_TERRAIN_AVAILABLE
1908
if (armed) {
1909
// tell terrain we have just armed, so it can setup
1910
// a reference location for terrain adjustment
1911
auto *terrain = AP::terrain();
1912
if (terrain != nullptr) {
1913
terrain->set_reference_location();
1914
}
1915
}
1916
#endif
1917
1918
#if AP_FENCE_ENABLED
1919
if (armed) {
1920
auto *fence = AP::fence();
1921
if (fence != nullptr) {
1922
fence->auto_enable_fence_on_arming();
1923
}
1924
}
1925
#endif
1926
#if defined(HAL_ARM_GPIO_PIN)
1927
update_arm_gpio();
1928
#endif
1929
return armed;
1930
}
1931
1932
//returns true if disarming occurred successfully
1933
bool AP_Arming::disarm(const AP_Arming::Method method, bool do_disarm_checks)
1934
{
1935
if (!armed) { // already disarmed
1936
return false;
1937
}
1938
if (method == AP_Arming::Method::RUDDER) {
1939
// if throttle is not down, then pilot cannot rudder arm/disarm
1940
if (rc().get_throttle_channel().get_control_in() > 0) {
1941
return false;
1942
}
1943
// option must be enabled:
1944
if (get_rudder_arming_type() != AP_Arming::RudderArming::ARMDISARM) {
1945
gcs().send_text(MAV_SEVERITY_INFO, "Disarm: rudder disarm disabled");
1946
return false;
1947
}
1948
}
1949
armed = false;
1950
_last_disarm_method = method;
1951
1952
#if HAL_LOGGING_ENABLED
1953
Log_Write_Disarm(!do_disarm_checks, method); // Log_Write_Disarm takes "force"
1954
1955
check_forced_logging(method);
1956
#endif
1957
1958
#if HAL_HAVE_SAFETY_SWITCH
1959
AP_BoardConfig *board_cfg = AP_BoardConfig::get_singleton();
1960
if ((board_cfg != nullptr) &&
1961
(board_cfg->get_safety_button_options() & AP_BoardConfig::BOARD_SAFETY_OPTION_SAFETY_ON_DISARM)) {
1962
hal.rcout->force_safety_on();
1963
}
1964
#endif // HAL_HAVE_SAFETY_SWITCH
1965
1966
#if HAL_GYROFFT_ENABLED
1967
AP_GyroFFT *fft = AP::fft();
1968
if (fft != nullptr) {
1969
fft->save_params_on_disarm();
1970
}
1971
#endif
1972
1973
#if AP_FENCE_ENABLED
1974
AC_Fence *fence = AP::fence();
1975
if (fence != nullptr) {
1976
fence->auto_disable_fence_on_disarming();
1977
}
1978
#endif
1979
#if defined(HAL_ARM_GPIO_PIN)
1980
update_arm_gpio();
1981
#endif
1982
return true;
1983
}
1984
1985
#if defined(HAL_ARM_GPIO_PIN)
1986
void AP_Arming::update_arm_gpio()
1987
{
1988
if (!AP_BoardConfig::arming_gpio_disabled()) {
1989
hal.gpio->write(HAL_ARM_GPIO_PIN, HAL_ARM_GPIO_POL_INVERT ? !armed : armed);
1990
}
1991
}
1992
#endif
1993
1994
void AP_Arming::send_arm_disarm_statustext(const char *str) const
1995
{
1996
if (option_enabled(AP_Arming::Option::DISABLE_STATUSTEXT_ON_STATE_CHANGE)) {
1997
return;
1998
}
1999
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s", str);
2000
}
2001
2002
AP_Arming::Required AP_Arming::arming_required() const
2003
{
2004
#if AP_OPENDRONEID_ENABLED
2005
// cannot be disabled if OpenDroneID is present
2006
if (AP_OpenDroneID::get_singleton() != nullptr && AP::opendroneid().enabled()) {
2007
if (require != Required::YES_MIN_PWM && require != Required::YES_ZERO_PWM) {
2008
return Required::YES_MIN_PWM;
2009
}
2010
}
2011
#endif
2012
return require;
2013
}
2014
2015
#if AP_RC_CHANNEL_ENABLED
2016
// Copter and sub share the same RC input limits
2017
// Copter checks that min and max have been configured by default, Sub does not
2018
bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channel *channels[4]) const
2019
{
2020
// set rc-checks to success if RC checks are disabled
2021
if (!check_enabled(Check::RC)) {
2022
return true;
2023
}
2024
2025
bool ret = true;
2026
2027
const char *channel_names[] = { "Roll", "Pitch", "Throttle", "Yaw" };
2028
2029
for (uint8_t i=0; i<ARRAY_SIZE(channel_names);i++) {
2030
const RC_Channel *channel = channels[i];
2031
const char *channel_name = channel_names[i];
2032
// check if radio has been calibrated
2033
if (channel->get_radio_min() > RC_Channel::RC_CALIB_MIN_LIMIT_PWM) {
2034
check_failed(Check::RC, display_failure, "%s radio min too high", channel_name);
2035
ret = false;
2036
}
2037
if (channel->get_radio_max() < RC_Channel::RC_CALIB_MAX_LIMIT_PWM) {
2038
check_failed(Check::RC, display_failure, "%s radio max too low", channel_name);
2039
ret = false;
2040
}
2041
}
2042
return ret;
2043
}
2044
#endif // AP_RC_CHANNEL_ENABLED
2045
2046
#if HAL_VISUALODOM_ENABLED
2047
// check visual odometry is working
2048
bool AP_Arming::visodom_checks(bool display_failure) const
2049
{
2050
if (!check_enabled(Check::VISION)) {
2051
return true;
2052
}
2053
2054
AP_VisualOdom *visual_odom = AP::visualodom();
2055
if (visual_odom != nullptr) {
2056
char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
2057
if (!visual_odom->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
2058
check_failed(Check::VISION, display_failure, "VisOdom: %s", fail_msg);
2059
return false;
2060
}
2061
}
2062
2063
return true;
2064
}
2065
#endif
2066
2067
#if AP_RC_CHANNEL_ENABLED
2068
// check disarm switch is asserted
2069
bool AP_Arming::disarm_switch_checks(bool display_failure) const
2070
{
2071
const RC_Channel *chan = rc().find_channel_for_option(RC_Channel::AUX_FUNC::DISARM);
2072
if (chan != nullptr &&
2073
chan->get_aux_switch_pos() == RC_Channel::AuxSwitchPos::HIGH) {
2074
check_failed(display_failure, "Disarm Switch on");
2075
return false;
2076
}
2077
2078
return true;
2079
}
2080
#endif // AP_RC_CHANNEL_ENABLED
2081
2082
#if HAL_LOGGING_ENABLED
2083
void AP_Arming::Log_Write_Arm(const bool forced, const AP_Arming::Method method)
2084
{
2085
const struct log_Arm_Disarm pkt {
2086
LOG_PACKET_HEADER_INIT(LOG_ARM_DISARM_MSG),
2087
time_us : AP_HAL::micros64(),
2088
arm_state : is_armed(),
2089
arm_checks : get_enabled_checks(),
2090
forced : forced,
2091
method : (uint8_t)method,
2092
};
2093
AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));
2094
AP::logger().Write_Event(LogEvent::ARMED);
2095
}
2096
2097
void AP_Arming::Log_Write_Disarm(const bool forced, const AP_Arming::Method method)
2098
{
2099
const struct log_Arm_Disarm pkt {
2100
LOG_PACKET_HEADER_INIT(LOG_ARM_DISARM_MSG),
2101
time_us : AP_HAL::micros64(),
2102
arm_state : is_armed(),
2103
arm_checks : 0,
2104
forced : forced,
2105
method : (uint8_t)method
2106
};
2107
AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));
2108
AP::logger().Write_Event(LogEvent::DISARMED);
2109
}
2110
2111
// check if we should keep logging after disarming
2112
void AP_Arming::check_forced_logging(const AP_Arming::Method method)
2113
{
2114
// keep logging if disarmed for a bad reason
2115
switch(method) {
2116
case Method::TERMINATION:
2117
case Method::CPUFAILSAFE:
2118
case Method::BATTERYFAILSAFE:
2119
case Method::AFS:
2120
case Method::ADSBCOLLISIONACTION:
2121
case Method::PARACHUTE_RELEASE:
2122
case Method::CRASH:
2123
case Method::FENCEBREACH:
2124
case Method::RADIOFAILSAFE:
2125
case Method::GCSFAILSAFE:
2126
case Method::TERRRAINFAILSAFE:
2127
case Method::FAILSAFE_ACTION_TERMINATE:
2128
case Method::TERRAINFAILSAFE:
2129
case Method::BADFLOWOFCONTROL:
2130
case Method::EKFFAILSAFE:
2131
case Method::GCS_FAILSAFE_SURFACEFAILED:
2132
case Method::GCS_FAILSAFE_HOLDFAILED:
2133
case Method::PILOT_INPUT_FAILSAFE:
2134
case Method::DEADRECKON_FAILSAFE:
2135
case Method::BLACKBOX:
2136
// keep logging for longer if disarmed for a bad reason
2137
AP::logger().set_long_log_persist(true);
2138
return;
2139
2140
case Method::RUDDER:
2141
case Method::TOYMODE:
2142
case Method::MAVLINK:
2143
case Method::AUXSWITCH:
2144
case Method::MOTORTEST:
2145
case Method::SCRIPTING:
2146
case Method::SOLOPAUSEWHENLANDED:
2147
case Method::LANDED:
2148
case Method::MISSIONEXIT:
2149
case Method::DISARMDELAY:
2150
case Method::MOTORDETECTDONE:
2151
case Method::TAKEOFFTIMEOUT:
2152
case Method::AUTOLANDED:
2153
case Method::TOYMODELANDTHROTTLE:
2154
case Method::TOYMODELANDFORCE:
2155
case Method::LANDING:
2156
case Method::DDS:
2157
case Method::AUTO_ARM_ONCE:
2158
case Method::TURTLE_MODE:
2159
case Method::UNKNOWN:
2160
AP::logger().set_long_log_persist(false);
2161
return;
2162
}
2163
}
2164
#endif // HAL_LOGGING_ENABLED
2165
2166
AP_Arming *AP_Arming::_singleton = nullptr;
2167
2168
/*
2169
* Get the AP_Arming singleton
2170
*/
2171
AP_Arming *AP_Arming::get_singleton()
2172
{
2173
return AP_Arming::_singleton;
2174
}
2175
2176
namespace AP {
2177
2178
AP_Arming &arming()
2179
{
2180
return *AP_Arming::get_singleton();
2181
}
2182
2183
};
2184
2185
#pragma GCC diagnostic pop
2186
2187
#endif // AP_ARMING_ENABLED
2188
2189