mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: accel cal sample for 400ms instead of 1s
This commit is contained in:
parent
1e1d8efa22
commit
b306d7a356
|
@ -518,7 +518,7 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t num_samples = 0;
|
uint32_t num_samples = 0;
|
||||||
while (num_samples < 1000/update_dt_milliseconds) {
|
while (num_samples < 400/update_dt_milliseconds) {
|
||||||
wait_for_sample();
|
wait_for_sample();
|
||||||
// read samples from ins
|
// read samples from ins
|
||||||
update();
|
update();
|
||||||
|
|
Loading…
Reference in New Issue