mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_InertialSensor: check accel health during accel cal
This commit is contained in:
parent
875339f12a
commit
e6a4b9f68c
@ -472,6 +472,10 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact
|
||||
// capture sample
|
||||
for (uint8_t k=0; k<num_accels; k++) {
|
||||
samples[k][i] += get_accel(k);
|
||||
if (!get_accel_health(k)) {
|
||||
interact->printf_P(PSTR("accel[%u] not healthy"), (unsigned)k);
|
||||
goto failed;
|
||||
}
|
||||
}
|
||||
hal.scheduler->delay(10);
|
||||
num_samples++;
|
||||
|
Loading…
Reference in New Issue
Block a user