14 #define PWM_IGNORE_THIS_CHANNEL 1 16 #define F4Light_MAX_OUTPUT_CHANNELS 12 // motors and servos 45 void set_freq(uint32_t chmask, uint16_t freq_hz)
override;
46 uint16_t
get_freq(uint8_t ch)
override;
49 void write(uint8_t ch, uint16_t period_us)
override;
50 void write(uint8_t ch, uint16_t* period_us, uint8_t len);
51 uint16_t
read(uint8_t ch)
override;
52 void read(uint16_t* period_us, uint8_t len)
override;
80 return (uint32_t)((float)(dev->
state->
freq + speed_hz/2) / speed_hz);
static uint16_t _enabled_channels
void set_freq(uint32_t chmask, uint16_t freq_hz) override
static void init_channel(uint8_t ch)
static uint8_t _initialized[F4Light_MAX_OUTPUT_CHANNELS]
void set_output_mode(uint16_t mask, enum output_mode mode) override
static uint32_t _timer_period(uint16_t speed_hz, const timer_dev *dev)
static uint8_t _servo_mask
static void fill_timers()
static void set_pwm(uint8_t ch, uint16_t pwm)
uint16_t read(uint8_t ch) override
static void InitPWM(void)
void enable_ch(uint8_t ch) override
static bool is_servo_enabled(uint8_t ch)
#define F4Light_MAX_OUTPUT_CHANNELS
void disable_ch(uint8_t ch) override
static AP_HAL::OwnPtr< AP_HAL::Device > dev
static uint16_t _period[F4Light_MAX_OUTPUT_CHANNELS]
static const timer_dev * out_timers[16]
void write(uint8_t ch, uint16_t period_us) override
static void _timer3_isr_event(TIM_TypeDef *)
static void _set_pin_output_mode(uint8_t ch)
static uint32_t _timer2_preload
static uint8_t num_out_timers
static enum BOARD_PWM_MODES _mode
uint16_t get_freq(uint8_t ch) override
static uint16_t _timer3_preload
static uint16_t _freq[F4Light_MAX_OUTPUT_CHANNELS]
static uint8_t _used_channels
static void _set_output_mode(enum output_mode mode)
static void init_channels()
static void _init_alt_channels()
static bool _sbus_enabled
static void do_4way_if(AP_HAL::UARTDriver *uart)