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