Browse Source

AP_InertialSensor: added a small delay in accel calibration

allows threads to run on Linux
mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
c17a5e5ed1
  1. 2
      libraries/AP_InertialSensor/AP_InertialSensor.cpp

2
libraries/AP_InertialSensor/AP_InertialSensor.cpp

@ -371,6 +371,8 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact @@ -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…
Cancel
Save