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/ArduCopter/AP_Arming.cpp
Views: 1798
1
#include "Copter.h"
2
3
#pragma GCC diagnostic push
4
#if defined(__clang_major__) && __clang_major__ >= 14
5
#pragma GCC diagnostic ignored "-Wbitwise-instead-of-logical"
6
#endif
7
8
bool AP_Arming_Copter::pre_arm_checks(bool display_failure)
9
{
10
const bool passed = run_pre_arm_checks(display_failure);
11
set_pre_arm_check(passed);
12
return passed;
13
}
14
15
// perform pre-arm checks
16
// return true if the checks pass successfully
17
bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)
18
{
19
// exit immediately if already armed
20
if (copter.motors->armed()) {
21
return true;
22
}
23
24
// check if motor interlock and either Emergency Stop aux switches are used
25
// at the same time. This cannot be allowed.
26
bool passed = true;
27
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) &&
28
(rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP) ||
29
rc().find_channel_for_option(RC_Channel::AUX_FUNC::ARM_EMERGENCY_STOP))){
30
check_failed(display_failure, "Interlock/E-Stop Conflict");
31
passed = false;
32
}
33
34
// check if motor interlock aux switch is in use
35
// if it is, switch needs to be in disabled position to arm
36
// otherwise exit immediately.
37
if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) {
38
check_failed(display_failure, "Motor Interlock Enabled");
39
passed = false;
40
}
41
42
if (!disarm_switch_checks(display_failure)) {
43
passed = false;
44
}
45
46
// always check motors
47
char failure_msg[100] {};
48
if (!copter.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) {
49
check_failed(display_failure, "Motors: %s", failure_msg);
50
passed = false;
51
}
52
53
// If not passed all checks return false
54
if (!passed) {
55
return false;
56
}
57
58
// if pre arm checks are disabled run only the mandatory checks
59
if (checks_to_perform == 0) {
60
return mandatory_checks(display_failure);
61
}
62
63
// bitwise & ensures all checks are run
64
return parameter_checks(display_failure)
65
& oa_checks(display_failure)
66
& gcs_failsafe_check(display_failure)
67
& winch_checks(display_failure)
68
& rc_throttle_failsafe_checks(display_failure)
69
& alt_checks(display_failure)
70
#if AP_AIRSPEED_ENABLED
71
& AP_Arming::airspeed_checks(display_failure)
72
#endif
73
& AP_Arming::pre_arm_checks(display_failure);
74
}
75
76
bool AP_Arming_Copter::rc_throttle_failsafe_checks(bool display_failure) const
77
{
78
if (!check_enabled(ARMING_CHECK_RC)) {
79
// this check has been disabled
80
return true;
81
}
82
83
// throttle failsafe. In this case the parameter also gates the
84
// no-pulses RC failure case - the radio-in value can be zero due
85
// to not having received any RC pulses at all. Note that if we
86
// have ever seen RC and then we *lose* RC then these checks are
87
// likely to pass if the user is relying on no-pulses to detect RC
88
// failure. However, arming is precluded in that case by being in
89
// RC failsafe.
90
if (copter.g.failsafe_throttle == FS_THR_DISABLED) {
91
return true;
92
}
93
94
#if FRAME_CONFIG == HELI_FRAME
95
const char *rc_item = "Collective";
96
#else
97
const char *rc_item = "Throttle";
98
#endif
99
100
if (!rc().has_had_rc_receiver() && !rc().has_had_rc_override()) {
101
check_failed(ARMING_CHECK_RC, display_failure, "RC not found");
102
return false;
103
}
104
105
// check throttle is not too low - must be above failsafe throttle
106
if (copter.channel_throttle->get_radio_in() < copter.g.failsafe_throttle_value) {
107
check_failed(ARMING_CHECK_RC, display_failure, "%s below failsafe", rc_item);
108
return false;
109
}
110
111
return true;
112
}
113
114
bool AP_Arming_Copter::barometer_checks(bool display_failure)
115
{
116
if (!AP_Arming::barometer_checks(display_failure)) {
117
return false;
118
}
119
120
bool ret = true;
121
// check Baro
122
if (check_enabled(ARMING_CHECK_BARO)) {
123
// Check baro & inav alt are within 1m if EKF is operating in an absolute position mode.
124
// Do not check if intending to operate in a ground relative height mode as EKF will output a ground relative height
125
// that may differ from the baro height due to baro drift.
126
nav_filter_status filt_status = copter.inertial_nav.get_filter_status();
127
bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs);
128
if (using_baro_ref) {
129
if (fabsf(copter.inertial_nav.get_position_z_up_cm() - copter.baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) {
130
check_failed(ARMING_CHECK_BARO, display_failure, "Altitude disparity");
131
ret = false;
132
}
133
}
134
}
135
return ret;
136
}
137
138
bool AP_Arming_Copter::ins_checks(bool display_failure)
139
{
140
bool ret = AP_Arming::ins_checks(display_failure);
141
142
if (check_enabled(ARMING_CHECK_INS)) {
143
144
// get ekf attitude (if bad, it's usually the gyro biases)
145
if (!pre_arm_ekf_attitude_check()) {
146
check_failed(ARMING_CHECK_INS, display_failure, "EKF attitude is bad");
147
ret = false;
148
}
149
}
150
151
return ret;
152
}
153
154
bool AP_Arming_Copter::board_voltage_checks(bool display_failure)
155
{
156
if (!AP_Arming::board_voltage_checks(display_failure)) {
157
return false;
158
}
159
160
// check battery voltage
161
if (check_enabled(ARMING_CHECK_VOLTAGE)) {
162
if (copter.battery.has_failsafed()) {
163
check_failed(ARMING_CHECK_VOLTAGE, display_failure, "Battery failsafe");
164
return false;
165
}
166
}
167
168
return true;
169
}
170
171
// expected to return true if the terrain database is required to have
172
// all data loaded
173
bool AP_Arming_Copter::terrain_database_required() const
174
{
175
176
if (copter.wp_nav->get_terrain_source() == AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER) {
177
// primary terrain source is from rangefinder, allow arming without terrain database
178
return false;
179
}
180
181
if (copter.wp_nav->get_terrain_source() == AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE &&
182
copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::TERRAIN) {
183
return true;
184
}
185
return AP_Arming::terrain_database_required();
186
}
187
188
bool AP_Arming_Copter::parameter_checks(bool display_failure)
189
{
190
// check various parameter values
191
if (check_enabled(ARMING_CHECK_PARAMETERS)) {
192
193
// failsafe parameter checks
194
if (copter.g.failsafe_throttle) {
195
// check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900
196
if (copter.channel_throttle->get_radio_min() <= copter.g.failsafe_throttle_value+10 || copter.g.failsafe_throttle_value < 910) {
197
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check FS_THR_VALUE");
198
return false;
199
}
200
}
201
if (copter.g.failsafe_gcs == FS_GCS_ENABLED_CONTINUE_MISSION) {
202
// FS_GCS_ENABLE == 2 has been removed
203
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "FS_GCS_ENABLE=2 removed, see FS_OPTIONS");
204
}
205
206
// lean angle parameter check
207
if (copter.aparm.angle_max < 1000 || copter.aparm.angle_max > 8000) {
208
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check ANGLE_MAX");
209
return false;
210
}
211
212
// acro balance parameter check
213
#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED
214
if ((copter.g.acro_balance_roll > copter.attitude_control->get_angle_roll_p().kP()) || (copter.g.acro_balance_pitch > copter.attitude_control->get_angle_pitch_p().kP())) {
215
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check ACRO_BAL_ROLL/PITCH");
216
return false;
217
}
218
#endif
219
220
// pilot-speed-up parameter check
221
if (copter.g.pilot_speed_up <= 0) {
222
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check PILOT_SPEED_UP");
223
return false;
224
}
225
226
#if FRAME_CONFIG == HELI_FRAME
227
char fail_msg[100]{};
228
// check input manager parameters
229
if (!copter.input_manager.parameter_check(fail_msg, ARRAY_SIZE(fail_msg))) {
230
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "%s", fail_msg);
231
return false;
232
}
233
234
// Ensure an Aux Channel is configured for motor interlock
235
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) == nullptr) {
236
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Motor Interlock not configured");
237
return false;
238
}
239
240
#else
241
switch (copter.g2.frame_class.get()) {
242
case AP_Motors::MOTOR_FRAME_HELI_QUAD:
243
case AP_Motors::MOTOR_FRAME_HELI_DUAL:
244
case AP_Motors::MOTOR_FRAME_HELI:
245
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Invalid MultiCopter FRAME_CLASS");
246
return false;
247
248
default:
249
break;
250
}
251
#endif // HELI_FRAME
252
253
// checks when using range finder for RTL
254
#if MODE_RTL_ENABLED
255
if (copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::TERRAIN) {
256
// get terrain source from wpnav
257
const char *failure_template = "RTL_ALT_TYPE is above-terrain but %s";
258
switch (copter.wp_nav->get_terrain_source()) {
259
case AC_WPNav::TerrainSource::TERRAIN_UNAVAILABLE:
260
check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "no terrain data");
261
return false;
262
break;
263
case AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER:
264
#if AP_RANGEFINDER_ENABLED
265
if (!copter.rangefinder_state.enabled || !copter.rangefinder.has_orientation(ROTATION_PITCH_270)) {
266
check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "no rangefinder");
267
return false;
268
}
269
// check if RTL_ALT is higher than rangefinder's max range
270
if (copter.g.rtl_altitude > copter.rangefinder.max_distance_cm_orient(ROTATION_PITCH_270)) {
271
check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "RTL_ALT>RNGFND_MAX_CM");
272
return false;
273
}
274
#else
275
check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "rangefinder not in firmware");
276
#endif
277
break;
278
case AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE:
279
// these checks are done in AP_Arming
280
break;
281
}
282
}
283
#endif
284
285
// check adsb avoidance failsafe
286
#if HAL_ADSB_ENABLED
287
if (copter.failsafe.adsb) {
288
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "ADSB threat detected");
289
return false;
290
}
291
#endif
292
293
// ensure controllers are OK with us arming:
294
char failure_msg[100] = {};
295
if (!copter.pos_control->pre_arm_checks("PSC", failure_msg, ARRAY_SIZE(failure_msg))) {
296
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
297
return false;
298
}
299
if (!copter.attitude_control->pre_arm_checks("ATC", failure_msg, ARRAY_SIZE(failure_msg))) {
300
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
301
return false;
302
}
303
}
304
305
return true;
306
}
307
308
bool AP_Arming_Copter::oa_checks(bool display_failure)
309
{
310
#if AP_OAPATHPLANNER_ENABLED
311
char failure_msg[100] = {};
312
if (copter.g2.oa.pre_arm_check(failure_msg, ARRAY_SIZE(failure_msg))) {
313
return true;
314
}
315
// display failure
316
if (strlen(failure_msg) == 0) {
317
check_failed(display_failure, "%s", "Check Object Avoidance");
318
} else {
319
check_failed(display_failure, "%s", failure_msg);
320
}
321
return false;
322
#else
323
return true;
324
#endif
325
}
326
327
bool AP_Arming_Copter::rc_calibration_checks(bool display_failure)
328
{
329
const RC_Channel *channels[] = {
330
copter.channel_roll,
331
copter.channel_pitch,
332
copter.channel_throttle,
333
copter.channel_yaw
334
};
335
336
// bitwise & ensures all checks are run
337
copter.ap.pre_arm_rc_check = rc_checks_copter_sub(display_failure, channels)
338
& AP_Arming::rc_calibration_checks(display_failure);
339
340
return copter.ap.pre_arm_rc_check;
341
}
342
343
// performs pre_arm gps related checks and returns true if passed
344
bool AP_Arming_Copter::gps_checks(bool display_failure)
345
{
346
// check if fence requires GPS
347
bool fence_requires_gps = false;
348
#if AP_FENCE_ENABLED
349
// if circular or polygon fence is enabled we need GPS
350
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
351
#endif
352
353
// check if flight mode requires GPS
354
bool mode_requires_gps = copter.flightmode->requires_GPS() || fence_requires_gps || (copter.simple_mode == Copter::SimpleMode::SUPERSIMPLE);
355
356
// call parent gps checks
357
if (mode_requires_gps) {
358
if (!AP_Arming::gps_checks(display_failure)) {
359
AP_Notify::flags.pre_arm_gps_check = false;
360
return false;
361
}
362
}
363
364
// run mandatory gps checks first
365
if (!mandatory_gps_checks(display_failure)) {
366
AP_Notify::flags.pre_arm_gps_check = false;
367
return false;
368
}
369
370
// return true if GPS is not required
371
if (!mode_requires_gps) {
372
AP_Notify::flags.pre_arm_gps_check = true;
373
return true;
374
}
375
376
// return true immediately if gps check is disabled
377
if (!check_enabled(ARMING_CHECK_GPS)) {
378
AP_Notify::flags.pre_arm_gps_check = true;
379
return true;
380
}
381
382
// warn about hdop separately - to prevent user confusion with no gps lock
383
if ((copter.gps.num_sensors() > 0) && (copter.gps.get_hdop() > copter.g.gps_hdop_good)) {
384
check_failed(ARMING_CHECK_GPS, display_failure, "High GPS HDOP");
385
AP_Notify::flags.pre_arm_gps_check = false;
386
return false;
387
}
388
389
// if we got here all must be ok
390
AP_Notify::flags.pre_arm_gps_check = true;
391
return true;
392
}
393
394
// check ekf attitude is acceptable
395
bool AP_Arming_Copter::pre_arm_ekf_attitude_check()
396
{
397
// get ekf filter status
398
nav_filter_status filt_status = copter.inertial_nav.get_filter_status();
399
400
return filt_status.flags.attitude;
401
}
402
403
#if HAL_PROXIMITY_ENABLED
404
// check nothing is too close to vehicle
405
bool AP_Arming_Copter::proximity_checks(bool display_failure) const
406
{
407
408
if (!AP_Arming::proximity_checks(display_failure)) {
409
return false;
410
}
411
412
if (!check_enabled(ARMING_CHECK_PARAMETERS)) {
413
// check is disabled
414
return true;
415
}
416
417
// get closest object if we might use it for avoidance
418
#if AP_AVOIDANCE_ENABLED
419
float angle_deg, distance;
420
if (copter.avoid.proximity_avoidance_enabled() && copter.g2.proximity.get_closest_object(angle_deg, distance)) {
421
// display error if something is within 60cm
422
const float tolerance = 0.6f;
423
if (distance <= tolerance) {
424
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Proximity %d deg, %4.2fm (want > %0.1fm)", (int)angle_deg, (double)distance, (double)tolerance);
425
return false;
426
}
427
}
428
#endif
429
430
return true;
431
}
432
#endif // HAL_PROXIMITY_ENABLED
433
434
// performs mandatory gps checks. returns true if passed
435
bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
436
{
437
// check if flight mode requires GPS
438
bool mode_requires_gps = copter.flightmode->requires_GPS();
439
440
// always check if inertial nav has started and is ready
441
const auto &ahrs = AP::ahrs();
442
char failure_msg[100] = {};
443
if (!ahrs.pre_arm_check(mode_requires_gps, failure_msg, sizeof(failure_msg))) {
444
check_failed(display_failure, "AHRS: %s", failure_msg);
445
return false;
446
}
447
448
// check if fence requires GPS
449
bool fence_requires_gps = false;
450
#if AP_FENCE_ENABLED
451
// if circular or polygon fence is enabled we need GPS
452
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
453
#endif
454
455
if (mode_requires_gps || copter.option_is_enabled(Copter::FlightOption::REQUIRE_POSITION_FOR_ARMING)) {
456
if (!copter.position_ok()) {
457
// vehicle level position estimate checks
458
check_failed(display_failure, "Need Position Estimate");
459
return false;
460
}
461
} else if (fence_requires_gps) {
462
if (!copter.position_ok()) {
463
// clarify to user why they need GPS in non-GPS flight mode
464
check_failed(display_failure, "Fence enabled, need position estimate");
465
return false;
466
}
467
} else {
468
// return true if GPS is not required
469
return true;
470
}
471
472
// check for GPS glitch (as reported by EKF)
473
nav_filter_status filt_status;
474
if (ahrs.get_filter_status(filt_status)) {
475
if (filt_status.flags.gps_glitching) {
476
check_failed(display_failure, "GPS glitching");
477
return false;
478
}
479
}
480
481
// check EKF's compass, position, height and velocity variances are below failsafe threshold
482
if (copter.g.fs_ekf_thresh > 0.0f) {
483
float vel_variance, pos_variance, hgt_variance, tas_variance;
484
Vector3f mag_variance;
485
ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance);
486
if (mag_variance.length() >= copter.g.fs_ekf_thresh) {
487
check_failed(display_failure, "EKF compass variance");
488
return false;
489
}
490
if (pos_variance >= copter.g.fs_ekf_thresh) {
491
check_failed(display_failure, "EKF position variance");
492
return false;
493
}
494
if (vel_variance >= copter.g.fs_ekf_thresh) {
495
check_failed(display_failure, "EKF velocity variance");
496
return false;
497
}
498
if (hgt_variance >= copter.g.fs_ekf_thresh) {
499
check_failed(display_failure, "EKF height variance");
500
return false;
501
}
502
}
503
504
// if we got here all must be ok
505
return true;
506
}
507
508
// Check GCS failsafe
509
bool AP_Arming_Copter::gcs_failsafe_check(bool display_failure)
510
{
511
if (copter.failsafe.gcs) {
512
check_failed(display_failure, "GCS failsafe on");
513
return false;
514
}
515
return true;
516
}
517
518
// check winch
519
bool AP_Arming_Copter::winch_checks(bool display_failure) const
520
{
521
#if AP_WINCH_ENABLED
522
// pass if parameter or all arming checks disabled
523
if (!check_enabled(ARMING_CHECK_PARAMETERS)) {
524
return true;
525
}
526
527
const AP_Winch *winch = AP::winch();
528
if (winch == nullptr) {
529
return true;
530
}
531
char failure_msg[100] = {};
532
if (!winch->pre_arm_check(failure_msg, sizeof(failure_msg))) {
533
check_failed(display_failure, "%s", failure_msg);
534
return false;
535
}
536
#endif
537
return true;
538
}
539
540
// performs altitude checks. returns true if passed
541
bool AP_Arming_Copter::alt_checks(bool display_failure)
542
{
543
// always EKF altitude estimate
544
if (!copter.flightmode->has_manual_throttle() && !copter.ekf_alt_ok()) {
545
check_failed(display_failure, "Need Alt Estimate");
546
return false;
547
}
548
549
return true;
550
}
551
552
// arm_checks - perform final checks before arming
553
// always called just before arming. Return true if ok to arm
554
// has side-effect that logging is started
555
bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
556
{
557
const auto &ahrs = AP::ahrs();
558
559
// always check if inertial nav has started and is ready
560
if (!ahrs.healthy()) {
561
check_failed(true, "AHRS not healthy");
562
return false;
563
}
564
565
#ifndef ALLOW_ARM_NO_COMPASS
566
// if non-compass is source of heading we can skip compass health check
567
if (!ahrs.using_noncompass_for_yaw()) {
568
const Compass &_compass = AP::compass();
569
// check compass health
570
if (!_compass.healthy()) {
571
check_failed(true, "Compass not healthy");
572
return false;
573
}
574
}
575
#endif
576
577
// always check if the current mode allows arming
578
if (!copter.flightmode->allows_arming(method)) {
579
check_failed(true, "%s mode not armable", copter.flightmode->name());
580
return false;
581
}
582
583
// succeed if arming checks are disabled
584
if (checks_to_perform == 0) {
585
return true;
586
}
587
588
// check lean angle
589
if (check_enabled(ARMING_CHECK_INS)) {
590
if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > copter.aparm.angle_max) {
591
check_failed(ARMING_CHECK_INS, true, "Leaning");
592
return false;
593
}
594
}
595
596
// check adsb
597
#if HAL_ADSB_ENABLED
598
if (check_enabled(ARMING_CHECK_PARAMETERS)) {
599
if (copter.failsafe.adsb) {
600
check_failed(ARMING_CHECK_PARAMETERS, true, "ADSB threat detected");
601
return false;
602
}
603
}
604
#endif
605
606
// check throttle
607
if (check_enabled(ARMING_CHECK_RC)) {
608
#if FRAME_CONFIG == HELI_FRAME
609
const char *rc_item = "Collective";
610
#else
611
const char *rc_item = "Throttle";
612
#endif
613
// check throttle is not too high - skips checks if arming from GCS/scripting in Guided,Guided_NoGPS or Auto
614
if (!((AP_Arming::method_is_GCS(method) || method == AP_Arming::Method::SCRIPTING) && copter.flightmode->allows_GCS_or_SCR_arming_with_throttle_high())) {
615
// above top of deadband is too always high
616
if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) {
617
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);
618
return false;
619
}
620
// in manual modes throttle must be at zero
621
#if FRAME_CONFIG != HELI_FRAME
622
if ((copter.flightmode->has_manual_throttle() || copter.flightmode->mode_number() == Mode::Number::DRIFT) && copter.channel_throttle->get_control_in() > 0) {
623
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);
624
return false;
625
}
626
#endif
627
}
628
}
629
630
// check if safety switch has been pushed
631
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
632
check_failed(true, "Safety Switch");
633
return false;
634
}
635
636
// superclass method should always be the last thing called; it
637
// has side-effects which would need to be cleaned up if one of
638
// our arm checks failed
639
return AP_Arming::arm_checks(method);
640
}
641
642
// mandatory checks that will be run if ARMING_CHECK is zero or arming forced
643
bool AP_Arming_Copter::mandatory_checks(bool display_failure)
644
{
645
// call mandatory gps checks and update notify status because regular gps checks will not run
646
bool result = mandatory_gps_checks(display_failure);
647
AP_Notify::flags.pre_arm_gps_check = result;
648
649
// call mandatory alt check
650
if (!alt_checks(display_failure)) {
651
result = false;
652
}
653
654
return result & AP_Arming::mandatory_checks(display_failure);
655
}
656
657
void AP_Arming_Copter::set_pre_arm_check(bool b)
658
{
659
copter.ap.pre_arm_check = b;
660
AP_Notify::flags.pre_arm_check = b;
661
}
662
663
bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_checks)
664
{
665
static bool in_arm_motors = false;
666
667
// exit immediately if already in this function
668
if (in_arm_motors) {
669
return false;
670
}
671
in_arm_motors = true;
672
673
// return true if already armed
674
if (copter.motors->armed()) {
675
in_arm_motors = false;
676
return true;
677
}
678
679
if (!AP_Arming::arm(method, do_arming_checks)) {
680
AP_Notify::events.arming_failed = true;
681
in_arm_motors = false;
682
return false;
683
}
684
685
#if HAL_LOGGING_ENABLED
686
// let logger know that we're armed (it may open logs e.g.)
687
AP::logger().set_vehicle_armed(true);
688
#endif
689
690
// disable cpu failsafe because initialising everything takes a while
691
copter.failsafe_disable();
692
693
// notify that arming will occur (we do this early to give plenty of warning)
694
AP_Notify::flags.armed = true;
695
// call notify update a few times to ensure the message gets out
696
for (uint8_t i=0; i<=10; i++) {
697
AP::notify().update();
698
}
699
700
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
701
send_arm_disarm_statustext("Arming motors");
702
#endif
703
704
// Remember Orientation
705
// --------------------
706
copter.init_simple_bearing();
707
708
auto &ahrs = AP::ahrs();
709
710
copter.initial_armed_bearing = ahrs.yaw_sensor;
711
712
if (!ahrs.home_is_set()) {
713
// Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home)
714
ahrs.resetHeightDatum();
715
LOGGER_WRITE_EVENT(LogEvent::EKF_ALT_RESET);
716
717
// we have reset height, so arming height is zero
718
copter.arming_altitude_m = 0;
719
} else if (!ahrs.home_is_locked()) {
720
// Reset home position if it has already been set before (but not locked)
721
if (!copter.set_home_to_current_location(false)) {
722
// ignore failure
723
}
724
725
// remember the height when we armed
726
copter.arming_altitude_m = copter.inertial_nav.get_position_z_up_cm() * 0.01;
727
}
728
copter.update_super_simple_bearing(false);
729
730
// Reset SmartRTL return location. If activated, SmartRTL will ultimately try to land at this point
731
#if MODE_SMARTRTL_ENABLED
732
copter.g2.smart_rtl.set_home(copter.position_ok());
733
#endif
734
735
hal.util->set_soft_armed(true);
736
737
#if HAL_SPRAYER_ENABLED
738
// turn off sprayer's test if on
739
copter.sprayer.test_pump(false);
740
#endif
741
742
// output lowest possible value to motors
743
copter.motors->output_min();
744
745
// finally actually arm the motors
746
copter.motors->armed(true);
747
748
#if HAL_LOGGING_ENABLED
749
// log flight mode in case it was changed while vehicle was disarmed
750
AP::logger().Write_Mode((uint8_t)copter.flightmode->mode_number(), copter.control_mode_reason);
751
#endif
752
753
// re-enable failsafe
754
copter.failsafe_enable();
755
756
// perf monitor ignores delay due to arming
757
AP::scheduler().perf_info.ignore_this_loop();
758
759
// flag exiting this function
760
in_arm_motors = false;
761
762
// Log time stamp of arming event
763
copter.arm_time_ms = millis();
764
765
// Start the arming delay
766
copter.ap.in_arming_delay = true;
767
768
// assumed armed without a arming, switch. Overridden in switches.cpp
769
copter.ap.armed_with_airmode_switch = false;
770
771
// return success
772
return true;
773
}
774
775
// arming.disarm - disarm motors
776
bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_checks)
777
{
778
// return immediately if we are already disarmed
779
if (!copter.motors->armed()) {
780
return true;
781
}
782
783
// do not allow disarm via mavlink if we think we are flying:
784
if (do_disarm_checks &&
785
AP_Arming::method_is_GCS(method) &&
786
!copter.ap.land_complete) {
787
return false;
788
}
789
790
if (!AP_Arming::disarm(method, do_disarm_checks)) {
791
return false;
792
}
793
794
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
795
send_arm_disarm_statustext("Disarming motors");
796
#endif
797
798
auto &ahrs = AP::ahrs();
799
800
// save compass offsets learned by the EKF if enabled
801
Compass &compass = AP::compass();
802
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LEARN_EKF) {
803
for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
804
Vector3f magOffsets;
805
if (ahrs.getMagOffsets(i, magOffsets)) {
806
compass.set_and_save_offsets(i, magOffsets);
807
}
808
}
809
}
810
811
// we are not in the air
812
copter.set_land_complete(true);
813
copter.set_land_complete_maybe(true);
814
815
// send disarm command to motors
816
copter.motors->armed(false);
817
818
#if MODE_AUTO_ENABLED
819
// reset the mission
820
copter.mode_auto.mission.reset();
821
#endif
822
823
#if HAL_LOGGING_ENABLED
824
AP::logger().set_vehicle_armed(false);
825
#endif
826
827
hal.util->set_soft_armed(false);
828
829
copter.ap.in_arming_delay = false;
830
831
#if AUTOTUNE_ENABLED
832
// Possibly save auto tuned parameters
833
copter.mode_autotune.autotune.disarmed(copter.flightmode == &copter.mode_autotune);
834
#endif
835
836
return true;
837
}
838
839
#pragma GCC diagnostic pop
840
841