cpu/stm32: add stm32g0 support

This commit is contained in:
Alexandre Abadie 2020-05-03 22:22:10 +02:00
parent 8c50212a8d
commit dada52ecd2
No known key found for this signature in database
GPG Key ID: 1C919A403CAE1405
22 changed files with 329 additions and 65 deletions

View File

@ -64,6 +64,15 @@ config CPU_FAM_F7
select HAS_CORTEXM_MPU
select HAS_PERIPH_HWRNG
config CPU_FAM_G0
bool
select CPU_STM32
select CPU_CORE_CORTEX_M0PLUS
select HAS_CPU_STM32G0
select HAS_CORTEXM_MPU
select HAS_PERIPH_FLASHPAGE
select HAS_PERIPH_FLASHPAGE_RAW
config CPU_FAM_G4
bool
select CPU_STM32
@ -279,6 +288,11 @@ config CPU_MODEL_STM32F769NI
bool
select CPU_FAM_F7
# STM32G0
config CPU_MODEL_STM32G070RB
bool
select CPU_FAM_G0
# STM32G4
config CPU_MODEL_STM32G474RE
bool
@ -414,6 +428,11 @@ config HAS_CPU_STM32F7
help
Indicates that the cpu being used belongs to the 'stm32f7' family.
config HAS_CPU_STM32G0
bool
help
Indicates that the cpu being used belongs to the 'stm32g0' family.
config HAS_CPU_STM32G4
bool
help
@ -452,6 +471,7 @@ config CPU_FAM
default "f3" if CPU_FAM_F3
default "f4" if CPU_FAM_F4
default "f7" if CPU_FAM_F7
default "g0" if CPU_FAM_G0
default "g4" if CPU_FAM_G4
default "l0" if CPU_FAM_L0
default "l1" if CPU_FAM_L1
@ -508,6 +528,9 @@ config CPU_MODEL
default "stm32f767zi" if CPU_MODEL_STM32F767ZI
default "stm32f769ni" if CPU_MODEL_STM32F769NI
# STM32G0
default "stm32g070rb" if CPU_MODEL_STM32G070RB
# STM32G4
default "stm32g474re" if CPU_MODEL_STM32G474RE

View File

@ -9,7 +9,7 @@ FEATURES_PROVIDED += periph_uart_modecfg
FEATURES_PROVIDED += periph_uart_nonblocking
FEATURES_PROVIDED += periph_wdt
ifneq (,$(filter $(CPU_FAM),f0 f1 f3 g4 l0 l1 l4 wb))
ifneq (,$(filter $(CPU_FAM),f0 f1 f3 g0 g4 l0 l1 l4 wb))
FEATURES_PROVIDED += periph_flashpage
FEATURES_PROVIDED += periph_flashpage_raw
endif
@ -31,7 +31,7 @@ ifneq (,$(filter $(CPU_FAM),f2 f4 f7 g4 l0 l4 wb))
endif
endif
ifneq (,$(filter $(CPU_FAM),f2 f4 f7 g4 l1 l4))
ifneq (,$(filter $(CPU_FAM),f2 f4 f7 g0 g4 l1 l4))
FEATURES_PROVIDED += cortexm_mpu
endif

View File

@ -48,18 +48,14 @@ static const uint8_t apbmul[] = {
uint32_t periph_apb_clk(uint8_t bus)
{
if (bus == APB1) {
return CLOCK_APB1;
}
#if defined (CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
else if (bus == APB12) {
return CLOCK_APB1;
}
#endif
else {
#ifdef CLOCK_APB2
if (bus == APB2) {
return CLOCK_APB2;
}
#else
(void)bus;
#endif
return CLOCK_APB1;
}
uint32_t periph_timer_clk(uint8_t bus)
@ -74,20 +70,28 @@ void periph_clk_en(bus_t bus, uint32_t mask)
#if defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
RCC->APB1ENR1 |= mask;
#elif defined(CPU_FAM_STM32G0)
RCC->APBENR1 |= mask;
#else
RCC->APB1ENR |= mask;
#endif
break;
#if !defined(CPU_FAM_STM32G0)
case APB2:
RCC->APB2ENR |= mask;
break;
#endif
#if defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
case APB12:
RCC->APB1ENR2 |= mask;
break;
#elif defined(CPU_FAM_STM32G0)
case APB12:
RCC->APBENR2 |= mask;
break;
#endif
#if defined(CPU_FAM_STM32L0)
#if defined(CPU_FAM_STM32L0) || defined(CPU_FAM_STM32G0)
case AHB:
RCC->AHBENR |= mask;
break;
@ -130,18 +134,26 @@ void periph_clk_dis(bus_t bus, uint32_t mask)
#if defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
RCC->APB1ENR1 &= ~(mask);
#elif defined(CPU_FAM_STM32G0)
RCC->APBENR1 &= ~(mask);
#else
RCC->APB1ENR &= ~(mask);
#endif
break;
#if !defined(CPU_FAM_STM32G0)
case APB2:
RCC->APB2ENR &= ~(mask);
break;
#endif
#if defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
case APB12:
RCC->APB1ENR2 &= ~(mask);
break;
#elif defined(CPU_FAM_STM32G0)
case APB12:
RCC->APBENR2 &= ~(mask);
break;
#endif
#if defined(CPU_FAM_STM32L0)
case AHB:

View File

@ -41,6 +41,8 @@
#if defined (CPU_FAM_STM32L4) || defined (CPU_FAM_STM32G4)
#define BIT_APB_PWREN RCC_APB1ENR1_PWREN
#elif defined (CPU_FAM_STM32G0)
#define BIT_APB_PWREN RCC_APBENR1_PWREN
#else
#define BIT_APB_PWREN RCC_APB1ENR_PWREN
#endif

View File

@ -37,6 +37,8 @@
#include "stm32f4xx.h"
#elif CPU_FAM_STM32F7
#include "stm32f7xx.h"
#elif CPU_FAM_STM32G0
#include "stm32g0xx.h"
#elif CPU_FAM_STM32G4
#include "stm32g4xx.h"
#elif CPU_FAM_STM32L0
@ -119,6 +121,8 @@ extern "C" {
#define CPU_IRQ_NUMOF (82U)
#elif defined(CPU_MODEL_STM32WB55RG)
#define CPU_IRQ_NUMOF (63U)
#elif defined(CPU_MODEL_STM32G070RB)
#define CPU_IRQ_NUMOF (30U)
#else
#error Number of IRQs not configured for this CPU
#endif
@ -134,7 +138,7 @@ extern "C" {
#elif defined(CPU_LINE_STM32F091xC) || defined(CPU_LINE_STM32F072xB) \
|| defined(CPU_LINE_STM32F030xC) || defined(CPU_LINE_STM32F103xE) \
|| defined(CPU_FAM_STM32F3) || defined(CPU_FAM_STM32L4) \
|| defined(CPU_FAM_STM32G4)
|| defined(CPU_FAM_STM32G4) || defined(CPU_FAM_STM32G0)
#define FLASHPAGE_SIZE (2048U)
#elif defined(CPU_LINE_STM32F051x8) || defined(CPU_LINE_STM32F042x6) \
|| defined(CPU_LINE_STM32F070xB) || defined(CPU_LINE_STM32F030x8) \
@ -153,7 +157,7 @@ extern "C" {
* However, the erase block is always FLASHPAGE_SIZE.
*/
#if defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32G4) || defined(CPU_FAM_STM32G0)
#define FLASHPAGE_RAW_BLOCKSIZE (8U)
#elif defined(CPU_FAM_STM32L0) || defined(CPU_FAM_STM32L1)
#define FLASHPAGE_RAW_BLOCKSIZE (4U)
@ -162,7 +166,7 @@ extern "C" {
#endif
#if defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32G4) || defined(CPU_FAM_STM32G0)
#define FLASHPAGE_RAW_ALIGNMENT (8U)
#else
/* Writing should be always 4 bytes aligned */

View File

@ -30,7 +30,8 @@ extern "C" {
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F3) || \
defined(CPU_FAM_STM32F7) || defined(CPU_FAM_STM32L0) || \
defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32L4) || \
defined(CPU_FAM_STM32WB) || defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32WB) || defined(CPU_FAM_STM32G4) || \
defined(CPU_FAM_STM32G0)
/**
* @brief Timing register settings
@ -40,7 +41,7 @@ extern "C" {
static const i2c_timing_param_t timing_params[] = {
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F7) || \
defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32G4) || defined(CPU_FAM_STM32G0)
[ I2C_SPEED_NORMAL ] = {
.presc = 0xB,
.scll = 0x13, /* t_SCLL = 5.0us */
@ -111,7 +112,7 @@ static const i2c_timing_param_t timing_params[] = {
#endif /* CPU_FAM_STM32F0 || CPU_FAM_STM32F3 || CPU_FAM_STM32F7 ||
CPU_FAM_STM32L0 || CPU_FAM_STM32L4 || CPU_FAM_STM32WB ||
CPU_FAM_STM32G4*/
CPU_FAM_STM32G4 || CPU_FAM_STM32G0 */
#ifdef __cplusplus
}

View File

@ -0,0 +1,42 @@
/*
* Copyright (C) 2020 Inria
*
* 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
* @{
*
* @file
* @brief STM32G0 CPU specific definitions for internal peripheral handling
*
* @author Alexandre Abadie <alexandre.abadie@inria.fr>
*
*/
#ifndef PERIPH_G0_PERIPH_CPU_H
#define PERIPH_G0_PERIPH_CPU_H
#ifdef __cplusplus
extern "C" {
#endif
#ifndef DOXYGEN
/**
* @brief Starting address of the ROM bootloader
* see application note AN2606
*/
#define STM32_BOOTLOADER_ADDR (0x1FFF0000)
#endif /* ndef DOXYGEN */
#ifdef __cplusplus
}
#endif
#endif /* PERIPH_G0_PERIPH_CPU_H */
/** @} */

View File

@ -35,6 +35,8 @@
#include "periph/f4/periph_cpu.h"
#elif defined(CPU_FAM_STM32F7)
#include "periph/f7/periph_cpu.h"
#elif defined(CPU_FAM_STM32G0)
#include "periph/g0/periph_cpu.h"
#elif defined(CPU_FAM_STM32G4)
#include "periph/g4/periph_cpu.h"
#elif defined(CPU_FAM_STM32L0)
@ -61,7 +63,8 @@ extern "C" {
#define CLOCK_LSI (37000U)
#elif defined(CPU_FAM_STM32F2) || defined(CPU_FAM_STM32F4) || \
defined(CPU_FAM_STM32F7) || defined(CPU_FAM_STM32L4) || \
defined(CPU_FAM_STM32WB) || defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32WB) || defined(CPU_FAM_STM32G4) || \
defined(CPU_FAM_STM32G0)
#define CLOCK_LSI (32000U)
#else
#error "error: LSI clock speed not defined for your target CPU"
@ -167,10 +170,10 @@ typedef enum {
APB1, /**< APB1 bus */
APB2, /**< APB2 bus */
#if defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32G4) || defined(CPU_FAM_STM32G0)
APB12, /**< AHB1 bus, second register */
#endif
#if defined(CPU_FAM_STM32L0)
#if defined(CPU_FAM_STM32L0) || defined(CPU_FAM_STM32G0)
AHB, /**< AHB bus */
IOP, /**< IOP bus */
#elif defined(CPU_FAM_STM32L1) || defined(CPU_FAM_STM32F1) || \
@ -686,7 +689,7 @@ typedef enum {
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F3) || \
defined(CPU_FAM_STM32F7) || defined(CPU_FAM_STM32L0) || \
defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32G4) || defined(CPU_FAM_STM32G0)
I2C_SPEED_FAST_PLUS, /**< fast plus mode: ~1Mbit/s */
#endif
} i2c_speed_t;
@ -720,7 +723,7 @@ typedef struct {
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F3) || \
defined(CPU_FAM_STM32F7) || defined(CPU_FAM_STM32L0) || \
defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32G4) || defined(CPU_FAM_STM32G0)
/**
* @brief Structure for I2C timing register settings
*

View File

@ -2,7 +2,7 @@ MODULE = periph
# Select the specific implementation for `periph_i2c`
ifneq (,$(filter periph_i2c,$(USEMODULE)))
ifneq (,$(filter $(CPU_FAM),f0 f3 f7 g4 l0 l4 wb))
ifneq (,$(filter $(CPU_FAM),f0 f3 f7 g0 g4 l0 l4 wb))
SRC += i2c_1.c
else # f1/f2/f4/l1
SRC += i2c_2.c

View File

@ -123,7 +123,7 @@ static inline DMA_TypeDef *dma_req(int stream_n)
{
return dma_base(stream_n);
}
#elif CPU_FAM_STM32L0 || CPU_FAM_STM32L4
#elif CPU_FAM_STM32L0 || CPU_FAM_STM32L4 || CPU_FAM_STM32G0
static inline DMA_Request_TypeDef *dma_req(int stream_n)
{
#ifdef DMA2
@ -182,7 +182,7 @@ static IRQn_Type dma_get_irqn(int stream)
else if (stream < 16) {
return ((IRQn_Type)((int)DMA2_Stream5_IRQn + (stream - 13)));
}
#elif CPU_FAM_STM32F0 || CPU_FAM_STM32L0
#elif CPU_FAM_STM32F0 || CPU_FAM_STM32L0 || CPU_FAM_STM32G0
if (stream == 0) {
return (DMA1_Channel1_IRQn);
}

View File

@ -33,7 +33,7 @@
#define KEY_REG (FLASH->PEKEYR)
#else
#if defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32G4) || defined(CPU_FAM_STM32G0)
#define FLASH_KEY1 ((uint32_t)0x45670123)
#define FLASH_KEY2 ((uint32_t)0xCDEF89AB)
#endif
@ -42,6 +42,10 @@
#define KEY_REG (FLASH->KEYR)
#endif
#if defined(CPU_FAM_STM32G0)
#define FLASH_SR_BSY (FLASH_SR_BSY1)
#endif
void _unlock(void)
{
if (CNTRL_REG & CNTRL_REG_LOCK) {

View File

@ -41,7 +41,7 @@
#define FLASHPAGE_DIV (4U) /* write 4 bytes in one go */
#else
#if defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32G4) || defined(CPU_FAM_STM32G0)
#define FLASHPAGE_DIV (8U)
#else
#define FLASHPAGE_DIV (2U)
@ -80,7 +80,7 @@ static void _erase_page(void *page_addr)
{
#if defined(CPU_FAM_STM32L0) || defined(CPU_FAM_STM32L1) || \
defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32G4) || defined(CPU_FAM_STM32G0)
uint32_t *dst = page_addr;
#else
uint16_t *dst = page_addr;
@ -106,7 +106,7 @@ static void _erase_page(void *page_addr)
DEBUG("[flashpage] erase: trigger the page erase\n");
*dst = (uint32_t)0;
#elif defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32G4) || defined(CPU_FAM_STM32G0)
DEBUG("[flashpage] erase: setting the page address\n");
uint8_t pn;
#if (FLASHPAGE_NUMOF <= MAX_PAGES_PER_BANK) || defined(CPU_FAM_STM32WB)
@ -168,7 +168,7 @@ void flashpage_write_raw(void *target_addr, const void *data, size_t len)
uint32_t *dst = target_addr;
const uint32_t *data_addr = data;
#elif defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32G4) || defined(CPU_FAM_STM32G0)
uint64_t *dst = target_addr;
const uint64_t *data_addr = data;
#else
@ -192,7 +192,8 @@ void flashpage_write_raw(void *target_addr, const void *data, size_t len)
DEBUG("[flashpage_raw] write: now writing the data\n");
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F1) || \
defined(CPU_FAM_STM32F3) || defined(CPU_FAM_STM32L4) || \
defined(CPU_FAM_STM32WB) || defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32WB) || defined(CPU_FAM_STM32G4) || \
defined(CPU_FAM_STM32G0)
/* set PG bit and program page to flash */
CNTRL_REG |= FLASH_CR_PG;
#endif
@ -206,7 +207,8 @@ void flashpage_write_raw(void *target_addr, const void *data, size_t len)
/* clear program bit again */
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F1) || \
defined(CPU_FAM_STM32F3) || defined(CPU_FAM_STM32L4) || \
defined(CPU_FAM_STM32WB) || defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32WB) || defined(CPU_FAM_STM32G4) || \
defined(CPU_FAM_STM32G0)
CNTRL_REG &= ~(FLASH_CR_PG);
#endif
DEBUG("[flashpage_raw] write: done writing data\n");
@ -235,7 +237,8 @@ void flashpage_write(int page, const void *data)
#if defined(CPU_FAM_STM32L0) || defined(CPU_FAM_STM32L1)
/* STM32L0/L1 only supports word sizes */
uint32_t *page_addr = flashpage_addr(page);
#elif defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32G4)
#elif defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32G4) || \
defined(CPU_FAM_STM32G0)
uint64_t *page_addr = flashpage_addr(page);
#else
/* Default is to support half-word sizes */

View File

@ -1,7 +1,7 @@
/*
* Copyright (C) 2014-2015 Freie Universität Berlin
* 2015 Hamburg University of Applied Sciences
* 2017 Inria
* 2017-2020 Inria
* 2017 OTA keys S.A.
*
* This file is subject to the terms and conditions of the GNU Lesser General
@ -44,7 +44,7 @@ static gpio_isr_ctx_t isr_ctx[EXTI_NUMOF];
#endif /* MODULE_PERIPH_GPIO_IRQ */
#if defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32G4) || defined(CPU_FAM_STM32G0)
#define EXTI_REG_RTSR (EXTI->RTSR1)
#define EXTI_REG_FTSR (EXTI->FTSR1)
#define EXTI_REG_PR (EXTI->PR1)
@ -88,7 +88,7 @@ static inline void port_init_clock(GPIO_TypeDef *port, gpio_t pin)
(void)port; /* <-- Only used for when port G requires special handling */
#if defined(CPU_FAM_STM32F0) || defined (CPU_FAM_STM32F3) || defined(CPU_FAM_STM32L1)
periph_clk_en(AHB, (RCC_AHBENR_GPIOAEN << _port_num(pin)));
#elif defined (CPU_FAM_STM32L0)
#elif defined (CPU_FAM_STM32L0) || defined(CPU_FAM_STM32G0)
periph_clk_en(IOP, (RCC_IOPENR_GPIOAEN << _port_num(pin)));
#elif defined (CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined (CPU_FAM_STM32G4)
@ -154,7 +154,7 @@ void gpio_init_analog(gpio_t pin)
* gpio_init first */
#if defined(CPU_FAM_STM32F0) || defined (CPU_FAM_STM32F3) || defined(CPU_FAM_STM32L1)
periph_clk_en(AHB, (RCC_AHBENR_GPIOAEN << _port_num(pin)));
#elif defined (CPU_FAM_STM32L0)
#elif defined (CPU_FAM_STM32L0) || defined(CPU_FAM_STM32G0)
periph_clk_en(IOP, (RCC_IOPENR_GPIOAEN << _port_num(pin)));
#elif defined (CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined (CPU_FAM_STM32G4)
@ -224,6 +224,8 @@ int gpio_init_int(gpio_t pin, gpio_mode_t mode, gpio_flank_t flank,
#ifndef CPU_FAM_STM32WB
#ifdef CPU_FAM_STM32F0
periph_clk_en(APB2, RCC_APB2ENR_SYSCFGCOMPEN);
#elif defined(CPU_FAM_STM32G0)
periph_clk_en(APB12, RCC_APBENR2_SYSCFGEN);
#else
periph_clk_en(APB2, RCC_APB2ENR_SYSCFGEN);
#endif
@ -233,7 +235,8 @@ int gpio_init_int(gpio_t pin, gpio_mode_t mode, gpio_flank_t flank,
gpio_init(pin, mode);
/* enable global pin interrupt */
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32L0)
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32L0) || \
defined(CPU_FAM_STM32G0)
if (pin_num < 2) {
NVIC_EnableIRQ(EXTI0_1_IRQn);
}
@ -259,19 +262,44 @@ int gpio_init_int(gpio_t pin, gpio_mode_t mode, gpio_flank_t flank,
EXTI_REG_RTSR |= ((flank & 0x1) << pin_num);
EXTI_REG_FTSR &= ~(1 << pin_num);
EXTI_REG_FTSR |= ((flank >> 1) << pin_num);
#if defined(CPU_FAM_STM32G0)
/* enable specific pin as exti sources */
EXTI->EXTICR[pin_num >> 2] &= ~(0xf << ((pin_num & 0x03) * 8));
EXTI->EXTICR[pin_num >> 2] |= (port_num << ((pin_num & 0x03) * 8));
/* clear any pending requests */
EXTI->RPR1 = (1 << pin_num);
EXTI->FPR1 = (1 << pin_num);
#else
/* enable specific pin as exti sources */
SYSCFG->EXTICR[pin_num >> 2] &= ~(0xf << ((pin_num & 0x03) * 4));
SYSCFG->EXTICR[pin_num >> 2] |= (port_num << ((pin_num & 0x03) * 4));
/* clear any pending requests */
EXTI_REG_PR = (1 << pin_num);
#endif
/* unmask the pins interrupt channel */
EXTI_REG_IMR |= (1 << pin_num);
return 0;
}
void isr_exti(void)
{
#if defined(CPU_FAM_STM32G0)
/* only generate interrupts against lines which have their IMR set */
uint32_t pending_rising_isr = (EXTI->RPR1 & EXTI_REG_IMR);
uint32_t pending_falling_isr = (EXTI->FPR1 & EXTI_REG_IMR);
for (size_t i = 0; i < EXTI_NUMOF; i++) {
if (pending_rising_isr & (1 << i)) {
EXTI->RPR1 = (1 << i); /* clear by writing a 1 */
isr_ctx[i].cb(isr_ctx[i].arg);
}
if (pending_falling_isr & (1 << i)) {
EXTI->FPR1 = (1 << i); /* clear by writing a 1 */
isr_ctx[i].cb(isr_ctx[i].arg);
}
}
#else
/* only generate interrupts against lines which have their IMR set */
uint32_t pending_isr = (EXTI_REG_PR & EXTI_REG_IMR);
for (size_t i = 0; i < EXTI_NUMOF; i++) {
@ -280,6 +308,7 @@ void isr_exti(void)
isr_ctx[i].cb(isr_ctx[i].arg);
}
}
#endif
cortexm_isr_end();
}
#endif /* MODULE_PERIPH_GPIO_IRQ */

View File

@ -48,7 +48,7 @@
#define PM_STOP_CONFIG (PWR_CR_LPSDSR | PWR_CR_ULP | PWR_CR_CWUF)
#elif defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32G4)
#define PM_STOP_CONFIG (PWR_CR1_LPMS_STOP1)
#elif defined(CPU_FAM_STM32WB)
#elif defined(CPU_FAM_STM32WB) || defined(CPU_FAM_STM32G0)
#define PM_STOP_CONFIG (PWR_CR1_LPMS_0)
#elif defined(CPU_FAM_STM32F7)
#define PM_STOP_CONFIG (PWR_CR1_LPDS | PWR_CR1_FPDS | PWR_CR1_LPUDS)
@ -68,7 +68,7 @@
#define PM_STANDBY_CONFIG (PWR_CR_PDDS | PWR_CR_CWUF | PWR_CR_CSBF | PWR_CR_ULP)
#elif defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32G4)
#define PM_STANDBY_CONFIG (PWR_CR1_LPMS_STANDBY)
#elif defined(CPU_FAM_STM32WB)
#elif defined(CPU_FAM_STM32WB) || defined(CPU_FAM_STM32G0)
#define PM_STANDBY_CONFIG (PWR_CR1_LPMS_0 | PWR_CR1_LPMS_1)
#elif defined(CPU_FAM_STM32F7)
#define PM_STANDBY_CONFIG (PWR_CR1_PDDS | PWR_CR1_CSBF)
@ -78,7 +78,7 @@
#endif
#if defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32WB) || \
defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32G4) || defined(CPU_FAM_STM32G0)
#define PWR_CR_REG PWR->CR1
#define PWR_WUP_REG PWR->CR3
/* Allow overridable SRAM2 retention mode using CFLAGS */

View File

@ -80,7 +80,7 @@ register. */
#elif defined(CPU_FAM_STM32G4)
#define IMR_REG IMR2
#define EXTI_IMR_BIT EXTI_IMR2_IM37
#elif defined(CPU_FAM_STM32L0)
#elif defined(CPU_FAM_STM32L0) || defined(CPU_FAM_STM32G0)
#define IMR_REG IMR
#define EXTI_IMR_BIT EXTI_IMR_IM29
#else
@ -122,7 +122,8 @@ void rtt_init(void)
* Needs to be configured to trigger on rising edges. */
EXTI->IMR_REG |= EXTI_IMR_BIT;
#if !defined(CPU_FAM_STM32L4) && !defined(CPU_FAM_STM32L0) && \
!defined(CPU_FAM_STM32WB) && !defined(CPU_FAM_STM32G4)
!defined(CPU_FAM_STM32WB) && !defined(CPU_FAM_STM32G4) && \
!defined(CPU_FAM_STM32G0)
EXTI->FTSR_REG &= ~(EXTI_FTSR_BIT);
EXTI->RTSR_REG |= EXTI_RTSR_BIT;
EXTI->PR_REG = EXTI_PR_BIT;
@ -215,7 +216,8 @@ void isr_lptim1(void)
}
LPTIM1->ICR = (LPTIM_ICR_ARRMCF | LPTIM_ICR_CMPMCF);
#if !defined(CPU_FAM_STM32L4) && !defined(CPU_FAM_STM32L0) && \
!defined(CPU_FAM_STM32WB) && !defined(CPU_FAM_STM32G4)
!defined(CPU_FAM_STM32WB) && !defined(CPU_FAM_STM32G4) && \
!defined(CPU_FAM_STM32G0)
EXTI->PR_REG = EXTI_PR_BIT; /* only clear the associated bit */
#endif

View File

@ -34,7 +34,7 @@
#include "periph/gpio.h"
#include "pm_layered.h"
#if defined(CPU_LINE_STM32L4R5xx)
#if defined(CPU_LINE_STM32L4R5xx) || defined(CPU_FAM_STM32G0)
#define ISR_REG ISR
#define ISR_TXE USART_ISR_TXE_TXFNF
#define ISR_RXNE USART_ISR_RXNE_RXFNE
@ -60,7 +60,7 @@
#define RDR_REG DR
#endif
#if defined(CPU_LINE_STM32L4R5xx)
#if defined(CPU_LINE_STM32L4R5xx) || defined(CPU_FAM_STM32G0)
#define RXENABLE (USART_CR1_RE | USART_CR1_RXNEIE_RXFNEIE)
#define USART_ISR_RXNE (USART_ISR_RXNE_RXFNE)
#else

View File

@ -22,7 +22,7 @@ else ifneq (,$(filter $(CPU_FAM),g4 wb))
CPU_CORE = cortex-m4
else ifeq (f7,$(CPU_FAM))
CPU_CORE = cortex-m7
else ifeq (l0,$(CPU_FAM))
else ifneq (,$(CPU_FAM),g0 l0)
CPU_CORE = cortex-m0plus
else
$(error Not supported CPU family: 'stm32$(CPU_FAM)')

View File

@ -180,6 +180,18 @@ ifeq ($(STM32_TYPE), F)
RAM_LEN = 512K
endif
endif
else ifeq ($(STM32_TYPE), G)
ifeq ($(STM32_FAMILY), 0)
ifneq (, $(filter $(STM32_MODEL2), 7))
RAM_LEN = 36K
endif
endif
ifeq ($(STM32_FAMILY), 4)
ifeq ($(STM32_MODEL), 474)
RAM_LEN = 96K
CCMRAM_LEN = 32K
endif
endif
else ifeq ($(STM32_TYPE), L)
ifeq ($(STM32_FAMILY), 0)
ifeq ($(STM32_MODEL2), 1)
@ -250,13 +262,6 @@ else ifeq ($(STM32_TYPE), L)
RAM_LEN = 640K
endif
endif
else ifeq ($(STM32_TYPE), G)
ifeq ($(STM32_FAMILY), 4)
ifeq ($(STM32_MODEL), 474)
RAM_LEN = 96K
CCMRAM_LEN = 32K
endif
endif
else ifeq ($(STM32_TYPE), W)
ifeq ($(STM32_FAMILY), B)
ifeq ($(STM32_MODEL), B55)

View File

@ -8,8 +8,8 @@ else ifneq (,$(filter $(CPU_FAM),l0 l1))
SRC += stmclk_l0l1.c
else ifneq (,$(filter $(CPU_FAM),l4 wb))
SRC += stmclk_l4wb.c
else ifneq (,$(filter $(CPU_FAM),g4))
SRC += stmclk_g4.c
else ifneq (,$(filter $(CPU_FAM),g0 g4))
SRC += stmclk_gx.c
endif
include $(RIOTBASE)/Makefile.base

View File

@ -24,7 +24,8 @@
#include "periph_conf.h"
#if defined(CPU_FAM_STM32L4) || defined(CPU_FAM_STM32F7) || \
defined(CPU_FAM_STM32WB) || defined(CPU_FAM_STM32G4)
defined(CPU_FAM_STM32WB) || defined(CPU_FAM_STM32G4) || \
defined(CPU_FAM_STM32G0)
#define REG_PWR_CR CR1
#define BIT_CR_DBP PWR_CR1_DBP
#else

View File

@ -11,7 +11,7 @@
* @{
*
* @file
* @brief Implementation of STM32 clock configuration for the G4 family
* @brief Implementation of STM32 clock configuration for the G0 and G4 families
*
* @author Alexandre Abadie <alexandre.abadie@inria.fr>
* @}
@ -25,21 +25,42 @@
#error "HSE is selected as input clock source but CLOCK_HSE is not set"
#endif
#if defined(CPU_FAM_STM32G0)
#define PLL_M_MIN (1)
#define PLL_M_MAX (8)
#define PLL_N_MIN (8)
#define PLL_N_MAX (86)
#define PLL_R_MIN (2)
#define PLL_R_MAX (8)
#else /* CPu_FAM_STM32G4 */
#define PLL_M_MIN (1)
#define PLL_M_MAX (16)
#define PLL_N_MIN (8)
#define PLL_N_MAX (127)
#define PLL_R_MIN (1)
#define PLL_R_MAX (8)
#endif
#if CLOCK_USE_PLL
#if (CLOCK_PLL_M < 1 || CLOCK_PLL_M > 16)
#if (CLOCK_PLL_M < PLL_M_MIN || CLOCK_PLL_M > PLL_M_MAX)
#error "PLL configuration: PLL M value is out of range"
#endif
#define PLL_M ((CLOCK_PLL_M - 1) << RCC_PLLCFGR_PLLM_Pos)
#if (CLOCK_PLL_N < 8 || CLOCK_PLL_N > 127)
#if (CLOCK_PLL_N < PLL_N_MIN || CLOCK_PLL_N > PLL_N_MAX)
#error "PLL configuration: PLL N value is out of range"
#endif
#define PLL_N (CLOCK_PLL_N << RCC_PLLCFGR_PLLN_Pos)
#if (CLOCK_PLL_R < 1 || CLOCK_PLL_R > 8)
#if (CLOCK_PLL_R < PLL_R_MIN || CLOCK_PLL_R > PLL_R_MAX)
#error "PLL configuration: PLL R value is out of range"
#endif
#if defined(CPU_FAM_STM32G0)
#define PLL_R ((CLOCK_PLL_R - 1) << RCC_PLLCFGR_PLLR_Pos)
#else /* CPU_FAM_STM32G4 */
#define PLL_R (((CLOCK_PLL_R >> 1) - 1) << RCC_PLLCFGR_PLLR_Pos)
#endif
#if CLOCK_HSE
#define PLL_IN CLOCK_HSE
@ -48,9 +69,25 @@
#define PLL_IN CLOCK_HSI
#define PLL_SRC RCC_PLLCFGR_PLLSRC_HSI
#endif
#endif /* CLOCK_USE_PLL */
#if defined(CPU_FAM_STM32G0)
#define RCC_CFGR_SW_HSI (0)
#define RCC_CFGR_SW_HSE (RCC_CFGR_SW_0)
#define RCC_CFGR_SW_PLL (RCC_CFGR_SW_1)
#endif
/** Determine the required flash wait states from the core clock frequency */
#if defined(CPU_FAM_STM32G0)
#if CLOCK_CORECLOCK >= 48000000
#define FLASH_WAITSTATES (FLASH_ACR_LATENCY_1) /* 2 wait states */
#elif CLOCK_CORECLOCK >= 24000000
#define FLASH_WAITSTATES (FLASH_ACR_LATENCY_0) /* 1 wait states */
#else
#define FLASH_WAITSTATES (0) /* 0 wait states */
#endif
#else /* CPU_FAM_STM32G4 */
#if CLOCK_AHB >= 136
#define FLASH_WAITSTATES (FLASH_ACR_LATENCY_4WS) /* 4 ws */
#elif CLOCK_AHB >= 102
@ -62,6 +99,7 @@
#else
#define FLASH_WAITSTATES (0) /* 0 ws */
#endif
#endif /* CPU_FAM_STM32G4 */
void stmclk_init_sysclk(void)
{
@ -75,13 +113,22 @@ void stmclk_init_sysclk(void)
/* use HSI as system clock while we do any further configuration and
* configure the AHB and APB clock dividers as configured by the board */
#if defined(CPU_FAM_STM32G0)
RCC->CFGR = (RCC_CFGR_SW_HSI | CLOCK_AHB_DIV | CLOCK_APB1_DIV);
#elif defined(CPU_FAM_STM32G4)
RCC->CFGR = (RCC_CFGR_SW_HSI | CLOCK_AHB_DIV | CLOCK_APB1_DIV | CLOCK_APB2_DIV);
#endif
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI) {}
#if defined(CPU_FAM_STM32G0)
/* we enable instruction cache, pre-fetch, and we set the required flash wait states */
FLASH->ACR |= (FLASH_ACR_ICEN | FLASH_ACR_PRFTEN | FLASH_WAITSTATES);
#elif defined(CPU_FAM_STM32G4)
/* we enable I+D caches, pre-fetch, and we set the actual number of
* needed flash wait states */
FLASH->ACR |= (FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_PRFTEN |
FLASH_WAITSTATES);
#endif
/* disable all active clocks except HSI -> resets the clk configuration */
RCC->CR = RCC_CR_HSION;

View File

@ -0,0 +1,86 @@
/*
* Copyright (C) 2020 Inria
*
* 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
* @{
*
* @file
* @brief Interrupt vector definitions for STM32G0
*
* @author Alexandre Abadie <alexandre.abadie@inria.fr>
*
* @}
*/
#include "vectors_cortexm.h"
/* define a local dummy handler as it needs to be in the same compilation unit
* as the alias definition */
void dummy_handler(void) {
dummy_handler_default();
}
/* STM32G0 specific interrupt vectors */
WEAK_DEFAULT void isr_adc1(void);
WEAK_DEFAULT void isr_dma1_channel1(void);
WEAK_DEFAULT void isr_dma1_channel2_3(void);
WEAK_DEFAULT void isr_dma1_ch4_7_dmamux1_ovr(void);
WEAK_DEFAULT void isr_exti(void);
WEAK_DEFAULT void isr_flash(void);
WEAK_DEFAULT void isr_i2c1(void);
WEAK_DEFAULT void isr_i2c2(void);
WEAK_DEFAULT void isr_rcc(void);
WEAK_DEFAULT void isr_rtc_tamp(void);
WEAK_DEFAULT void isr_spi1(void);
WEAK_DEFAULT void isr_spi2(void);
WEAK_DEFAULT void isr_tim1_brk_up_trg_com(void);
WEAK_DEFAULT void isr_tim1_cc(void);
WEAK_DEFAULT void isr_tim3(void);
WEAK_DEFAULT void isr_tim6(void);
WEAK_DEFAULT void isr_tim7(void);
WEAK_DEFAULT void isr_tim14(void);
WEAK_DEFAULT void isr_tim15(void);
WEAK_DEFAULT void isr_tim16(void);
WEAK_DEFAULT void isr_tim17(void);
WEAK_DEFAULT void isr_usart1(void);
WEAK_DEFAULT void isr_usart2(void);
WEAK_DEFAULT void isr_usart3_4(void);
WEAK_DEFAULT void isr_wwdg(void);
/* CPU specific interrupt vector table */
ISR_VECTOR(1) const isr_t vector_cpu[CPU_IRQ_NUMOF] = {
/* shared vectors for all family members */
[WWDG_IRQn ] = isr_wwdg, /* [ 0] Window WatchDog Interrupt */
[RTC_TAMP_IRQn ] = isr_rtc_tamp, /* [ 2] RTC interrupt through the EXTI line 19 & 21 */
[FLASH_IRQn ] = isr_flash, /* [ 3] FLASH global Interrupt */
[RCC_IRQn ] = isr_rcc, /* [ 4] RCC global Interrupt */
[EXTI0_1_IRQn ] = isr_exti, /* [ 5] EXTI 0 and 1 Interrupts */
[EXTI2_3_IRQn ] = isr_exti, /* [ 6] EXTI 2 and 3 Interrupts */
[EXTI4_15_IRQn ] = isr_exti, /* [ 7] EXTI 4 to 15 Interrupts */
[DMA1_Channel1_IRQn ] = isr_dma1_channel1, /* [ 9] DMA1 Channel 1 Interrupt */
[DMA1_Channel2_3_IRQn ] = isr_dma1_channel2_3, /* [10] DMA1 Channel 2 and Channel 3 Interrupts */
[DMA1_Ch4_7_DMAMUX1_OVR_IRQn ] = isr_dma1_ch4_7_dmamux1_ovr, /* [11] DMA1 Channel 4 to Channel 7 and DMAMUX1 Overrun Interrupts */
[ADC1_IRQn ] = isr_adc1, /* [12] ADC1 Interrupts */
[TIM1_BRK_UP_TRG_COM_IRQn ] = isr_tim1_brk_up_trg_com, /* [13] TIM1 Break, Update, Trigger and Commutation Interrupts */
[TIM1_CC_IRQn ] = isr_tim1_cc, /* [14] TIM1 Capture Compare Interrupt */
[TIM3_IRQn ] = isr_tim3, /* [16] TIM3 global Interrupt */
[TIM6_IRQn ] = isr_tim6, /* [17] TIM6 global Interrupts */
[TIM7_IRQn ] = isr_tim7, /* [18] TIM7 global Interrupt */
[TIM14_IRQn ] = isr_tim14, /* [19] TIM14 global Interrupt */
[TIM15_IRQn ] = isr_tim15, /* [20] TIM15 global Interrupt */
[TIM16_IRQn ] = isr_tim16, /* [21] TIM16 global Interrupt */
[TIM17_IRQn ] = isr_tim17, /* [22] TIM17 global Interrupt */
[I2C1_IRQn ] = isr_i2c1, /* [23] I2C1 Interrupt (combined with EXTI 23) */
[I2C2_IRQn ] = isr_i2c2, /* [24] I2C2 Interrupt */
[SPI1_IRQn ] = isr_spi1, /* [25] SPI1/I2S1 Interrupt */
[SPI2_IRQn ] = isr_spi2, /* [26] SPI2 Interrupt */
[USART1_IRQn ] = isr_usart1, /* [27] USART1 Interrupt */
[USART2_IRQn ] = isr_usart2, /* [28] USART2 Interrupt */
[USART3_4_IRQn ] = isr_usart3_4, /* [29] USART3, USART4 globlal Interrupts */
};