2018-01-05 02:19:51 -04:00
|
|
|
/*
|
|
|
|
* 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 <http://www.gnu.org/licenses/>.
|
2019-10-20 10:31:12 -03:00
|
|
|
*
|
2018-01-05 02:19:51 -04:00
|
|
|
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
|
|
|
*/
|
|
|
|
#include "shared_dma.h"
|
|
|
|
|
|
|
|
/*
|
|
|
|
code to handle sharing of DMA channels between peripherals
|
|
|
|
*/
|
|
|
|
|
2019-05-26 22:45:30 -03:00
|
|
|
#if CH_CFG_USE_SEMAPHORES == TRUE
|
2018-03-28 23:07:50 -03:00
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
using namespace ChibiOS;
|
|
|
|
|
2019-02-09 17:51:13 -04:00
|
|
|
Shared_DMA::dma_lock Shared_DMA::locks[SHARED_DMA_MAX_STREAM_ID+1];
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
void Shared_DMA::init(void)
|
|
|
|
{
|
|
|
|
for (uint8_t i=0; i<SHARED_DMA_MAX_STREAM_ID; i++) {
|
|
|
|
chBSemObjectInit(&locks[i].semaphore, false);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// constructor
|
|
|
|
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;
|
|
|
|
}
|
|
|
|
|
|
|
|
//remove any assigned deallocator or allocator
|
|
|
|
void Shared_DMA::unregister()
|
|
|
|
{
|
2019-02-10 03:04:57 -04:00
|
|
|
if (stream_id1 < SHARED_DMA_MAX_STREAM_ID &&
|
|
|
|
locks[stream_id1].obj == this) {
|
2018-03-14 03:06:30 -03:00
|
|
|
locks[stream_id1].deallocate(this);
|
2018-01-05 02:19:51 -04:00
|
|
|
locks[stream_id1].obj = nullptr;
|
|
|
|
}
|
|
|
|
|
2019-02-10 03:04:57 -04:00
|
|
|
if (stream_id2 < SHARED_DMA_MAX_STREAM_ID &&
|
|
|
|
locks[stream_id2].obj == this) {
|
2018-03-14 03:06:30 -03:00
|
|
|
locks[stream_id2].deallocate(this);
|
2018-01-05 02:19:51 -04:00
|
|
|
locks[stream_id2].obj = nullptr;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2019-02-09 17:51:13 -04:00
|
|
|
// lock one stream
|
|
|
|
void Shared_DMA::lock_stream(uint8_t stream_id)
|
|
|
|
{
|
2019-02-10 03:04:57 -04:00
|
|
|
if (stream_id < SHARED_DMA_MAX_STREAM_ID) {
|
2019-02-09 17:51:13 -04:00
|
|
|
chBSemWait(&locks[stream_id].semaphore);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// unlock one stream
|
|
|
|
void Shared_DMA::unlock_stream(uint8_t stream_id)
|
|
|
|
{
|
2019-02-10 03:04:57 -04:00
|
|
|
if (stream_id < SHARED_DMA_MAX_STREAM_ID) {
|
2019-02-09 17:51:13 -04:00
|
|
|
chBSemSignal(&locks[stream_id].semaphore);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// unlock one stream from an IRQ handler
|
|
|
|
void Shared_DMA::unlock_stream_from_IRQ(uint8_t stream_id)
|
|
|
|
{
|
2019-02-10 03:04:57 -04:00
|
|
|
if (stream_id < SHARED_DMA_MAX_STREAM_ID) {
|
2019-02-09 17:51:13 -04:00
|
|
|
chBSemSignalI(&locks[stream_id].semaphore);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// lock one stream, non-blocking
|
|
|
|
bool Shared_DMA::lock_stream_nonblocking(uint8_t stream_id)
|
|
|
|
{
|
2019-02-10 03:04:57 -04:00
|
|
|
if (stream_id < SHARED_DMA_MAX_STREAM_ID) {
|
2019-02-09 17:51:13 -04:00
|
|
|
return chBSemWaitTimeout(&locks[stream_id].semaphore, 1) == MSG_OK;
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
// lock the DMA channels
|
2018-03-02 06:34:57 -04:00
|
|
|
void Shared_DMA::lock_core(void)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
// see if another driver has DMA allocated. If so, call their
|
|
|
|
// deallocation function
|
2019-02-10 03:04:57 -04:00
|
|
|
if (stream_id1 < SHARED_DMA_MAX_STREAM_ID &&
|
2018-01-05 02:19:51 -04:00
|
|
|
locks[stream_id1].obj && locks[stream_id1].obj != this) {
|
2018-03-14 03:06:30 -03:00
|
|
|
locks[stream_id1].deallocate(locks[stream_id1].obj);
|
2018-01-05 02:19:51 -04:00
|
|
|
locks[stream_id1].obj = nullptr;
|
|
|
|
}
|
2019-02-10 03:04:57 -04:00
|
|
|
if (stream_id2 < SHARED_DMA_MAX_STREAM_ID &&
|
2018-01-05 02:19:51 -04:00
|
|
|
locks[stream_id2].obj && locks[stream_id2].obj != this) {
|
2018-03-14 03:06:30 -03:00
|
|
|
locks[stream_id2].deallocate(locks[stream_id2].obj);
|
2018-01-05 02:19:51 -04:00
|
|
|
locks[stream_id2].obj = nullptr;
|
|
|
|
}
|
2019-02-10 03:04:57 -04:00
|
|
|
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)) {
|
2018-01-05 02:19:51 -04:00
|
|
|
// allocate the DMA channels and put our deallocation function in place
|
2018-03-14 03:06:30 -03:00
|
|
|
allocate(this);
|
2019-02-10 17:01:12 -04:00
|
|
|
if (stream_id1 < SHARED_DMA_MAX_STREAM_ID) {
|
2018-01-05 02:19:51 -04:00
|
|
|
locks[stream_id1].deallocate = deallocate;
|
|
|
|
locks[stream_id1].obj = this;
|
|
|
|
}
|
2019-02-10 17:01:12 -04:00
|
|
|
if (stream_id2 < SHARED_DMA_MAX_STREAM_ID) {
|
2018-01-05 02:19:51 -04:00
|
|
|
locks[stream_id2].deallocate = deallocate;
|
|
|
|
locks[stream_id2].obj = this;
|
|
|
|
}
|
2019-02-13 03:44:45 -04:00
|
|
|
}
|
|
|
|
#ifdef STM32_DMA_STREAM_ID_ANY
|
|
|
|
else if (stream_id1 == STM32_DMA_STREAM_ID_ANY ||
|
|
|
|
stream_id2 == STM32_DMA_STREAM_ID_ANY) {
|
2019-02-10 03:04:57 -04:00
|
|
|
// call allocator without needing locking
|
|
|
|
allocate(this);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2019-02-13 03:44:45 -04:00
|
|
|
#endif
|
2018-02-05 23:59:10 -04:00
|
|
|
have_lock = true;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2018-03-02 06:34:57 -04:00
|
|
|
// lock the DMA channels, blocking method
|
|
|
|
void Shared_DMA::lock(void)
|
|
|
|
{
|
2019-02-10 17:01:12 -04:00
|
|
|
lock_stream(stream_id1);
|
|
|
|
lock_stream(stream_id2);
|
2018-03-02 06:34:57 -04:00
|
|
|
lock_core();
|
|
|
|
}
|
|
|
|
|
|
|
|
// lock the DMA channels, non-blocking
|
|
|
|
bool Shared_DMA::lock_nonblock(void)
|
|
|
|
{
|
2019-02-10 17:01:12 -04:00
|
|
|
if (!lock_stream_nonblocking(stream_id1)) {
|
|
|
|
chSysDisable();
|
|
|
|
if (locks[stream_id1].obj != nullptr && locks[stream_id1].obj != this) {
|
|
|
|
locks[stream_id1].obj->contention = true;
|
2018-03-02 06:34:57 -04:00
|
|
|
}
|
2019-02-10 17:01:12 -04:00
|
|
|
chSysEnable();
|
|
|
|
contention = true;
|
|
|
|
return false;
|
2018-03-02 06:34:57 -04:00
|
|
|
}
|
2019-02-10 17:01:12 -04:00
|
|
|
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;
|
2018-03-02 06:34:57 -04:00
|
|
|
}
|
2019-02-10 17:01:12 -04:00
|
|
|
chSysEnable();
|
|
|
|
contention = true;
|
|
|
|
return false;
|
2018-03-02 06:34:57 -04:00
|
|
|
}
|
|
|
|
lock_core();
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
// unlock the DMA channels
|
|
|
|
void Shared_DMA::unlock(void)
|
|
|
|
{
|
2018-02-05 23:59:10 -04:00
|
|
|
osalDbgAssert(have_lock, "must have lock");
|
2019-02-10 17:01:12 -04:00
|
|
|
unlock_stream(stream_id2);
|
|
|
|
unlock_stream(stream_id1);
|
2018-02-05 23:59:10 -04:00
|
|
|
have_lock = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// unlock the DMA channels from a lock zone
|
|
|
|
void Shared_DMA::unlock_from_lockzone(void)
|
|
|
|
{
|
|
|
|
osalDbgAssert(have_lock, "must have lock");
|
2019-02-10 17:01:12 -04:00
|
|
|
if (stream_id2 < SHARED_DMA_MAX_STREAM_ID) {
|
2019-02-09 17:51:13 -04:00
|
|
|
unlock_stream_from_IRQ(stream_id2);
|
2018-02-05 23:59:10 -04:00
|
|
|
chSchRescheduleS();
|
|
|
|
}
|
2019-02-10 17:01:12 -04:00
|
|
|
if (stream_id1 < SHARED_DMA_MAX_STREAM_ID) {
|
2019-02-09 17:51:13 -04:00
|
|
|
unlock_stream_from_IRQ(stream_id1);
|
2018-02-05 23:59:10 -04:00
|
|
|
chSchRescheduleS();
|
|
|
|
}
|
|
|
|
have_lock = false;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// unlock the DMA channels from an IRQ
|
|
|
|
void Shared_DMA::unlock_from_IRQ(void)
|
|
|
|
{
|
2018-02-05 23:59:10 -04:00
|
|
|
osalDbgAssert(have_lock, "must have lock");
|
2019-02-10 17:01:12 -04:00
|
|
|
unlock_stream_from_IRQ(stream_id2);
|
|
|
|
unlock_stream_from_IRQ(stream_id1);
|
2018-02-05 23:59:10 -04:00
|
|
|
have_lock = false;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2018-01-28 21:43:55 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
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<SHARED_DMA_MAX_STREAM_ID; i++) {
|
2019-02-09 17:51:13 -04:00
|
|
|
lock_stream(i);
|
2018-01-28 21:43:55 -04:00
|
|
|
}
|
|
|
|
}
|
2018-03-28 23:07:50 -03:00
|
|
|
|
2019-05-26 22:45:30 -03:00
|
|
|
#endif // CH_CFG_USE_SEMAPHORES
|