Browse Source

AP_Arming: don't reporting IMU inconsistencies if IMU not enabled

mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
bc5210d6f2
  1. 6
      libraries/AP_Arming/AP_Arming.cpp

6
libraries/AP_Arming/AP_Arming.cpp

@ -177,6 +177,9 @@ bool AP_Arming::ins_checks(bool report) @@ -177,6 +177,9 @@ bool AP_Arming::ins_checks(bool report)
if (ins.get_accel_count() > 1) {
const Vector3f &prime_accel_vec = ins.get_accel();
for(uint8_t i=0; i<ins.get_accel_count(); i++) {
if (!ins.use_accel(i)) {
continue;
}
// get next accel vector
const Vector3f &accel_vec = ins.get_accel(i);
Vector3f vec_diff = accel_vec - prime_accel_vec;
@ -206,6 +209,9 @@ bool AP_Arming::ins_checks(bool report) @@ -206,6 +209,9 @@ bool AP_Arming::ins_checks(bool report)
if (ins.get_gyro_count() > 1) {
const Vector3f &prime_gyro_vec = ins.get_gyro();
for(uint8_t i=0; i<ins.get_gyro_count(); i++) {
if (!ins.use_gyro(i)) {
continue;
}
// get next gyro vector
const Vector3f &gyro_vec = ins.get_gyro(i);
Vector3f vec_diff = gyro_vec - prime_gyro_vec;

Loading…
Cancel
Save