AP_InertialSensor: added a small delay in accel calibration

allows threads to run on Linux
This commit is contained in:
Andrew Tridgell 2013-10-08 11:48:37 +11:00
parent 1ccd6bb7ef
commit c17a5e5ed1
1 changed files with 2 additions and 0 deletions

View File

@ -371,6 +371,8 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact
samples[i] += get_accel();
hal.scheduler->delay(10);
num_samples++;
} else {
hal.scheduler->delay_microseconds(500);
}
}
samples[i] /= num_samples;