APM:Libraries
SoftSigReaderInt.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  */
16 
17 #include "SoftSigReaderInt.h"
19 
20 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
21 
22 using namespace ChibiOS;
23 extern const AP_HAL::HAL& hal;
24 
25 #if HAL_USE_EICU == TRUE
26 
27 #define eicu_lld_invert_polarity(eicup, channel) \
28  (eicup)->tim->CCER ^= ((uint16_t)(STM32_TIM_CCER_CC1P << ((channel) * 4)))
29 
30 // singleton instance
32 
34 {
35  _instance = this;
36 }
37 
38 void SoftSigReaderInt::init(EICUDriver* icu_drv, eicuchannel_t chan)
39 {
40  last_value = 0;
41  _icu_drv = icu_drv;
42  icucfg.dier = 0;
43  icucfg.frequency = INPUT_CAPTURE_FREQUENCY;
44  for (int i=0; i< EICU_CHANNEL_ENUM_END; i++) {
45  icucfg.iccfgp[i]=nullptr;
46  }
47  icucfg.iccfgp[chan] = &channel_config;
48 #ifdef HAL_RCIN_IS_INVERTED
49  channel_config.alvl = EICU_INPUT_ACTIVE_HIGH;
50 #else
51  channel_config.alvl = EICU_INPUT_ACTIVE_LOW;
52 #endif
53  channel_config.capture_cb = _irq_handler;
54  eicuStart(_icu_drv, &icucfg);
55  //sets input filtering to 4 timer clock
57  eicuEnable(_icu_drv);
58 }
59 
60 void SoftSigReaderInt::_irq_handler(EICUDriver *eicup, eicuchannel_t channel)
61 {
62  uint16_t value = eicup->tim->CCR[channel];
63  _instance->sigbuf.push(value);
64  eicu_lld_invert_polarity(eicup, channel);
65 }
66 
67 bool SoftSigReaderInt::read(uint32_t &widths0, uint32_t &widths1)
68 {
69  uint16_t p0, p1;
70  if (sigbuf.available() >= 2) {
71  if (sigbuf.pop(p0)&&sigbuf.pop(p1)) {
72  widths0 = uint16_t(p0 - last_value);
73  widths1 = uint16_t(p1 - p0);
74  last_value = p1;
75  return true;
76  }
77  }
78  return false;
79 }
80 
81 #endif // HAL_USE_EICU
82 
83 #endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
static void _irq_handler(EICUDriver *eicup, eicuchannel_t channel)
void stm32_timer_set_input_filter(stm32_tim_t *tim, uint8_t channel, uint8_t filter_mode)
Definition: stm32_util.c:18
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define eicu_lld_invert_polarity(eicup, channel)
bool pop(void)
Definition: RingBuffer.h:147
void init(EICUDriver *icu_drv, eicuchannel_t chan)
ObjectBuffer< uint16_t > sigbuf
uint32_t available(void) const
Definition: RingBuffer.h:114
EICUChannelConfig channel_config
bool read(uint32_t &widths0, uint32_t &widths1)
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
float value
static SoftSigReaderInt * _instance