APM:Libraries
SoftSigReader.cpp
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 
18 #include "SoftSigReader.h"
20 
21 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
22 
23 using namespace ChibiOS;
24 extern const AP_HAL::HAL& hal;
25 
26 #if HAL_USE_ICU == TRUE
27 
28 bool SoftSigReader::attach_capture_timer(ICUDriver* icu_drv, icuchannel_t chan, uint8_t dma_stream, uint32_t dma_channel)
29 {
30  if (chan > ICU_CHANNEL_2) {
31  return false;
32  }
33  signal = (uint32_t*)hal.util->malloc_type(sizeof(uint32_t)*_bounce_buf_size, AP_HAL::Util::MEM_DMA_SAFE);
34  if (signal == nullptr) {
35  return false;
36  }
37  _icu_drv = icu_drv;
38  //Setup Burst transfer of period and width measurement
39  dma = STM32_DMA_STREAM(dma_stream);
40  chSysLock();
41  bool dma_allocated = dmaStreamAllocate(dma,
42  12, //IRQ Priority
43  (stm32_dmaisr_t)_irq_handler,
44  (void *)this);
45  osalDbgAssert(!dma_allocated, "stream already allocated");
46  chSysUnlock();
47  //setup address for full word transfer from Timer
48  dmaStreamSetPeripheral(dma, &icu_drv->tim->DMAR);
49 
50  uint32_t dmamode = STM32_DMA_CR_DMEIE | STM32_DMA_CR_TEIE;
51  dmamode |= STM32_DMA_CR_CHSEL(dma_channel);
52  dmamode |= STM32_DMA_CR_PL(0);
53  dmaStreamSetMemory0(dma, signal);
54  dmaStreamSetTransactionSize(dma, _bounce_buf_size);
55  dmaStreamSetMode(dma, dmamode | STM32_DMA_CR_DIR_P2M | STM32_DMA_CR_PSIZE_WORD |
56  STM32_DMA_CR_MSIZE_WORD | STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
57 
58  icucfg.frequency = INPUT_CAPTURE_FREQUENCY;
59  icucfg.channel = chan;
60  icucfg.width_cb = NULL;
61  icucfg.period_cb = NULL;
62  icucfg.overflow_cb = NULL;
63 
64  if (chan == ICU_CHANNEL_1) {
65  icucfg.dier = STM32_TIM_DIER_CC1DE;
66  icucfg.mode = ICU_INPUT_ACTIVE_HIGH;
67  need_swap = true;
68  } else {
69  icucfg.mode = ICU_INPUT_ACTIVE_LOW;
70  icucfg.dier = STM32_TIM_DIER_CC2DE;
71  }
72 #ifdef HAL_RCIN_IS_INVERTED
73  icucfg.mode = (icucfg.mode==ICU_INPUT_ACTIVE_LOW)?ICU_INPUT_ACTIVE_HIGH:ICU_INPUT_ACTIVE_LOW;
74 #endif
75  icuStart(_icu_drv, &icucfg);
76  //Extended Timer Setup to enable DMA transfer
77  //selected offset for TIM_CCR1 and for two words
78  _icu_drv->tim->DCR = STM32_TIM_DCR_DBA(0x0D) | STM32_TIM_DCR_DBL(1);
79  //Enable DMA
80  dmaStreamEnable(dma);
81 
82  //sets input filtering to 4 timer clock
84 
85  //Start Timer
86  icuStartCapture(_icu_drv);
87  return true;
88 }
89 
90 void SoftSigReader::_irq_handler(void* self, uint32_t flags)
91 {
92  SoftSigReader* sig_reader = (SoftSigReader*)self;
93  sig_reader->sigbuf.push(sig_reader->signal, sig_reader->_bounce_buf_size);
94  //restart the DMA transfers
95  dmaStreamSetMemory0(sig_reader->dma, sig_reader->signal);
96  dmaStreamSetTransactionSize(sig_reader->dma, sig_reader->_bounce_buf_size);
97  dmaStreamEnable(sig_reader->dma);
98 }
99 
100 
101 bool SoftSigReader::read(uint32_t &widths0, uint32_t &widths1)
102 {
103  if (sigbuf.pop(widths0) && sigbuf.pop(widths1)) {
104  //the data is period and width, order depending on which
105  //channel is used and width type (0 or 1) depends on mode
106  //being set to HIGH or LOW. We need to swap the words when on
107  //channel 1
108  if (need_swap) {
109  uint32_t tmp = widths1;
110  widths1 = widths0;
111  widths0 = tmp;
112  }
113  widths1 -= widths0;
114  } else {
115  return false;
116  }
117  return true;
118 }
119 
120 
121 bool SoftSigReader::set_bounce_buf_size(uint16_t buf_size)
122 {
123  if (buf_size > _bounce_buf_size) {
124  if (signal) {
126  }
127  signal = (uint32_t*)hal.util->malloc_type(sizeof(uint32_t)*buf_size, AP_HAL::Util::MEM_DMA_SAFE);
128  if (signal == nullptr) {
129  return false;
130  }
131  _bounce_buf_size = buf_size;
132  } else {
133  _bounce_buf_size = buf_size;
134  }
135  return true;
136 }
137 
138 #endif // HAL_USE_ICU
139 
140 #endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
void stm32_timer_set_input_filter(stm32_tim_t *tim, uint8_t channel, uint8_t filter_mode)
Definition: stm32_util.c:18
bool attach_capture_timer(ICUDriver *icu_drv, icuchannel_t chan, uint8_t dma_stream, uint32_t dma_channel)
ObjectBuffer< uint32_t > sigbuf
Definition: SoftSigReader.h:39
AP_HAL::Util * util
Definition: HAL.h:115
virtual void free_type(void *ptr, size_t size, Memory_Type mem_type)
Definition: Util.h:116
bool pop(void)
Definition: RingBuffer.h:147
dma_channel
DMA channels.
Definition: dma.h:68
bool read(uint32_t &widths0, uint32_t &widths1)
#define NULL
Definition: hal_types.h:59
enum Dma_stream dma_stream
virtual void * malloc_type(size_t size, Memory_Type mem_type)
Definition: Util.h:115
bool push(const T &object)
Definition: RingBuffer.h:129
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
#define INPUT_CAPTURE_FREQUENCY
Definition: SoftSigReader.h:25
static void _irq_handler(void *self, uint32_t flags)
bool set_bounce_buf_size(uint16_t buf_size)
const stm32_dma_stream_t * dma
Definition: SoftSigReader.h:42
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14