From 3114a988f8b23b28638981acdbcef141f2c8a573 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Wed, 14 Oct 2015 12:44:35 -0300 Subject: [PATCH] AP_Arming: remove check for max INS instances For all supported boards the maximum number of instances is 3. --- libraries/AP_Arming/AP_Arming.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 48a0fb6103..25cc2d1e55 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -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;