Browse Source

AP_Arming: remove check for max INS instances

For all supported boards the maximum number of instances is 3.
mission-4.1.18
Lucas De Marchi 9 years ago committed by Andrew Tridgell
parent
commit
3114a988f8
  1. 3
      libraries/AP_Arming/AP_Arming.cpp

3
libraries/AP_Arming/AP_Arming.cpp

@ -155,7 +155,7 @@ bool AP_Arming::ins_checks(bool report) @@ -155,7 +155,7 @@ bool AP_Arming::ins_checks(bool report)
}
return false;
}
#if INS_MAX_INSTANCES > 1
// check all accelerometers point in roughly same direction
if (ins.get_accel_count() > 1) {
const Vector3f &prime_accel_vec = ins.get_accel();
@ -206,7 +206,6 @@ bool AP_Arming::ins_checks(bool report) @@ -206,7 +206,6 @@ bool AP_Arming::ins_checks(bool report)
}
}
}
#endif
}
return true;

Loading…
Cancel
Save