AP_Arming: remove check for max INS instances

For all supported boards the maximum number of instances is 3.
This commit is contained in:
Lucas De Marchi 2015-10-14 12:44:35 -03:00 committed by Andrew Tridgell
parent 09f185eb5e
commit 3114a988f8
1 changed files with 1 additions and 2 deletions

View File

@ -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)
}
}
}
#endif
}
return true;