Browse Source

AP_InertialSensor: fixed freeing of fifo buffer

master
Andrew Tridgell 8 years ago
parent
commit
f3a778f980
  1. 2
      libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp
  2. 3
      libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp

2
libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp

@ -262,7 +262,7 @@ AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000(AP_InertialSensor &imu, @@ -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;
}

3
libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp

@ -220,6 +220,9 @@ AP_InertialSensor_MPU9250::AP_InertialSensor_MPU9250(AP_InertialSensor &imu, @@ -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…
Cancel
Save