From 7e04b5d1f1656f464a1e406085e04d9e2266f3ca Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 13 Jul 2014 22:05:21 +0900 Subject: [PATCH] INS: calibrated method checks all accelerometers --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 91cece2f67..7cf4800e78 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -490,7 +490,14 @@ failed: /// @note this should not be called while flying because it reads from the eeprom which can be slow bool AP_InertialSensor::calibrated() { - return _accel_offset[0].load(); + // check each accelerometer has offsets saved + for (uint8_t i=0; i