diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 668d896639..6898992fbd 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -424,6 +424,8 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact _accel_scale[k] = Vector3f(1,1,1); } + memset(samples, 0, sizeof(samples)); + // capture data from 6 positions for (uint8_t i=0; i<6; i++) { const prog_char_t *msg; @@ -462,10 +464,6 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact // clear out any existing samples from ins update(); - // average 32 samples - for (uint8_t k=0; k