/* * This file is free software: you can redistribute it and/or modify it * under the terms of the GNU General Public License as published by the * Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * This file is distributed in the hope that it will be useful, but * WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. * See the GNU General Public License for more details. * * You should have received a copy of the GNU General Public License along * with this program. If not, see . * * Code by Andrew Tridgell and Siddharth Bharat Purohit */ #include "shared_dma.h" /* code to handle sharing of DMA channels between peripherals */ #if CH_CFG_USE_SEMAPHORES == TRUE using namespace ChibiOS; Shared_DMA::dma_lock Shared_DMA::locks[SHARED_DMA_MAX_STREAM_ID]; void Shared_DMA::init(void) { for (uint8_t i=0; icontention = true; } chSysEnable(); contention = true; return false; } } if (stream_id2 != SHARED_DMA_NONE) { if (chBSemWaitTimeout(&locks[stream_id2].semaphore, 1) != MSG_OK) { 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; } } lock_core(); return 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"); if (stream_id2 != SHARED_DMA_NONE) { chBSemSignalI(&locks[stream_id2].semaphore); } if (stream_id1 != SHARED_DMA_NONE) { chBSemSignalI(&locks[stream_id1].semaphore); } have_lock = false; } /* lock all channels - used on reboot to ensure no sensor DMA is in progress */ void Shared_DMA::lock_all(void) { for (uint8_t i=0; i