From f6a41a89366daadd88a118b7c00c788cbf30d84f Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Mon, 28 Dec 2015 20:16:16 -0800 Subject: [PATCH] AP_InertialSensor: ensure that accel calibration object isn't allocated more than once --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index dc89b7bea5..29fd0f288b 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -1241,9 +1241,14 @@ bool AP_InertialSensor::is_still() // called during the startup of accel cal void AP_InertialSensor::acal_init() { - _acal = new AP_AccelCal; + if (_acal == NULL) { + _acal = new AP_AccelCal; + } + if (_accel_calibrator == NULL) { + _accel_calibrator = new AccelCalibrator[INS_MAX_INSTANCES]; + } + _acal->register_client(this); - _accel_calibrator = new AccelCalibrator[INS_MAX_INSTANCES]; } // update accel calibrator