Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/AP_Arming_Copter.cpp
9498 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 (should_skip_all_checks()) {
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
// acro balance parameter check
222
#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED
223
if (is_negative(copter.g.acro_balance_roll) || is_negative(copter.g.acro_balance_pitch) ||
224
(copter.g.acro_balance_roll > copter.attitude_control->get_angle_roll_p().kP()) ||
225
(copter.g.acro_balance_pitch > copter.attitude_control->get_angle_pitch_p().kP())) {
226
check_failed(Check::PARAMETERS, display_failure, "Check ACRO_BAL_ROLL/PITCH");
227
return false;
228
}
229
#endif
230
231
// pilot-speed-up parameter check
232
if (copter.g.pilot_speed_up_cms <= 0) {
233
check_failed(Check::PARAMETERS, display_failure, "Check PILOT_SPEED_UP");
234
return false;
235
}
236
237
#if FRAME_CONFIG == HELI_FRAME
238
char fail_msg[100]{};
239
// check input manager parameters
240
if (!copter.input_manager.parameter_check(fail_msg, ARRAY_SIZE(fail_msg))) {
241
check_failed(Check::PARAMETERS, display_failure, "%s", fail_msg);
242
return false;
243
}
244
245
// Ensure an Aux Channel is configured for motor interlock
246
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) == nullptr) {
247
check_failed(Check::PARAMETERS, display_failure, "Motor Interlock not configured");
248
return false;
249
}
250
251
#else
252
switch (copter.g2.frame_class.get()) {
253
case AP_Motors::MOTOR_FRAME_HELI_QUAD:
254
case AP_Motors::MOTOR_FRAME_HELI_DUAL:
255
case AP_Motors::MOTOR_FRAME_HELI:
256
check_failed(Check::PARAMETERS, display_failure, "Invalid MultiCopter FRAME_CLASS");
257
return false;
258
259
default:
260
break;
261
}
262
#endif // HELI_FRAME
263
264
// checks when using range finder for RTL
265
#if MODE_RTL_ENABLED
266
if (copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::TERRAIN) {
267
// get terrain source from wpnav
268
const char *failure_template = "RTL_ALT_TYPE is above-terrain but %s";
269
switch (copter.wp_nav->get_terrain_source()) {
270
case AC_WPNav::TerrainSource::TERRAIN_UNAVAILABLE:
271
check_failed(Check::PARAMETERS, display_failure, failure_template, "no terrain data");
272
return false;
273
break;
274
case AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER:
275
#if AP_RANGEFINDER_ENABLED
276
if (!copter.rangefinder_state.enabled || !copter.rangefinder.has_orientation(ROTATION_PITCH_270)) {
277
check_failed(Check::PARAMETERS, display_failure, failure_template, "no rangefinder");
278
return false;
279
}
280
// check if RTL_ALT_M is higher than rangefinder's max range
281
if (copter.mode_rtl.get_altitude_m() > copter.rangefinder.max_distance_orient(ROTATION_PITCH_270)) {
282
check_failed(Check::PARAMETERS, display_failure, failure_template, "RTL_ALT_M above RNGFND_MAX");
283
return false;
284
}
285
#else
286
check_failed(Check::PARAMETERS, display_failure, failure_template, "rangefinder not in firmware");
287
#endif
288
break;
289
case AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE:
290
// these checks are done in AP_Arming
291
break;
292
}
293
}
294
#endif
295
296
// check adsb avoidance failsafe
297
#if HAL_ADSB_ENABLED
298
if (copter.failsafe.adsb) {
299
check_failed(Check::PARAMETERS, display_failure, "ADSB threat detected");
300
return false;
301
}
302
#endif
303
304
// ensure controllers are OK with us arming:
305
char failure_msg[100] = {};
306
if (!copter.pos_control->pre_arm_checks("PSC", failure_msg, ARRAY_SIZE(failure_msg))) {
307
check_failed(Check::PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
308
return false;
309
}
310
if (!copter.attitude_control->pre_arm_checks("ATC", failure_msg, ARRAY_SIZE(failure_msg))) {
311
check_failed(Check::PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
312
return false;
313
}
314
}
315
316
return true;
317
}
318
319
bool AP_Arming_Copter::oa_checks(bool display_failure)
320
{
321
#if AP_OAPATHPLANNER_ENABLED
322
char failure_msg[100] = {};
323
if (copter.g2.oa.pre_arm_check(failure_msg, ARRAY_SIZE(failure_msg))) {
324
return true;
325
}
326
// display failure
327
if (strlen(failure_msg) == 0) {
328
check_failed(display_failure, "%s", "Check Object Avoidance");
329
} else {
330
check_failed(display_failure, "%s", failure_msg);
331
}
332
return false;
333
#else
334
return true;
335
#endif
336
}
337
338
bool AP_Arming_Copter::rc_calibration_checks(bool display_failure)
339
{
340
const RC_Channel *channels[] = {
341
copter.channel_roll,
342
copter.channel_pitch,
343
copter.channel_throttle,
344
copter.channel_yaw
345
};
346
347
// bitwise & ensures all checks are run
348
copter.ap.pre_arm_rc_check = rc_checks_copter_sub(display_failure, channels)
349
& AP_Arming::rc_calibration_checks(display_failure);
350
351
return copter.ap.pre_arm_rc_check;
352
}
353
354
// performs pre_arm gps related checks and returns true if passed
355
bool AP_Arming_Copter::gps_checks(bool display_failure)
356
{
357
// check if fence requires position
358
bool fence_requires_position = false;
359
#if AP_FENCE_ENABLED
360
// if circular or polygon fence is enabled we need position
361
fence_requires_position = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
362
#endif
363
364
// check if flight mode requires GPS
365
const bool mode_requires_position = copter.flightmode->requires_position() || fence_requires_position || (copter.simple_mode == Copter::SimpleMode::SUPERSIMPLE);
366
const bool mode_requires_gps = AP::ahrs().using_gps() && mode_requires_position;
367
368
// call parent gps checks
369
if (mode_requires_gps) {
370
if (!AP_Arming::gps_checks(display_failure)) {
371
AP_Notify::flags.pre_arm_gps_check = false;
372
return false;
373
}
374
}
375
376
// run mandatory position checks first
377
if (!mandatory_position_checks(display_failure)) {
378
AP_Notify::flags.pre_arm_gps_check = false;
379
return false;
380
}
381
382
// return true if GPS is not required
383
if (!mode_requires_gps) {
384
AP_Notify::flags.pre_arm_gps_check = true;
385
return true;
386
}
387
388
// return true immediately if gps check is disabled
389
if (!check_enabled(Check::GPS)) {
390
AP_Notify::flags.pre_arm_gps_check = true;
391
return true;
392
}
393
394
// warn about hdop separately - to prevent user confusion with no gps lock
395
if ((copter.gps.num_sensors() > 0) && (copter.gps.get_hdop() > copter.g.gps_hdop_good)) {
396
check_failed(Check::GPS, display_failure, "High GPS HDOP");
397
AP_Notify::flags.pre_arm_gps_check = false;
398
return false;
399
}
400
401
// if we got here all must be ok
402
AP_Notify::flags.pre_arm_gps_check = true;
403
return true;
404
}
405
406
// check ekf attitude is acceptable
407
bool AP_Arming_Copter::pre_arm_ekf_attitude_check()
408
{
409
return AP::ahrs().has_status(AP_AHRS::Status::ATTITUDE_VALID);
410
}
411
412
#if HAL_PROXIMITY_ENABLED
413
// check nothing is too close to vehicle
414
bool AP_Arming_Copter::proximity_checks(bool display_failure) const
415
{
416
417
if (!AP_Arming::proximity_checks(display_failure)) {
418
return false;
419
}
420
421
if (!check_enabled(Check::PARAMETERS)) {
422
// check is disabled
423
return true;
424
}
425
426
// get closest object if we might use it for avoidance
427
#if AP_AVOIDANCE_ENABLED
428
float angle_deg, distance;
429
if (copter.avoid.proximity_avoidance_enabled() && copter.g2.proximity.get_closest_object(angle_deg, distance)) {
430
// display error if something is within 60cm
431
const float tolerance = 0.6f;
432
if (distance <= tolerance) {
433
check_failed(Check::PARAMETERS, display_failure, "Proximity %d deg, %4.2fm (want > %0.1fm)", (int)angle_deg, (double)distance, (double)tolerance);
434
return false;
435
}
436
}
437
#endif
438
439
return true;
440
}
441
#endif // HAL_PROXIMITY_ENABLED
442
443
// performs mandatory position checks. returns true if passed
444
bool AP_Arming_Copter::mandatory_position_checks(bool display_failure)
445
{
446
// check if flight mode requires position
447
bool mode_requires_position = copter.flightmode->requires_position();
448
449
// always check if inertial nav has started and is ready
450
const auto &ahrs = AP::ahrs();
451
char failure_msg[100] = {};
452
if (!ahrs.pre_arm_check(mode_requires_position, failure_msg, sizeof(failure_msg))) {
453
check_failed(display_failure, "AHRS: %s", failure_msg);
454
return false;
455
}
456
457
// check if fence requires position estimate
458
bool fence_requires_position = false;
459
#if AP_FENCE_ENABLED
460
// if circular or polygon fence is enabled we need position estimate
461
fence_requires_position = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
462
#endif
463
464
if (mode_requires_position || require_location == RequireLocation::YES) {
465
if (!copter.position_ok()) {
466
// vehicle level position estimate checks
467
check_failed(display_failure, "Need Position Estimate");
468
return false;
469
}
470
} else if (fence_requires_position) {
471
if (!copter.position_ok()) {
472
// clarify to user why they need GPS in non-GPS flight mode
473
check_failed(display_failure, "Fence enabled, need position estimate");
474
return false;
475
}
476
} else {
477
// return true if GPS is not required
478
return true;
479
}
480
481
// check for GPS glitch (as reported by EKF)
482
// this can only be true if the EKF is using the GPS
483
nav_filter_status filt_status;
484
if (ahrs.get_filter_status(filt_status)) {
485
if (filt_status.flags.gps_glitching) {
486
check_failed(display_failure, "GPS glitching");
487
return false;
488
}
489
}
490
491
// check EKF's compass, position, height and velocity variances are below failsafe threshold
492
if (copter.g.fs_ekf_thresh > 0.0f) {
493
float vel_variance, pos_variance, hgt_variance, tas_variance;
494
Vector3f mag_variance;
495
ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance);
496
const struct {
497
const char *name;
498
float value;
499
} variances[] {
500
{ "compass", mag_variance.length() },
501
{ "position", pos_variance },
502
{ "velocity", vel_variance },
503
{ "height", hgt_variance },
504
};
505
for (auto &variance : variances) {
506
if (variance.value < copter.g.fs_ekf_thresh) {
507
continue;
508
}
509
check_failed(display_failure, "EKF %s variance", variance.name);
510
return false;
511
}
512
}
513
514
// if we got here all must be ok
515
return true;
516
}
517
518
// Check GCS failsafe
519
bool AP_Arming_Copter::gcs_failsafe_check(bool display_failure)
520
{
521
if (copter.failsafe.gcs) {
522
check_failed(display_failure, "GCS failsafe on");
523
return false;
524
}
525
return true;
526
}
527
528
// check winch
529
bool AP_Arming_Copter::winch_checks(bool display_failure) const
530
{
531
#if AP_WINCH_ENABLED
532
// pass if parameter or all arming checks disabled
533
if (!check_enabled(Check::PARAMETERS)) {
534
return true;
535
}
536
537
const AP_Winch *winch = AP::winch();
538
if (winch == nullptr) {
539
return true;
540
}
541
char failure_msg[100] = {};
542
if (!winch->pre_arm_check(failure_msg, sizeof(failure_msg))) {
543
check_failed(display_failure, "%s", failure_msg);
544
return false;
545
}
546
#endif
547
return true;
548
}
549
550
// performs altitude checks. returns true if passed
551
bool AP_Arming_Copter::alt_checks(bool display_failure)
552
{
553
// always EKF altitude estimate
554
if (!copter.flightmode->has_manual_throttle() && !copter.ekf_alt_ok()) {
555
check_failed(display_failure, "Need Alt Estimate");
556
return false;
557
}
558
559
return true;
560
}
561
562
// arm_checks - perform final checks before arming
563
// always called just before arming. Return true if ok to arm
564
// has side-effect that logging is started
565
bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
566
{
567
const auto &ahrs = AP::ahrs();
568
569
// always check if inertial nav has started and is ready
570
if (!ahrs.healthy()) {
571
check_failed(true, "AHRS not healthy");
572
return false;
573
}
574
575
#ifndef ALLOW_ARM_NO_COMPASS
576
// if non-compass is source of heading we can skip compass health check
577
if (!ahrs.using_noncompass_for_yaw()) {
578
const Compass &_compass = AP::compass();
579
// check compass health
580
if (!_compass.healthy()) {
581
check_failed(true, "Compass %d not healthy", _compass.get_first_usable() + 1);
582
return false;
583
}
584
}
585
#endif
586
587
// always check if the current mode allows arming
588
if (!copter.flightmode->allows_arming(method)) {
589
check_failed(true, "%s mode not armable", copter.flightmode->name());
590
return false;
591
}
592
593
// succeed if arming checks are disabled
594
if (should_skip_all_checks()) {
595
return true;
596
}
597
598
// check lean angle
599
if (check_enabled(Check::INS)) {
600
if (acosf(ahrs.cos_roll()*ahrs.cos_pitch()) > copter.attitude_control->lean_angle_max_rad()) {
601
check_failed(Check::INS, true, "Leaning");
602
return false;
603
}
604
}
605
606
// check adsb
607
#if HAL_ADSB_ENABLED
608
if (check_enabled(Check::PARAMETERS)) {
609
if (copter.failsafe.adsb) {
610
check_failed(Check::PARAMETERS, true, "ADSB threat detected");
611
return false;
612
}
613
}
614
#endif
615
616
// check throttle
617
if (check_enabled(Check::RC)) {
618
#if FRAME_CONFIG == HELI_FRAME
619
const char *rc_item = "Collective";
620
#else
621
const char *rc_item = "Throttle";
622
#endif
623
// check throttle is not too high - skips checks if arming from GCS/scripting in Guided,Guided_NoGPS or Auto
624
if (!((AP_Arming::method_is_GCS(method) || method == AP_Arming::Method::SCRIPTING) && copter.flightmode->allows_GCS_or_SCR_arming_with_throttle_high())) {
625
// above top of deadband is too always high
626
if (copter.get_pilot_desired_climb_rate_ms() > 0.0f) {
627
check_failed(Check::RC, true, "%s too high", rc_item);
628
return false;
629
}
630
// in manual modes throttle must be at zero
631
#if FRAME_CONFIG != HELI_FRAME
632
if ((copter.flightmode->has_manual_throttle() || copter.flightmode->mode_number() == Mode::Number::DRIFT) && copter.channel_throttle->get_control_in() > 0) {
633
check_failed(Check::RC, true, "%s too high", rc_item);
634
return false;
635
}
636
#endif
637
}
638
}
639
640
// check if safety switch has been pushed
641
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
642
check_failed(true, "Safety Switch");
643
return false;
644
}
645
646
// superclass method should always be the last thing called; it
647
// has side-effects which would need to be cleaned up if one of
648
// our arm checks failed
649
return AP_Arming::arm_checks(method);
650
}
651
652
// mandatory checks that will be run if ARMING_SKIPCHK skips all or arming forced
653
bool AP_Arming_Copter::mandatory_checks(bool display_failure)
654
{
655
// call mandatory position checks and update notify status because regular position checks will not run
656
bool result = mandatory_position_checks(display_failure);
657
AP_Notify::flags.pre_arm_gps_check = result;
658
659
// call mandatory alt check
660
if (!alt_checks(display_failure)) {
661
result = false;
662
}
663
664
return result & AP_Arming::mandatory_checks(display_failure);
665
}
666
667
void AP_Arming_Copter::set_pre_arm_check(bool b)
668
{
669
copter.ap.pre_arm_check = b;
670
AP_Notify::flags.pre_arm_check = b;
671
}
672
673
bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_checks)
674
{
675
static bool in_arm_motors = false;
676
677
// exit immediately if already in this function
678
if (in_arm_motors) {
679
return false;
680
}
681
in_arm_motors = true;
682
683
// return true if already armed
684
if (copter.motors->armed()) {
685
in_arm_motors = false;
686
return true;
687
}
688
689
if (!AP_Arming::arm(method, do_arming_checks)) {
690
AP_Notify::events.arming_failed = true;
691
in_arm_motors = false;
692
return false;
693
}
694
695
#if HAL_LOGGING_ENABLED
696
// let logger know that we're armed (it may open logs e.g.)
697
AP::logger().set_vehicle_armed(true);
698
#endif
699
700
// disable cpu failsafe because initialising everything takes a while
701
copter.failsafe_disable();
702
703
// notify that arming will occur (we do this early to give plenty of warning)
704
AP_Notify::flags.armed = true;
705
// call notify update a few times to ensure the message gets out
706
for (uint8_t i=0; i<=10; i++) {
707
AP::notify().update();
708
}
709
710
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
711
send_arm_disarm_statustext("Arming motors");
712
#endif
713
714
// Remember Orientation
715
// --------------------
716
copter.init_simple_bearing();
717
718
auto &ahrs = AP::ahrs();
719
720
copter.initial_armed_bearing_rad = ahrs.get_yaw_rad();
721
722
if (!ahrs.home_is_set()) {
723
// Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home)
724
ahrs.resetHeightDatum();
725
LOGGER_WRITE_EVENT(LogEvent::EKF_ALT_RESET);
726
727
// we have reset height, so arming height is zero
728
copter.arming_altitude_m = 0;
729
} else if (!ahrs.home_is_locked()) {
730
// Reset home position if it has already been set before (but not locked)
731
if (!copter.set_home_to_current_location(false)) {
732
// ignore failure
733
}
734
735
// remember the height when we armed (ignore failures)
736
float pos_d_m = 0;
737
UNUSED_RESULT(AP::ahrs().get_relative_position_D_origin_float(pos_d_m));
738
copter.arming_altitude_m = -pos_d_m;
739
}
740
copter.update_super_simple_bearing(false);
741
742
// Reset SmartRTL return location. If activated, SmartRTL will ultimately try to land at this point
743
#if MODE_SMARTRTL_ENABLED
744
copter.g2.smart_rtl.set_home(copter.position_ok());
745
#endif
746
747
hal.util->set_soft_armed(true);
748
749
#if HAL_SPRAYER_ENABLED
750
// turn off sprayer's test if on
751
copter.sprayer.test_pump(false);
752
#endif
753
754
// output lowest possible value to motors
755
copter.motors->output_min();
756
757
// finally actually arm the motors
758
copter.motors->armed(true);
759
760
#if HAL_LOGGING_ENABLED
761
// log flight mode in case it was changed while vehicle was disarmed
762
AP::logger().Write_Mode((uint8_t)copter.flightmode->mode_number(), copter.control_mode_reason);
763
#endif
764
765
// re-enable failsafe
766
copter.failsafe_enable();
767
768
// perf monitor ignores delay due to arming
769
AP::scheduler().perf_info.ignore_this_loop();
770
771
// flag exiting this function
772
in_arm_motors = false;
773
774
// Log time stamp of arming event
775
copter.arm_time_ms = millis();
776
777
// Start the arming delay
778
copter.ap.in_arming_delay = true;
779
780
// assumed armed without a arming, switch. Overridden in switches.cpp
781
copter.ap.armed_with_airmode_switch = false;
782
783
// return success
784
return true;
785
}
786
787
// arming.disarm - disarm motors
788
bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_checks)
789
{
790
// return immediately if we are already disarmed
791
if (!copter.motors->armed()) {
792
return true;
793
}
794
795
// do not allow disarm via mavlink if we think we are flying:
796
if (do_disarm_checks &&
797
AP_Arming::method_is_GCS(method) &&
798
!copter.ap.land_complete) {
799
return false;
800
}
801
802
if (method == AP_Arming::Method::RUDDER) {
803
if (!copter.flightmode->has_manual_throttle() && !copter.ap.land_complete) {
804
return false;
805
}
806
}
807
808
if (!AP_Arming::disarm(method, do_disarm_checks)) {
809
return false;
810
}
811
812
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
813
send_arm_disarm_statustext("Disarming motors");
814
#endif
815
816
auto &ahrs = AP::ahrs();
817
818
// save compass offsets learned by the EKF if enabled
819
Compass &compass = AP::compass();
820
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LearnType::COPY_FROM_EKF) {
821
for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
822
Vector3f magOffsets;
823
if (ahrs.getMagOffsets(i, magOffsets)) {
824
compass.set_and_save_offsets(i, magOffsets);
825
}
826
}
827
}
828
829
// we are not in the air
830
copter.set_land_complete(true);
831
copter.set_land_complete_maybe(true);
832
833
// send disarm command to motors
834
copter.motors->armed(false);
835
836
#if MODE_AUTO_ENABLED
837
// reset the mission
838
copter.mode_auto.mission.reset();
839
#endif
840
841
#if HAL_LOGGING_ENABLED
842
AP::logger().set_vehicle_armed(false);
843
#endif
844
845
hal.util->set_soft_armed(false);
846
847
copter.ap.in_arming_delay = false;
848
849
#if AUTOTUNE_ENABLED
850
// Possibly save auto tuned parameters
851
copter.mode_autotune.autotune.disarmed(copter.flightmode == &copter.mode_autotune);
852
#endif
853
854
return true;
855
}
856
857
#pragma GCC diagnostic pop
858
859