drivers: STM32 dualcore concurrent register access protection with HSEM

In case of dualcore, STM32H7, STM32W and STM32MP1,
protect concurrent register write access with HSEM.
Done for following drivers:
clock_control, counter, flash, gpio, interrupt_controller

Signed-off-by: Alexandre Bourdiol <alexandre.bourdiol@st.com>
This commit is contained in:
Alexandre Bourdiol 2020-06-23 09:48:07 +02:00 committed by Carles Cufí
commit c8ceca2d53
13 changed files with 186 additions and 71 deletions

View file

@ -9,6 +9,7 @@
#include <drivers/clock_control.h> #include <drivers/clock_control.h>
#include <sys/util.h> #include <sys/util.h>
#include <drivers/clock_control/stm32_clock_control.h> #include <drivers/clock_control/stm32_clock_control.h>
#include "stm32_hsem.h"
/* Macros to fill up prescaler values */ /* Macros to fill up prescaler values */
#define z_sysclk_prescaler(v) LL_RCC_SYSCLK_DIV_ ## v #define z_sysclk_prescaler(v) LL_RCC_SYSCLK_DIV_ ## v
@ -41,21 +42,6 @@
#endif #endif
#endif /* CONFIG_CPU_CORTEX_M7 */ #endif /* CONFIG_CPU_CORTEX_M7 */
/**
* @brief fill in AHB/APB buses configuration structure
*/
#if !defined(CONFIG_CPU_CORTEX_M4)
static void config_bus_prescalers(void)
{
LL_RCC_SetSysPrescaler(sysclk_prescaler(CONFIG_CLOCK_STM32_D1CPRE));
LL_RCC_SetAHBPrescaler(ahb_prescaler(CONFIG_CLOCK_STM32_HPRE));
LL_RCC_SetAPB1Prescaler(apb1_prescaler(CONFIG_CLOCK_STM32_D2PPRE1));
LL_RCC_SetAPB2Prescaler(apb2_prescaler(CONFIG_CLOCK_STM32_D2PPRE2));
LL_RCC_SetAPB3Prescaler(apb3_prescaler(CONFIG_CLOCK_STM32_D1PPRE));
LL_RCC_SetAPB4Prescaler(apb4_prescaler(CONFIG_CLOCK_STM32_D3PPRE));
}
#endif /* CONFIG_CPU_CORTEX_M4 */
static uint32_t get_bus_clock(uint32_t clock, uint32_t prescaler) static uint32_t get_bus_clock(uint32_t clock, uint32_t prescaler)
{ {
return clock / prescaler; return clock / prescaler;
@ -65,12 +51,13 @@ static inline int stm32_clock_control_on(struct device *dev,
clock_control_subsys_t sub_system) clock_control_subsys_t sub_system)
{ {
struct stm32_pclken *pclken = (struct stm32_pclken *)(sub_system); struct stm32_pclken *pclken = (struct stm32_pclken *)(sub_system);
int rc = 0;
ARG_UNUSED(dev); ARG_UNUSED(dev);
/* Both cores can access bansk by following LL API */ /* Both cores can access bansk by following LL API */
/* Using "_Cn_" LL API would restrict access to one or the other */ /* Using "_Cn_" LL API would restrict access to one or the other */
z_stm32_hsem_lock(CFG_HW_RCC_SEMID, HSEM_LOCK_DEFAULT_RETRY);
switch (pclken->bus) { switch (pclken->bus) {
case STM32_CLOCK_BUS_AHB1: case STM32_CLOCK_BUS_AHB1:
LL_AHB1_GRP1_EnableClock(pclken->enr); LL_AHB1_GRP1_EnableClock(pclken->enr);
@ -100,22 +87,26 @@ static inline int stm32_clock_control_on(struct device *dev,
LL_APB4_GRP1_EnableClock(pclken->enr); LL_APB4_GRP1_EnableClock(pclken->enr);
break; break;
default: default:
return -ENOTSUP; rc = -ENOTSUP;
break;
} }
return 0; z_stm32_hsem_unlock(CFG_HW_RCC_SEMID);
return rc;
} }
static inline int stm32_clock_control_off(struct device *dev, static inline int stm32_clock_control_off(struct device *dev,
clock_control_subsys_t sub_system) clock_control_subsys_t sub_system)
{ {
struct stm32_pclken *pclken = (struct stm32_pclken *)(sub_system); struct stm32_pclken *pclken = (struct stm32_pclken *)(sub_system);
int rc = 0;
ARG_UNUSED(dev); ARG_UNUSED(dev);
/* Both cores can access bansk by following LL API */ /* Both cores can access bansk by following LL API */
/* Using "_Cn_" LL API would restrict access to one or the other */ /* Using "_Cn_" LL API would restrict access to one or the other */
z_stm32_hsem_lock(CFG_HW_RCC_SEMID, HSEM_LOCK_DEFAULT_RETRY);
switch (pclken->bus) { switch (pclken->bus) {
case STM32_CLOCK_BUS_AHB1: case STM32_CLOCK_BUS_AHB1:
LL_AHB1_GRP1_DisableClock(pclken->enr); LL_AHB1_GRP1_DisableClock(pclken->enr);
@ -145,10 +136,12 @@ static inline int stm32_clock_control_off(struct device *dev,
LL_APB4_GRP1_DisableClock(pclken->enr); LL_APB4_GRP1_DisableClock(pclken->enr);
break; break;
default: default:
return -ENOTSUP; rc = -ENOTSUP;
break;
} }
z_stm32_hsem_unlock(CFG_HW_RCC_SEMID);
return 0; return rc;
} }
static int stm32_clock_control_get_subsys_rate(struct device *clock, static int stm32_clock_control_get_subsys_rate(struct device *clock,
@ -220,6 +213,11 @@ static int stm32_clock_control_init(struct device *dev)
#ifdef CONFIG_CLOCK_STM32_SYSCLK_SRC_PLL #ifdef CONFIG_CLOCK_STM32_SYSCLK_SRC_PLL
/* HW semaphore Clock enable */
LL_AHB4_GRP1_EnableClock(LL_AHB4_GRP1_PERIPH_HSEM);
z_stm32_hsem_lock(CFG_HW_RCC_SEMID, HSEM_LOCK_DEFAULT_RETRY);
#ifdef CONFIG_CLOCK_STM32_PLL_SRC_HSE #ifdef CONFIG_CLOCK_STM32_PLL_SRC_HSE
if (IS_ENABLED(CONFIG_CLOCK_STM32_HSE_BYPASS)) { if (IS_ENABLED(CONFIG_CLOCK_STM32_HSE_BYPASS)) {
@ -260,13 +258,20 @@ static int stm32_clock_control_init(struct device *dev)
} }
/* Set buses (Sys,AHB, APB1, APB2 & APB4) prescalers */ /* Set buses (Sys,AHB, APB1, APB2 & APB4) prescalers */
config_bus_prescalers(); LL_RCC_SetSysPrescaler(sysclk_prescaler(CONFIG_CLOCK_STM32_D1CPRE));
LL_RCC_SetAHBPrescaler(ahb_prescaler(CONFIG_CLOCK_STM32_HPRE));
LL_RCC_SetAPB1Prescaler(apb1_prescaler(CONFIG_CLOCK_STM32_D2PPRE1));
LL_RCC_SetAPB2Prescaler(apb2_prescaler(CONFIG_CLOCK_STM32_D2PPRE2));
LL_RCC_SetAPB3Prescaler(apb3_prescaler(CONFIG_CLOCK_STM32_D1PPRE));
LL_RCC_SetAPB4Prescaler(apb4_prescaler(CONFIG_CLOCK_STM32_D3PPRE));
/* Set PLL1 as System Clock Source */ /* Set PLL1 as System Clock Source */
LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL1); LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL1);
while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL1) { while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL1) {
} }
z_stm32_hsem_unlock(CFG_HW_RCC_SEMID);
#else #else
#error "CONFIG_CLOCK_STM32_SYSCLK_SRC_PLL not selected" #error "CONFIG_CLOCK_STM32_SYSCLK_SRC_PLL not selected"
#endif /* CLOCK_STM32_SYSCLK_SRC_PLL */ #endif /* CLOCK_STM32_SYSCLK_SRC_PLL */

View file

@ -11,7 +11,7 @@
#include <sys/util.h> #include <sys/util.h>
#include <drivers/clock_control/stm32_clock_control.h> #include <drivers/clock_control/stm32_clock_control.h>
#include "clock_stm32_ll_common.h" #include "clock_stm32_ll_common.h"
#include "stm32_hsem.h"
#ifdef CONFIG_CLOCK_STM32_SYSCLK_SRC_PLL #ifdef CONFIG_CLOCK_STM32_SYSCLK_SRC_PLL
@ -47,6 +47,12 @@ void config_enable_default_clocks(void)
#ifdef CONFIG_CLOCK_STM32_LSE #ifdef CONFIG_CLOCK_STM32_LSE
/* LSE belongs to the back-up domain, enable access.*/ /* LSE belongs to the back-up domain, enable access.*/
#if defined(CONFIG_SOC_SERIES_STM32WBX)
/* HW semaphore Clock enable */
LL_AHB3_GRP1_EnableClock(LL_AHB3_GRP1_PERIPH_HSEM);
#endif
z_stm32_hsem_lock(CFG_HW_RCC_SEMID, HSEM_LOCK_DEFAULT_RETRY);
#ifdef LL_APB1_GRP1_PERIPH_PWR #ifdef LL_APB1_GRP1_PERIPH_PWR
/* Enable the power interface clock */ /* Enable the power interface clock */
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_PWR); LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_PWR);
@ -65,5 +71,8 @@ void config_enable_default_clocks(void)
} }
LL_PWR_DisableBkUpAccess(); LL_PWR_DisableBkUpAccess();
z_stm32_hsem_unlock(CFG_HW_RCC_SEMID);
#endif #endif
} }

View file

@ -22,6 +22,8 @@
#include <logging/log.h> #include <logging/log.h>
#include "stm32_hsem.h"
LOG_MODULE_REGISTER(counter_rtc_stm32, CONFIG_COUNTER_LOG_LEVEL); LOG_MODULE_REGISTER(counter_rtc_stm32, CONFIG_COUNTER_LOG_LEVEL);
#define T_TIME_OFFSET 946684800 #define T_TIME_OFFSET 946684800
@ -65,7 +67,9 @@ static int rtc_stm32_start(struct device *dev)
{ {
ARG_UNUSED(dev); ARG_UNUSED(dev);
z_stm32_hsem_lock(CFG_HW_RCC_SEMID, HSEM_LOCK_DEFAULT_RETRY);
LL_RCC_EnableRTC(); LL_RCC_EnableRTC();
z_stm32_hsem_unlock(CFG_HW_RCC_SEMID);
return 0; return 0;
} }
@ -75,7 +79,9 @@ static int rtc_stm32_stop(struct device *dev)
{ {
ARG_UNUSED(dev); ARG_UNUSED(dev);
z_stm32_hsem_lock(CFG_HW_RCC_SEMID, HSEM_LOCK_DEFAULT_RETRY);
LL_RCC_DisableRTC(); LL_RCC_DisableRTC();
z_stm32_hsem_unlock(CFG_HW_RCC_SEMID);
return 0; return 0;
} }
@ -279,6 +285,8 @@ static int rtc_stm32_init(struct device *dev)
clock_control_on(clk, (clock_control_subsys_t *) &cfg->pclken); clock_control_on(clk, (clock_control_subsys_t *) &cfg->pclken);
z_stm32_hsem_lock(CFG_HW_RCC_SEMID, HSEM_LOCK_DEFAULT_RETRY);
LL_PWR_EnableBkUpAccess(); LL_PWR_EnableBkUpAccess();
LL_RCC_ForceBackupDomainReset(); LL_RCC_ForceBackupDomainReset();
LL_RCC_ReleaseBackupDomainReset(); LL_RCC_ReleaseBackupDomainReset();
@ -328,6 +336,8 @@ static int rtc_stm32_init(struct device *dev)
LL_RCC_EnableRTC(); LL_RCC_EnableRTC();
z_stm32_hsem_unlock(CFG_HW_RCC_SEMID);
if (LL_RTC_DeInit(RTC) != SUCCESS) { if (LL_RTC_DeInit(RTC) != SUCCESS) {
return -EIO; return -EIO;
} }

View file

@ -18,6 +18,7 @@
#include <logging/log.h> #include <logging/log.h>
#include "flash_stm32.h" #include "flash_stm32.h"
#include "stm32_hsem.h"
LOG_MODULE_REGISTER(flash_stm32, CONFIG_FLASH_LOG_LEVEL); LOG_MODULE_REGISTER(flash_stm32, CONFIG_FLASH_LOG_LEVEL);
@ -58,8 +59,6 @@ LOG_MODULE_REGISTER(flash_stm32, CONFIG_FLASH_LOG_LEVEL);
*/ */
#define STM32_FLASH_TIMEOUT (2 * STM32_FLASH_MAX_ERASE_TIME) #define STM32_FLASH_TIMEOUT (2 * STM32_FLASH_MAX_ERASE_TIME)
#define CFG_HW_FLASH_SEMID 2
static const struct flash_parameters flash_stm32_parameters = { static const struct flash_parameters flash_stm32_parameters = {
.write_block_size = FLASH_STM32_WRITE_BLOCK_SIZE, .write_block_size = FLASH_STM32_WRITE_BLOCK_SIZE,
/* Some SoCs (L0/L1) use an EEPROM under the hood. Distinguish /* Some SoCs (L0/L1) use an EEPROM under the hood. Distinguish
@ -79,24 +78,14 @@ static const struct flash_parameters flash_stm32_parameters = {
*/ */
static inline void _flash_stm32_sem_take(struct device *dev) static inline void _flash_stm32_sem_take(struct device *dev)
{ {
#ifdef CONFIG_SOC_SERIES_STM32WBX
while (LL_HSEM_1StepLock(HSEM, CFG_HW_FLASH_SEMID)) {
}
#endif /* CONFIG_SOC_SERIES_STM32WBX */
k_sem_take(&FLASH_STM32_PRIV(dev)->sem, K_FOREVER); k_sem_take(&FLASH_STM32_PRIV(dev)->sem, K_FOREVER);
z_stm32_hsem_lock(CFG_HW_FLASH_SEMID, HSEM_LOCK_WAIT_FOREVER);
} }
static inline void _flash_stm32_sem_give(struct device *dev) static inline void _flash_stm32_sem_give(struct device *dev)
{ {
z_stm32_hsem_unlock(CFG_HW_FLASH_SEMID);
k_sem_give(&FLASH_STM32_PRIV(dev)->sem); k_sem_give(&FLASH_STM32_PRIV(dev)->sem);
#ifdef CONFIG_SOC_SERIES_STM32WBX
LL_HSEM_ReleaseLock(HSEM, CFG_HW_FLASH_SEMID, 0);
#endif /* CONFIG_SOC_SERIES_STM32WBX */
} }
#define flash_stm32_sem_init(dev) k_sem_init(&FLASH_STM32_PRIV(dev)->sem, 1, 1) #define flash_stm32_sem_init(dev) k_sem_init(&FLASH_STM32_PRIV(dev)->sem, 1, 1)

View file

@ -18,6 +18,7 @@
#include <sys/util.h> #include <sys/util.h>
#include <drivers/interrupt_controller/exti_stm32.h> #include <drivers/interrupt_controller/exti_stm32.h>
#include "stm32_hsem.h"
#include "gpio_stm32.h" #include "gpio_stm32.h"
#include "gpio_utils.h" #include "gpio_utils.h"
@ -172,6 +173,7 @@ int gpio_stm32_configure(uint32_t *base_addr, int pin, int conf, int altf)
ospeed = conf & (STM32_OSPEEDR_MASK << STM32_OSPEEDR_SHIFT); ospeed = conf & (STM32_OSPEEDR_MASK << STM32_OSPEEDR_SHIFT);
pupd = conf & (STM32_PUPDR_MASK << STM32_PUPDR_SHIFT); pupd = conf & (STM32_PUPDR_MASK << STM32_PUPDR_SHIFT);
z_stm32_hsem_lock(CFG_HW_GPIO_SEMID, HSEM_LOCK_DEFAULT_RETRY);
LL_GPIO_SetPinMode(gpio, pin_ll, mode >> STM32_MODER_SHIFT); LL_GPIO_SetPinMode(gpio, pin_ll, mode >> STM32_MODER_SHIFT);
if (STM32_MODER_ALT_MODE == mode) { if (STM32_MODER_ALT_MODE == mode) {
@ -198,6 +200,7 @@ int gpio_stm32_configure(uint32_t *base_addr, int pin, int conf, int altf)
LL_GPIO_SetPinPull(gpio, pin_ll, pupd >> STM32_PUPDR_SHIFT); LL_GPIO_SetPinPull(gpio, pin_ll, pupd >> STM32_PUPDR_SHIFT);
z_stm32_hsem_unlock(CFG_HW_GPIO_SEMID);
#endif /* CONFIG_SOC_SERIES_STM32F1X */ #endif /* CONFIG_SOC_SERIES_STM32F1X */
return 0; return 0;
@ -233,6 +236,8 @@ static void gpio_stm32_set_exti_source(int port, int pin)
} }
#endif #endif
z_stm32_hsem_lock(CFG_HW_EXTI_SEMID, HSEM_LOCK_DEFAULT_RETRY);
#ifdef CONFIG_SOC_SERIES_STM32F1X #ifdef CONFIG_SOC_SERIES_STM32F1X
LL_GPIO_AF_SetEXTISource(port, line); LL_GPIO_AF_SetEXTISource(port, line);
#elif CONFIG_SOC_SERIES_STM32MP1X #elif CONFIG_SOC_SERIES_STM32MP1X
@ -243,6 +248,7 @@ static void gpio_stm32_set_exti_source(int port, int pin)
#else #else
LL_SYSCFG_SetEXTISource(port, line); LL_SYSCFG_SetEXTISource(port, line);
#endif #endif
z_stm32_hsem_unlock(CFG_HW_EXTI_SEMID);
} }
static int gpio_stm32_get_exti_source(int pin) static int gpio_stm32_get_exti_source(int pin)
@ -325,9 +331,13 @@ static int gpio_stm32_port_set_masked_raw(struct device *dev,
GPIO_TypeDef *gpio = (GPIO_TypeDef *)cfg->base; GPIO_TypeDef *gpio = (GPIO_TypeDef *)cfg->base;
uint32_t port_value; uint32_t port_value;
z_stm32_hsem_lock(CFG_HW_GPIO_SEMID, HSEM_LOCK_DEFAULT_RETRY);
port_value = LL_GPIO_ReadOutputPort(gpio); port_value = LL_GPIO_ReadOutputPort(gpio);
LL_GPIO_WriteOutputPort(gpio, (port_value & ~mask) | (mask & value)); LL_GPIO_WriteOutputPort(gpio, (port_value & ~mask) | (mask & value));
z_stm32_hsem_unlock(CFG_HW_GPIO_SEMID);
return 0; return 0;
} }
@ -376,7 +386,9 @@ static int gpio_stm32_port_toggle_bits(struct device *dev,
* On F1 series, using LL API requires a costly pin mask translation. * On F1 series, using LL API requires a costly pin mask translation.
* Skip it and use CMSIS API directly. Valid also on other series. * Skip it and use CMSIS API directly. Valid also on other series.
*/ */
z_stm32_hsem_lock(CFG_HW_GPIO_SEMID, HSEM_LOCK_DEFAULT_RETRY);
WRITE_REG(gpio->ODR, READ_REG(gpio->ODR) ^ pins); WRITE_REG(gpio->ODR, READ_REG(gpio->ODR) ^ pins);
z_stm32_hsem_unlock(CFG_HW_GPIO_SEMID);
return 0; return 0;
} }
@ -391,17 +403,12 @@ static int gpio_stm32_config(struct device *dev,
int err = 0; int err = 0;
int pincfg; int pincfg;
#if defined(CONFIG_STM32H7_DUAL_CORE)
while (LL_HSEM_1StepLock(HSEM, LL_HSEM_ID_1)) {
}
#endif /* CONFIG_STM32H7_DUAL_CORE */
/* figure out if we can map the requested GPIO /* figure out if we can map the requested GPIO
* configuration * configuration
*/ */
err = gpio_stm32_flags_to_conf(flags, &pincfg); err = gpio_stm32_flags_to_conf(flags, &pincfg);
if (err != 0) { if (err != 0) {
goto release_lock; goto exit;
} }
if ((flags & GPIO_OUTPUT) != 0) { if ((flags & GPIO_OUTPUT) != 0) {
@ -414,11 +421,7 @@ static int gpio_stm32_config(struct device *dev,
gpio_stm32_configure(cfg->base, pin, pincfg, 0); gpio_stm32_configure(cfg->base, pin, pincfg, 0);
release_lock: exit:
#if defined(CONFIG_STM32H7_DUAL_CORE)
LL_HSEM_ReleaseLock(HSEM, LL_HSEM_ID_1, 0);
#endif /* CONFIG_STM32H7_DUAL_CORE */
return err; return err;
} }
@ -430,11 +433,6 @@ static int gpio_stm32_pin_interrupt_configure(struct device *dev,
int edge = 0; int edge = 0;
int err = 0; int err = 0;
#if defined(CONFIG_STM32H7_DUAL_CORE)
while (LL_HSEM_1StepLock(HSEM, LL_HSEM_ID_1)) {
}
#endif /* CONFIG_STM32H7_DUAL_CORE */
if (mode == GPIO_INT_MODE_DISABLED) { if (mode == GPIO_INT_MODE_DISABLED) {
if (gpio_stm32_get_exti_source(pin) == cfg->port) { if (gpio_stm32_get_exti_source(pin) == cfg->port) {
stm32_exti_disable(pin); stm32_exti_disable(pin);
@ -442,18 +440,18 @@ static int gpio_stm32_pin_interrupt_configure(struct device *dev,
stm32_exti_trigger(pin, STM32_EXTI_TRIG_NONE); stm32_exti_trigger(pin, STM32_EXTI_TRIG_NONE);
} }
/* else: No irq source configured for pin. Nothing to disable */ /* else: No irq source configured for pin. Nothing to disable */
goto release_lock; goto exit;
} }
/* Level trigger interrupts not supported */ /* Level trigger interrupts not supported */
if (mode == GPIO_INT_MODE_LEVEL) { if (mode == GPIO_INT_MODE_LEVEL) {
err = -ENOTSUP; err = -ENOTSUP;
goto release_lock; goto exit;
} }
if (stm32_exti_set_callback(pin, gpio_stm32_isr, dev) != 0) { if (stm32_exti_set_callback(pin, gpio_stm32_isr, dev) != 0) {
err = -EBUSY; err = -EBUSY;
goto release_lock; goto exit;
} }
gpio_stm32_enable_int(cfg->port, pin); gpio_stm32_enable_int(cfg->port, pin);
@ -474,11 +472,7 @@ static int gpio_stm32_pin_interrupt_configure(struct device *dev,
stm32_exti_enable(pin); stm32_exti_enable(pin);
release_lock: exit:
#if defined(CONFIG_STM32H7_DUAL_CORE)
LL_HSEM_ReleaseLock(HSEM, LL_HSEM_ID_1, 0);
#endif /* CONFIG_STM32H7_DUAL_CORE */
return err; return err;
} }
@ -529,6 +523,7 @@ static int gpio_stm32_init(struct device *device)
if (cfg->port == STM32_PORTG) { if (cfg->port == STM32_PORTG) {
/* Port G[15:2] requires external power supply */ /* Port G[15:2] requires external power supply */
/* Cf: L4XX RM, §5.1 Power supplies */ /* Cf: L4XX RM, §5.1 Power supplies */
z_stm32_hsem_lock(CFG_HW_RCC_SEMID, HSEM_LOCK_DEFAULT_RETRY);
if (LL_APB1_GRP1_IsEnabledClock(LL_APB1_GRP1_PERIPH_PWR)) { if (LL_APB1_GRP1_IsEnabledClock(LL_APB1_GRP1_PERIPH_PWR)) {
LL_PWR_EnableVddIO2(); LL_PWR_EnableVddIO2();
} else { } else {
@ -536,6 +531,7 @@ static int gpio_stm32_init(struct device *device)
LL_PWR_EnableVddIO2(); LL_PWR_EnableVddIO2();
LL_APB1_GRP1_DisableClock(LL_APB1_GRP1_PERIPH_PWR); LL_APB1_GRP1_DisableClock(LL_APB1_GRP1_PERIPH_PWR);
} }
z_stm32_hsem_unlock(CFG_HW_RCC_SEMID);
} }
#endif /* PWR_CR2_IOSV */ #endif /* PWR_CR2_IOSV */

View file

@ -22,6 +22,8 @@
#include <sys/__assert.h> #include <sys/__assert.h>
#include <drivers/interrupt_controller/exti_stm32.h> #include <drivers/interrupt_controller/exti_stm32.h>
#include "stm32_hsem.h"
#if defined(CONFIG_SOC_SERIES_STM32F0X) || \ #if defined(CONFIG_SOC_SERIES_STM32F0X) || \
defined(CONFIG_SOC_SERIES_STM32L0X) || \ defined(CONFIG_SOC_SERIES_STM32L0X) || \
defined(CONFIG_SOC_SERIES_STM32G0X) defined(CONFIG_SOC_SERIES_STM32G0X)
@ -118,6 +120,8 @@ void stm32_exti_enable(int line)
void stm32_exti_disable(int line) void stm32_exti_disable(int line)
{ {
z_stm32_hsem_lock(CFG_HW_EXTI_SEMID, HSEM_LOCK_DEFAULT_RETRY);
if (line < 32) { if (line < 32) {
#if defined(CONFIG_SOC_SERIES_STM32H7X) && defined(CONFIG_CPU_CORTEX_M4) #if defined(CONFIG_SOC_SERIES_STM32H7X) && defined(CONFIG_CPU_CORTEX_M4)
LL_C2_EXTI_DisableIT_0_31(1 << line); LL_C2_EXTI_DisableIT_0_31(1 << line);
@ -127,6 +131,7 @@ void stm32_exti_disable(int line)
} else { } else {
__ASSERT_NO_MSG(line); __ASSERT_NO_MSG(line);
} }
z_stm32_hsem_unlock(CFG_HW_EXTI_SEMID);
} }
/** /**
@ -183,6 +188,8 @@ void stm32_exti_trigger(int line, int trigger)
__ASSERT_NO_MSG(line); __ASSERT_NO_MSG(line);
} }
z_stm32_hsem_lock(CFG_HW_EXTI_SEMID, HSEM_LOCK_DEFAULT_RETRY);
switch (trigger) { switch (trigger) {
case STM32_EXTI_TRIG_NONE: case STM32_EXTI_TRIG_NONE:
LL_EXTI_DisableRisingTrig_0_31(1 << line); LL_EXTI_DisableRisingTrig_0_31(1 << line);
@ -203,6 +210,7 @@ void stm32_exti_trigger(int line, int trigger)
default: default:
__ASSERT_NO_MSG(trigger); __ASSERT_NO_MSG(trigger);
} }
z_stm32_hsem_unlock(CFG_HW_EXTI_SEMID);
} }
/** /**

View file

@ -2,3 +2,5 @@
add_subdirectory(${SOC_SERIES}) add_subdirectory(${SOC_SERIES})
add_subdirectory(common) add_subdirectory(common)
zephyr_include_directories(common)

View file

@ -0,0 +1,96 @@
/*
* Copyright (c) 2019 STMicroelectronics
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_INCLUDE_DRIVERS_HSEM_STM32_HSEM_H_
#define ZEPHYR_INCLUDE_DRIVERS_HSEM_STM32_HSEM_H_
#include <soc.h>
#include <kernel.h>
#if defined(CONFIG_SOC_SERIES_STM32WBX) || defined(CONFIG_STM32H7_DUAL_CORE)
/** HW semaphore Complement ID list defined in hw_conf.h from STM32WB
* and used also for H7 dualcore targets
*/
/** Index of the semaphore used to manage the entry Stop Mode procedure */
#define CFG_HW_ENTRY_STOP_MODE_SEMID 4U
#define CFG_HW_ENTRY_STOP_MODE_MASK_SEMID (1U << CFG_HW_ENTRY_STOP_MODE_SEMID)
/** Index of the semaphore used to access the RCC and PWR */
#define CFG_HW_RCC_SEMID 3U
/** Index of the semaphore used to access the FLASH */
#define CFG_HW_FLASH_SEMID 2U
/** Index of the semaphore used to access the PKA */
#define CFG_HW_PKA_SEMID 1U
/** Index of the semaphore used to access the RNG */
#define CFG_HW_RNG_SEMID 0U
/** Index of the semaphore used to access GPIO */
#define CFG_HW_GPIO_SEMID 5U
/** Index of the semaphore used to access the EXTI */
#define CFG_HW_EXTI_SEMID 6U
#elif defined(CONFIG_SOC_SERIES_STM32MP1X)
/** HW semaphore from STM32MP1
* EXTI and GPIO are inherited from STM32MP1 Linux.
* Other SEMID are not used by linux and must not be used here,
* but reserved for MPU.
*/
/** Index of the semaphore used to access GPIO */
#define CFG_HW_GPIO_SEMID 0U
/** Index of the semaphore used to access the EXTI */
#define CFG_HW_EXTI_SEMID 1U
#else
/** Fake semaphore ID definition for compilation purpose only */
#define CFG_HW_RCC_SEMID 0U
#define CFG_HW_FLASH_SEMID 0U
#define CFG_HW_PKA_SEMID 0U
#define CFG_HW_RNG_SEMID 0u
#define CFG_HW_GPIO_SEMID 0U
#define CFG_HW_EXTI_SEMID 0U
#endif /* CONFIG_SOC_SERIES_STM32WBX || CONFIG_STM32H7_DUAL_CORE */
/** Hardware Semaphore wait forever value */
#define HSEM_LOCK_WAIT_FOREVER 0xFFFFFFFFU
/** Hardware Semaphore default retry value */
#define HSEM_LOCK_DEFAULT_RETRY 0xFFFFU
/**
* @brief Lock Hardware Semaphore
*/
static inline void z_stm32_hsem_lock(uint32_t hsem, uint32_t retry)
{
#if defined(CONFIG_SOC_SERIES_STM32WBX) || defined(CONFIG_STM32H7_DUAL_CORE) \
|| defined(CONFIG_SOC_SERIES_STM32MP1X)
while (LL_HSEM_1StepLock(HSEM, hsem)) {
if (retry != HSEM_LOCK_WAIT_FOREVER) {
retry--;
if (retry == 0) {
k_panic();
}
}
}
#endif /* CONFIG_SOC_SERIES_STM32WBX || CONFIG_STM32H7_DUAL_CORE || ... */
}
/**
* @brief Release Hardware Semaphore
*/
static inline void z_stm32_hsem_unlock(uint32_t hsem)
{
#if defined(CONFIG_SOC_SERIES_STM32WBX) || defined(CONFIG_STM32H7_DUAL_CORE) \
|| defined(CONFIG_SOC_SERIES_STM32MP1X)
LL_HSEM_ReleaseLock(HSEM, hsem, 0);
#endif /* CONFIG_SOC_SERIES_STM32WBX || CONFIG_STM32H7_DUAL_CORE || ... */
}
#endif /* ZEPHYR_INCLUDE_DRIVERS_HSEM_STM32_HSEM_H_ */

View file

@ -18,12 +18,6 @@
#include <devicetree.h> #include <devicetree.h>
#ifdef CONFIG_STM32H7_DUAL_CORE #ifdef CONFIG_STM32H7_DUAL_CORE
#define LL_HSEM_ID_0 (0U) /* HW semaphore 0 */
#define LL_HSEM_MASK_0 (1 << LL_HSEM_ID_0)
#define LL_HSEM_ID_1 (1U) /* HW semaphore 1 */
#define LL_HSEM_MASK_1 (1 << LL_HSEM_ID_1)
#include <stm32h7xx_ll_hsem.h> #include <stm32h7xx_ll_hsem.h>
#ifdef CONFIG_CPU_CORTEX_M4 #ifdef CONFIG_CPU_CORTEX_M4

View file

@ -15,6 +15,7 @@
#include <soc.h> #include <soc.h>
#include <arch/cpu.h> #include <arch/cpu.h>
#include <arch/arm/aarch32/cortex_m/cmsis.h> #include <arch/arm/aarch32/cortex_m/cmsis.h>
#include "stm32_hsem.h"
#if defined(CONFIG_STM32H7_BOOT_CM4_CM7) #if defined(CONFIG_STM32H7_BOOT_CM4_CM7)
void stm32h7_m4_boot_stop(void) void stm32h7_m4_boot_stop(void)
@ -77,13 +78,13 @@ static int stm32h7_m4_init(struct device *arg)
#if defined(CONFIG_STM32H7_BOOT_CM4_CM7) #if defined(CONFIG_STM32H7_BOOT_CM4_CM7)
/* Activate HSEM notification for Cortex-M4*/ /* Activate HSEM notification for Cortex-M4*/
LL_HSEM_EnableIT_C2IER(HSEM, LL_HSEM_MASK_0); LL_HSEM_EnableIT_C2IER(HSEM, CFG_HW_ENTRY_STOP_MODE_MASK_SEMID);
/* Boot and enter stop mode */ /* Boot and enter stop mode */
stm32h7_m4_boot_stop(); stm32h7_m4_boot_stop();
/* Clear HSEM flag */ /* Clear HSEM flag */
LL_HSEM_ClearFlag_C2ICR(HSEM, LL_HSEM_MASK_0); LL_HSEM_ClearFlag_C2ICR(HSEM, CFG_HW_ENTRY_STOP_MODE_MASK_SEMID);
#endif /* CONFIG_STM32H7_BOOT_CM4_CM7 */ #endif /* CONFIG_STM32H7_BOOT_CM4_CM7 */
return 0; return 0;

View file

@ -15,6 +15,7 @@
#include <soc.h> #include <soc.h>
#include <arch/cpu.h> #include <arch/cpu.h>
#include <arch/arm/aarch32/cortex_m/cmsis.h> #include <arch/arm/aarch32/cortex_m/cmsis.h>
#include "stm32_hsem.h"
#if defined(CONFIG_STM32H7_DUAL_CORE) #if defined(CONFIG_STM32H7_DUAL_CORE)
static int stm32h7_m4_wakeup(struct device *arg) static int stm32h7_m4_wakeup(struct device *arg)
@ -32,9 +33,9 @@ static int stm32h7_m4_wakeup(struct device *arg)
*/ */
/*Take HSEM */ /*Take HSEM */
LL_HSEM_1StepLock(HSEM, LL_HSEM_ID_0); LL_HSEM_1StepLock(HSEM, CFG_HW_ENTRY_STOP_MODE_SEMID);
/*Release HSEM in order to notify the CPU2(CM4)*/ /*Release HSEM in order to notify the CPU2(CM4)*/
LL_HSEM_ReleaseLock(HSEM, LL_HSEM_ID_0, 0); LL_HSEM_ReleaseLock(HSEM, CFG_HW_ENTRY_STOP_MODE_SEMID, 0);
/* wait until CPU2 wakes up from stop mode */ /* wait until CPU2 wakes up from stop mode */
timeout = 0xFFFF; timeout = 0xFFFF;

View file

@ -24,6 +24,8 @@
/* Add include for DTS generated information */ /* Add include for DTS generated information */
#include <devicetree.h> #include <devicetree.h>
#include <stm32mp1xx_ll_hsem.h>
#ifdef CONFIG_EXTI_STM32 #ifdef CONFIG_EXTI_STM32
#include <stm32mp1xx_ll_exti.h> #include <stm32mp1xx_ll_exti.h>
#endif #endif

View file

@ -26,6 +26,8 @@
/* Add include for DTS generated information */ /* Add include for DTS generated information */
#include <devicetree.h> #include <devicetree.h>
#include <stm32wbxx_ll_hsem.h>
#ifdef CONFIG_GPIO_STM32 #ifdef CONFIG_GPIO_STM32
#include <stm32wbxx_ll_gpio.h> #include <stm32wbxx_ll_gpio.h>
#endif #endif