APM:Copter
AP_Arming.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // performs pre-arm checks. expects to be called at 1hz.
5 {
6  // perform pre-arm checks & display failures every 30 seconds
7  static uint8_t pre_arm_display_counter = PREARM_DISPLAY_PERIOD/2;
8  pre_arm_display_counter++;
9  bool display_fail = false;
10  if (pre_arm_display_counter >= PREARM_DISPLAY_PERIOD) {
11  display_fail = true;
12  pre_arm_display_counter = 0;
13  }
14 
15  set_pre_arm_check(pre_arm_checks(display_fail));
16 }
17 
18 // performs pre-arm checks and arming checks
19 bool AP_Arming_Copter::all_checks_passing(bool arming_from_gcs)
20 {
22 
23  return copter.ap.pre_arm_check && arm_checks(true, arming_from_gcs);
24 }
25 
26 // perform pre-arm checks
27 // return true if the checks pass successfully
28 bool AP_Arming_Copter::pre_arm_checks(bool display_failure)
29 {
30  // exit immediately if already armed
31  if (copter.motors->armed()) {
32  return true;
33  }
34 
35  // check if motor interlock and Emergency Stop aux switches are used
36  // at the same time. This cannot be allowed.
37  if (copter.check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK) && copter.check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP)){
38  if (display_failure) {
39  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Interlock/E-Stop Conflict");
40  }
41  return false;
42  }
43 
44  // check if motor interlock aux switch is in use
45  // if it is, switch needs to be in disabled position to arm
46  // otherwise exit immediately. This check to be repeated,
47  // as state can change at any time.
48  if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) {
49  if (display_failure) {
50  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Motor Interlock Enabled");
51  }
52  }
53 
54  // succeed if pre arm checks are disabled
56  return true;
57  }
58 
59  return fence_checks(display_failure)
60  & parameter_checks(display_failure)
61  & motor_checks(display_failure)
62  & pilot_throttle_checks(display_failure) &
63  AP_Arming::pre_arm_checks(display_failure);
64 }
65 
66 bool AP_Arming_Copter::barometer_checks(bool display_failure)
67 {
68  if (!AP_Arming::barometer_checks(display_failure)) {
69  return false;
70  }
71 
72  bool ret = true;
73  // check Baro
75  // Check baro & inav alt are within 1m if EKF is operating in an absolute position mode.
76  // Do not check if intending to operate in a ground relative height mode as EKF will output a ground relative height
77  // that may differ from the baro height due to baro drift.
79  bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs);
80  if (using_baro_ref) {
81  if (fabsf(_inav.get_altitude() - copter.baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) {
82  if (display_failure) {
83  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Altitude disparity");
84  }
85  ret = false;
86  }
87  }
88  }
89  return ret;
90 }
91 
92 bool AP_Arming_Copter::compass_checks(bool display_failure)
93 {
94  bool ret = AP_Arming::compass_checks(display_failure);
95 
97  // check compass offsets have been set. AP_Arming only checks
98  // this if learning is off; Copter *always* checks.
99  if (!_compass.configured()) {
100  if (display_failure) {
101  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Compass not calibrated");
102  }
103  ret = false;
104  }
105  }
106 
107  return ret;
108 }
109 
110 bool AP_Arming_Copter::fence_checks(bool display_failure)
111 {
112  #if AC_FENCE == ENABLED
113  // check fence is initialised
114  const char *fail_msg = nullptr;
115  if (!copter.fence.pre_arm_check(fail_msg)) {
116  if (display_failure && fail_msg != nullptr) {
117  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: %s", fail_msg);
118  }
119  return false;
120  }
121  #endif
122  return true;
123 }
124 
125 bool AP_Arming_Copter::ins_checks(bool display_failure)
126 {
127  bool ret = AP_Arming::ins_checks(display_failure);
128 
130 
131  // get ekf attitude (if bad, it's usually the gyro biases)
133  if (display_failure) {
134  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: gyros still settling");
135  }
136  ret = false;
137  }
138  }
139 
140  return ret;
141 }
142 
143 bool AP_Arming_Copter::board_voltage_checks(bool display_failure)
144 {
145  if (!AP_Arming::board_voltage_checks(display_failure)) {
146  return false;
147  }
148 
149  // check battery voltage
151  if (copter.battery.has_failsafed()) {
152  if (display_failure) {
153  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Battery failsafe");
154  }
155  return false;
156  }
157 
158  // call parent battery checks
159  if (!AP_Arming::battery_checks(display_failure)) {
160  return false;
161  }
162  }
163 
164  return true;
165 }
166 
167 bool AP_Arming_Copter::parameter_checks(bool display_failure)
168 {
169  // check various parameter values
171 
172  // ensure ch7 and ch8 have different functions
173  if (copter.check_duplicate_auxsw()) {
174  if (display_failure) {
175  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Duplicate Aux Switch Options");
176  }
177  return false;
178  }
179 
180  // failsafe parameter checks
181  if (copter.g.failsafe_throttle) {
182  // check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900
183  if (copter.channel_throttle->get_radio_min() <= copter.g.failsafe_throttle_value+10 || copter.g.failsafe_throttle_value < 910) {
184  if (display_failure) {
185  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check FS_THR_VALUE");
186  }
187  return false;
188  }
189  }
190 
191  // lean angle parameter check
192  if (copter.aparm.angle_max < 1000 || copter.aparm.angle_max > 8000) {
193  if (display_failure) {
194  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check ANGLE_MAX");
195  }
196  return false;
197  }
198 
199  // acro balance parameter check
200 #if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED
201  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())) {
202  if (display_failure) {
203  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: ACRO_BAL_ROLL/PITCH");
204  }
205  return false;
206  }
207 #endif
208 
209  #if RANGEFINDER_ENABLED == ENABLED && OPTFLOW == ENABLED
210  // check range finder if optflow enabled
211  if (copter.optflow.enabled() && !copter.rangefinder.pre_arm_check()) {
212  if (display_failure) {
213  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: check range finder");
214  }
215  return false;
216  }
217  #endif
218 
219  #if FRAME_CONFIG == HELI_FRAME
220  // check helicopter parameters
221  if (!copter.motors->parameter_check(display_failure)) {
222  return false;
223  }
224  // Inverted flight feature disabled for Heli Single and Dual frames
225  if (copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_QUAD && (copter.g.ch7_option == 43 || copter.g.ch8_option == 43 || copter.g.ch9_option == 43 || copter.g.ch10_option == 43 || copter.g.ch11_option == 43 || copter.g.ch12_option == 43)) {
226  if (display_failure) {
227  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Inverted flight option not supported");
228  }
229  return false;
230  }
231  #endif // HELI_FRAME
232 
233  // check for missing terrain data
234  if (!pre_arm_terrain_check(display_failure)) {
235  return false;
236  }
237 
238  // check adsb avoidance failsafe
239 #if ADSB_ENABLED == ENABLE
240  if (copter.failsafe.adsb) {
241  if (display_failure) {
242  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: ADSB threat detected");
243  }
244  return false;
245  }
246 #endif
247 
248  // check for something close to vehicle
249  if (!pre_arm_proximity_check(display_failure)) {
250  return false;
251  }
252 
253  // Check for 0 value PID's - some items can / should be 0 and as such are not checked.
254  // If the ATC_RAT_*_FF is non zero then the corresponding ATC_RAT_* PIDS can be 0.
255  if (is_zero(copter.pos_control->get_pos_xy_p().kP())) {
256  parameter_checks_pid_warning_message(display_failure, "PSC_POSXY_P");
257  return false;
258  } else if (is_zero(copter.pos_control->get_pos_z_p().kP())) {
259  parameter_checks_pid_warning_message(display_failure, "PSC_POSZ_P");
260  return false;
261  } else if (is_zero(copter.pos_control->get_vel_z_p().kP())) {
262  parameter_checks_pid_warning_message(display_failure, "PSC_VELZ_P");
263  return false;
264  } else if (is_zero(copter.pos_control->get_accel_z_pid().kP())) {
265  parameter_checks_pid_warning_message(display_failure, "PSC_ACCZ_P");
266  return false;
267  } else if (is_zero(copter.pos_control->get_accel_z_pid().kI())) {
268  parameter_checks_pid_warning_message(display_failure, "PSC_ACCZ_I");
269  return false;
270  } else if (is_zero(copter.attitude_control->get_rate_roll_pid().kP()) && is_zero(copter.attitude_control->get_rate_roll_pid().ff())) {
271  parameter_checks_pid_warning_message(display_failure, "ATC_RAT_RLL_P");
272  return false;
273  } else if (is_zero(copter.attitude_control->get_rate_roll_pid().kI()) && is_zero(copter.attitude_control->get_rate_roll_pid().ff())) {
274  parameter_checks_pid_warning_message(display_failure, "ATC_RAT_RLL_I");
275  return false;
276  } else if (is_zero(copter.attitude_control->get_rate_roll_pid().kD()) && is_zero(copter.attitude_control->get_rate_roll_pid().ff())) {
277  parameter_checks_pid_warning_message(display_failure, "ATC_RAT_RLL_D");
278  return false;
279  } else if (is_zero(copter.attitude_control->get_rate_pitch_pid().kP()) && is_zero(copter.attitude_control->get_rate_pitch_pid().ff())) {
280  parameter_checks_pid_warning_message(display_failure, "ATC_RAT_PIT_P");
281  return false;
282  } else if (is_zero(copter.attitude_control->get_rate_pitch_pid().kI()) && is_zero(copter.attitude_control->get_rate_pitch_pid().ff())) {
283  parameter_checks_pid_warning_message(display_failure, "ATC_RAT_PIT_I");
284  return false;
285  } else if (is_zero(copter.attitude_control->get_rate_pitch_pid().kD()) && is_zero(copter.attitude_control->get_rate_pitch_pid().ff())) {
286  parameter_checks_pid_warning_message(display_failure, "ATC_RAT_PIT_D");
287  return false;
288  } else if (is_zero(copter.attitude_control->get_rate_yaw_pid().kP()) && is_zero(copter.attitude_control->get_rate_yaw_pid().ff())) {
289  parameter_checks_pid_warning_message(display_failure, "ATC_RAT_YAW_P");
290  return false;
291  } else if (is_zero(copter.attitude_control->get_rate_yaw_pid().kI()) && is_zero(copter.attitude_control->get_rate_yaw_pid().ff())) {
292  parameter_checks_pid_warning_message(display_failure, "ATC_RAT_YAW_I");
293  return false;
294  } else if (is_zero(copter.attitude_control->get_angle_pitch_p().kP())) {
295  parameter_checks_pid_warning_message(display_failure, "ATC_ANG_PIT_P");
296  return false;
297  } else if (is_zero(copter.attitude_control->get_angle_roll_p().kP())) {
298  parameter_checks_pid_warning_message(display_failure, "ATC_ANG_RLL_P");
299  return false;
300  } else if (is_zero(copter.attitude_control->get_angle_yaw_p().kP())) {
301  parameter_checks_pid_warning_message(display_failure, "ATC_ANG_YAW_P");
302  return false;
303  }
304  }
305 
306  return true;
307 }
308 
309 void AP_Arming_Copter::parameter_checks_pid_warning_message(bool display_failure, const char *error_msg)
310 {
311  if (display_failure) {
312  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check PIDs - %s", error_msg);
313  }
314 }
315 
316 // check motor setup was successful
317 bool AP_Arming_Copter::motor_checks(bool display_failure)
318 {
319  // check motors initialised correctly
320  if (!copter.motors->initialised_ok()) {
321  if (display_failure) {
322  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: check firmware or FRAME_CLASS");
323  }
324  return false;
325  }
326  return true;
327 }
328 
329 bool AP_Arming_Copter::pilot_throttle_checks(bool display_failure)
330 {
331  // check throttle is above failsafe throttle
332  // this is near the bottom to allow other failures to be displayed before checking pilot throttle
334  if (copter.g.failsafe_throttle != FS_THR_DISABLED && copter.channel_throttle->get_radio_in() < copter.g.failsafe_throttle_value) {
335  if (display_failure) {
336  #if FRAME_CONFIG == HELI_FRAME
337  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Collective below Failsafe");
338  #else
339  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Throttle below Failsafe");
340  #endif
341  }
342  return false;
343  }
344  }
345 
346  return true;
347 }
348 
349 bool AP_Arming_Copter::rc_calibration_checks(bool display_failure)
350 {
351  const RC_Channel *channels[] = {
352  copter.channel_roll,
353  copter.channel_pitch,
354  copter.channel_throttle,
355  copter.channel_yaw
356  };
357 
358  copter.ap.pre_arm_rc_check = rc_checks_copter_sub(display_failure, channels)
359  & AP_Arming::rc_calibration_checks(display_failure);
360 
361  return copter.ap.pre_arm_rc_check;
362 }
363 
364 // performs pre_arm gps related checks and returns true if passed
365 bool AP_Arming_Copter::gps_checks(bool display_failure)
366 {
367  // always check if inertial nav has started and is ready
368  if (!ahrs.healthy()) {
369  if (display_failure) {
370  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Waiting for Nav Checks");
371  }
372  return false;
373  }
374 
375  // check if flight mode requires GPS
376  bool mode_requires_gps = copter.flightmode->requires_GPS();
377 
378  // check if fence requires GPS
379  bool fence_requires_gps = false;
380  #if AC_FENCE == ENABLED
381  // if circular or polygon fence is enabled we need GPS
382  fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
383  #endif
384 
385  // return true if GPS is not required
386  if (!mode_requires_gps && !fence_requires_gps) {
388  return true;
389  }
390 
391  // ensure GPS is ok
392  if (!copter.position_ok()) {
393  if (display_failure) {
394  const char *reason = ahrs.prearm_failure_reason();
395  if (reason) {
396  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: %s", reason);
397  } else {
398  if (!mode_requires_gps && fence_requires_gps) {
399  // clarify to user why they need GPS in non-GPS flight mode
400  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Fence enabled, need 3D Fix");
401  } else {
402  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Need 3D Fix");
403  }
404  }
405  }
407  return false;
408  }
409 
410  // check for GPS glitch (as reported by EKF)
411  nav_filter_status filt_status;
412  if (_ahrs_navekf.get_filter_status(filt_status)) {
413  if (filt_status.flags.gps_glitching) {
414  if (display_failure) {
415  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: GPS glitching");
416  }
417  return false;
418  }
419  }
420 
421  // check EKF compass variance is below failsafe threshold
422  float vel_variance, pos_variance, hgt_variance, tas_variance;
423  Vector3f mag_variance;
424  Vector2f offset;
425  _ahrs_navekf.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance, offset);
426  if (mag_variance.length() >= copter.g.fs_ekf_thresh) {
427  if (display_failure) {
428  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: EKF compass variance");
429  }
430  return false;
431  }
432 
433  // check home and EKF origin are not too far
434  if (copter.far_from_EKF_origin(ahrs.get_home())) {
435  if (display_failure) {
436  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: EKF-home variance");
437  }
439  return false;
440  }
441 
442  // return true immediately if gps check is disabled
445  return true;
446  }
447 
448  // warn about hdop separately - to prevent user confusion with no gps lock
449  if (copter.gps.get_hdop() > copter.g.gps_hdop_good) {
450  if (display_failure) {
451  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: High GPS HDOP");
452  }
454  return false;
455  }
456 
457  // call parent gps checks
458  if (!AP_Arming::gps_checks(display_failure)) {
460  return false;
461  }
462 
463  // if we got here all must be ok
465  return true;
466 }
467 
468 // check ekf attitude is acceptable
470 {
471  // get ekf filter status
472  nav_filter_status filt_status = _inav.get_filter_status();
473 
474  return filt_status.flags.attitude;
475 }
476 
477 // check we have required terrain data
478 bool AP_Arming_Copter::pre_arm_terrain_check(bool display_failure)
479 {
480 #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
481  // succeed if not using terrain data
482  if (!copter.terrain_use()) {
483  return true;
484  }
485 
486  // check if terrain following is enabled, using a range finder but RTL_ALT is higher than rangefinder's max range
487  // To-Do: modify RTL return path to fly at or above the RTL_ALT and remove this check
488 
489  if (copter.rangefinder_state.enabled && (copter.g.rtl_altitude > copter.rangefinder.max_distance_cm_orient(ROTATION_PITCH_270))) {
490  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: RTL_ALT above rangefinder max range");
491  return false;
492  }
493 
494  // show terrain statistics
495  uint16_t terr_pending, terr_loaded;
496  copter.terrain.get_statistics(terr_pending, terr_loaded);
497  bool have_all_data = (terr_pending <= 0);
498  if (!have_all_data && display_failure) {
499  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Waiting for Terrain data");
500  }
501  return have_all_data;
502 #else
503  return true;
504 #endif
505 }
506 
507 // check nothing is too close to vehicle
509 {
510 #if PROXIMITY_ENABLED == ENABLED
511 
512  // return true immediately if no sensor present
513  if (copter.g2.proximity.get_status() == AP_Proximity::Proximity_NotConnected) {
514  return true;
515  }
516 
517  // return false if proximity sensor unhealthy
518  if (copter.g2.proximity.get_status() < AP_Proximity::Proximity_Good) {
519  if (display_failure) {
520  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: check proximity sensor");
521  }
522  return false;
523  }
524 
525  // get closest object if we might use it for avoidance
526 #if AC_AVOID_ENABLED == ENABLED
527  float angle_deg, distance;
528  if (copter.avoid.proximity_avoidance_enabled() && copter.g2.proximity.get_closest_object(angle_deg, distance)) {
529  // display error if something is within 60cm
530  if (distance <= 0.6f) {
531  if (display_failure) {
532  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Proximity %d deg, %4.2fm", (int)angle_deg, (double)distance);
533  }
534  return false;
535  }
536  }
537 #endif
538 
539  return true;
540 #else
541  return true;
542 #endif
543 }
544 
545 // arm_checks - perform final checks before arming
546 // always called just before arming. Return true if ok to arm
547 // has side-effect that logging is started
548 bool AP_Arming_Copter::arm_checks(bool display_failure, bool arming_from_gcs)
549 {
550  // always check if inertial nav has started and is ready
551  if (!ahrs.healthy()) {
552  if (display_failure) {
553  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Waiting for Nav Checks");
554  }
555  return false;
556  }
557 
558 #ifndef ALLOW_ARM_NO_COMPASS
559  // check compass health
560  if (!_compass.healthy()) {
561  if (display_failure) {
562  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Compass not healthy");
563  }
564  return false;
565  }
566 #endif
567 
568  if (_compass.is_calibrating()) {
569  if (display_failure) {
570  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Compass calibration running");
571  }
572  return false;
573  }
574 
575  //check if compass has calibrated and requires reboot
577  if (display_failure) {
578  gcs().send_text(MAV_SEVERITY_CRITICAL, "Arm: Compass calibrated requires reboot");
579  }
580  return false;
581  }
582 
583  control_mode_t control_mode = copter.control_mode;
584 
585  // always check if the current mode allows arming
586  if (!copter.flightmode->allows_arming(arming_from_gcs)) {
587  if (display_failure) {
588  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Mode not armable");
589  }
590  return false;
591  }
592 
593  // always check motors
594  if (!motor_checks(display_failure)) {
595  return false;
596  }
597 
598  // if we are using motor interlock switch and it's enabled, fail to arm
599  // skip check in Throw mode which takes control of the motor interlock
600  if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) {
601  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Motor Interlock Enabled");
602  return false;
603  }
604 
605  // if we are not using Emergency Stop switch option, force Estop false to ensure motors
606  // can run normally
607  if (!copter.check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP)){
608  copter.set_motor_emergency_stop(false);
609  // if we are using motor Estop switch, it must not be in Estop position
610  } else if (copter.check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP) && copter.ap.motor_emergency_stop){
611  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Motor Emergency Stopped");
612  return false;
613  }
614 
615  // succeed if arming checks are disabled
617  return true;
618  }
619 
620  // check lean angle
622  if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > copter.aparm.angle_max) {
623  if (display_failure) {
624  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Leaning");
625  }
626  return false;
627  }
628  }
629 
630  // check adsb
631 #if ADSB_ENABLED == ENABLE
633  if (copter.failsafe.adsb) {
634  if (display_failure) {
635  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: ADSB threat detected");
636  }
637  return false;
638  }
639  }
640 #endif
641 
642  // check throttle
644  // check throttle is not too low - must be above failsafe throttle
645  if (copter.g.failsafe_throttle != FS_THR_DISABLED && copter.channel_throttle->get_radio_in() < copter.g.failsafe_throttle_value) {
646  if (display_failure) {
647  #if FRAME_CONFIG == HELI_FRAME
648  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective below Failsafe");
649  #else
650  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Throttle below Failsafe");
651  #endif
652  }
653  return false;
654  }
655 
656  // check throttle is not too high - skips checks if arming from GCS in Guided
657  if (!(arming_from_gcs && (control_mode == GUIDED || control_mode == GUIDED_NOGPS))) {
658  // above top of deadband is too always high
659  if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) {
660  if (display_failure) {
661  #if FRAME_CONFIG == HELI_FRAME
662  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective too high");
663  #else
664  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Throttle too high");
665  #endif
666  }
667  return false;
668  }
669  // in manual modes throttle must be at zero
670  if ((copter.flightmode->has_manual_throttle() || control_mode == DRIFT) && copter.channel_throttle->get_control_in() > 0) {
671  if (display_failure) {
672  #if FRAME_CONFIG == HELI_FRAME
673  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective too high");
674  #else
675  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Throttle too high");
676  #endif
677  }
678  return false;
679  }
680  }
681  }
682 
683  // check if safety switch has been pushed
685  if (display_failure) {
686  gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Safety Switch");
687  }
688  return false;
689  }
690 
691  // superclass method should always be the last thing called; it
692  // has side-effects which would need to be cleaned up if one of
693  // our arm checks failed
694  return AP_Arming::arm_checks(arming_from_gcs);
695 }
696 
698 {
699  copter.ap.pre_arm_check = b;
701 }
const AP_AHRS_NavEKF & _ahrs_navekf
Definition: AP_Arming.h:53
bool arm_checks(bool display_failure, bool arming_from_gcs)
Definition: AP_Arming.cpp:548
const AP_InertialNav_NavEKF & _inav
Definition: AP_Arming.h:52
bool barometer_checks(bool display_failure) override
Definition: AP_Arming.cpp:66
float get_altitude() const
control_mode_t
Definition: defines.h:91
ROTATION_PITCH_270
bool board_voltage_checks(bool display_failure) override
Definition: AP_Arming.cpp:143
bool get_filter_status(nav_filter_status &status) const
struct _USB_OTG_GOTGCTL_TypeDef::@51 b
#define AC_FENCE_TYPE_CIRCLE
const struct Location & get_home(void) const
bool all_checks_passing(bool arming_from_gcs)
Definition: AP_Arming.cpp:19
virtual bool barometer_checks(bool report)
virtual const char * prearm_failure_reason(void) const
AP_HAL::Util * util
Definition: defines.h:96
GCS & gcs()
Definition: defines.h:101
bool configured(uint8_t i)
float distance
bool rc_calibration_checks(bool display_failure) override
Definition: AP_Arming.cpp:349
virtual bool ins_checks(bool report)
ARMING_CHECK_PARAMETERS
bool parameter_checks(bool display_failure)
Definition: AP_Arming.cpp:167
float cos_roll() const
bool ins_checks(bool display_failure) override
Definition: AP_Arming.cpp:125
nav_filter_status get_filter_status() const
void update(void)
Definition: AP_Arming.cpp:4
bool pilot_throttle_checks(bool display_failure)
Definition: AP_Arming.cpp:329
bool is_zero(const T fVal1)
#define f(i)
bool pre_arm_proximity_check(bool display_failure)
Definition: AP_Arming.cpp:508
AP_Int16 checks_to_perform
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
bool pre_arm_terrain_check(bool display_failure)
Definition: AP_Arming.cpp:478
#define FS_THR_DISABLED
Definition: defines.h:455
bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const override
void set_pre_arm_check(bool b)
Definition: AP_Arming.cpp:697
virtual bool pre_arm_checks(bool report)
virtual enum safety_state safety_switch_state(void)
bool healthy[COMPASS_MAX_INSTANCES]
void send_text(MAV_SEVERITY severity, const char *fmt,...)
#define PREARM_DISPLAY_PERIOD
Definition: config.h:171
bool pre_arm_checks(bool display_failure) override
Definition: AP_Arming.cpp:28
virtual bool gps_checks(bool report)
float cos_pitch() const
Compass & _compass
float length(void) const
bool battery_checks(bool report)
struct nav_filter_status::@138 flags
bool motor_checks(bool display_failure)
Definition: AP_Arming.cpp:317
virtual bool rc_calibration_checks(bool report)
bool fence_checks(bool display_failure)
Definition: AP_Arming.cpp:110
static struct notify_flags_and_values_type flags
virtual bool healthy(void) const=0
#define PREARM_MAX_ALT_DISPARITY_CM
Definition: config.h:176
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
bool arm_checks(uint8_t method)
virtual bool compass_checks(bool report)
bool is_calibrating() const
#define AC_FENCE_TYPE_POLYGON
bool pre_arm_ekf_attitude_check()
Definition: AP_Arming.cpp:469
#define degrees(x)
void parameter_checks_pid_warning_message(bool display_failure, const char *error_msg)
Definition: AP_Arming.cpp:309
bool compass_checks(bool display_failure) override
Definition: AP_Arming.cpp:92
bool gps_checks(bool display_failure) override
Definition: AP_Arming.cpp:365
virtual bool board_voltage_checks(bool report)
bool compass_cal_requires_reboot()
bool rc_checks_copter_sub(bool display_failure, const RC_Channel *channels[4], const bool check_min_max=true) const
const AP_AHRS & ahrs