34 #pragma GCC optimize ("O2") 45 #define PPM_CHANNELS 2 // independent input pins 63 TIM_TypeDef * tim = (TIM_TypeDef *)v;
95 time = ((0xFFFF - input->
last_val) + val)+1;
99 if(time>0x7fff) time=0x7fff;
104 .state = input->
state 112 if (input->
state == 0) {
142 if(last_tim != timer->
id) {
149 last_tim = timer->
id;
static Pulse pb_remove(volatile pulse_buffer *pb)
Remove and return the first item from a ring buffer.
static void timer_cc_enable(const timer_dev *dev, timer_Channel channel)
Enable a timer channel's capture/compare signal.
static void timer_cc_set_pol(const timer_dev *dev, timer_Channel channel, timer_cc_polarity pol)
Set a timer channel's capture/compare output polarity.
static int pb_is_empty(volatile pulse_buffer *pb)
Returns true if and only if the ring buffer is empty.
static uint16_t pb_full_count(volatile pulse_buffer *pb)
Return the number of elements stored in the ring buffer.
Simple circular buffer for PEM input.
volatile pulse_buffer pulses
timer_Channel timer_channel
void pwmInit(bool ppmsum)
static uint64_t systick_uptime(void)
Returns the system uptime, in milliseconds.
static void pb_init(volatile pulse_buffer *pb, uint16_t size, Pulse *buf)
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
static INLINE uint16_t timer_get_capture(const timer_dev *dev, timer_Channel channel)
const struct TIM_Channel PWM_Channels[]
void timer_enable_NVICirq(const timer_dev *dev, uint8_t interrupt, uint8_t priority)
static INLINE void timer_pause(const timer_dev *dev)
Stop a timer's counter from changing.
Pulse pulse_mem[PULSES_QUEUE_SIZE]
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
static INLINE void timer_resume(const timer_dev *dev)
Start a timer's counter.
#define PULSES_QUEUE_SIZE
static AP_HAL::OwnPtr< AP_HAL::Device > dev
static int pb_is_full(volatile pulse_buffer *pb)
Returns true if and only if the ring buffer is full.
const timer_dev *const timer_device
struct PPM_State PPM_Inputs[]
bool getPPM_Pulse(Pulse *p, uint8_t ch)
void timer_attach_all_interrupts(const timer_dev *dev, Handler handler)
Board-specific pin information.
static void timer_enable_irq(const timer_dev *dev, timer_interrupt_id interrupt)
Enable a timer interrupt.
static void timer_ic_set_mode(const timer_dev *dev, timer_Channel _channel, uint8_t mode, uint16_t filter)
Configure a channel's input capture mode.
struct PPM_State PPM_Inputs [PPM_CHANNELS] IN_CCM
static uint16_t num_ppm_channels
uint32_t configTimeBase(const timer_dev *dev, uint16_t period, uint16_t khz)
static void gpio_set_af_mode(const gpio_dev *const dev, uint8_t pin, uint8_t mode)
static void pb_insert(volatile pulse_buffer *pb, Pulse element)
static void pwmInitializeInput(uint8_t ppmsum)
void revo_call_handler(Handler h, uint32_t arg)
static void pwmIRQHandler(uint32_t v)
uint16_t getPPM_count(uint8_t ch)
Stores STM32-specific information related to a given Maple pin.
const gpio_dev *const gpio_device