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