7 #pragma GCC optimize ("O2") 24 #define F4Light_OUT_CHANNELS 6 // motor's channels enabled by default 28 #define SERVO_PIN_5 ((uint8_t)-1) 32 #define SERVO_PIN_6 ((uint8_t)-1) 36 #define SERVO_PIN_7 ((uint8_t)-1) 40 #define SERVO_PIN_8 ((uint8_t)-1) 44 #define SERVO_PIN_9 ((uint8_t)-1) 48 #define SERVO_PIN_10 ((uint8_t)-1) 52 #define SERVO_PIN_11 ((uint8_t)-1) 167 #define PWM_TIMER_KHZ 2000 // 1000 in cleanflight 168 #define ONESHOT125_TIMER_KHZ 8000 // 8000 in cleanflight 169 #define ONESHOT42_TIMER_KHZ 28000 // 24000 in cleanflight 170 #define PWM_BRUSHED_TIMER_KHZ 16000 // 8000 in cleanflight 172 #define _BV(bit) (1U << (bit)) 192 uint8_t map = hal_param_helper->_motor_layout;
303 period = (uint32_t)-1;
309 period = (uint32_t)-1;
316 period = (uint32_t)-1;
322 period = (uint32_t)-1;
364 #else // raw and dirty way 371 TIMER2->state->freq_scale=1;
372 TIMER3->state->freq_scale=1;
405 period = (uint32_t)-1;
410 period = (uint32_t)-1;
416 period = (uint32_t)-1;
422 period = (uint32_t)-1;
462 uint16_t freq = freq_hz;
471 if(
_once_mode && freq_hz>50) freq = freq_hz / 2;
491 uint16_t freq =
_freq[ch];
568 for (
int i = 0; i < len; i++) {
569 write(i + ch, period_us[i]);
582 for (
int i = 0; i < len; i++) {
583 period_us[i] =
read(i);
static uint16_t _enabled_channels
void timer_set_mode(const timer_dev *dev, timer_Channel channel, timer_mode mode)
static void _pinMode(uint8_t pin, uint8_t output)
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]
static const uint8_t *const revo_motor_map[]
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)
static const uint8_t output_channels_cleanflight[]
timer_Channel timer_channel
static void _write(uint8_t pin, uint8_t value)
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
uint16_t read(uint8_t ch) override
static uint16_t constrain_period(uint16_t p)
static void InitPWM(void)
void enable_ch(uint8_t ch) override
static bool is_servo_enabled(uint8_t ch)
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define ONESHOT42_TIMER_KHZ
static INLINE void timer_resume(const timer_dev *dev)
Start a timer's counter.
static const uint8_t * output_channels
#define F4Light_MAX_OUTPUT_CHANNELS
void disable_ch(uint8_t ch) override
static AP_HAL::OwnPtr< AP_HAL::Device > dev
#define PWM_BRUSHED_TIMER_KHZ
static uint16_t timer_get_reload(const timer_dev *dev)
Returns a timer's reload value.
static uint16_t _period[F4Light_MAX_OUTPUT_CHANNELS]
const timer_dev *const timer_device
static const timer_dev * out_timers[16]
void write(uint8_t ch, uint16_t period_us) override
#define F4Light_OUT_CHANNELS
static const uint8_t output_channels_servo[]
static void timer_set_compare(const timer_dev *dev, timer_Channel channel, uint16_t value)
Set the compare value for the given timer channel.
#define BOARD_NR_GPIO_PINS
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
uint16_t RCOutput::_period [F4Light_MAX_OUTPUT_CHANNELS] IN_CCM
static uint16_t _timer3_preload
static uint16_t _freq[F4Light_MAX_OUTPUT_CHANNELS]
static uint8_t _used_channels
void esc4wayProcess(AP_HAL::UARTDriver *uartPort)
uint32_t configTimeBase(const timer_dev *dev, uint16_t period, uint16_t khz)
#define ONESHOT125_TIMER_KHZ
static void _set_output_mode(enum output_mode mode)
static void init_channels()
static INLINE void timer_set_reload(const timer_dev *dev, uint32_t arr)
Set a timer's reload value.
#define PWM_IGNORE_THIS_CHANNEL
static const uint8_t output_channels_arducopter[]
Stores STM32-specific information related to a given Maple pin.
static bool _sbus_enabled
static const uint8_t output_channels_openpilot[]
static void do_4way_if(AP_HAL::UARTDriver *uart)
static void timer_generate_update(const timer_dev *dev)
Generate an update event for the given timer.
uint8_t esc4wayInit(const uint8_t *output_channels, uint8_t nm)