Browse Source

HAL_Chibios: don't unregister shared DMA

the shared DMA handle is a property of the bus, not the device, so
should not be unregistered when the device is removed
master
Andrew Tridgell 7 years ago
parent
commit
755eca31c2
  1. 1
      libraries/AP_HAL_ChibiOS/I2CDevice.cpp
  2. 1
      libraries/AP_HAL_ChibiOS/SPIDevice.cpp
  3. 1
      libraries/AP_HAL_ChibiOS/shared_dma.cpp

1
libraries/AP_HAL_ChibiOS/I2CDevice.cpp

@ -59,7 +59,6 @@ I2CDevice::I2CDevice(uint8_t bus, uint8_t address) : @@ -59,7 +59,6 @@ I2CDevice::I2CDevice(uint8_t bus, uint8_t address) :
I2CDevice::~I2CDevice()
{
businfo[_busnum].dma_handle->unregister();
printf("I2C device bus %u address 0x%02x closed\n",
(unsigned)_busnum, (unsigned)_address);
free(pname);

1
libraries/AP_HAL_ChibiOS/SPIDevice.cpp

@ -164,7 +164,6 @@ SPIDevice::~SPIDevice() @@ -164,7 +164,6 @@ SPIDevice::~SPIDevice()
{
//printf("SPI device %s on %u:%u closed\n", device_desc.name,
// (unsigned)bus.bus, (unsigned)device_desc.device);
bus.dma_handle->unregister();
free(pname);
}

1
libraries/AP_HAL_ChibiOS/shared_dma.cpp

@ -53,7 +53,6 @@ void Shared_DMA::unregister() @@ -53,7 +53,6 @@ void Shared_DMA::unregister()
locks[stream_id2].deallocate();
locks[stream_id2].obj = nullptr;
}
}
// lock the DMA channels

Loading…
Cancel
Save