HAL_ChibiOS: added checking of lock state in shared_dma

and use lock around check for tx completion in UART handler
This commit is contained in:
Andrew Tridgell 2018-02-06 14:59:10 +11:00
parent dce4c90467
commit 41758348e5
3 changed files with 28 additions and 1 deletions

View File

@ -511,19 +511,22 @@ bool UARTDriver::wait_timeout(uint16_t n, uint32_t timeout_ms)
*/
void UARTDriver::write_pending_bytes_DMA(uint32_t n)
{
chSysLock();
if (!tx_bounce_buf_ready && txdma) {
if (!(txdma->stream->CR & STM32_DMA_CR_EN)) {
if (txdma->stream->NDTR == 0) {
tx_bounce_buf_ready = true;
_last_write_completed_us = AP_HAL::micros();
dma_handle->unlock();
dma_handle->unlock_from_lockzone();
}
}
}
if (!tx_bounce_buf_ready) {
chSysUnlock();
return;
}
chSysUnlock();
/* TX DMA channel preparation.*/
_writebuf.advance(tx_len);

View File

@ -91,22 +91,41 @@ void Shared_DMA::lock(void)
locks[stream_id2].obj = this;
}
}
have_lock = true;
}
// unlock the DMA channels
void Shared_DMA::unlock(void)
{
osalDbgAssert(have_lock, "must have lock");
if (stream_id2 != SHARED_DMA_NONE) {
chBSemSignal(&locks[stream_id2].semaphore);
}
if (stream_id1 != SHARED_DMA_NONE) {
chBSemSignal(&locks[stream_id1].semaphore);
}
have_lock = false;
}
// unlock the DMA channels from a lock zone
void Shared_DMA::unlock_from_lockzone(void)
{
osalDbgAssert(have_lock, "must have lock");
if (stream_id2 != SHARED_DMA_NONE) {
chBSemSignalI(&locks[stream_id2].semaphore);
chSchRescheduleS();
}
if (stream_id1 != SHARED_DMA_NONE) {
chBSemSignalI(&locks[stream_id1].semaphore);
chSchRescheduleS();
}
have_lock = false;
}
// unlock the DMA channels from an IRQ
void Shared_DMA::unlock_from_IRQ(void)
{
osalDbgAssert(have_lock, "must have lock");
chSysLockFromISR();
if (stream_id2 != SHARED_DMA_NONE) {
chBSemSignalI(&locks[stream_id2].semaphore);
@ -114,5 +133,6 @@ void Shared_DMA::unlock_from_IRQ(void)
if (stream_id1 != SHARED_DMA_NONE) {
chBSemSignalI(&locks[stream_id1].semaphore);
}
have_lock = false;
chSysUnlockFromISR();
}

View File

@ -49,6 +49,9 @@ public:
// unlock call from an IRQ
void unlock_from_IRQ(void);
// unlock call from a chSysLock zone
void unlock_from_lockzone(void);
//should be called inside the destructor of Shared DMA participants
void unregister(void);
@ -57,6 +60,7 @@ private:
dma_allocate_fn_t deallocate;
uint8_t stream_id1;
uint8_t stream_id2;
bool have_lock;
static struct dma_lock {
// semaphore to ensure only one peripheral uses a DMA channel at a time