From aec790757180839fc98f5729bd983bcea0162908 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 9 Mar 2015 08:25:08 +1100 Subject: [PATCH] AP_InertialSensor: updated comment on accel check in gyro cal --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index f67b101f84..b92f98be31 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -758,7 +758,8 @@ AP_InertialSensor::_init_gyro() if (accel_diff.length() > 0.2f) { // the accelerometers changed during the gyro sum. Skip // this sample. This copes with doing gyro cal on a - // steadily moving platform + // steadily moving platform. The value 0.2 corresponds + // with around 5 degrees/second of rotation. continue; }