mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
HAL_ChibiOS: fixed 3-way DMA sharing bug
when we have 3 way contention across two DMA streams we could get the dma_deallocate function called in an object from two places at once. This adds a mutex that prevents that scenario
This commit is contained in:
parent
0e09dc75c0
commit
a945c97ec6
@ -53,6 +53,7 @@ I2CBus I2CDeviceManager::businfo[ARRAY_SIZE_SIMPLE(I2CD)];
|
||||
// get a handle for DMA sharing DMA channels with other subsystems
|
||||
void I2CBus::dma_init(void)
|
||||
{
|
||||
chMtxObjectInit(&dma_lock);
|
||||
dma_handle = new Shared_DMA(I2CD[busnum].dma_channel_tx, I2CD[busnum].dma_channel_rx,
|
||||
FUNCTOR_BIND_MEMBER(&I2CBus::dma_allocate, void, Shared_DMA *),
|
||||
FUNCTOR_BIND_MEMBER(&I2CBus::dma_deallocate, void, Shared_DMA *));
|
||||
@ -163,12 +164,14 @@ I2CDevice::~I2CDevice()
|
||||
*/
|
||||
void I2CBus::dma_allocate(Shared_DMA *ctx)
|
||||
{
|
||||
chMtxLock(&dma_lock);
|
||||
if (!i2c_started) {
|
||||
osalDbgAssert(I2CD[busnum].i2c->state == I2C_STOP, "i2cStart state");
|
||||
i2cStart(I2CD[busnum].i2c, &i2ccfg);
|
||||
osalDbgAssert(I2CD[busnum].i2c->state == I2C_READY, "i2cStart state");
|
||||
i2c_started = true;
|
||||
}
|
||||
chMtxUnlock(&dma_lock);
|
||||
}
|
||||
|
||||
/*
|
||||
@ -176,12 +179,14 @@ void I2CBus::dma_allocate(Shared_DMA *ctx)
|
||||
*/
|
||||
void I2CBus::dma_deallocate(Shared_DMA *)
|
||||
{
|
||||
chMtxLock(&dma_lock);
|
||||
if (i2c_started) {
|
||||
osalDbgAssert(I2CD[busnum].i2c->state == I2C_READY, "i2cStart state");
|
||||
i2cStop(I2CD[busnum].i2c);
|
||||
osalDbgAssert(I2CD[busnum].i2c->state == I2C_STOP, "i2cStart state");
|
||||
i2c_started = false;
|
||||
}
|
||||
chMtxUnlock(&dma_lock);
|
||||
}
|
||||
|
||||
bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
|
||||
|
@ -39,6 +39,12 @@ public:
|
||||
uint32_t busclock;
|
||||
bool i2c_started;
|
||||
bool i2c_active;
|
||||
|
||||
// we need an additional lock in the dma_allocate and
|
||||
// dma_deallocate functions to cope with 3-way contention as we
|
||||
// have two DMA channels that we are handling with the shared_dma
|
||||
// code
|
||||
mutex_t dma_lock;
|
||||
|
||||
void dma_allocate(Shared_DMA *);
|
||||
void dma_deallocate(Shared_DMA *);
|
||||
|
@ -61,6 +61,8 @@ SPIBus::SPIBus(uint8_t _bus) :
|
||||
DeviceBus(APM_SPI_PRIORITY),
|
||||
bus(_bus)
|
||||
{
|
||||
chMtxObjectInit(&dma_lock);
|
||||
|
||||
// allow for sharing of DMA channels with other peripherals
|
||||
dma_handle = new Shared_DMA(spi_devices[bus].dma_channel_rx,
|
||||
spi_devices[bus].dma_channel_tx,
|
||||
@ -82,11 +84,13 @@ void SPIBus::dma_allocate(Shared_DMA *ctx)
|
||||
*/
|
||||
void SPIBus::dma_deallocate(Shared_DMA *ctx)
|
||||
{
|
||||
chMtxLock(&dma_lock);
|
||||
// another non-SPI peripheral wants one of our DMA channels
|
||||
if (spi_started) {
|
||||
spiStop(spi_devices[bus].driver);
|
||||
spi_started = false;
|
||||
}
|
||||
chMtxUnlock(&dma_lock);
|
||||
}
|
||||
|
||||
|
||||
|
@ -34,6 +34,12 @@ public:
|
||||
void dma_allocate(Shared_DMA *ctx);
|
||||
void dma_deallocate(Shared_DMA *ctx);
|
||||
bool spi_started;
|
||||
|
||||
// we need an additional lock in the dma_allocate and
|
||||
// dma_deallocate functions to cope with 3-way contention as we
|
||||
// have two DMA channels that we are handling with the shared_dma
|
||||
// code
|
||||
mutex_t dma_lock;
|
||||
};
|
||||
|
||||
struct SPIDesc {
|
||||
|
Loading…
Reference in New Issue
Block a user