20 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS 25 #if HAL_USE_EICU == TRUE 27 #define eicu_lld_invert_polarity(eicup, channel) \ 28 (eicup)->tim->CCER ^= ((uint16_t)(STM32_TIM_CCER_CC1P << ((channel) * 4))) 44 for (
int i=0; i< EICU_CHANNEL_ENUM_END; i++) {
48 #ifdef HAL_RCIN_IS_INVERTED 62 uint16_t
value = eicup->tim->CCR[channel];
73 widths1 = uint16_t(p1 - p0);
81 #endif // HAL_USE_EICU 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)
#define eicu_lld_invert_polarity(eicup, channel)
void init(EICUDriver *icu_drv, eicuchannel_t chan)
ObjectBuffer< uint16_t > sigbuf
uint32_t available(void) const
EICUChannelConfig channel_config
bool read(uint32_t &widths0, uint32_t &widths1)
bool push(const T &object)
AP_HAL::AnalogSource * chan
#define INPUT_CAPTURE_FREQUENCY
static SoftSigReaderInt * _instance