AP_InertialSensor: ensure that accel calibration object isn't allocated more than once

This commit is contained in:
Jonathan Challinger 2015-12-28 20:16:16 -08:00
parent 57d2594bd7
commit f6a41a8936
1 changed files with 7 additions and 2 deletions

View File

@ -1241,9 +1241,14 @@ bool AP_InertialSensor::is_still()
// called during the startup of accel cal // called during the startup of accel cal
void AP_InertialSensor::acal_init() void AP_InertialSensor::acal_init()
{ {
if (_acal == NULL) {
_acal = new AP_AccelCal; _acal = new AP_AccelCal;
_acal->register_client(this); }
if (_accel_calibrator == NULL) {
_accel_calibrator = new AccelCalibrator[INS_MAX_INSTANCES]; _accel_calibrator = new AccelCalibrator[INS_MAX_INSTANCES];
}
_acal->register_client(this);
} }
// update accel calibrator // update accel calibrator