forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathshared_dma.cpp
189 lines (173 loc) · 5.51 KB
/
shared_dma.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
/*
* 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/>.
*
* 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; 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()
{
if (locks[stream_id1].obj == this) {
locks[stream_id1].deallocate(this);
locks[stream_id1].obj = nullptr;
}
if (locks[stream_id2].obj == this) {
locks[stream_id2].deallocate(this);
locks[stream_id2].obj = nullptr;
}
}
// lock the DMA channels
void Shared_DMA::lock_core(void)
{
// see if another driver has DMA allocated. If so, call their
// deallocation function
if (stream_id1 != SHARED_DMA_NONE &&
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_NONE &&
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_NONE && locks[stream_id1].obj == nullptr) ||
(stream_id2 != SHARED_DMA_NONE && locks[stream_id2].obj == nullptr)) {
// allocate the DMA channels and put our deallocation function in place
allocate(this);
if (stream_id1 != SHARED_DMA_NONE) {
locks[stream_id1].deallocate = deallocate;
locks[stream_id1].obj = this;
}
if (stream_id2 != SHARED_DMA_NONE) {
locks[stream_id2].deallocate = deallocate;
locks[stream_id2].obj = this;
}
}
have_lock = true;
}
// lock the DMA channels, blocking method
void Shared_DMA::lock(void)
{
if (stream_id1 != SHARED_DMA_NONE) {
chBSemWait(&locks[stream_id1].semaphore);
}
if (stream_id2 != SHARED_DMA_NONE) {
chBSemWait(&locks[stream_id2].semaphore);
}
lock_core();
}
// lock the DMA channels, non-blocking
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;
}
}
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<SHARED_DMA_MAX_STREAM_ID; i++) {
chBSemWait(&locks[i].semaphore);
}
}
#endif // CH_CFG_USE_SEMAPHORES