APM:Libraries
shared_dma.h
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  *
15  * Code by Andrew Tridgell and Siddharth Bharat Purohit
16  */
17 #pragma once
18 
19 #include "AP_HAL_ChibiOS.h"
20 
21 #define SHARED_DMA_MAX_STREAM_ID (8*2)
22 
23 // DMA stream ID for stream_id2 when only one is needed
24 #define SHARED_DMA_NONE 255
25 
27 {
28 public:
29  FUNCTOR_TYPEDEF(dma_allocate_fn_t, void, Shared_DMA *);
30  FUNCTOR_TYPEDEF(dma_deallocate_fn_t, void, Shared_DMA *);
31 
32  // the use of two stream IDs is for support of peripherals that
33  // need both a RX and TX DMA channel
34  Shared_DMA(uint8_t stream_id1, uint8_t stream_id2,
35  dma_allocate_fn_t allocate,
36  dma_allocate_fn_t deallocate);
37 
38  // initialise the stream locks
39  static void init(void);
40 
41  // blocking lock call
42  void lock(void);
43 
44  // non-blocking lock call
45  bool lock_nonblock(void);
46 
47  // unlock call. The DMA channel will not be immediately
48  // deallocated. Instead it will be deallocated if another driver
49  // needs it
50  void unlock(void);
51 
52  // unlock call from an IRQ
53  void unlock_from_IRQ(void);
54 
55  // unlock call from a chSysLock zone
56  void unlock_from_lockzone(void);
57 
58  //should be called inside the destructor of Shared DMA participants
59  void unregister(void);
60 
61  // return true if this DMA channel is being actively contended for
62  // by multiple drivers
63  bool has_contention(void) const { return contention; }
64 
65  // lock all shared DMA channels. Used on reboot
66  static void lock_all(void);
67 
68 private:
69  dma_allocate_fn_t allocate;
70  dma_allocate_fn_t deallocate;
71  uint8_t stream_id1;
72  uint8_t stream_id2;
73  bool have_lock;
74 
75  // we set the contention flag if two drivers are fighting over a DMA channel.
76  // the UART driver uses this to change its max transmit size to reduce latency
77  bool contention;
78 
79  // core of lock call, after semaphores gained
80  void lock_core(void);
81 
82  static struct dma_lock {
83  // semaphore to ensure only one peripheral uses a DMA channel at a time
84  binary_semaphore_t semaphore;
85 
86  // a de-allocation function that is called to release an existing user
87  dma_deallocate_fn_t deallocate;
88 
89  // point to object that holds the allocation, if allocated
92 };
FUNCTOR_TYPEDEF(dma_allocate_fn_t, void, Shared_DMA *)
dma_allocate_fn_t deallocate
Definition: shared_dma.h:70
binary_semaphore_t semaphore
Definition: shared_dma.h:84
Shared_DMA(uint8_t stream_id1, uint8_t stream_id2, dma_allocate_fn_t allocate, dma_allocate_fn_t deallocate)
Definition: shared_dma.cpp:35
void unlock_from_lockzone(void)
Definition: shared_dma.cpp:149
void unregister(void)
Definition: shared_dma.cpp:47
static struct ChibiOS::Shared_DMA::dma_lock locks[SHARED_DMA_MAX_STREAM_ID]
Definition: shared_dma.cpp:25
dma_deallocate_fn_t deallocate
Definition: shared_dma.h:87
bool lock_nonblock(void)
Definition: shared_dma.cpp:104
bool has_contention(void) const
Definition: shared_dma.h:63
void unlock_from_IRQ(void)
Definition: shared_dma.cpp:164
static void lock_all(void)
Definition: shared_dma.cpp:182
static void init(void)
Definition: shared_dma.cpp:27
dma_allocate_fn_t allocate
Definition: shared_dma.h:69
void lock_core(void)
Definition: shared_dma.cpp:61
#define SHARED_DMA_MAX_STREAM_ID
Definition: shared_dma.h:21