HAL_ChibiOS: reduce latency of DMA sharing

if we are sharing a DMA channel between i2c and SPI then this saves
latency on SPI by giving up the DMA channel between retries
This commit is contained in:
Andrew Tridgell 2018-07-12 14:12:02 +10:00
parent ccb32cf357
commit 73cfd40e7f
1 changed files with 7 additions and 7 deletions

View File

@ -197,8 +197,6 @@ bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
return false; return false;
} }
bus.dma_handle->lock();
#if defined(STM32F7) #if defined(STM32F7)
if (_use_smbus) { if (_use_smbus) {
bus.i2ccfg.cr1 |= I2C_CR1_SMBHEN; bus.i2ccfg.cr1 |= I2C_CR1_SMBHEN;
@ -221,25 +219,21 @@ bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
*/ */
if (send && send_len) { if (send && send_len) {
if (!_transfer(send, send_len, nullptr, 0)) { if (!_transfer(send, send_len, nullptr, 0)) {
bus.dma_handle->unlock();
return false; return false;
} }
} }
if (recv && recv_len) { if (recv && recv_len) {
if (!_transfer(nullptr, 0, recv, recv_len)) { if (!_transfer(nullptr, 0, recv, recv_len)) {
bus.dma_handle->unlock();
return false; return false;
} }
} }
} else { } else {
// combined transfer // combined transfer
if (!_transfer(send, send_len, recv, recv_len)) { if (!_transfer(send, send_len, recv, recv_len)) {
bus.dma_handle->unlock();
return false; return false;
} }
} }
bus.dma_handle->unlock();
return true; return true;
} }
@ -256,6 +250,10 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
uint32_t timeout_ms = 1+2*(((8*1000000UL/bus.busclock)*MAX(send_len, recv_len))/1000); uint32_t timeout_ms = 1+2*(((8*1000000UL/bus.busclock)*MAX(send_len, recv_len))/1000);
timeout_ms = MAX(timeout_ms, _timeout_ms); timeout_ms = MAX(timeout_ms, _timeout_ms);
// we get the lock inside the retry loop to allow us to give up the DMA channel to an
// SPI device on retries
bus.dma_handle->lock();
// if we are not using DMA then we may need to start the bus here // if we are not using DMA then we may need to start the bus here
bus.dma_allocate(bus.dma_handle); bus.dma_allocate(bus.dma_handle);
@ -267,7 +265,9 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
ret = i2cMasterTransmitTimeout(I2CD[bus.busnum].i2c, _address, send, send_len, ret = i2cMasterTransmitTimeout(I2CD[bus.busnum].i2c, _address, send, send_len,
recv, recv_len, MS2ST(timeout_ms)); recv, recv_len, MS2ST(timeout_ms));
} }
bus.dma_handle->unlock();
bus.i2c_active = false; bus.i2c_active = false;
if (ret != MSG_OK) { if (ret != MSG_OK) {
//restart the bus //restart the bus