APM:Libraries
AP_Arming.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 #include "AP_Arming.h"
17 #include <AP_Notify/AP_Notify.h>
19 #include <GCS_MAVLink/GCS.h>
20 
21 #define AP_ARMING_COMPASS_MAGFIELD_EXPECTED 530
22 #define AP_ARMING_COMPASS_MAGFIELD_MIN 185 // 0.35 * 530 milligauss
23 #define AP_ARMING_COMPASS_MAGFIELD_MAX 875 // 1.65 * 530 milligauss
24 #define AP_ARMING_BOARD_VOLTAGE_MIN 4.3f
25 #define AP_ARMING_BOARD_VOLTAGE_MAX 5.8f
26 #define AP_ARMING_ACCEL_ERROR_THRESHOLD 0.75f
27 #define AP_ARMING_AHRS_GPS_ERROR_MAX 10 // accept up to 10m difference between AHRS and GPS
28 
29 extern const AP_HAL::HAL& hal;
30 
32 
33  // @Param: REQUIRE
34  // @DisplayName: Require Arming Motors
35  // @Description: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, require rudder stick or GCS arming before arming motors and sends the minimum throttle PWM value to the throttle channel when disarmed. If 2, require rudder stick or GCS arming and send 0 PWM to throttle channel when disarmed. See the ARMING_CHECK_* parameters to see what checks are done before arming. Note, if setting this parameter to 0 a reboot is required to arm the plane. Also note, even with this parameter at 0, if ARMING_CHECK parameter is not also zero the plane may fail to arm throttle at boot due to a pre-arm check failure.
36  // @Values: 0:Disabled,1:THR_MIN PWM when disarmed,2:0 PWM when disarmed
37  // @User: Advanced
38  AP_GROUPINFO_FLAGS_FRAME("REQUIRE", 0, AP_Arming, require, 1,
41 
42  // @Param: CHECK
43  // @DisplayName: Arm Checks to Peform (bitmask)
44  // @Description: Checks prior to arming motor. This is a bitmask of checks that will be performed before allowing arming. The default is no checks, allowing arming at any time. You can select whatever checks you prefer by adding together the values of each check type to set this parameter. For example, to only allow arming when you have GPS lock and no RC failsafe you would set ARMING_CHECK to 72. For most users it is recommended that you set this to 1 to enable all checks.
45  // @Values: 0:None,1:All,2:Barometer,4:Compass,8:GPS Lock,16:INS(INertial Sensors - accels & gyros),32:Parameters(unused),64:RC Channels,128:Board voltage,256:Battery Level,1024:LoggingAvailable,2048:Hardware safety switch,4096:GPS configuration
46  // @Values{Plane}: 0:None,1:All,2:Barometer,4:Compass,8:GPS Lock,16:INS(INertial Sensors - accels & gyros),32:Parameters(unused),64:RC Channels,128:Board voltage,256:Battery Level,512:Airspeed,1024:LoggingAvailable,2048:Hardware safety switch,4096:GPS configuration
47  // @Bitmask: 0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,10:Logging Available,11:Hardware safety switch,12:GPS Configuration
48  // @Bitmask{Plane}: 0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch,12:GPS Configuration
49  // @User: Standard
50  AP_GROUPINFO("CHECK", 2, AP_Arming, checks_to_perform, ARMING_CHECK_ALL),
51 
52  // @Param: ACCTHRESH
53  // @DisplayName: Accelerometer error threshold
54  // @Description: Accelerometer error threshold used to determine inconsistent accelerometers. Compares this error range to other accelerometers to detect a hardware or calibration error. Lower value means tighter check and harder to pass arming check. Not all accelerometers are created equal.
55  // @Units: m/s/s
56  // @Range: 0.25 3.0
57  // @User: Advanced
58  AP_GROUPINFO("ACCTHRESH", 3, AP_Arming, accel_error_threshold, AP_ARMING_ACCEL_ERROR_THRESHOLD),
59 
60  // @Param: VOLT_MIN
61  // @DisplayName: Arming voltage minimum on the first battery
62  // @Description: The minimum voltage of the first battery required to arm, 0 disables the check
63  // @Units: V
64  // @Increment: 0.1
65  // @User: Standard
66  AP_GROUPINFO("VOLT_MIN", 4, AP_Arming, _min_voltage[0], 0),
67 
68  // @Param: VOLT2_MIN
69  // @DisplayName: Arming voltage minimum on the second battery
70  // @Description: The minimum voltage of the second battery required to arm, 0 disables the check
71  // @Units: V
72  // @Increment: 0.1
73  // @User: Standard
74  AP_GROUPINFO("VOLT2_MIN", 5, AP_Arming, _min_voltage[1], 0),
75 
77 };
78 
79 //The function point is particularly hacky, hacky, tacky
80 //but I don't want to reimplement messaging to GCS at the moment:
82  const AP_BattMonitor &battery) :
83  ahrs(ahrs_ref),
84  _compass(compass),
85  _battery(battery),
86  armed(false),
87  arming_method(NONE)
88 {
90 
91 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
92  // default REQUIRE parameter to 1 (needed for Copter which is missing the parameter declaration above)
93  require.set_default(YES_MIN_PWM);
94 #endif
95 
96  memset(last_accel_pass_ms, 0, sizeof(last_accel_pass_ms));
97  memset(last_gyro_pass_ms, 0, sizeof(last_gyro_pass_ms));
98 }
99 
101 {
103 }
104 
106 {
107  return require == NONE || armed;
108 }
109 
111 {
112  return checks_to_perform;
113 }
114 
116 {
119  if (!AP::baro().all_healthy()) {
120  if (report) {
121  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Barometer not healthy");
122  }
123  return false;
124  }
125  }
126 
127  return true;
128 }
129 
130 bool AP_Arming::airspeed_checks(bool report)
131 {
135  if (airspeed == nullptr) {
136  // not an airspeed capable vehicle
137  return true;
138  }
139  for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
140  if (airspeed->enabled(i) && airspeed->use(i) && !airspeed->healthy(i)) {
141  if (report) {
142  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Airspeed[%u] not healthy", i);
143  }
144  return false;
145  }
146  }
147  }
148 
149  return true;
150 }
151 
152 bool AP_Arming::logging_checks(bool report)
153 {
156  if (DataFlash_Class::instance()->logging_failed()) {
157  if (report) {
158  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Logging failed");
159  }
160  return false;
161  }
162  if (!DataFlash_Class::instance()->CardInserted()) {
163  if (report) {
164  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: No SD card");
165  }
166  return false;
167  }
168  }
169  return true;
170 }
171 
172 bool AP_Arming::ins_checks(bool report)
173 {
176  const AP_InertialSensor &ins = AP::ins();
177  if (!ins.get_gyro_health_all()) {
178  if (report) {
179  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Gyros not healthy");
180  }
181  return false;
182  }
183  if (!ins.gyro_calibrated_ok_all()) {
184  if (report) {
185  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Gyros not calibrated");
186  }
187  return false;
188  }
189  if (!ins.get_accel_health_all()) {
190  if (report) {
191  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Accels not healthy");
192  }
193  return false;
194  }
195  if (!ins.accel_calibrated_ok_all()) {
196  if (report) {
197  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: 3D Accel calibration needed");
198  }
199  return false;
200  }
201 
202  //check if accelerometers have calibrated and require reboot
203  if (ins.accel_cal_requires_reboot()) {
204  if (report) {
205  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Accels calibrated requires reboot");
206  }
207  return false;
208  }
209 
210  // check all accelerometers point in roughly same direction
211  if (ins.get_accel_count() > 1) {
212  const Vector3f &prime_accel_vec = ins.get_accel();
213  for(uint8_t i=0; i<ins.get_accel_count(); i++) {
214  if (!ins.use_accel(i)) {
215  continue;
216  }
217  // get next accel vector
218  const Vector3f &accel_vec = ins.get_accel(i);
219  Vector3f vec_diff = accel_vec - prime_accel_vec;
220  // allow for user-defined difference, typically 0.75 m/s/s. Has to pass in last 10 seconds
221  float threshold = accel_error_threshold;
222  if (i >= 2) {
223  /*
224  we allow for a higher threshold for IMU3 as it
225  runs at a different temperature to IMU1/IMU2,
226  and is not used for accel data in the EKF
227  */
228  threshold *= 3;
229  }
230 
231  // EKF is less sensitive to Z-axis error
232  vec_diff.z *= 0.5f;
233 
234  if (vec_diff.length() <= threshold) {
236  }
237  if (AP_HAL::millis() - last_accel_pass_ms[i] > 10000) {
238  if (report) {
239  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Accels inconsistent");
240  }
241  return false;
242  }
243  }
244  }
245 
246  // check all gyros are giving consistent readings
247  if (ins.get_gyro_count() > 1) {
248  const Vector3f &prime_gyro_vec = ins.get_gyro();
249  for(uint8_t i=0; i<ins.get_gyro_count(); i++) {
250  if (!ins.use_gyro(i)) {
251  continue;
252  }
253  // get next gyro vector
254  const Vector3f &gyro_vec = ins.get_gyro(i);
255  Vector3f vec_diff = gyro_vec - prime_gyro_vec;
256  // allow for up to 5 degrees/s difference. Pass if it has
257  // been OK in last 10 seconds
258  if (vec_diff.length() <= radians(5)) {
260  }
261  if (AP_HAL::millis() - last_gyro_pass_ms[i] > 10000) {
262  if (report) {
263  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Gyros inconsistent");
264  }
265  return false;
266  }
267  }
268  }
269  }
270 
271  return true;
272 }
273 
274 bool AP_Arming::compass_checks(bool report)
275 {
278 
279  if (!_compass.use_for_yaw()) {
280  // compass use is disabled
281  return true;
282  }
283 
284  if (!_compass.healthy()) {
285  if (report) {
286  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Compass not healthy");
287  }
288  return false;
289  }
290  // check compass learning is on or offsets have been set
292  if (report) {
293  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Compass not calibrated");
294  }
295  return false;
296  }
297 
298  //check if compass is calibrating
299  if (_compass.is_calibrating()) {
300  if (report) {
301  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Compass calibration running");
302  }
303  return false;
304  }
305 
306  //check if compass has calibrated and requires reboot
308  if (report) {
309  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Compass calibrated requires reboot");
310  }
311  return false;
312  }
313 
314  // check for unreasonable compass offsets
315  Vector3f offsets = _compass.get_offsets();
316  if (offsets.length() > _compass.get_offsets_max()) {
317  if (report) {
318  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Compass offsets too high");
319  }
320  return false;
321  }
322 
323  // check for unreasonable mag field length
324  float mag_field = _compass.get_field().length();
325  if (mag_field > AP_ARMING_COMPASS_MAGFIELD_MAX || mag_field < AP_ARMING_COMPASS_MAGFIELD_MIN) {
326  if (report) {
327  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Check mag field");
328  }
329  return false;
330  }
331 
332  // check all compasses point in roughly same direction
333  if (!_compass.consistent()) {
334  if (report) {
335  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Compasses inconsistent");
336  }
337  return false;
338  }
339  }
340 
341  return true;
342 }
343 
344 bool AP_Arming::gps_checks(bool report)
345 {
346  const AP_GPS &gps = AP::gps();
348 
349  //GPS OK?
350  if (!AP::ahrs().home_is_set() ||
351  gps.status() < AP_GPS::GPS_OK_FIX_3D) {
352  if (report) {
353  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Bad GPS Position");
354  }
355  return false;
356  }
357 
358  //GPS update rate acceptable
359  if (!gps.is_healthy()) {
360  if (report) {
361  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: GPS is not healthy");
362  }
363  return false;
364  }
365 
366  // check GPSs are within 50m of each other and that blending is healthy
367  float distance_m;
368  if (!gps.all_consistent(distance_m)) {
369  if (report) {
370  gcs().send_text(MAV_SEVERITY_CRITICAL,
371  "PreArm: GPS positions differ by %4.1fm",
372  (double)distance_m);
373  }
374  return false;
375  }
376  if (!gps.blend_health_check()) {
377  if (report) {
378  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: GPS blending unhealthy");
379  }
380  return false;
381  }
382 
383  // check AHRS and GPS are within 10m of each other
384  Location gps_loc = gps.location();
385  Location ahrs_loc;
386  if (ahrs.get_position(ahrs_loc)) {
387  const float distance = location_diff(gps_loc, ahrs_loc).length();
388  if (distance > AP_ARMING_AHRS_GPS_ERROR_MAX) {
389  if (report) {
390  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: GPS and AHRS differ by %4.1fm", (double)distance);
391  }
392  return false;
393  }
394  }
395  }
396 
397  if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS_CONFIG)) {
398  uint8_t first_unconfigured = gps.first_unconfigured_gps();
399  if (first_unconfigured != AP_GPS::GPS_ALL_CONFIGURED) {
400  if (report) {
401  gcs().send_text(MAV_SEVERITY_CRITICAL,
402  "PreArm: GPS %d failing configuration checks",
403  first_unconfigured + 1);
405  }
406  return false;
407  }
408  }
409 
410  return true;
411 }
412 
413 bool AP_Arming::battery_checks(bool report)
414 {
417 
418  if (AP_Notify::flags.failsafe_battery) {
419  if (report) {
420  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Battery failsafe on");
421  }
422  return false;
423  }
424 
425  for (uint8_t i = 0; i < _battery.num_instances(); i++) {
426  if ((_min_voltage[i] > 0.0f) && (_battery.voltage(i) < _min_voltage[i])) {
427  if (report) {
428  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Battery %d voltage %.1f below minimum %.1f",
429  i+1,
430  (double)_battery.voltage(i),
431  (double)_min_voltage[i]);
432  }
433  return false;
434  }
435  }
436  }
437  return true;
438 }
439 
441 {
444 
445  // check if safety switch has been pushed
447  if (report) {
448  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Hardware safety switch");
449  }
450  return false;
451  }
452  }
453 
454  return true;
455 }
456 
458 {
459  bool check_passed = true;
460  for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
461  const RC_Channel *ch = RC_Channels::rc_channel(i);
462  if (ch == nullptr) {
463  continue;
464  }
465  const uint16_t trim = ch->get_radio_trim();
466  if (ch->get_radio_min() > trim) {
467  if (report) {
468  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: RC%d minimum is greater than trim", i + 1);
469  }
470  check_passed = false;
471  }
472  if (ch->get_radio_max() < trim) {
473  if (report) {
474  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: RC%d maximum is less than trim", i + 1);
475  }
476  check_passed = false;
477  }
478  }
479 
480  return check_passed;
481 }
482 
484 {
487 
488  if (AP_Notify::flags.failsafe_radio) {
489  if (report) {
490  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Radio failsafe on");
491  }
492  return false;
493  }
494 
495  if (!rc_calibration_checks(report)) {
496  return false;
497  }
498  }
499 
500  return true;
501 }
502 
503 bool AP_Arming::servo_checks(bool report) const
504 {
505  bool check_passed = true;
506  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
507  const SRV_Channel *ch = SRV_Channels::srv_channel(i);
508  if (ch == nullptr || ch->get_function() == SRV_Channel::k_none) {
509  continue;
510  }
511 
512  const uint16_t trim = ch->get_trim();
513  if (ch->get_output_min() > trim) {
514  if (report) {
515  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: SERVO%d minimum is greater than trim", i + 1);
516  }
517  check_passed = false;
518  }
519  if (ch->get_output_max() < trim) {
520  if (report) {
521  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: SERVO%d maximum is less than trim", i + 1);
522  }
523  check_passed = false;
524  }
525  }
526 
527  return check_passed;
528 }
529 
531 {
532 #if HAL_HAVE_BOARD_VOLTAGE
533  // check board voltage
536  if (report) {
537  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check board voltage");
538  }
539  return false;
540  }
541  }
542 #endif
543  return true;
544 }
545 
546 bool AP_Arming::pre_arm_checks(bool report)
547 {
548 #if !APM_BUILD_TYPE(APM_BUILD_ArduCopter)
549  if (armed || require == NONE) {
550  // if we are already armed or don't need any arming checks
551  // then skip the checks
552  return true;
553  }
554 #endif
555 
556  return hardware_safety_check(report)
557  & barometer_checks(report)
558  & ins_checks(report)
559  & compass_checks(report)
560  & gps_checks(report)
561  & battery_checks(report)
562  & logging_checks(report)
563  & manual_transmitter_checks(report)
564  & servo_checks(report)
565  & board_voltage_checks(report);
566 }
567 
568 bool AP_Arming::arm_checks(uint8_t method)
569 {
570  // ensure the GPS drivers are ready on any final changes
573  if (!AP::gps().prepare_for_arming()) {
574  return false;
575  }
576  }
577 
578  // note that this will prepare DataFlash to start logging
579  // so should be the last check to be done before arming
580  if ((checks_to_perform & ARMING_CHECK_ALL) ||
583  df->PrepForArming();
584  if (!df->logging_started()) {
585  gcs().send_text(MAV_SEVERITY_CRITICAL, "Arm: Logging not started");
586  return false;
587  }
588  }
589  return true;
590 }
591 
592 //returns true if arming occurred successfully
593 bool AP_Arming::arm(uint8_t method)
594 {
595 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
596  // Copter should never use this function
597  return false;
598 #else
599  if (armed) { //already armed
600  return false;
601  }
602 
603  //are arming checks disabled?
605  armed = true;
607  gcs().send_text(MAV_SEVERITY_INFO, "Throttle armed");
608  return true;
609  }
610 
611  if (pre_arm_checks(true) && arm_checks(method)) {
612  armed = true;
613  arming_method = method;
614 
615  gcs().send_text(MAV_SEVERITY_INFO, "Throttle armed");
616 
617  //TODO: Log motor arming to the dataflash
618  //Can't do this from this class until there is a unified logging library
619 
620  } else {
621  armed = false;
623  }
624 
625  return armed;
626 #endif
627 }
628 
629 //returns true if disarming occurred successfully
631 {
632 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
633  // Copter should never use this function
634  return false;
635 #else
636  if (!armed) { // already disarmed
637  return false;
638  }
639  armed = false;
640 
641  gcs().send_text(MAV_SEVERITY_INFO, "Throttle disarmed");
642 
643  //TODO: Log motor disarming to the dataflash
644  //Can't do this from this class until there is a unified logging library.
645 
646  return true;
647 #endif
648 }
649 
651 {
652  return (AP_Arming::ArmingRequired)require.get();
653 }
654 
655 // Copter and sub share the same RC input limits
656 // Copter checks that min and max have been configured by default, Sub does not
657 bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channel *channels[4], const bool check_min_max) const
658 {
659  // set rc-checks to success if RC checks are disabled
661  return true;
662  }
663 
664  bool ret = true;
665 
666  const char *channel_names[] = { "Roll", "Pitch", "Throttle", "Yaw" };
667 
668  for (uint8_t i=0; i<ARRAY_SIZE(channel_names);i++) {
669  const RC_Channel *channel = channels[i];
670  const char *channel_name = channel_names[i];
671  // check if radio has been calibrated
672  if (check_min_max && !channel->min_max_configured()) {
673  if (display_failure) {
674  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: RC %s not configured", channel_name);
675  }
676  ret = false;
677  }
678  if (channel->get_radio_min() > 1300) {
679  if (display_failure) {
680  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: %s radio min too high", channel_name);
681  }
682  ret = false;
683  }
684  if (channel->get_radio_max() < 1700) {
685  if (display_failure) {
686  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: %s radio max too low", channel_name);
687  }
688  ret = false;
689  }
690  bool fail = true;
691  if (i == 2) {
692  // skip checking trim for throttle as older code did not check it
693  fail = false;
694  }
695  if (channel->get_radio_trim() < channel->get_radio_min()) {
696  if (display_failure) {
697  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: %s radio trim below min", channel_name);
698  }
699  if (fail) {
700  ret = false;
701  }
702  }
703  if (channel->get_radio_trim() > channel->get_radio_max()) {
704  if (display_failure) {
705  gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: %s radio trim above max", channel_name);
706  }
707  if (fail) {
708  ret = false;
709  }
710  }
711  }
712  return ret;
713 }
bool accel_cal_requires_reboot() const
AP_Int8 require
Definition: AP_Arming.h:68
Definition: AP_GPS.h:48
void PrepForArming()
Definition: DataFlash.cpp:450
bool enabled(uint8_t i) const
Definition: AP_Airspeed.h:85
bool use_for_yaw(uint8_t i) const
return true if the compass should be used for yaw calculations
bool servo_checks(bool report) const
Definition: AP_Arming.cpp:503
virtual bool arm(uint8_t method)
Definition: AP_Arming.cpp:593
SRV_Channel::Aux_servo_function_t get_function(void) const
Definition: SRV_Channel.h:175
int16_t get_radio_trim() const
Definition: RC_Channel.h:94
virtual float board_voltage(void)=0
bool logging_checks(bool report)
Definition: AP_Arming.cpp:152
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
uint8_t arming_method
Definition: AP_Arming.h:81
static RC_Channel * rc_channel(uint8_t chan)
Definition: RC_Channel.h:145
const Vector3f & get_gyro(uint8_t i) const
virtual bool get_position(struct Location &loc) const =0
Interface definition for the various Ground Control System.
bool logging_started(void)
Definition: DataFlash.cpp:548
uint16_t get_output_max(void) const
Definition: SRV_Channel.h:164
virtual bool barometer_checks(bool report)
Definition: AP_Arming.cpp:115
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
#define AP_ARMING_BOARD_VOLTAGE_MAX
Definition: AP_Arming.cpp:25
bool all_consistent(float &distance) const
Definition: AP_GPS.cpp:1002
AP_HAL::Util * util
Definition: HAL.h:115
void broadcast_first_configuration_failure_reason(void) const
Definition: AP_GPS.cpp:991
bool is_healthy(uint8_t instance) const
Definition: AP_GPS.cpp:1532
GCS & gcs()
#define AP_PARAM_FRAME_ROVER
Definition: AP_Param.h:78
bool configured(uint8_t i)
bool use_accel(uint8_t instance) const
const Location & location(uint8_t instance) const
Definition: AP_GPS.h:200
float distance
Definition: location.cpp:94
static uint16_t channels[SRXL_MAX_CHANNELS]
Definition: srxl.cpp:59
#define AP_ARMING_BOARD_VOLTAGE_MIN
Definition: AP_Arming.cpp:24
void fail(const char *why)
Definition: eedump.c:28
uint32_t last_accel_pass_ms[INS_MAX_INSTANCES]
Definition: AP_Arming.h:82
AP_Float accel_error_threshold
Definition: AP_Arming.h:70
virtual bool ins_checks(bool report)
Definition: AP_Arming.cpp:172
static AP_InertialSensor ins
Definition: AHRS_Test.cpp:18
AP_Float _min_voltage[AP_BATT_MONITOR_MAX_INSTANCES]
Definition: AP_Arming.h:71
const AP_Airspeed * get_airspeed(void) const
Definition: AP_AHRS.h:174
const Vector3f & get_accel(uint8_t i) const
const Vector3f & get_field(uint8_t i) const
Return the current field as a Vector3f in milligauss.
Definition: AP_Compass.h:122
uint16_t get_enabled_checks()
Definition: AP_Arming.cpp:110
#define NUM_RC_CHANNELS
Definition: RC_Channel.h:11
#define AP_GROUPINFO_FLAGS_FRAME(name, idx, clazz, element, def, flags, frame_flags)
Definition: AP_Param.h:99
static SRV_Channel * srv_channel(uint8_t i)
Definition: SRV_Channel.h:405
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:139
bool get_accel_health_all(void) const
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Arming.h:61
bool use_gyro(uint8_t instance) const
Object managing one RC channel.
Definition: RC_Channel.h:15
#define AP_PARAM_NO_SHIFT
Definition: AP_Param.h:60
ArmingRequired
Definition: AP_Arming.h:35
#define f(i)
bool manual_transmitter_checks(bool report)
Definition: AP_Arming.cpp:483
bool blend_health_check() const
Definition: AP_GPS.cpp:1018
AP_Int16 checks_to_perform
Definition: AP_Arming.h:69
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
bool min_max_configured() const
Definition: RC_Channel.cpp:339
uint32_t millis()
Definition: system.cpp:157
const Vector3f & get_offsets(uint8_t i) const
Definition: AP_Compass.h:166
virtual bool pre_arm_checks(bool report)
Definition: AP_Arming.cpp:546
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
T z
Definition: vector3.h:67
#define AP_ARMING_COMPASS_MAGFIELD_MAX
Definition: AP_Arming.cpp:23
virtual enum safety_state safety_switch_state(void)
Definition: Util.h:42
uint16_t get_output_min(void) const
Definition: SRV_Channel.h:161
bool healthy[COMPASS_MAX_INSTANCES]
Definition: AP_Compass.h:301
uint16_t get_offsets_max(void) const
Definition: AP_Compass.h:327
#define AP_ARMING_COMPASS_MAGFIELD_MIN
Definition: AP_Arming.cpp:22
bool armed
Definition: AP_Arming.h:79
bool consistent() const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
#define AP_ARMING_ACCEL_ERROR_THRESHOLD
Definition: AP_Arming.cpp:26
static Compass compass
Definition: AHRS_Test.cpp:20
GPS_Status status(uint8_t instance) const
Query GPS status.
Definition: AP_GPS.h:189
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
bool is_armed()
Definition: AP_Arming.cpp:105
uint16_t compass_magfield_expected() const
Definition: AP_Arming.cpp:100
bool hardware_safety_check(bool report)
Definition: AP_Arming.cpp:440
virtual bool gps_checks(bool report)
Definition: AP_Arming.cpp:344
#define AIRSPEED_MAX_SENSORS
Definition: AP_Airspeed.h:11
Compass & _compass
Definition: AP_Arming.h:75
bool learn_offsets_enabled() const
Definition: AP_Compass.h:194
AP_BattMonitor & battery()
float length(void) const
Definition: vector3.cpp:288
bool battery_checks(bool report)
Definition: AP_Arming.cpp:413
bool disarm()
Definition: AP_Arming.cpp:630
uint16_t get_trim(void) const
Definition: SRV_Channel.h:167
float length(void) const
Definition: vector2.cpp:24
virtual bool rc_calibration_checks(bool report)
Definition: AP_Arming.cpp:457
AP_Airspeed airspeed
Definition: Airspeed.cpp:34
AP_AHRS & ahrs()
Definition: AP_AHRS.cpp:488
ArmingRequired arming_required()
Definition: AP_Arming.cpp:650
static constexpr float radians(float deg)
Definition: AP_Math.h:158
static struct notify_flags_and_values_type flags
Definition: AP_Notify.h:117
#define AP_ARMING_COMPASS_MAGFIELD_EXPECTED
Definition: AP_Arming.cpp:21
bool airspeed_checks(bool report)
Definition: AP_Arming.cpp:130
int16_t get_radio_min() const
Definition: RC_Channel.h:88
int16_t get_radio_max() const
Definition: RC_Channel.h:91
#define AP_PARAM_FRAME_PLANE
Definition: AP_Param.h:79
bool arm_checks(uint8_t method)
Definition: AP_Arming.cpp:568
bool gyro_calibrated_ok_all() const
virtual bool compass_checks(bool report)
Definition: AP_Arming.cpp:274
bool is_calibrating() const
uint8_t get_gyro_count(void) const
AP_InertialSensor & ins()
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
#define AP_ARMING_AHRS_GPS_ERROR_MAX
Definition: AP_Arming.cpp:27
uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES]
Definition: AP_Arming.h:83
static AP_GPS gps
Definition: AHRS_Test.cpp:22
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
AP_Baro & baro()
Definition: AP_Baro.cpp:737
uint8_t first_unconfigured_gps(void) const
Definition: AP_GPS.cpp:981
const AP_BattMonitor & _battery
Definition: AP_Arming.h:76
AP_Arming(const AP_AHRS &ahrs_ref, Compass &compass, const AP_BattMonitor &battery)
Definition: AP_Arming.cpp:81
uint8_t num_instances(void) const
float voltage(uint8_t instance) const
voltage - returns battery voltage in millivolts
bool accel_calibrated_ok_all() const
bool healthy(uint8_t i) const
Definition: AP_Airspeed.h:135
#define NUM_SERVO_CHANNELS
Definition: SRV_Channel.h:24
virtual bool board_voltage_checks(bool report)
Definition: AP_Arming.cpp:530
bool compass_cal_requires_reboot()
Definition: AP_Compass.h:143
bool get_gyro_health_all(void) const
#define AP_GROUPEND
Definition: AP_Param.h:121
uint8_t get_accel_count(void) const
bool rc_checks_copter_sub(bool display_failure, const RC_Channel *channels[4], const bool check_min_max=true) const
Definition: AP_Arming.cpp:657
const AP_AHRS & ahrs
Definition: AP_Arming.h:74
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
AP_HAL::AnalogIn * analogin
Definition: HAL.h:108
AP_Int8 use
Definition: AP_Airspeed.h:181