arch: arm: soc: provide support for stm32f0.

Fixes #3923

Signed-off-by: Maciej Debski <maciej.debski@rndity.com>
Signed-off-by: Neil Armstrong <narmstrong@baylibre.com>
This commit is contained in:
Maciej Debski 2017-08-09 11:20:33 +02:00 committed by Kumar Gala
parent cfe28f579e
commit db8fd88fab
13 changed files with 550 additions and 0 deletions

View File

@ -0,0 +1,22 @@
# Kconfig - ST Microelectronics STM32F0 MCU line
#
# Copyright (c) 2017 RnDity Sp. z o.o.
#
# SPDX-License-Identifier: Apache-2.0
#
if SOC_SERIES_STM32F0X
source "arch/arm/soc/st_stm32/stm32f0/Kconfig.defconfig.stm32f0*"
config SOC_SERIES
default stm32f0
if WATCHDOG
config IWDG_STM32
def_bool y
endif # WATCHDOG
endif # SOC_SERIES_STM32F0X

View File

@ -0,0 +1,22 @@
# Kconfig - ST Microelectronics STM32F030X8 MCU
#
# Copyright (c) 2017 RnDity Sp. z o.o.
#
# SPDX-License-Identifier: Apache-2.0
#
if SOC_STM32F030X8
config SOC
string
default stm32f030x8
config FLASH_PAGE_SIZE
hex
default 0x800
config NUM_IRQS
int
default 29
endif # SOC_STM32F030X8

View File

@ -0,0 +1,18 @@
# Kconfig - ST Microelectronics STM32F0 MCU series
#
# Copyright (c) 2017 RnDity Sp. z o.o.
#
# SPDX-License-Identifier: Apache-2.0
#
config SOC_SERIES_STM32F0X
bool "STM32F0x Series MCU"
select CPU_CORTEX_M
select CPU_CORTEX_M0
select SOC_FAMILY_STM32
select SYS_POWER_LOW_POWER_STATE_SUPPORTED
select CPU_HAS_SYSTICK
select HAS_STM32CUBE
select CLOCK_CONTROL_STM32_CUBE if CLOCK_CONTROL
help
Enable support for STM32F0 MCU series

View File

@ -0,0 +1,15 @@
# Kconfig - ST Microelectronics STM32F0 MCU line
#
# Copyright (c) 2017 RnDity Sp. z o.o.
#
# SPDX-License-Identifier: Apache-2.0
#
choice
prompt "STM32F0x MCU Selection"
depends on SOC_SERIES_STM32F0X
config SOC_STM32F030X8
bool "STM32F030X8"
endchoice

View File

@ -0,0 +1,10 @@
# Makefile - ST Microelectronics STM32F0xx series
#
# Copyright (c) 2017 RnDity Sp. z o.o.
#
# SPDX-License-Identifier: Apache-2.0
#
obj-y += soc.o
obj-$(CONFIG_GPIO) += soc_gpio.o

View File

@ -0,0 +1,51 @@
/*
* Copyright (c) 2017 RnDity Sp. z o.o.
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef _STM32F0X_FLASH_REGISTERS_H_
#define _STM32F0X_FLASH_REGISTERS_H_
#include <zephyr/types.h>
/**
* @brief
*
* Based on reference manual:
* STM32F030x4/x6/x8/xC,
* STM32F070x6/xB advanced ARM ® -based MCUs
*
* Chapter 3.3.5: Embedded Flash Memory
*/
enum {
STM32_FLASH_LATENCY_0 = 0x0,
STM32_FLASH_LATENCY_1 = 0x1
};
/* 3.3.5.1 FLASH_ACR */
union ef_acr {
u32_t val;
struct {
u32_t latency :3 __packed;
u32_t rsvd__3 :1 __packed;
u32_t prftbe :1 __packed;
u32_t prftbs :1 __packed;
u32_t rsvd__6_31 :26 __packed;
} bit;
};
/* 3.3.5 Embedded flash registers */
struct stm32_flash {
union ef_acr acr;
u32_t keyr;
u32_t optkeyr;
u32_t sr;
u32_t cr;
u32_t ar;
u32_t obr;
u32_t wrpr;
};
#endif /* _STM32F0X_FLASH_REGISTERS_H_ */

View File

@ -0,0 +1,76 @@
/*
* Copyright (c) 2017 RnDity Sp. z o.o.
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef _STM32F0X_GPIO_REGISTERS_H_
#define _STM32F0X_GPIO_REGISTERS_H_
/**
* @brief
*
* Based on reference manual:
* STM32F030x4/x6/x8/xC,
* STM32F070x6/xB advanced ARM ® -based MCUs
*
* Chapter 8: General-purpose I/Os (GPIO)
* Chapter 9: System configuration controller (SYSCFG)
*/
struct stm32f0x_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_cfgr1 {
u32_t val;
struct {
u32_t mem_mode :2 __packed;
u32_t rsvd__2_7 :6 __packed;
u32_t adc_dma_rmp :1 __packed;
u32_t usart1_tx_dma_rmp :1 __packed;
u32_t usart1_rx_dma_rmp :1 __packed;
u32_t tim16_dma_rmp :1 __packed;
u32_t tim17_dma_rmp :1 __packed;
u32_t rsvd__13_15 :3 __packed;
u32_t i2c_pb6_fmp :1 __packed;
u32_t i2c_pb7_fmp :1 __packed;
u32_t i2c_pb8_fmp :1 __packed;
u32_t i2c_pb9_fmp :1 __packed;
u32_t i2c1_fmp :1 __packed;
u32_t rsvd__21 :1 __packed;
u32_t i2c_pa9_fmp :1 __packed;
u32_t i2c_pa10_fmp :1 __packed;
u32_t rsvd__24_25 :2 __packed;
u32_t usart3_dma_rmp :1 __packed;
u32_t rsvd__27_31 :5 __packed;
} bit;
};
union syscfg__exticr {
u32_t val;
struct {
u16_t exti;
u16_t rsvd__16_31;
} bit;
};
struct stm32f0x_syscfg {
union syscfg_cfgr1 cfgr1;
union syscfg__exticr exticr1;
union syscfg__exticr exticr2;
union syscfg__exticr exticr3;
union syscfg__exticr exticr4;
u32_t cfgr2;
};
#endif /* _STM32F0X_GPIO_REGISTERS_H_ */

View File

@ -0,0 +1,9 @@
/* linker.ld - Linker command/script file */
/*
* Copyright (c) 2014-2016 Wind River Systems, Inc.
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <arch/arm/cortex_m/scripts/linker.ld>

View File

@ -0,0 +1,62 @@
/*
* Copyright (c) 2017 RnDity Sp. z o.o.
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief System/hardware module for STM32F0 processor
*/
#include <kernel.h>
#include <device.h>
#include <init.h>
#include <soc.h>
#include <arch/cpu.h>
#include <cortex_m/exc.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 stm32f0_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 4MHz */
SystemCoreClock = 4000000;
return 0;
}
SYS_INIT(stm32f0_init, PRE_KERNEL_1, 0);

View File

@ -0,0 +1,48 @@
/*
* Copyright (c) 2017 RnDity Sp. z o.o.
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file SoC configuration macros for the STM32F0 family processors.
*
* Based on reference manual:
* STM32F030x4/x6/x8/xC,
* STM32F070x6/xB advanced ARM ® -based MCUs
*
* Chapter 2.2: Memory organization
*/
#ifndef _STM32F0_SOC_H_
#define _STM32F0_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 <drivers/rand32.h>
#include <stm32f0xx.h>
#include "soc_irq.h"
#ifdef CONFIG_SERIAL_HAS_DRIVER
#include <stm32f0xx_ll_usart.h>
#endif
#ifdef CONFIG_CLOCK_CONTROL_STM32_CUBE
#include <stm32f0xx_ll_utils.h>
#include <stm32f0xx_ll_bus.h>
#include <stm32f0xx_ll_rcc.h>
#include <stm32f0xx_ll_system.h>
#endif /* CONFIG_CLOCK_CONTROL_STM32_CUBE */
#endif /* !_ASMLANGUAGE */
#endif /* _STM32F0_SOC_H_ */

View File

@ -0,0 +1,144 @@
/*
* Copyright (c) 2017 RnDity Sp. z o.o.
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @brief
*
* Based on reference manual:
* STM32F030x4/x6/x8/xC,
* STM32F070x6/xB advanced ARM ® -based MCUs
*
* Chapter 8: 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 stm32f0x_gpio *gpio =
(struct stm32f0x_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 stm32f0x_gpio *gpio = (struct stm32f0x_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 stm32f0x_gpio *gpio = (struct stm32f0x_gpio *)base;
return (gpio->idr >> pin) & 0x1;
}
int stm32_gpio_enable_int(int port, int pin)
{
volatile struct stm32f0x_syscfg *syscfg =
(struct stm32f0x_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_APB1_2,
.enr = LL_APB1_GRP2_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;
}

View File

@ -0,0 +1,59 @@
/*
* Copyright (c) 2017 RnDity Sp. z o.o.
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file Interrupt numbers for STM32F0 family processors.
*
* Based on reference manual:
* STM32F030x4/x6/x8/xC,
* STM32F070x6/xB advanced ARM ® -based MCUs
*
* Chapter 11.1.3: Interrupt and exception vectors
*/
#ifndef _STM32F0_SOC_IRQ_H_
#define _STM32F0_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 STM32F0_IRQ_WWDG 0
/* reserved */
#define STM32F0_IRQ_RTC 2
#define STM32F0_IRQ_FLASH 3
#define STM32F0_IRQ_RCC 4
#define STM32F0_IRQ_EXTI0_1 5
#define STM32F0_IRQ_EXTI2_3 6
#define STM32F0_IRQ_EXTI4_15 7
/* reserved */
#define STM32F0_IRQ_DMA_CH1 9
#define STM32F0_IRQ_DMA_CH2_3 10
#define STM32F0_IRQ_DMA_CH4_5 11
#define STM32F0_IRQ_ADC 12
#define STM32F0_IRQ_TIM1_BRK_UP_TRG_COM 13
#define STM32F0_IRQ_TIM1_CC 14
/* reserved */
#define STM32F0_IRQ_TIM3 16
#define STM32F0_IRQ_TIM6 17
/* reserved */
#define STM32F0_IRQ_TIM14 19
#define STM32F0_IRQ_TIM15 20
#define STM32F0_IRQ_TIM16 21
#define STM32F0_IRQ_TIM17 22
#define STM32F0_IRQ_I2C1 23
#define STM32F0_IRQ_I2C2 24
#define STM32F0_IRQ_SPI1 25
#define STM32F0_IRQ_SPI2 26
#define STM32F0_IRQ_USART1 27
#define STM32F0_IRQ_USART2 28
#define STM32F0_IRQ_USART3_4_5_6 29
/* reserved */
#define STM32F0_IRQ_USB 31
#endif /* _STM32F0_SOC_IRQ_H_ */

View File

@ -0,0 +1,14 @@
/*
* Copyright (c) 2017 RnDity Sp. z o.o.
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef _STM32F0X_SOC_REGISTERS_H_
#define _STM32F0X_SOC_REGISTERS_H_
/* include register mapping headers */
#include "flash_registers.h"
#include "gpio_registers.h"
#endif /* _STM32F0X_SOC_REGISTERS_H_ */