123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214 |
- #include "shared_dma.h"
- #if CH_CFG_USE_SEMAPHORES == TRUE
- using namespace ChibiOS;
- Shared_DMA::dma_lock Shared_DMA::locks[SHARED_DMA_MAX_STREAM_ID+1];
- void Shared_DMA::init(void)
- {
- for (uint8_t i=0; i<SHARED_DMA_MAX_STREAM_ID; i++) {
- chBSemObjectInit(&locks[i].semaphore, false);
- }
- }
- Shared_DMA::Shared_DMA(uint8_t _stream_id1,
- uint8_t _stream_id2,
- dma_allocate_fn_t _allocate,
- dma_deallocate_fn_t _deallocate)
- {
- stream_id1 = _stream_id1;
- stream_id2 = _stream_id2;
- allocate = _allocate;
- deallocate = _deallocate;
- }
- void Shared_DMA::unregister()
- {
- if (stream_id1 < SHARED_DMA_MAX_STREAM_ID &&
- locks[stream_id1].obj == this) {
- locks[stream_id1].deallocate(this);
- locks[stream_id1].obj = nullptr;
- }
- if (stream_id2 < SHARED_DMA_MAX_STREAM_ID &&
- locks[stream_id2].obj == this) {
- locks[stream_id2].deallocate(this);
- locks[stream_id2].obj = nullptr;
- }
- }
- void Shared_DMA::lock_stream(uint8_t stream_id)
- {
- if (stream_id < SHARED_DMA_MAX_STREAM_ID) {
- chBSemWait(&locks[stream_id].semaphore);
- }
- }
- void Shared_DMA::unlock_stream(uint8_t stream_id)
- {
- if (stream_id < SHARED_DMA_MAX_STREAM_ID) {
- chBSemSignal(&locks[stream_id].semaphore);
- }
- }
- void Shared_DMA::unlock_stream_from_IRQ(uint8_t stream_id)
- {
- if (stream_id < SHARED_DMA_MAX_STREAM_ID) {
- chBSemSignalI(&locks[stream_id].semaphore);
- }
- }
- bool Shared_DMA::lock_stream_nonblocking(uint8_t stream_id)
- {
- if (stream_id < SHARED_DMA_MAX_STREAM_ID) {
- return chBSemWaitTimeout(&locks[stream_id].semaphore, 1) == MSG_OK;
- }
- return true;
- }
- void Shared_DMA::lock_core(void)
- {
-
-
- if (stream_id1 < SHARED_DMA_MAX_STREAM_ID &&
- locks[stream_id1].obj && locks[stream_id1].obj != this) {
- locks[stream_id1].deallocate(locks[stream_id1].obj);
- locks[stream_id1].obj = nullptr;
- }
- if (stream_id2 < SHARED_DMA_MAX_STREAM_ID &&
- locks[stream_id2].obj && locks[stream_id2].obj != this) {
- locks[stream_id2].deallocate(locks[stream_id2].obj);
- locks[stream_id2].obj = nullptr;
- }
- if ((stream_id1 < SHARED_DMA_MAX_STREAM_ID && locks[stream_id1].obj == nullptr) ||
- (stream_id2 < SHARED_DMA_MAX_STREAM_ID && locks[stream_id2].obj == nullptr)) {
-
- allocate(this);
- if (stream_id1 < SHARED_DMA_MAX_STREAM_ID) {
- locks[stream_id1].deallocate = deallocate;
- locks[stream_id1].obj = this;
- }
- if (stream_id2 < SHARED_DMA_MAX_STREAM_ID) {
- locks[stream_id2].deallocate = deallocate;
- locks[stream_id2].obj = this;
- }
- }
- #ifdef STM32_DMA_STREAM_ID_ANY
- else if (stream_id1 == STM32_DMA_STREAM_ID_ANY ||
- stream_id2 == STM32_DMA_STREAM_ID_ANY) {
-
- allocate(this);
- }
- #endif
- have_lock = true;
- }
- void Shared_DMA::lock(void)
- {
- lock_stream(stream_id1);
- lock_stream(stream_id2);
- lock_core();
- }
- bool Shared_DMA::lock_nonblock(void)
- {
- if (!lock_stream_nonblocking(stream_id1)) {
- chSysDisable();
- if (locks[stream_id1].obj != nullptr && locks[stream_id1].obj != this) {
- locks[stream_id1].obj->contention = true;
- }
- chSysEnable();
- contention = true;
- return false;
- }
- if (!lock_stream_nonblocking(stream_id2)) {
- unlock_stream(stream_id1);
- chSysDisable();
- if (locks[stream_id2].obj != nullptr && locks[stream_id2].obj != this) {
- locks[stream_id2].obj->contention = true;
- }
- chSysEnable();
- contention = true;
- return false;
- }
- lock_core();
- return true;
- }
- void Shared_DMA::unlock(void)
- {
- osalDbgAssert(have_lock, "must have lock");
- unlock_stream(stream_id2);
- unlock_stream(stream_id1);
- have_lock = false;
- }
- void Shared_DMA::unlock_from_lockzone(void)
- {
- osalDbgAssert(have_lock, "must have lock");
- if (stream_id2 < SHARED_DMA_MAX_STREAM_ID) {
- unlock_stream_from_IRQ(stream_id2);
- chSchRescheduleS();
- }
- if (stream_id1 < SHARED_DMA_MAX_STREAM_ID) {
- unlock_stream_from_IRQ(stream_id1);
- chSchRescheduleS();
- }
- have_lock = false;
- }
- void Shared_DMA::unlock_from_IRQ(void)
- {
- osalDbgAssert(have_lock, "must have lock");
- unlock_stream_from_IRQ(stream_id2);
- unlock_stream_from_IRQ(stream_id1);
- have_lock = false;
- }
- void Shared_DMA::lock_all(void)
- {
- for (uint8_t i=0; i<SHARED_DMA_MAX_STREAM_ID; i++) {
- lock_stream(i);
- }
- }
- #endif
|