mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: added a small delay in accel calibration
allows threads to run on Linux
This commit is contained in:
parent
1ccd6bb7ef
commit
c17a5e5ed1
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue