Browse Source

AP_Arming: check for AHRS health and calibration for arming

mission-4.1.18
Andrew Tridgell 10 years ago
parent
commit
a2adb9b1b0
  1. 12
      libraries/AP_Arming/AP_Arming.cpp

12
libraries/AP_Arming/AP_Arming.cpp

@ -132,6 +132,18 @@ bool AP_Arming::ins_checks(bool report) @@ -132,6 +132,18 @@ bool AP_Arming::ins_checks(bool report)
}
return false;
}
if (!ahrs.healthy()) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: AHRS not healthy!"));
}
return false;
}
if (ahrs.have_inertial_nav() && !ins.calibrated()) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: EKF requires 3D accel cal"));
}
return false;
}
#if INS_MAX_INSTANCES > 1
// check all accelerometers point in roughly same direction
if (ins.get_accel_count() > 1) {

Loading…
Cancel
Save