110 uint32_t temp = dev->
GPIOx->AFR[pin >> 0x03] & ~((uint32_t)0xF << ((uint32_t)((uint32_t)pin & (uint32_t)0x07) * 4));
111 dev->
GPIOx->AFR[pin >> 0x03] = temp | ((uint32_t)(mode) << ((uint32_t)((uint32_t)pin & (uint32_t)0x07) * 4));
121 uint16_t bv =
BIT(pin);
124 dev->
GPIOx->BSRRL = bv;
126 dev->
GPIOx->BSRRH = bv;
163 dev->
GPIOx->OSPEEDR &= ~(GPIO_OSPEEDER_OSPEEDR0 << (pin * 2));
164 dev->
GPIOx->OSPEEDR |= ((uint32_t)(gpio_speed) << (pin * 2));
170 uint32_t tmp = ((uint32_t)0x0F) << (0x04 * (pin & (uint8_t)0x03));
171 SYSCFG->EXTICR[pin >> 0x02] &= ~tmp;
172 SYSCFG->EXTICR[pin >> 0x02] |= (((uint32_t)gpio_port) << (0x04 * (pin & (uint8_t)0x03)));
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
#define assert_param(expr)
const gpio_dev *const _GPIOE
const gpio_dev *const _GPIOB
const gpio_dev *const _GPIOD
static afio_exti_port gpio_exti_port(const gpio_dev *const dev)
const gpio_dev *const _GPIOA
const gpio_dev *const _GPIOG
const gpio_dev *const _GPIOC
void gpio_init(const gpio_dev *const dev)
static void gpio_toggle_bit(const gpio_dev *const dev, uint8_t pin)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
const gpio_dev *const _GPIOF
gpio_pin_mode
GPIO Pin modes.
static INLINE uint8_t gpio_read_bit(const gpio_dev *const dev, uint8_t pin)
static void gpio_set_speed(const gpio_dev *const dev, uint8_t pin, GPIOSpeed_t gpio_speed)
static void gpio_set_af_mode(const gpio_dev *const dev, uint8_t pin, uint8_t mode)
static void afio_exti_select(afio_exti_port gpio_port, afio_exti_num pin)
static INLINE void gpio_write_bit(const gpio_dev *const dev, uint8_t pin, uint8_t val)
afio_exti_port
External interrupt line port selector.