arm: stm32l0: Add support for stm32l0 soc
Add necessary kconfig and minimal device tree support for the stm32l072xz variants. Signed-off-by: Endre Karlson <endre.karlson@gmail.com>
This commit is contained in:
parent
3c789e6ae7
commit
deeb74651b
13 changed files with 497 additions and 0 deletions
5
arch/arm/soc/st_stm32/stm32l0/CMakeLists.txt
Normal file
5
arch/arm/soc/st_stm32/stm32l0/CMakeLists.txt
Normal file
|
@ -0,0 +1,5 @@
|
|||
zephyr_include_directories(${ZEPHYR_BASE}/drivers)
|
||||
zephyr_sources(
|
||||
soc.c
|
||||
)
|
||||
zephyr_sources_ifdef(CONFIG_GPIO soc_gpio.c)
|
20
arch/arm/soc/st_stm32/stm32l0/Kconfig.defconfig.series
Normal file
20
arch/arm/soc/st_stm32/stm32l0/Kconfig.defconfig.series
Normal file
|
@ -0,0 +1,20 @@
|
|||
# Kconfig - ST Microelectronics STM32L0 MCU line
|
||||
#
|
||||
# Copyright (c) 2018 Endre Karlson <endre.karlson@gmail.com>
|
||||
#
|
||||
# SPDX-License-Identifier: Apache-2.0
|
||||
#
|
||||
|
||||
if SOC_SERIES_STM32L0X
|
||||
|
||||
source "arch/arm/soc/st_stm32/stm32l0/Kconfig.defconfig.stm32l0*"
|
||||
|
||||
config SOC_SERIES
|
||||
default stm32l0
|
||||
|
||||
if GPIO_STM32
|
||||
|
||||
endif # GPIO_STM32
|
||||
|
||||
|
||||
endif # SOC_SERIES_STM32L0X
|
31
arch/arm/soc/st_stm32/stm32l0/Kconfig.defconfig.stm32l072xz
Normal file
31
arch/arm/soc/st_stm32/stm32l0/Kconfig.defconfig.stm32l072xz
Normal file
|
@ -0,0 +1,31 @@
|
|||
# Kconfig - ST Microelectronics STM32L072XB MCU
|
||||
#
|
||||
# Copyright (c) 2018 Endre Karlson <endre.karlson@gmail.com>
|
||||
#
|
||||
# SPDX-License-Identifier: Apache-2.0
|
||||
#
|
||||
|
||||
if SOC_STM32L072XZ
|
||||
|
||||
config SOC
|
||||
string
|
||||
default stm32l072xx
|
||||
|
||||
config NUM_IRQS
|
||||
int
|
||||
default 32
|
||||
|
||||
if GPIO_STM32
|
||||
|
||||
config GPIO_STM32_PORTD
|
||||
default y
|
||||
|
||||
config GPIO_STM32_PORTE
|
||||
default y
|
||||
|
||||
config GPIO_STM32_PORTH
|
||||
default y
|
||||
|
||||
endif # GPIO_STM32
|
||||
|
||||
endif # SOC_STM32L072XZ
|
19
arch/arm/soc/st_stm32/stm32l0/Kconfig.series
Normal file
19
arch/arm/soc/st_stm32/stm32l0/Kconfig.series
Normal file
|
@ -0,0 +1,19 @@
|
|||
# Kconfig - ST Microelectronics STM32L4 MCU series
|
||||
#
|
||||
# Copyright (c) 2018 Endre Karlson <endre.karlson@gmail.com>
|
||||
#
|
||||
# SPDX-License-Identifier: Apache-2.0
|
||||
#
|
||||
|
||||
config SOC_SERIES_STM32L0X
|
||||
bool "STM32L0x Series MCU"
|
||||
select CPU_CORTEX_M
|
||||
select CPU_CORTEX_M0PLUS
|
||||
select CPU_CORTEX_M_HAS_VTOR
|
||||
select SOC_FAMILY_STM32
|
||||
select SYS_POWER_LOW_POWER_STATE_SUPPORTED
|
||||
select HAS_STM32CUBE
|
||||
select CPU_HAS_SYSTICK
|
||||
select CLOCK_CONTROL_STM32_CUBE if CLOCK_CONTROL
|
||||
help
|
||||
Enable support for STM32L0 MCU series
|
15
arch/arm/soc/st_stm32/stm32l0/Kconfig.soc
Normal file
15
arch/arm/soc/st_stm32/stm32l0/Kconfig.soc
Normal file
|
@ -0,0 +1,15 @@
|
|||
# Kconfig - ST Microelectronics STM32L0 MCU line
|
||||
#
|
||||
# Copyright (c) 2018 Endre Karlson <endre.karlson@gmail.com>
|
||||
#
|
||||
# SPDX-License-Identifier: Apache-2.0
|
||||
#
|
||||
|
||||
choice
|
||||
prompt "STM32L0x MCU Selection"
|
||||
depends on SOC_SERIES_STM32L0X
|
||||
|
||||
config SOC_STM32L072XZ
|
||||
bool "STM32L072XZ"
|
||||
|
||||
endchoice
|
17
arch/arm/soc/st_stm32/stm32l0/dts.fixup
Normal file
17
arch/arm/soc/st_stm32/stm32l0/dts.fixup
Normal file
|
@ -0,0 +1,17 @@
|
|||
/* SoC level DTS fixup file */
|
||||
|
||||
#define CONFIG_NUM_IRQ_PRIO_BITS ARM_V6M_NVIC_E000E100_ARM_NUM_IRQ_PRIORITY_BITS
|
||||
|
||||
#define CONFIG_UART_STM32_PORT_1_BASE_ADDRESS ST_STM32_USART_40013800_BASE_ADDRESS
|
||||
#define CONFIG_UART_STM32_PORT_1_BAUD_RATE ST_STM32_USART_40013800_CURRENT_SPEED
|
||||
#define CONFIG_UART_STM32_PORT_1_IRQ_PRI ST_STM32_USART_40013800_IRQ_0_PRIORITY
|
||||
#define CONFIG_UART_STM32_PORT_1_NAME ST_STM32_USART_40013800_LABEL
|
||||
#define PORT_1_IRQ ST_STM32_USART_40013800_IRQ_0
|
||||
|
||||
#define CONFIG_UART_STM32_PORT_2_BASE_ADDRESS ST_STM32_USART_40004400_BASE_ADDRESS
|
||||
#define CONFIG_UART_STM32_PORT_2_BAUD_RATE ST_STM32_USART_40004400_CURRENT_SPEED
|
||||
#define CONFIG_UART_STM32_PORT_2_IRQ_PRI ST_STM32_USART_40004400_IRQ_0_PRIORITY
|
||||
#define CONFIG_UART_STM32_PORT_2_NAME ST_STM32_USART_40004400_LABEL
|
||||
#define PORT_2_IRQ ST_STM32_USART_40004400_IRQ_0
|
||||
|
||||
/* End of SoC Level DTS fixup file */
|
54
arch/arm/soc/st_stm32/stm32l0/gpio_registers.h
Normal file
54
arch/arm/soc/st_stm32/stm32l0/gpio_registers.h
Normal file
|
@ -0,0 +1,54 @@
|
|||
/*
|
||||
* Copyright (c) 2018 Endre Karlson <endre.karlson@gmail.com>
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
#ifndef _STM32L0X_GPIO_REGISTERS_H_
|
||||
#define _STM32L0X_GPIO_REGISTERS_H_
|
||||
|
||||
/**
|
||||
* @brief
|
||||
*
|
||||
* Based on reference manual:
|
||||
* STM32L0X advanced ARM ® -based 32-bit MCUs
|
||||
|
||||
*
|
||||
* Chapter 9: General-purpose I/Os (GPIO)
|
||||
* Chapter 10: System configuration controller (SYSCFG)
|
||||
*/
|
||||
|
||||
struct stm32l0x_gpio {
|
||||
u32_t moder;
|
||||
u32_t otyper;
|
||||
u32_t ospeedr;
|
||||
u32_t pupdr;
|
||||
u32_t idr;
|
||||
u32_t odr;
|
||||
u32_t bsrr;
|
||||
u32_t lckr;
|
||||
u32_t afr[2];
|
||||
u32_t brr;
|
||||
};
|
||||
|
||||
union syscfg_exticr {
|
||||
u32_t val;
|
||||
struct {
|
||||
u16_t exti;
|
||||
u16_t rsvd__16_31;
|
||||
} bit;
|
||||
};
|
||||
|
||||
struct stm32l0x_syscfg {
|
||||
u32_t cfgr1;
|
||||
u32_t cfgr2;
|
||||
union syscfg_exticr exticr1;
|
||||
union syscfg_exticr exticr2;
|
||||
union syscfg_exticr exticr3;
|
||||
union syscfg_exticr exticr4;
|
||||
u32_t comp1_ctrl;
|
||||
u32_t comp2_ctrl;
|
||||
u32_t cfgr3;
|
||||
};
|
||||
|
||||
#endif /* _STM32L0X_GPIO_REGISTERS_H_ */
|
9
arch/arm/soc/st_stm32/stm32l0/linker.ld
Normal file
9
arch/arm/soc/st_stm32/stm32l0/linker.ld
Normal file
|
@ -0,0 +1,9 @@
|
|||
/* linker.ld - Linker command/script file */
|
||||
|
||||
/*
|
||||
* Copyright (c) 2018 Endre Karlson <endre.karlson@gmail.com>
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
#include <arch/arm/cortex_m/scripts/linker.ld>
|
65
arch/arm/soc/st_stm32/stm32l0/soc.c
Normal file
65
arch/arm/soc/st_stm32/stm32l0/soc.c
Normal file
|
@ -0,0 +1,65 @@
|
|||
/*
|
||||
* Copyright (c) 2018 Endre Karlson <endre.karlson@gmail.com>
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file
|
||||
* @brief System/hardware module for STM32L0 processor
|
||||
*/
|
||||
|
||||
#include <kernel.h>
|
||||
#include <device.h>
|
||||
#include <init.h>
|
||||
#include <soc.h>
|
||||
#include <arch/cpu.h>
|
||||
#include <cortex_m/exc.h>
|
||||
#include <linker/linker-defs.h>
|
||||
#include <string.h>
|
||||
|
||||
|
||||
/**
|
||||
* @brief This function configures the source of stm32cube time base.
|
||||
* Cube HAL expects a 1ms tick which matches with k_uptime_get_32.
|
||||
* Tick interrupt priority is not used
|
||||
* @return HAL status
|
||||
*/
|
||||
uint32_t HAL_GetTick(void)
|
||||
{
|
||||
return k_uptime_get_32();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Perform basic hardware initialization at boot.
|
||||
*
|
||||
* This needs to be run from the very beginning.
|
||||
* So the init priority has to be 0 (zero).
|
||||
*
|
||||
* @return 0
|
||||
*/
|
||||
static int stm32l0_init(struct device *arg)
|
||||
{
|
||||
u32_t key;
|
||||
|
||||
ARG_UNUSED(arg);
|
||||
|
||||
key = irq_lock();
|
||||
|
||||
_ClearFaults();
|
||||
|
||||
/* Install default handler that simply resets the CPU
|
||||
* if configured in the kernel, NOP otherwise
|
||||
*/
|
||||
NMI_INIT();
|
||||
|
||||
irq_unlock(key);
|
||||
|
||||
/* Update CMSIS SystemCoreClock variable (HCLK) */
|
||||
/* At reset, system core clock is set to 2.1 MHz from MSI */
|
||||
SystemCoreClock = 2097152;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
SYS_INIT(stm32l0_init, PRE_KERNEL_1, 0);
|
47
arch/arm/soc/st_stm32/stm32l0/soc.h
Normal file
47
arch/arm/soc/st_stm32/stm32l0/soc.h
Normal file
|
@ -0,0 +1,47 @@
|
|||
/*
|
||||
* Copyright (c) 2018 Endre Karlson <endre.karlson@gmail.com>
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file SoC configuration macros for the STM32L0 family processors.
|
||||
*
|
||||
* Based on reference manual:
|
||||
* STM32L0X advanced ARM ® -based 32-bit MCUs
|
||||
*
|
||||
* Chapter 2.2: Memory organization
|
||||
*/
|
||||
|
||||
|
||||
#ifndef _STM32L0_SOC_H_
|
||||
#define _STM32L0_SOC_H_
|
||||
|
||||
#define GPIO_REG_SIZE 0x400
|
||||
/* base address for where GPIO registers start */
|
||||
#define GPIO_PORTS_BASE (GPIOA_BASE)
|
||||
|
||||
#ifndef _ASMLANGUAGE
|
||||
|
||||
#include <device.h>
|
||||
#include <misc/util.h>
|
||||
#include <random/rand32.h>
|
||||
|
||||
#include <stm32l0xx.h>
|
||||
|
||||
#include "soc_irq.h"
|
||||
|
||||
#ifdef CONFIG_SERIAL_HAS_DRIVER
|
||||
#include <stm32l0xx_ll_usart.h>
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_CLOCK_CONTROL_STM32_CUBE
|
||||
#include <stm32l0xx_ll_utils.h>
|
||||
#include <stm32l0xx_ll_bus.h>
|
||||
#include <stm32l0xx_ll_rcc.h>
|
||||
#include <stm32l0xx_ll_system.h>
|
||||
#endif /* CONFIG_CLOCK_CONTROL_STM32_CUBE */
|
||||
|
||||
#endif /* !_ASMLANGUAGE */
|
||||
|
||||
#endif /* _STM32L0_SOC_H_ */
|
144
arch/arm/soc/st_stm32/stm32l0/soc_gpio.c
Normal file
144
arch/arm/soc/st_stm32/stm32l0/soc_gpio.c
Normal file
|
@ -0,0 +1,144 @@
|
|||
/*
|
||||
* Copyright (c) 2018 Endre Karlson <endre.karlson@gmail.com>
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief
|
||||
*
|
||||
* Based on reference manual:
|
||||
* STM32F030x4/x6/x8/xC,
|
||||
* STM32F070x6/xB advanced ARM ® -based MCUs
|
||||
*
|
||||
* Chapter 9: General-purpose I/Os (GPIO)
|
||||
*/
|
||||
|
||||
#include <errno.h>
|
||||
|
||||
#include <device.h>
|
||||
#include "soc.h"
|
||||
#include "soc_registers.h"
|
||||
#include <gpio.h>
|
||||
#include <gpio/gpio_stm32.h>
|
||||
|
||||
int stm32_gpio_flags_to_conf(int flags, int *pincfg)
|
||||
{
|
||||
int direction = flags & GPIO_DIR_MASK;
|
||||
int pud = flags & GPIO_PUD_MASK;
|
||||
|
||||
if (!pincfg) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
if (direction == GPIO_DIR_OUT) {
|
||||
*pincfg = STM32_MODER_OUTPUT_MODE;
|
||||
} else {
|
||||
/* pull-{up,down} maybe? */
|
||||
*pincfg = STM32_MODER_INPUT_MODE;
|
||||
if (pud == GPIO_PUD_PULL_UP) {
|
||||
*pincfg = *pincfg | STM32_PUPDR_PULL_UP;
|
||||
} else if (pud == GPIO_PUD_PULL_DOWN) {
|
||||
*pincfg = *pincfg | STM32_PUPDR_PULL_DOWN;
|
||||
} else {
|
||||
/* floating */
|
||||
*pincfg = *pincfg | STM32_PUPDR_NO_PULL;
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int stm32_gpio_configure(u32_t *base_addr, int pin, int conf, int altf)
|
||||
{
|
||||
volatile struct stm32l0x_gpio *gpio =
|
||||
(struct stm32l0x_gpio *)(base_addr);
|
||||
unsigned int mode, otype, ospeed, pupd;
|
||||
unsigned int pin_shift = pin << 1;
|
||||
unsigned int afr_bank = pin / 8;
|
||||
unsigned int afr_shift = (pin % 8) << 2;
|
||||
u32_t scratch;
|
||||
|
||||
mode = (conf >> STM32_MODER_SHIFT) & STM32_MODER_MASK;
|
||||
otype = (conf >> STM32_OTYPER_SHIFT) & STM32_OTYPER_MASK;
|
||||
ospeed = (conf >> STM32_OSPEEDR_SHIFT) & STM32_OSPEEDR_MASK;
|
||||
pupd = (conf >> STM32_PUPDR_SHIFT) & STM32_PUPDR_MASK;
|
||||
|
||||
scratch = gpio->moder & ~(STM32_MODER_MASK << pin_shift);
|
||||
gpio->moder = scratch | (mode << pin_shift);
|
||||
|
||||
scratch = gpio->ospeedr & ~(STM32_OSPEEDR_MASK << pin_shift);
|
||||
gpio->ospeedr = scratch | (ospeed << pin_shift);
|
||||
|
||||
scratch = gpio->otyper & ~(STM32_OTYPER_MASK << pin);
|
||||
gpio->otyper = scratch | (otype << pin);
|
||||
|
||||
scratch = gpio->pupdr & ~(STM32_PUPDR_MASK << pin_shift);
|
||||
gpio->pupdr = scratch | (pupd << pin_shift);
|
||||
|
||||
scratch = gpio->afr[afr_bank] & ~(STM32_AFR_MASK << afr_shift);
|
||||
gpio->afr[afr_bank] = scratch | (altf << afr_shift);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int stm32_gpio_set(u32_t *base, int pin, int value)
|
||||
{
|
||||
struct stm32l0x_gpio *gpio = (struct stm32l0x_gpio *)base;
|
||||
|
||||
int pval = 1 << (pin & 0xf);
|
||||
|
||||
if (value) {
|
||||
gpio->odr |= pval;
|
||||
} else {
|
||||
gpio->odr &= ~pval;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int stm32_gpio_get(u32_t *base, int pin)
|
||||
{
|
||||
struct stm32l0x_gpio *gpio = (struct stm32l0x_gpio *)base;
|
||||
|
||||
return (gpio->idr >> pin) & 0x1;
|
||||
}
|
||||
|
||||
int stm32_gpio_enable_int(int port, int pin)
|
||||
{
|
||||
volatile struct stm32l0x_syscfg *syscfg =
|
||||
(struct stm32l0x_syscfg *)SYSCFG_BASE;
|
||||
volatile union syscfg_exticr *exticr;
|
||||
|
||||
/* Enable System Configuration Controller clock. */
|
||||
struct device *clk =
|
||||
device_get_binding(STM32_CLOCK_CONTROL_NAME);
|
||||
|
||||
struct stm32_pclken pclken = {
|
||||
.bus = STM32_CLOCK_BUS_APB2,
|
||||
.enr = LL_APB2_GRP1_PERIPH_SYSCFG
|
||||
};
|
||||
|
||||
clock_control_on(clk, (clock_control_subsys_t *) &pclken);
|
||||
|
||||
int shift = 0;
|
||||
|
||||
if (pin <= 3) {
|
||||
exticr = &syscfg->exticr1;
|
||||
} else if (pin <= 7) {
|
||||
exticr = &syscfg->exticr2;
|
||||
} else if (pin <= 11) {
|
||||
exticr = &syscfg->exticr3;
|
||||
} else if (pin <= 15) {
|
||||
exticr = &syscfg->exticr4;
|
||||
} else {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
shift = 4 * (pin % 4);
|
||||
|
||||
exticr->val &= ~(0xf << shift);
|
||||
exticr->val |= port << shift;
|
||||
|
||||
return 0;
|
||||
}
|
58
arch/arm/soc/st_stm32/stm32l0/soc_irq.h
Normal file
58
arch/arm/soc/st_stm32/stm32l0/soc_irq.h
Normal file
|
@ -0,0 +1,58 @@
|
|||
/*
|
||||
* Copyright (c) 2018 Endre Karlson <endre.karlson@gmail.com>
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file Interrupt numbers for STM32L0 family processors.
|
||||
*
|
||||
* Based on reference manual:
|
||||
* STM32L0X advanced ARM ® -based 32-bit MCUs
|
||||
*
|
||||
* Chapter 11.1.3: Interrupt and exception vectors
|
||||
*/
|
||||
|
||||
|
||||
#ifndef _STM32L0_SOC_IRQ_H_
|
||||
#define _STM32L0_SOC_IRQ_H_
|
||||
|
||||
/* FIXME: Remove when use of enum line number in IRQ_CONNECT is
|
||||
* made possible by ZEP-1165.
|
||||
* soc_irq.h, once it is possible, should be removed.
|
||||
*/
|
||||
|
||||
#define STM32L0_IRQ_WWDG 0
|
||||
#define STM32L0_IRQ_PVD 1
|
||||
#define STM32L0_IRQ_RTC 2
|
||||
#define STM32L0_IRQ_FLASH 3
|
||||
#define STM32L0_IRQ_RCC 4
|
||||
#define STM32L0_IRQ_EXTI0_1 5
|
||||
#define STM32L0_IRQ_EXTI2_3 6
|
||||
#define STM32L0_IRQ_EXTI4_15 7
|
||||
#define STM32L0_IRQ_TSC 8
|
||||
#define STM32L0_IRQ_DMA_CH1 9
|
||||
#define STM32L0_IRQ_DMA_CH2_3 10
|
||||
#define STM32L0_IRQ_DMA_CH4_7 11
|
||||
#define STM32L0_IRQ_ADC 12
|
||||
#define STM32L0_IRQ_LPTIM1 13
|
||||
#define STM32L0_IRQ_USART_4_5 14
|
||||
#define STM32L0_IRQ_TIM2 15
|
||||
#define STM32L0_IRQ_TIM3 16
|
||||
#define STM32L0_IRQ_TIM6_DAC 17
|
||||
#define STM32L0_IRQ_TIM7 18
|
||||
/* reserved */
|
||||
#define STM32L0_IRQ_TIM21 20
|
||||
#define STM32L0_IRQ_I2C3 21
|
||||
#define STM32L0_IRQ_TIM22 22
|
||||
#define STM32L0_IRQ_I2C1 23
|
||||
#define STM32L0_IRQ_I2C2 24
|
||||
#define STM32L0_IRQ_SPI1 25
|
||||
#define STM32L0_IRQ_SPI2 26
|
||||
#define STM32L0_IRQ_USART1 27
|
||||
#define STM32L0_IRQ_USART2 28
|
||||
#define STM32L0_IRQ_LPUART1_AES_RNG 29
|
||||
#define STM32L0_IRQ_LCD 30
|
||||
#define STM32L0_IRQ_USB 31
|
||||
|
||||
#endif /* _STM32L0_SOC_IRQ_H_ */
|
13
arch/arm/soc/st_stm32/stm32l0/soc_registers.h
Normal file
13
arch/arm/soc/st_stm32/stm32l0/soc_registers.h
Normal file
|
@ -0,0 +1,13 @@
|
|||
/*
|
||||
* Copyright (c) 2018 Endre Karlson <endre.karlson@gmail.com>
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
#ifndef _STM32L0X_SOC_REGISTERS_H_
|
||||
#define _STM32L0X_SOC_REGISTERS_H_
|
||||
|
||||
/* include register mapping headers */
|
||||
#include "gpio_registers.h"
|
||||
|
||||
#endif /* _STM32L0X_SOC_REGISTERS_H_ */
|
Loading…
Add table
Add a link
Reference in a new issue