mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: fixed freeing of fifo buffer
This commit is contained in:
parent
6f28c61c8d
commit
f3a778f980
|
@ -262,7 +262,7 @@ AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000(AP_InertialSensor &imu,
|
|||
AP_InertialSensor_MPU6000::~AP_InertialSensor_MPU6000()
|
||||
{
|
||||
if (_fifo_buffer != nullptr) {
|
||||
delete[] _fifo_buffer;
|
||||
hal.util->dma_free(_fifo_buffer, MPU_FIFO_BUFFER_LEN * MPU_SAMPLE_SIZE);
|
||||
}
|
||||
delete _auxiliary_bus;
|
||||
}
|
||||
|
|
|
@ -220,6 +220,9 @@ AP_InertialSensor_MPU9250::AP_InertialSensor_MPU9250(AP_InertialSensor &imu,
|
|||
|
||||
AP_InertialSensor_MPU9250::~AP_InertialSensor_MPU9250()
|
||||
{
|
||||
if (_fifo_buffer != nullptr) {
|
||||
hal.util->dma_free(_fifo_buffer, MPU_FIFO_BUFFER_LEN * MPU_SAMPLE_SIZE);
|
||||
}
|
||||
delete _auxiliary_bus;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue