21 #if HAL_USE_EXT == TRUE 34 #define NUM_PINS ARRAY_SIZE_SIMPLE(_gpio_tab) 35 #define PIN_ENABLED(pin) ((pin)<NUM_PINS && _gpio_tab[pin].enabled) 100 if (value == PAL_LOW) {
133 uint8_t pad = PAL_PAD(line);
134 stm32_gpio_t *pal_port = PAL_PORT(line);
135 uint8_t ext_port = 0xff;
140 { GPIOA, EXT_MODE_GPIOA },
141 { GPIOB, EXT_MODE_GPIOB },
142 { GPIOC, EXT_MODE_GPIOC },
143 { GPIOD, EXT_MODE_GPIOD },
144 { GPIOE, EXT_MODE_GPIOE },
145 { GPIOF, EXT_MODE_GPIOF },
147 { GPIOG, EXT_MODE_GPIOG },
150 { GPIOH, EXT_MODE_GPIOH },
153 { GPIOI, EXT_MODE_GPIOI },
158 if (pal_port == port_mapping[i].port) {
159 ext_port = port_mapping[i].ext_port;
162 if (ext_port == 0xff) {
168 }
else if (!p && !
ext_irq[pad]) {
175 chmode = EXT_CH_MODE_LOW_LEVEL;
178 chmode = EXT_CH_MODE_FALLING_EDGE;
181 chmode = EXT_CH_MODE_RISING_EDGE;
184 chmode = EXT_CH_MODE_BOTH_EDGES;
194 _ext_started =
false;
196 extcfg.channels[pad].mode = chmode;
197 extcfg.channels[pad].mode |= (p?EXT_CH_MODE_AUTOSTART:0) | ext_port;
200 extStart(&EXTD1, &
extcfg);
215 return _attach_interrupt(g->
pal_line, p, mode);
220 return _usb_connected;
229 palSetLineMode(
line, output);
234 return palReadLine(
line);
239 palWriteLine(
line, value);
249 if (
ext_irq[channel] !=
nullptr) {
254 #endif // HAL_USE_EXT void pinMode(uint8_t pin, uint8_t output)
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)
DigitalSource(ioline_t line)
#define HAL_GPIO_INTERRUPT_LOW
void write(uint8_t pin, uint8_t value)
static struct gpio_entry * gpio_by_pin_num(uint8_t pin_num, bool check_enabled=true)
#define HAL_GPIO_INTERRUPT_BOTH
static uint8_t get_pwm_count(void)
static void ext_interrupt_cb(EXTDriver *extp, expchannel_t channel)
int8_t analogPinToDigitalPin(uint8_t pin)
void write(uint8_t value)
AP_HAL::DigitalSource * channel(uint16_t n)
#define HAL_GPIO_INTERRUPT_FALLING
#define HAL_GPIO_INTERRUPT_RISING
void mode(uint8_t output)
bool _attach_interrupt(ioline_t line, AP_HAL::Proc p, uint8_t mode)
bool usb_connected(void) override
uint8_t read(uint8_t pin)
static struct gpio_entry _gpio_tab[]
#define ARRAY_SIZE_SIMPLE(_arr)
static AP_HAL::Proc ext_irq[EXT_MAX_CHANNELS]