From 106a91c64c45f40f3c4ebcffb3824a03f0da8f0e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 5 Nov 2016 20:19:29 +1100 Subject: [PATCH] AP_InertialSensor: use init_gyro() on startup this saves the calibration parameters which should be done on calibration --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 8ed7c61c26..a92088d810 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -624,7 +624,7 @@ AP_InertialSensor::init(uint16_t sample_rate) // calibrate gyros unless gyro calibration has been disabled if (gyro_calibration_timing() != GYRO_CAL_NEVER) { - _init_gyro(); + init_gyro(); } _sample_period_usec = 1000*1000UL / _sample_rate;