mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: allow gyro calibration to take up to 30 seconds
this gives time for the user time to get their battery hatches on and hold the model steady. 5 seconds was just far too short
This commit is contained in:
parent
20f3f19285
commit
f84f432ecf
|
@ -687,9 +687,9 @@ AP_InertialSensor::_init_gyro()
|
|||
|
||||
uint8_t num_converged = 0;
|
||||
|
||||
// we try to get a good calibration estimate for up to 10 seconds
|
||||
// we try to get a good calibration estimate for up to 30 seconds
|
||||
// if the gyros are stable, we should get it in 1 second
|
||||
for (int16_t j = 0; j <= 20 && num_converged < num_gyros; j++) {
|
||||
for (int16_t j = 0; j <= 30*4 && num_converged < num_gyros; j++) {
|
||||
Vector3f gyro_sum[INS_MAX_INSTANCES], gyro_avg[INS_MAX_INSTANCES], gyro_diff[INS_MAX_INSTANCES];
|
||||
float diff_norm[INS_MAX_INSTANCES];
|
||||
uint8_t i;
|
||||
|
|
Loading…
Reference in New Issue