diff --git a/cpu/sam0_common/Kconfig b/cpu/sam0_common/Kconfig index 3d45cbcedb..ff64fc1193 100644 --- a/cpu/sam0_common/Kconfig +++ b/cpu/sam0_common/Kconfig @@ -15,6 +15,11 @@ config CPU_COMMON_SAM0 select HAS_PERIPH_FLASHPAGE_RWEE select HAS_PERIPH_GPIO select HAS_PERIPH_GPIO_IRQ + select HAS_PERIPH_GPIO_LL + select HAS_PERIPH_GPIO_LL_IRQ + select HAS_PERIPH_GPIO_LL_IRQ_LEVEL_TRIGGERED_HIGH + select HAS_PERIPH_GPIO_LL_IRQ_LEVEL_TRIGGERED_LOW + select HAS_PERIPH_GPIO_LL_IRQ_UNMASK select HAS_PERIPH_I2C_RECONFIGURE select HAS_PERIPH_RTT_SET_COUNTER select HAS_PERIPH_RTT_OVERFLOW diff --git a/cpu/sam0_common/Makefile.features b/cpu/sam0_common/Makefile.features index bc8ae8f278..43d620c6f9 100644 --- a/cpu/sam0_common/Makefile.features +++ b/cpu/sam0_common/Makefile.features @@ -13,6 +13,11 @@ FEATURES_PROVIDED += periph_flashpage_in_address_space FEATURES_PROVIDED += periph_flashpage_pagewise FEATURES_PROVIDED += periph_flashpage_rwee FEATURES_PROVIDED += periph_gpio periph_gpio_irq +FEATURES_PROVIDED += periph_gpio_ll +FEATURES_PROVIDED += periph_gpio_ll_irq +FEATURES_PROVIDED += periph_gpio_ll_irq_level_triggered_high +FEATURES_PROVIDED += periph_gpio_ll_irq_level_triggered_low +FEATURES_PROVIDED += periph_gpio_ll_irq_unmask FEATURES_PROVIDED += periph_i2c_reconfigure FEATURES_PROVIDED += periph_rtt_overflow FEATURES_PROVIDED += periph_rtt_set_counter @@ -35,6 +40,9 @@ FEATURES_PROVIDED += periph_wdt periph_wdt_cb periph_wdt_warning_period FEATURES_CONFLICT += periph_rtc:periph_rtt FEATURES_CONFLICT_MSG += "The RTC and RTT map to the same hardware peripheral." +FEATURES_CONFLICT += periph_gpio_irq:periph_gpio_ll_irq +FEATURES_CONFLICT_MSG += "GPIO IRQs can only be managed with one API." + include $(RIOTCPU)/cortexm_common/Makefile.features # Add sam0 configurations after including cortexm_common so sam0 takes precendence diff --git a/cpu/sam0_common/include/gpio_ll_arch.h b/cpu/sam0_common/include/gpio_ll_arch.h new file mode 100644 index 0000000000..8f72b1997c --- /dev/null +++ b/cpu/sam0_common/include/gpio_ll_arch.h @@ -0,0 +1,147 @@ +/* + * Copyright (C) 2016 Freie Universität Berlin + * 2017 OTA keys S.A. + * 2023 Otto-von-Guericke-Universität Magdeburg + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @ingroup cpu_sam0_common + * @ingroup drivers_periph_gpio_ll + * @{ + * + * @file + * @brief CPU specific part of the Peripheral GPIO Low-Level API + * + * @author Marian Buschsieweke + */ + +#ifndef GPIO_LL_ARCH_H +#define GPIO_LL_ARCH_H + +#include "architecture.h" +#include "periph/gpio_ll.h" +#include "periph_cpu.h" + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef DOXYGEN /* hide implementation specific details from Doxygen */ + +/* Provide base address of the GPIO peripheral via APB */ +#if defined(PORT_SEC) +# define GPIO_APB_BASE PORT_SEC +#else +# define GPIO_APB_BASE PORT +#endif + +/* Provide base address of the GPIO peripheral via IOBUS */ +#if defined(PORT_IOBUS_SEC) +# define GPIO_IOBUS_BASE PORT_IOBUS_SEC +#elif defined(PORT_IOBUS) +# define GPIO_IOBUS_BASE PORT_IOBUS +#else +# define GPIO_IOBUS_BASE GPIO_APB_BASE /* no IOBUS present, fall back to APB */ +#endif + +/** + * @brief Get a GPIO port by number + */ +#define GPIO_PORT(num) ((uintptr_t)&GPIO_IOBUS_BASE->Group[(num)]) + +/** + * @brief Get a GPIO port number by gpio_port_t value + */ +#define GPIO_PORT_NUM(port) \ + (((port) - (uintptr_t)&GPIO_IOBUS_BASE->Group[0]) / sizeof(GPIO_IOBUS_BASE->Group[0])) + +static inline PortGroup *sam0_gpio_iobus2ap(PortGroup *iobus) +{ + const uintptr_t iobus_base = (uintptr_t)GPIO_IOBUS_BASE; + const uintptr_t apb_base = (uintptr_t)GPIO_APB_BASE; + + return (PortGroup *)((uintptr_t)iobus - (iobus_base - apb_base)); +} + +static inline uword_t gpio_ll_read(gpio_port_t port) +{ + PortGroup *p = (PortGroup *)port; + if (!IS_USED(MODULE_PERIPH_GPIO_FAST_READ)) { + p = sam0_gpio_iobus2ap(p); + } + return p->IN.reg; +} + +static inline uword_t gpio_ll_read_output(gpio_port_t port) +{ + PortGroup *p = (PortGroup *)port; + return p->OUT.reg; +} + +static inline void gpio_ll_set(gpio_port_t port, uword_t mask) +{ + PortGroup *p = (PortGroup *)port; + p->OUTSET.reg = mask; +} + +static inline void gpio_ll_clear(gpio_port_t port, uword_t mask) +{ + PortGroup *p = (PortGroup *)port; + p->OUTCLR.reg = mask; +} + +static inline void gpio_ll_toggle(gpio_port_t port, uword_t mask) +{ + PortGroup *p = (PortGroup *)port; + p->OUTTGL.reg = mask; +} + +static inline void gpio_ll_write(gpio_port_t port, uword_t mask) +{ + PortGroup *p = (PortGroup *)port; + p->OUT.reg = mask; +} + +static inline gpio_port_t gpio_get_port(gpio_t pin) +{ + return (gpio_port_t)(pin & ~(0x1f)); +} + +static inline uint8_t gpio_get_pin_num(gpio_t pin) +{ + return pin & 0x1f; +} + +static inline gpio_port_t gpio_port_pack_addr(void *addr) +{ + return (gpio_port_t)addr; +} + +static inline void * gpio_port_unpack_addr(gpio_port_t port) +{ + if (port < GPIO_PORT(0)) { + return (void *)port; + } + if (port > GPIO_PORT(ARRAY_SIZE(GPIO_IOBUS_BASE->Group))) { + return (void *)port; + } + + return NULL; +} + +static inline bool is_gpio_port_num_valid(uint_fast8_t num) +{ + return (num < ARRAY_SIZE(GPIO_IOBUS_BASE->Group)); +} + +#endif /* DOXYGEN */ +#ifdef __cplusplus +} +#endif + +#endif /* GPIO_LL_ARCH_H */ +/** @} */ diff --git a/cpu/sam0_common/include/periph_cpu_common.h b/cpu/sam0_common/include/periph_cpu_common.h index 18af20c4c5..f8f63e01cc 100644 --- a/cpu/sam0_common/include/periph_cpu_common.h +++ b/cpu/sam0_common/include/periph_cpu_common.h @@ -126,6 +126,60 @@ typedef enum { GPIO_OD_PU = 0xff /**< not supported by HW */ } gpio_mode_t; +#define HAVE_GPIO_SLEW_T +typedef enum { + GPIO_SLEW_SLOWEST = 0, + GPIO_SLEW_SLOW = 0, + GPIO_SLEW_FAST = 0, + GPIO_SLEW_FASTEST = 0, +} gpio_slew_t; + +#define HAVE_GPIO_PULL_STRENGTH_T +typedef enum { + GPIO_PULL_WEAKEST = 0, + GPIO_PULL_WEAK = 0, + GPIO_PULL_STRONG = 0, + GPIO_PULL_STRONGEST = 0 +} gpio_pull_strength_t; + +#define HAVE_GPIO_DRIVE_STRENGTH_T +typedef enum { + GPIO_DRIVE_WEAKEST = 0, + GPIO_DRIVE_WEAK = 0, + GPIO_DRIVE_STRONG = 1, + GPIO_DRIVE_STRONGEST = 1 +} gpio_drive_strength_t; + +#define HAVE_GPIO_PULL_T +typedef enum { + GPIO_FLOATING, + GPIO_PULL_UP, + GPIO_PULL_DOWN, + GPIO_PULL_KEEP, +} gpio_pull_t; + +#define HAVE_GPIO_STATE_T +typedef enum { + GPIO_OUTPUT_PUSH_PULL, + GPIO_OUTPUT_OPEN_DRAIN, + GPIO_OUTPUT_OPEN_SOURCE, + GPIO_INPUT, + GPIO_USED_BY_PERIPHERAL, + GPIO_DISCONNECT, +} gpio_state_t; + +#define HAVE_GPIO_IRQ_TRIG_T +typedef enum { + GPIO_TRIGGER_EDGE_RISING = EIC_CONFIG_SENSE0_RISE_Val, + GPIO_TRIGGER_EDGE_FALLING = EIC_CONFIG_SENSE0_FALL_Val, + GPIO_TRIGGER_EDGE_BOTH = EIC_CONFIG_SENSE0_BOTH_Val, + GPIO_TRIGGER_LEVEL_HIGH = EIC_CONFIG_SENSE0_HIGH_Val, + GPIO_TRIGGER_LEVEL_LOW = EIC_CONFIG_SENSE0_LOW_Val, +} gpio_irq_trig_t; + +#define HAVE_GPIO_CONF_T +typedef union gpio_conf_sam0 gpio_conf_t; + /** * @brief Override active flank configuration values * @{ @@ -139,6 +193,49 @@ typedef enum { /** @} */ #endif /* ndef DOXYGEN */ +/** + * @brief GPIO pin configuration for SAM0 MCUs + * @ingroup drivers_periph_gpio_ll + */ +union gpio_conf_sam0 { + uint8_t bits; /**< the raw bits */ + struct { + /** + * @brief State of the pin + */ + gpio_state_t state : 3; + /** + * @brief Pull resistor configuration + */ + gpio_pull_t pull : 2; + /** + * @brief Drive strength of the GPIO + * + * @warning If the requested drive strength is not available, the + * closest fit supported will be configured instead. + * + * This value is ignored when @ref gpio_conf_nrf5x::state is configured + * to @ref GPIO_INPUT or @ref GPIO_DISCONNECT. + */ + gpio_drive_strength_t drive_strength : 1; + /** + * @brief Initial value of the output + * + * Ignored if @ref gpio_conf_nrf5x::state is set to @ref GPIO_INPUT or + * @ref GPIO_DISCONNECT. If the pin was previously in a high impedance + * state, it is guaranteed to directly transition to the given initial + * value. + * + * @ref gpio_ll_query_conf will write the current value of the specified + * pin here, which is read from the input register when the state is + * @ref GPIO_INPUT, otherwise the state from the output register is + * consulted. + */ + bool initial_value : 1; + uint8_t : 1; /*< padding */ + }; +}; + /** * @brief Available MUX values for configuring a pin's alternate function */ @@ -158,6 +255,7 @@ typedef enum { GPIO_MUX_L = 0xb, /**< select peripheral function L */ GPIO_MUX_M = 0xc, /**< select peripheral function M */ GPIO_MUX_N = 0xd, /**< select peripheral function N */ + GPIO_MUX_DISABLED = 0xff, /**< Disable */ } gpio_mux_t; #endif diff --git a/cpu/sam0_common/periph/gpio_ll.c b/cpu/sam0_common/periph/gpio_ll.c new file mode 100644 index 0000000000..8c399950dd --- /dev/null +++ b/cpu/sam0_common/periph/gpio_ll.c @@ -0,0 +1,222 @@ +/* + * Copyright (C) 2023 Otto-von-Guericke-Universität Magdeburg + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @ingroup cpu_stm32 + * @ingroup drivers_periph_gpio + * @{ + * + * @file + * @brief GPIO Low-level API implementation for the SAM0 GPIO peripheral + * + * @author Marian Buschsieweke + * + * This implementation uses the IOBUS for single-cycle I/O for writes in any + * case. Reading via the IOBUS requires however for continuous sampling to + * be enabled, as reads on the IOBUS cannot stall the CPU to wait for the + * on-demand sampling result to be available. Therefore, reads are done by + * default via the slower APB bus. + * + * To also enable reading via the IOBUS, add the following snipped to your + * `Makefile`: + * + * ``` + * FEATURES_OPTIONAL += periph_gpio_fast_read + * ``` + * + * This enables continuous sampling on any pin configured as input, so that + * the IOBUS can safely be used for reads as well. Consequently, it will now + * consistently use the IOBUS for I/O. + * + * @} + */ + +#include +#include + +#include "compiler_hints.h" +#include "cpu.h" +#include "irq.h" +#include "periph/gpio_ll.h" + +#ifdef MODULE_FMT +#include "fmt.h" +#else +static inline void print_str(const char *str) +{ + fputs(str, stdout); +} +#endif + +void gpio_ll_mux(gpio_port_t port, uint8_t pin, gpio_mux_t mux) +{ + assume(pin < 32); + assume(gpio_port_unpack_addr(port) == NULL); + PortGroup *iobus = (PortGroup *)port; + PortGroup *apb = sam0_gpio_iobus2ap(iobus); + + unsigned irq_state = irq_disable(); + if (mux == GPIO_MUX_DISABLED) { + apb->PINCFG[pin].bit.PMUXEN = 0; + } + else { + unsigned pmux_reg = pin >> 1; + unsigned pmux_pos = (pin & 0x01) << 2; + apb->PINCFG[pin].bit.PMUXEN = 1; + unsigned pmux = apb->PMUX[pmux_reg].reg; + pmux &= ~(PORT_PMUX_PMUXE_Msk << pmux_pos); + pmux |= (unsigned)mux << pmux_pos; + apb->PMUX[pmux_reg].reg = pmux; + } + irq_restore(irq_state); +} + +int gpio_ll_init(gpio_port_t port, uint8_t pin, gpio_conf_t conf) +{ + assume(pin < 32); + assume(gpio_port_unpack_addr(port) == NULL); + PortGroup *iobus = (PortGroup *)port; + PortGroup *apb = sam0_gpio_iobus2ap(iobus); + uint32_t pin_mask = 1U << pin; + uint8_t pin_cfg = 0; + bool initial_value = false; + bool output_enable = false; + + initial_value = conf.initial_value; + + switch (conf.state) { + case GPIO_INPUT: + pin_cfg |= PORT_PINCFG_INEN; + break; + case GPIO_OUTPUT_PUSH_PULL: + output_enable = true; + break; + case GPIO_USED_BY_PERIPHERAL: + pin_cfg |= PORT_PINCFG_PMUXEN; + break; + case GPIO_DISCONNECT: + break; + case GPIO_OUTPUT_OPEN_DRAIN: + case GPIO_OUTPUT_OPEN_SOURCE: + default: + return -ENOTSUP; + } + + switch (conf.pull) { + case GPIO_PULL_UP: + pin_cfg |= PORT_PINCFG_PULLEN; + initial_value = true; + break; + case GPIO_PULL_DOWN: + pin_cfg |= PORT_PINCFG_PULLEN; + initial_value = false; + break; + case GPIO_FLOATING: + break; + default: + return -ENOTSUP; + } + + if (conf.drive_strength == GPIO_DRIVE_STRONG) { + pin_cfg |= PORT_PINCFG_DRVSTR; + } + + if (IS_USED(MODULE_PERIPH_GPIO_FAST_READ)) { + /* This read-modify-write needs to be made atomic to avoid + * corrupting the control register. */ + unsigned state = irq_disable(); + if (conf.state == GPIO_INPUT) { + apb->CTRL.reg |= pin_mask; + } + else { + apb->CTRL.reg &= ~pin_mask; + } + irq_restore(state); + } + + /* Writing the settings now in careful order. All accesses are done via + * the clear / set special registers that are naturally atomic, except + * for the PINCFG register. But that is not shared with other pins, so + * no need to sync that. (The API says concurrent configurations of the + * exact same GPIO pin are forbidden.) */ + if (initial_value) { + iobus->OUTSET.reg = pin_mask; + } + else { + iobus->OUTCLR.reg = pin_mask; + } + + apb->PINCFG[pin].reg = pin_cfg; + + if (output_enable) { + iobus->DIRSET.reg = pin_mask; + } + else { + iobus->DIRCLR.reg = pin_mask; + } + + return 0; +} + +gpio_conf_t gpio_ll_query_conf(gpio_port_t port, uint8_t pin) +{ + gpio_conf_t result = { 0 }; + assume(pin < 32); + assume(gpio_port_unpack_addr(port) == NULL); + PortGroup *iobus = (PortGroup *)port; + PortGroup *apb = sam0_gpio_iobus2ap(iobus); + + uint32_t pin_mask = 1U << pin; + uint8_t pin_cfg = apb->PINCFG[pin].reg; + + if (pin_cfg & PORT_PINCFG_DRVSTR) { + result.drive_strength = GPIO_DRIVE_STRONG; + } + + if (pin_cfg & PORT_PINCFG_PULLEN) { + if (iobus->OUT.reg & pin_mask) { + result.pull = GPIO_PULL_UP; + } + else { + result.pull = GPIO_PULL_DOWN; + } + } + + if (pin_cfg & PORT_PINCFG_PMUXEN) { + result.state = GPIO_USED_BY_PERIPHERAL; + } + else { + if (iobus->DIR.reg & pin_mask) { + result.state = GPIO_OUTPUT_PUSH_PULL; + } + else { + if (pin_cfg & PORT_PINCFG_INEN) { + result.state = GPIO_INPUT; + } + else { + result.state = GPIO_DISCONNECT; + } + } + } + + result.initial_value = iobus->OUT.reg & pin_mask; + + return result; +} + +void gpio_ll_print_conf(gpio_conf_t conf) +{ + static const char *drive_strs[] = { + [GPIO_DRIVE_WEAK] = "weak", + [GPIO_DRIVE_STRONG] = "strong", + }; + + gpio_ll_print_conf_common(conf); + print_str(", drive: "); + print_str(drive_strs[conf.drive_strength]); +} diff --git a/cpu/sam0_common/periph/gpio_ll_irq.c b/cpu/sam0_common/periph/gpio_ll_irq.c new file mode 100644 index 0000000000..49c35bf88d --- /dev/null +++ b/cpu/sam0_common/periph/gpio_ll_irq.c @@ -0,0 +1,312 @@ +/* + * Copyright (C) 2015 HAW Hamburg + * 2016 INRIA + * 2023 Gerson Fernando Budke + * 2023 Hugues Larrive + * 2023 Otto-von-Guericke-Universität Magdeburg + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_sam0_common + * @ingroup drivers_periph_gpio_ll_irq + * @{ + * + * @file + * @brief IRQ implementation of the GPIO Low-Level API for SAM0 + * + * @author Marian Buschsieweke + * + * @} + */ + +#include + +#include "bitarithm.h" +#include "cpu.h" +#include "irq.h" +#include "periph/gpio_ll_irq.h" +#include "periph_conf.h" +#include "periph_cpu.h" + +#define ENABLE_DEBUG 0 +#include "debug.h" + +/** + * @brief Number of external interrupt lines + */ +#ifdef CPU_COMMON_SAML1X +#define IRQS_NUMOF (8U) +#else +#define IRQS_NUMOF (16U) +#endif + +/** + * @brief The GCLK used for clocking EXTI + */ +#ifndef CONFIG_SAM0_GCLK_GPIO +#define CONFIG_SAM0_GCLK_GPIO (SAM0_GCLK_MAIN) +#endif + +/* Consistify naming */ +#ifndef EIC_SEC +#define EIC_SEC EIC +#endif + +struct isr_ctx { + gpio_ll_cb_t cb; + void *arg; +}; + +static struct isr_ctx isr_ctx[IRQS_NUMOF]; + +extern void gpio_ll_mux(gpio_port_t port, uint8_t pin, gpio_mux_t mux); + +static int get_exti_num(unsigned port_num, uint8_t pin) +{ + if (port_num >= ARRAY_SIZE(exti_config)) { + return -1; + } + return exti_config[port_num][pin]; +} + +static IRQn_Type exti2irqn(unsigned exti_num) +{ + (void)exti_num; + assume(exti_num < IRQS_NUMOF); +#if defined(CPU_COMMON_SAMD5X) + return EIC_0_IRQn + exti_num; +#elif defined(CPU_COMMON_SAML1X) + if (exti_num <= 3) { + return EIC_0_IRQn + exti_num; + } + return EIC_OTHER_IRQn; +#else + return EIC_IRQn; +#endif +} + +static void enable_trigger(unsigned exti_num, gpio_irq_trig_t trig) +{ + unsigned config_reg = exti_num >> 3; + unsigned config_pos = (exti_num & 0x7) << 2; + + /* configure trigger with IRQs disabled */ + unsigned irq_state = irq_disable(); + uint32_t conf = EIC_SEC->CONFIG[config_reg].reg; + conf &= ~(EIC_CONFIG_SENSE0_Msk << config_pos); + conf |= ((uint32_t)trig) << config_pos; + EIC_SEC->CONFIG[config_reg].reg = conf; + irq_restore(irq_state); + + NVIC_EnableIRQ(exti2irqn(exti_num)); +} + +static void disable_trigger(unsigned exti_num) +{ + unsigned config_reg = exti_num >> 3; + unsigned config_pos = (exti_num & 0x7) << 2; + + /* configure trigger with IRQs disabled */ + unsigned irq_state = irq_disable(); + uint32_t conf = EIC_SEC->CONFIG[config_reg].reg; + conf &= ~(EIC_CONFIG_SENSE0_Msk << config_pos); + EIC_SEC->CONFIG[config_reg].reg = conf; + irq_restore(irq_state); +} + +static void eic_sync(void) +{ +#ifdef EIC_STATUS_SYNCBUSY + while (EIC_SEC->STATUS.bit.SYNCBUSY) { } +#endif +#ifdef EIC_SYNCBUSY_ENABLE + while (EIC_SEC->SYNCBUSY.bit.ENABLE) { } +#endif +} + +static void eic_enable_clock(void) +{ + /* Enable EIC clock */ +#ifdef PM_APBAMASK_EIC + PM->APBAMASK.reg |= PM_APBAMASK_EIC; + GCLK->CLKCTRL.reg = EIC_GCLK_ID + | GCLK_CLKCTRL_CLKEN + | GCLK_CLKCTRL_GEN(CONFIG_SAM0_GCLK_GPIO); + while (GCLK->STATUS.bit.SYNCBUSY) {} +#endif +#ifdef MCLK_APBAMASK_EIC + MCLK->APBAMASK.reg |= MCLK_APBAMASK_EIC; + GCLK->PCHCTRL[EIC_GCLK_ID].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(CONFIG_SAM0_GCLK_GPIO); + /* disable the EIC module*/ + EIC_SEC->CTRLA.reg = 0; + eic_sync(); +#endif +} + +static void eic_enable(void) +{ +#ifdef EIC_CTRL_ENABLE + EIC_SEC->CTRL.reg = EIC_CTRL_ENABLE; +#endif +#ifdef EIC_CTRLA_ENABLE + EIC_SEC->CTRLA.reg = EIC_CTRLA_ENABLE; +#endif +} + +void gpio_ll_irq_mask(gpio_port_t port, uint8_t pin) +{ + unsigned port_num = GPIO_PORT_NUM(port); + int exti_num = get_exti_num(port_num, pin); + assume((unsigned)exti_num < IRQS_NUMOF); + + EIC_SEC->INTENCLR.reg = 1U << exti_num; +} + +void gpio_ll_irq_unmask(gpio_port_t port, uint8_t pin) +{ + unsigned port_num = GPIO_PORT_NUM(port); + int exti_num = get_exti_num(port_num, pin); + assume((unsigned)exti_num < IRQS_NUMOF); + + EIC_SEC->INTENSET.reg = 1U << exti_num; +} + +void gpio_ll_irq_unmask_and_clear(gpio_port_t port, uint8_t pin) +{ + unsigned port_num = GPIO_PORT_NUM(port); + int exti_num = get_exti_num(port_num, pin); + assume(exti_num >= 0); + + uint32_t mask = 1U << exti_num; + EIC_SEC->INTFLAG.reg = mask; + EIC_SEC->INTENSET.reg = mask; +} + +int gpio_ll_irq(gpio_port_t port, uint8_t pin, gpio_irq_trig_t trig, + gpio_ll_cb_t cb, void *arg) +{ + unsigned port_num = GPIO_PORT_NUM(port); + int exti_num = get_exti_num(port_num, pin); + + assume(cb); + + if (exti_num < 0) { + return -ENOTSUP; + } + + if (isr_ctx[exti_num].cb) { + DEBUG("[gpio_ll_irq] IRQ already configured for EXTI %d (P%c%u)\n", + exti_num, 'A' + (char)port_num, (unsigned)pin); + } + + isr_ctx[exti_num].cb = cb; + isr_ctx[exti_num].arg = arg; + + gpio_ll_mux(port, pin, GPIO_MUX_A); + + eic_enable_clock(); + + enable_trigger(exti_num, trig); + + /* clear any spurious IRQ */ + EIC_SEC->INTFLAG.reg = 1U << exti_num; + + /* enable IRQ */ + EIC_SEC->INTENSET.reg = 1U << exti_num; + +#ifdef EIC_WAKEUP_WAKEUPEN0 + unsigned irq_state = irq_disable(); + EIC_SEC->WAKEUP.reg |= 1U << exti_num; + irq_restore(irq_state); +#endif + + eic_enable(); + + eic_sync(); + + return 0; +} + +void gpio_ll_irq_off(gpio_port_t port, uint8_t pin) +{ + unsigned port_num = GPIO_PORT_NUM(port); + int exti_num = get_exti_num(port_num, pin); + + assume((unsigned)exti_num < IRQS_NUMOF); + + /* First, disable IRQs */ + EIC_SEC->INTENCLR.reg = 1U << exti_num; + + gpio_ll_mux(port, pin, GPIO_MUX_DISABLED); + + /* Disabling the trigger may conserve power */ + disable_trigger(exti_num); + +#ifdef EIC_WAKEUP_WAKEUPEN0 + unsigned irq_state = irq_disable(); + EIC_SEC->WAKEUP.reg &= ~(1U << exti_num); + irq_restore(irq_state); +#endif + + /* Finally, clear the callback */ + isr_ctx[exti_num].cb = NULL; +} + +MAYBE_UNUSED +static void isr_eic_unknown_num(void) +{ + /* read & clear interrupt flags */ + uint32_t state = EIC_SEC->INTFLAG.reg & EIC_SEC->INTENSET.reg; + state &= EIC_INTFLAG_EXTINT_Msk; + EIC_SEC->INTFLAG.reg = state; + + /* execute interrupt callbacks */ + uint8_t num = 0; + while (state) { + state = bitarithm_test_and_clear(state, &num); + isr_ctx[num].cb(isr_ctx[num].arg); + } + + cortexm_isr_end(); +} + +MAYBE_UNUSED +static void isr_eic_known_num(unsigned num) +{ + EIC_SEC->INTFLAG.reg = 1U << num; + isr_ctx[num].cb(isr_ctx[num].arg); + cortexm_isr_end(); +} + +#if !defined(CPU_COMMON_SAML1X) && !defined(CPU_COMMON_SAMD5X) +void isr_eic(void) { isr_eic_unknown_num(); } +#endif + +#if defined(CPU_COMMON_SAML1X) +void isr_eic_other(void) { isr_eic_unknown_num(); } +#endif + +#if defined(CPU_COMMON_SAML1X) || defined(CPU_COMMON_SAMD5X) +void isr_eic0(void) { isr_eic_known_num(0); } +void isr_eic1(void) { isr_eic_known_num(1); } +void isr_eic2(void) { isr_eic_known_num(2); } +void isr_eic3(void) { isr_eic_known_num(3); } +#endif +#if defined(CPU_COMMON_SAMD5X) +void isr_eic4(void) { isr_eic_known_num(4); } +void isr_eic5(void) { isr_eic_known_num(5); } +void isr_eic6(void) { isr_eic_known_num(6); } +void isr_eic7(void) { isr_eic_known_num(7); } +void isr_eic8(void) { isr_eic_known_num(8); } +void isr_eic9(void) { isr_eic_known_num(9); } +void isr_eic10(void) { isr_eic_known_num(10); } +void isr_eic11(void) { isr_eic_known_num(11); } +void isr_eic12(void) { isr_eic_known_num(12); } +void isr_eic13(void) { isr_eic_known_num(13); } +void isr_eic14(void) { isr_eic_known_num(14); } +void isr_eic15(void) { isr_eic_known_num(15); } +#endif diff --git a/tests/periph/gpio_ll/main.c b/tests/periph/gpio_ll/main.c index 9cc9ce42c2..4505989ed8 100644 --- a/tests/periph/gpio_ll/main.c +++ b/tests/periph/gpio_ll/main.c @@ -464,6 +464,15 @@ static void test_gpio_ll_init(void) /* This is mandatory */ expect(is_supported); + /* Ensure that gpio_ll_query_conf() correctly detects the state as + * disconnected. */ + { + gpio_conf_t conf = gpio_ll_query_conf(port_out, PIN_OUT_0); + gpio_ll_print_conf(conf); + puts(""); + expect(conf.state == GPIO_DISCONNECT); + } + is_supported = (0 == gpio_ll_init(port_in, PIN_IN_0, gpio_ll_in_pd)); if (is_supported) { ztimer_sleep(ZTIMER_USEC, US_PER_MS); @@ -692,18 +701,27 @@ static void test_irq_edge(void) gpio_ll_irq_off(port_in, PIN_IN_0); } -struct mutex_counter { +struct irq_level_cb_arg { mutex_t mutex; unsigned counter; + enum { + LOW, + HIGH + } trigger_level; }; __attribute__((unused)) static void irq_level_cb(void *_arg) { - struct mutex_counter *arg = _arg; + struct irq_level_cb_arg *arg = _arg; if (!arg->counter) { - gpio_ll_toggle(port_out, 1UL << PIN_OUT_0); + if (arg->trigger_level == HIGH) { + gpio_ll_clear(port_out, 1UL << PIN_OUT_0); + } + else { + gpio_ll_set(port_out, 1UL << PIN_OUT_0); + } mutex_unlock(&arg->mutex); } else { @@ -713,9 +731,10 @@ static void irq_level_cb(void *_arg) static void test_irq_level(void) { - struct mutex_counter arg = { .mutex = MUTEX_INIT_LOCKED, .counter = 10 }; + struct irq_level_cb_arg arg = { .mutex = MUTEX_INIT_LOCKED, .counter = 10 }; if (IS_USED(MODULE_PERIPH_GPIO_LL_IRQ_LEVEL_TRIGGERED_HIGH)) { + arg.trigger_level = HIGH; puts_optional("Testing level-triggered on HIGH on PIN_IN_0 (when input " "is LOW when setting up IRQ)"); gpio_ll_clear(port_out, 1UL << PIN_OUT_0); @@ -750,6 +769,7 @@ static void test_irq_level(void) } if (IS_USED(MODULE_PERIPH_GPIO_LL_IRQ_LEVEL_TRIGGERED_LOW)) { + arg.trigger_level = LOW; puts_optional("Testing level-triggered on LOW on PIN_IN_0 (when input " "is HIGH when setting up IRQ)"); gpio_ll_set(port_out, 1UL << PIN_OUT_0);