6 #pragma GCC optimize ("O2") 61 if (pwm && timer !=
NULL) {
89 #ifdef BUZZER_PWM_HZ // passive buzzer
void timer_set_mode(const timer_dev *dev, timer_Channel channel, timer_mode mode)
static void _pinMode(uint8_t pin, uint8_t output)
void mode(uint8_t output)
static uint32_t _timer_period(uint16_t speed_hz, const timer_dev *dev)
timer_Channel timer_channel
#define assert_param(expr)
static void _write(uint8_t pin, uint8_t value)
static afio_exti_port gpio_exti_port(const gpio_dev *const dev)
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
void digitalToggle(uint8_t pin)
void detach_interrupt(uint8_t pin)
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
void exti_attach_interrupt_pri(afio_exti_num num, afio_exti_port port, Handler handler, exti_trigger_mode mode, uint8_t priority)
void digitalWrite(uint8_t pin, uint8_t value)
uint8_t read(uint8_t pin) override
uint8_t digitalRead(uint8_t pin)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
void toggle(uint8_t pin) override
const timer_dev *const timer_device
static uint8_t _read(uint8_t pin)
void write(uint8_t pin, uint8_t value) override
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
Board-specific pin information.
gpio_pin_mode
GPIO Pin modes.
static void _toggle(uint8_t pin)
static bool _attach_interrupt(uint8_t pin, Handler h, uint8_t mode, uint8_t priority)
static void gpio_set_speed(const gpio_dev *const dev, uint8_t pin, GPIOSpeed_t gpio_speed)
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)
void pinMode(uint8_t pin, uint8_t output) override
static INLINE void timer_set_reload(const timer_dev *dev, uint32_t arr)
Set a timer's reload value.
void exti_detach_interrupt(afio_exti_num num)
Unregister an external interrupt handler.
static DigitalSource * get_channel(uint16_t pin)
AP_HAL::DigitalSource * channel(uint16_t n)
Stores STM32-specific information related to a given Maple pin.
const gpio_dev *const gpio_device
static exti_trigger_mode exti_out_mode(ExtIntTriggerMode mode)