1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2025-01-17 04:52:59 +01:00
19185: cpu/gd32v: add periph_gpio_irq support r=gschorcht a=gschorcht

### Contribution description

This PR provides the `periph_gpio_irq` support and is one of a bunch of follow up PRs that complete the peripheral drivers for GD32VF103.

### Testing procedure

Use a GD32VF103 board and flash `tests/periph_gpio`. Note: The Sipeed Longan Nano works also with `seeedstudio-gd32` board defintion and could be used for testing.
```
BOARD=seeedstudio-gd32 make -C tests/periph_gpio flash  (until PR #19170 is merged only `seeedstudio
```
With the GPIO PB8 and PB9 connected, the following test sequence should work:
```
> init_out 1 8
> init_int 1 9 2 0
GPIO_PIN(1, 9) successfully initialized as ext int
> set 1 8
INT: external interrupt from pin 9
> clear 1 8
INT: external interrupt from pin 9
```


### Issues/PRs references


19187: cpu/gd32v: add pm_layered support in periph_pm r=gschorcht a=gschorcht

### Contribution description

This PR provides the `pm_layered` support and is one of a bunch of follow up PRs that complete the peripheral drivers for GD32VF103.

Since the configuration of the deep sleep and the standby mode require the access CSR (control and status registers) of the MCU, the Nuclei-SDK NMSIS is added as package which provides a low-level interface for Nuclei-based RISC-V MCUs.

### Testing procedure

The best way to test it is to rebase this PR onto PR #19186 and to flash `tests/periph_pm` to any GD32VF103 board. Note: The Sipeed Longan Nano works also with `seeedstudio-gd32` board definition and could be used for testing.
```
BOARD=seeedstudio-gd32 make -C tests/periph_pm flash
```
The test output should be:
```
main(): This is RIOT! (Version: 2023.04-devel-174-g7dc91-cpu/gd32v/periph_pm_test)
...
mode 0 blockers: 1 
mode 1 blockers: 2 
mode 2 blockers: 0 
Lowest allowed mode: 2
```
Using command the `set_rtc 1 5` command should let the MCU deep sleep for 5 seconds
```
> set_rtc 1 5
Setting power mode 1 for 5 seconds.
␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀␀> 
```
while command `set_rtc 1 5` should set the MCU into the standby mode which is left with restart.
```
> set_rtc 0 5
Setting power mode 0 for 5 seconds.
main(): This is RIOT! (Version: 2023.04-devel-174-g7dc91-cpu/gd32v/periph_pm_test)
...
mode 0 blockers: 1 
mode 1 blockers: 2 
mode 2 blockers: 0 
Lowest allowed mode: 2
> 
```
The garbage on UART interface after deep sleep is caused by the clock synchronisation that becomes necessary after deep sleep and is the same as for other boards.

### Issues/PRs references

Co-authored-by: Gunar Schorcht <gunar@schorcht.net>
This commit is contained in:
bors[bot] 2023-01-24 14:38:28 +00:00 committed by GitHub
commit f85366ae60
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
17 changed files with 309 additions and 7 deletions

View File

@ -8,9 +8,11 @@
config CPU_FAM_GD32V
bool
select CPU_CORE_RV32IMAC
select HAS_ARCH_NUCLEI
select HAS_CPU_GD32V
select HAS_PERIPH_CLIC
select HAS_PERIPH_GPIO
select HAS_PERIPH_GPIO_IRQ
select HAS_PERIPH_FLASHPAGE
select HAS_PERIPH_FLASHPAGE_IN_ADDRESS_SPACE
select HAS_PERIPH_FLASHPAGE_PAGEWISE
@ -22,6 +24,9 @@ config CPU_FAM_GD32V
select MODULE_PERIPH_CLIC if TEST_KCONFIG
select MODULE_PERIPH_WDT if MODULE_PERIPH_PM && HAS_PERIPH_WDT
select PACKAGE_NMSIS_SDK
menu "GD32V configuration"
config CPU_MODEL_GD32VF103CBT6
bool
@ -54,4 +59,6 @@ config CPU_CORE
rsource "periph/Kconfig"
endmenu
source "$(RIOTCPU)/riscv_common/Kconfig"

View File

@ -0,0 +1 @@
DEFAULT_MODULE += pm_layered

View File

@ -1,4 +1,5 @@
USEMODULE += periph
USEPKG += nmsis_sdk
FEATURES_REQUIRED += periph_clic

View File

@ -1,7 +1,9 @@
CPU_CORE := rv32imac
FEATURES_PROVIDED += arch_nuclei
FEATURES_PROVIDED += periph_clic
FEATURES_PROVIDED += periph_gpio
FEATURES_PROVIDED += periph_gpio_irq
FEATURES_PROVIDED += periph_rtc
FEATURES_PROVIDED += periph_timer
FEATURES_PROVIDED += periph_timer_periodic
@ -12,3 +14,9 @@ FEATURES_PROVIDED += periph_flashpage_in_address_space
FEATURES_PROVIDED += periph_flashpage_pagewise
include $(RIOTCPU)/riscv_common/Makefile.features
# This configuration enables modules that are only available when using Kconfig
# module modelling
ifeq (1, $(TEST_KCONFIG))
KCONFIG_ADD_CONFIG += $(RIOTCPU)/gd32v/gd32v.config
endif

View File

@ -29,6 +29,8 @@ extern void __libc_init_array(void);
void cpu_init(void)
{
gd32vf103_clock_init();
/* enable PMU required for pm_layered */
periph_clk_en(APB1, RCU_APB1EN_PMUEN_Msk);
/* Common RISC-V initialization */
riscv_init();
early_init();

1
cpu/gd32v/gd32v.config Normal file
View File

@ -0,0 +1 @@
CONFIG_MODULE_PM_LAYERED=y

View File

@ -33,7 +33,39 @@ extern "C" {
* @name Power management configuration
* @{
*/
#define PROVIDES_PM_SET_LOWEST
/**
* @brief Number of usable low power modes
*/
#define PM_NUM_MODES (3U) /**< Number of usable low power modes */
/**
* @brief Power modes
*
* The GD32V has three power modes (terminology as defined by GigaDevice).
* - Sleep: Only the clock of the RISC-V core is switched off.
* - Deep sleep: The RISC-V core including all AHB and APB peripheralsa and all
* high speed clocks are off. The LDO is in operation and the
* SRAM is retained.
* The MCU can be woken up by external interrupts or events
* without restart.
* - Standby: The RISC-V core including all AHB and APB peripherals, all
* high-speed clocks, and the LDO are off. The SRAM is not
* retained.
* The MCU can be woken up by WKUP or the NRST pin, watchdog
* reset and RTC alarms with restart.
*/
enum {
GD32V_PM_STANDBY = 0, /**< STANDBY mode, */
GD32V_PM_DEEPSLEEP = 1, /**< DEEPSLEEP mode, corresponds to STOP mode of STM32 */
GD32V_PM_IDLE = 2 /**< IDLE mode */
};
/**
* @brief Wake-up pin used
*/
#ifndef CONFIG_PM_EWUP_USED
#define CONFIG_PM_EWUP_USED (0U)
#endif
/** @} */
/**
@ -94,6 +126,7 @@ typedef uint32_t gpio_t;
* - bit 4: output type (0: push-pull, 1: open-drain)
*/
#define GPIO_MODE(io, pr, ot) ((io << 0) | (pr << 2) | (ot << 4))
/**
* @brief Override GPIO mode options
*
@ -110,6 +143,18 @@ typedef enum {
GPIO_OD_PU = (0xff) /**< not supported by HW */
} gpio_mode_t;
/** @} */
/**
* @brief Override flank configuration values
* @{
*/
#define HAVE_GPIO_FLANK_T
typedef enum {
GPIO_RISING = 1, /**< emit interrupt on rising flank */
GPIO_FALLING = 2, /**< emit interrupt on falling flank */
GPIO_BOTH = 3 /**< emit interrupt on both flanks */
} gpio_flank_t;
/** @} */
#endif /* ndef DOXYGEN */
/**

View File

@ -8,3 +8,9 @@
config MODULE_PERIPH
bool
default y
config PM_EWUP_USED
bool "Use PA0/WKUP pin"
depends on MODULE_PM_LAYERED
help
If enabled, the PA0/WKUP pin can be used to wake up the MCU from standby mode.

View File

@ -1,5 +1,7 @@
/*
* Copyright (C) 2020 Koen Zandberg <koen@bergzand.net>
* Copyright (C) 2014-2015 Freie Universität Berlin
* 2020 Koen Zandberg <koen@bergzand.net>
* 2023 Gunar Schorcht <gunar@schorcht.net>
*
* 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
@ -10,13 +12,19 @@
* @{
*
* @file
* @brief GD32V GPIO implementation
* @brief Low-level GPIO driver implementation for GD32V
*
* @author Koen Zandberg <koen@bergzand.net>
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
* @author Gunar Schorcht
*/
#include "assert.h"
#include "bitarithm.h"
#include "cpu.h"
#include "clic.h"
#include "log.h"
#include "periph_cpu.h"
#include "periph/gpio.h"
@ -26,6 +34,19 @@
#define MODE_MASK (0x0f)
#define ODR_POS (4U)
#ifdef MODULE_PERIPH_GPIO_IRQ
/**
* @brief Number of available external interrupt lines
*/
#define GPIO_ISR_CHAN_NUMOF (16U)
#define GPIO_ISR_CHAN_MASK (0xFFFF)
/**
* @brief Allocate memory for one callback and argument per EXTI channel
*/
static gpio_isr_ctx_t exti_ctx[GPIO_ISR_CHAN_NUMOF];
#endif /* MODULE_PERIPH_GPIO_IRQ */
/**
* @brief Extract the port base address from the given pin identifier
*/
@ -184,4 +205,116 @@ void gpio_write(gpio_t pin, int value)
}
}
#ifdef MODULE_PERIPH_GPIO_IRQ
/* Forward declaration of ISR */
static void _gpio_isr(unsigned irqn);
static inline unsigned _irq_num(unsigned pin_num)
{
if (pin_num < 5) {
return EXTI0_IRQn + pin_num;
}
if (pin_num < 10) {
return EXTI5_9_IRQn;
}
return EXTI10_15_IRQn;
}
#ifndef NDEBUG
uint8_t exti_line_port[GPIO_ISR_CHAN_NUMOF];
#endif
int gpio_init_int(gpio_t pin, gpio_mode_t mode, gpio_flank_t flank,
gpio_cb_t cb, void *arg)
{
assert(cb != NULL);
int pin_num = _pin_num(pin);
int port_num = _port_num(pin);
/* disable interrupts on the channel we want to edit (just in case) */
EXTI->INTEN &= ~(1 << pin_num);
/* configure pin as input */
gpio_init(pin, mode);
#ifndef NDEBUG
/* GD32V has 16 EXTI lines for GPIO interrupts, where all ports share
* the same EXTI line for the same pin. That means the pin PA<n> shares
* the EXTI line with PB<n>, PC<n>, PD<n> and PE<n>. */
if ((exti_ctx[pin_num].cb != 0) && (exti_line_port[pin_num] != port_num)) {
LOG_ERROR("EXTI line for GPIO_PIN(%u, %u) is used by GPIO_PIN(%u, %u).\n",
port_num, pin_num, exti_line_port[pin_num], pin_num);
assert(0);
}
exti_line_port[pin_num] = port_num;
#endif
/* set callback */
exti_ctx[pin_num].cb = cb;
exti_ctx[pin_num].arg = arg;
/* enable alternate function clock for the GPIO module */
periph_clk_en(APB2, RCU_APB2EN_AFEN_Msk);
/* configure the EXTI channel */
volatile uint32_t *afio_exti_ss = &AFIO->EXTISS0 + (pin_num >> 2);
*afio_exti_ss &= ~(0xfUL << ((pin_num & 0x03) * 4));
*afio_exti_ss |= (uint32_t)port_num << ((pin_num & 0x03) * 4);
/* configure the active flank */
EXTI->RTEN &= ~(1 << pin_num);
EXTI->RTEN |= ((flank & 0x1) << pin_num);
EXTI->FTEN &= ~(1 << pin_num);
EXTI->FTEN |= ((flank >> 1) << pin_num);
/* clear any pending requests */
EXTI->PD = (1 << pin_num);
/* enable global pin interrupt */
unsigned irqn = _irq_num(pin_num);
clic_set_handler(irqn, _gpio_isr);
clic_enable_interrupt(irqn, CPU_DEFAULT_IRQ_PRIO);
/* unmask the pins interrupt channel */
EXTI->INTEN |= (1 << pin_num);
return 0;
}
void gpio_irq_enable(gpio_t pin)
{
EXTI->INTEN |= (1 << _pin_num(pin));
}
void gpio_irq_disable(gpio_t pin)
{
EXTI->INTEN &= ~(1 << _pin_num(pin));
}
static void _gpio_isr(unsigned irqn)
{
(void)irqn;
/* read all pending interrupts wired to isr_exti */
uint32_t pending_isr = EXTI->PD & GPIO_ISR_CHAN_MASK;
/* clear by writing a 1 */
EXTI->PD = pending_isr;
/* only generate soft interrupts against lines which have their IMR set */
pending_isr &= EXTI->INTEN;
/* iterate over all set bits */
uint8_t pin = 0;
while (pending_isr) {
pending_isr = bitarithm_test_and_clear(pending_isr, &pin);
exti_ctx[pin].cb(exti_ctx[pin].arg);
}
}
#endif
/** @} */

View File

@ -1,5 +1,6 @@
/*
* Copyright 2020 Koen Zandberg
* 2023 Gunar Schorcht
*
* 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
@ -13,16 +14,67 @@
* @brief Implementation of the CPU power management for Gigadevice GD32V
*
* @author Koen Zandberg <koen@bergzand.net>
* @author Gunar Schorcht <gunar@schorcht.net>
* @}
*/
#include <stdint.h>
#include <stdio.h>
#include "periph/pm.h"
#include "periph/wdt.h"
void pm_set_lowest(void)
#undef MCAUSE_CAUSE /* redefined in NMSIS header */
#include "core_feature_base.h"
void pm_set(unsigned mode)
{
__asm__ volatile ("wfi");
bool csr_deepsleep = false; /* RISC-V sleep mode */
switch (mode) {
case GD32V_PM_STANDBY:
csr_deepsleep = true;
/* set the STANDBY mode flag */
PMU->CTL |= PMU_CTL_WURST_Msk;
/* reset the wake up flag */
PMU->CTL |= PMU_CTL_STBMOD_Msk;
break;
case GD32V_PM_DEEPSLEEP:
csr_deepsleep = true;
/* reset the STANDBY mode flag */
PMU->CTL &= ~PMU_CTL_STBMOD_Msk;
/* use LDO low powered in deep sleep mode */
PMU->CTL |= PMU_CTL_LDOLP_Msk;
break;
case GD32V_PM_IDLE:
csr_deepsleep = false;
break;
default:
break;
}
if (csr_deepsleep) {
/* Enable WKUP pin if used */
PMU->CS &= ~PMU_CS_WUPEN_Msk;
PMU->CS |= (CONFIG_PM_EWUP_USED) ? PMU_CS_WUPEN_Msk : 0;
/* set CSR_SLEEPVALUE bit in RISC-V system control register */
__set_wfi_sleepmode(WFI_DEEP_SLEEP);
}
else {
/* clear CSR_SLEEPVALUE bit in RISC-V system control register */
__set_wfi_sleepmode(WFI_SHALLOW_SLEEP);
}
/* trigger sleeping, TODO wait for wake up event (__WFE) implementation */
__WFI();
if (csr_deepsleep) {
/* clear CSR_SLEEPVALUE bit in RISC-V system control register */
__set_wfi_sleepmode(WFI_SHALLOW_SLEEP);
/* after deep sleep, the IRC8M is used as clock so that a clock
* reinitialization is required */
gd32vf103_clock_init();
}
}
void pm_reboot(void)

View File

@ -22,6 +22,7 @@
#include "periph_cpu.h"
#include "cpu.h"
#include "clic.h"
#include "pm_layered.h"
#define RXENABLE (USART_CTL0_REN_Msk | USART_CTL0_RBNEIE_Msk)
@ -56,14 +57,18 @@ static inline void uart_init_pins(uart_t uart, uart_rx_cb_t rx_cb)
static inline void uart_enable_clock(uart_t uart)
{
/* TODO: add pm blocker */
if (isr_ctx[uart].rx_cb) {
pm_block(GD32V_PM_DEEPSLEEP);
}
periph_clk_en(uart_config[uart].bus, uart_config[uart].rcu_mask);
}
static inline void uart_disable_clock(uart_t uart)
{
periph_clk_dis(uart_config[uart].bus, uart_config[uart].rcu_mask);
/* TODO remove pm blocker */
if (isr_ctx[uart].rx_cb) {
pm_unblock(GD32V_PM_DEEPSLEEP);
}
}
static inline void uart_init_usart(uart_t uart, uint32_t baudrate)

View File

@ -55,6 +55,7 @@ rsource "mynewt-core/Kconfig"
rsource "nanocbor/Kconfig"
rsource "nanopb/Kconfig"
rsource "nanors/Kconfig"
rsource "nmsis_sdk/Kconfig"
rsource "nrfx/Kconfig"
rsource "qcbor/Kconfig"
rsource "qdsa/Kconfig"

16
pkg/nmsis_sdk/Kconfig Normal file
View File

@ -0,0 +1,16 @@
# Copyright (c) 2023 Gunar Schorcht
#
# 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.
config PACKAGE_NMSIS_SDK
bool "NMSIS SDK for Nuclei-based MCUs"
depends on HAS_ARCH_NUCLEI
help
Vendor SDK from Nuclei System Technology for Nuclei-based MCUs
config HAS_ARCH_NUCLEI
bool
help
Indicates that the MCU is Nuclei-based

10
pkg/nmsis_sdk/Makefile Normal file
View File

@ -0,0 +1,10 @@
PKG_NAME=nmsis_sdk
PKG_URL=https://github.com/Nuclei-Software/NMSIS.git
# v1.1.0
PKG_VERSION=c213b493a423750f139e8a3e1400b36a2ceaf914
PKG_LICENSE=Apache-2.0
include $(RIOTBASE)/pkg/pkg.mk
all:
@

View File

@ -0,0 +1,2 @@
# This package can only be used with the Nuclei-based MCUs
FEATURES_REQUIRED += arch_nuclei

View File

@ -0,0 +1,3 @@
PSEUDOMODULES += nmsis_sdk
INCLUDES += -I$(PKGDIRBASE)/nmsis_sdk/NMSIS/Core/Include

9
pkg/nmsis_sdk/doc.txt Normal file
View File

@ -0,0 +1,9 @@
/**
* @defgroup pkg_nmsis_sdk Nuclei MCU Software Interface Standard
* @ingroup pkg
* @brief Vendor SDK from Nuclei System Technology for Nuclei-based MCUs
*
* The NMSIS SDK is required for Nuclei-based MCUs, for example the GDVF103.
*
* @see https://github.com/Nuclei-Software/nuclei-sdk
*/