InertialSensor: remove gyro cal on first arming

This commit is contained in:
Randy Mackay 2015-10-15 15:06:34 +09:00
parent 2ea23d66b0
commit b751d2bb18
2 changed files with 2 additions and 3 deletions

View File

@ -306,7 +306,7 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] PROGMEM = {
// @Param: GYR_CAL
// @DisplayName: Gyro Calibration scheme
// @Description: Conrols when automatic gyro calibration is performed
// @Values: 0:Never, 1:Start-up only, 2:Start-up and first arming (Copter only)
// @Values: 0:Never, 1:Start-up only
// @User: Advanced
AP_GROUPINFO("GYR_CAL", 24, AP_InertialSensor, _gyro_cal_timing, 1),

View File

@ -66,8 +66,7 @@ public:
enum Gyro_Calibration_Timing {
GYRO_CAL_NEVER = 0,
GYRO_CAL_STARTUP_ONLY = 1,
GYRO_CAL_STARTUP_AND_FIRST_BOOT = 2
GYRO_CAL_STARTUP_ONLY = 1
};
/// Perform startup initialisation.