AP_InertialSensor: on accel cal failure don't save values to zero

When the accel calibration fails leave the previous values saved but set them to defaults (scale default is ones, not zeros) and notify the GCS
This fixes an arithmetic exception when doing a second accel cal after the first one failed
This commit is contained in:
Francisco Ferreira 2016-11-12 10:36:33 +00:00 committed by Tom Pittenger
parent a3fcebc501
commit bfbb275577

View File

@ -1639,8 +1639,8 @@ void AP_InertialSensor::_acal_save_calibrations()
void AP_InertialSensor::_acal_event_failure()
{
for (uint8_t i=0; i<_accel_count; i++) {
_accel_offset[i].set_and_save(Vector3f(0,0,0));
_accel_scale[i].set_and_save(Vector3f(0,0,0));
_accel_offset[i].set_and_notify(Vector3f(0,0,0));
_accel_scale[i].set_and_notify(Vector3f(1,1,1));
}
}