HAL_ChibiOS: enable checking for DMA contention

This commit is contained in:
Andrew Tridgell 2018-03-14 19:50:32 +11:00
parent 0fb4e4720d
commit a86e85c6b2
2 changed files with 20 additions and 0 deletions

View File

@ -105,6 +105,12 @@ bool Shared_DMA::lock_nonblock(void)
{
if (stream_id1 != SHARED_DMA_NONE) {
if (chBSemWaitTimeout(&locks[stream_id1].semaphore, 1) != MSG_OK) {
chSysDisable();
if (locks[stream_id1].obj != nullptr && locks[stream_id1].obj != this) {
locks[stream_id1].obj->contention = true;
}
chSysEnable();
contention = true;
return false;
}
}
@ -113,6 +119,12 @@ bool Shared_DMA::lock_nonblock(void)
if (stream_id1 != SHARED_DMA_NONE) {
chBSemSignal(&locks[stream_id1].semaphore);
}
chSysDisable();
if (locks[stream_id2].obj != nullptr && locks[stream_id2].obj != this) {
locks[stream_id2].obj->contention = true;
}
chSysEnable();
contention = true;
return false;
}
}

View File

@ -58,6 +58,10 @@ public:
//should be called inside the destructor of Shared DMA participants
void unregister(void);
// return true if this DMA channel is being actively contended for
// by multiple drivers
bool has_contention(void) const { return contention; }
// lock all shared DMA channels. Used on reboot
static void lock_all(void);
@ -68,6 +72,10 @@ private:
uint8_t stream_id2;
bool have_lock;
// we set the contention flag if two drivers are fighting over a DMA channel.
// the UART driver uses this to change its max transmit size to reduce latency
bool contention;
// core of lock call, after semaphores gained
void lock_core(void);