stm32: add support for STM32F0xx family

Add support for the STM32F0xx family of devices using a Cortex-M0 core
and slightly newer peripherals than F1xx family.

Signed-off-by: Vincent Palatin <vpalatin@chromium.org>

BRANCH=none
BUG=none
TEST=run EC console on STM32F072B Discovery board.
and pass all available unit-tests on target.

Change-Id: Idaa3fcbf1c0da8a8f448c0e88e58bfd976b0a735
Reviewed-on: https://chromium-review.googlesource.com/188983
Reviewed-by: Vincent Palatin <vpalatin@chromium.org>
Commit-Queue: Vincent Palatin <vpalatin@chromium.org>
Tested-by: Vincent Palatin <vpalatin@chromium.org>
This commit is contained in:
Vincent Palatin
2014-03-03 11:10:45 -08:00
committed by chrome-internal-fetch
parent 0f73a129b4
commit 39327cc4cd
14 changed files with 608 additions and 17 deletions

40
chip/stm32/adc-stm32f0.c Normal file
View File

@@ -0,0 +1,40 @@
/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
#include "adc.h"
#include "adc_chip.h"
#include "common.h"
#include "console.h"
#include "dma.h"
#include "hooks.h"
#include "registers.h"
#include "task.h"
#include "timer.h"
#include "util.h"
int adc_enable_watchdog(int ain_id, int high, int low)
{
return EC_ERROR_UNKNOWN;
}
int adc_disable_watchdog(void)
{
return EC_ERROR_UNKNOWN;
}
int adc_read_channel(enum adc_channel ch)
{
return EC_ERROR_UNKNOWN;
}
int adc_read_all_channels(int *data)
{
return EC_ERROR_UNKNOWN;
}
static void adc_init(void)
{
}
DECLARE_HOOK(HOOK_INIT, adc_init, HOOK_PRIO_DEFAULT);

View File

@@ -6,18 +6,30 @@
# STM32 chip specific files build
#
# STM32 SoC family has a Cortex-M3 ARM core
ifeq ($(CHIP_FAMILY),stm32f0)
# STM32F0xx sub-family has a Cortex-M0 ARM core
CORE:=cortex-m0
# Force ARMv6-M ISA used by the Cortex-M0
CFLAGS_CPU+=-march=armv6-m -mcpu=cortex-m0
else
# other STM32 SoCs have a Cortex-M3 ARM core
CORE:=cortex-m
# Force Cortex-M3 subset of instructions
CFLAGS_CPU+=-march=armv7-m -mcpu=cortex-m3
endif
# STM32F0xx and STM32F1xx are using the same flash controller
FLASH_FAMILY=$(subst stm32f0,stm32f,$(CHIP_FAMILY))
# STM32F0xx chips will re-use STM32L I2C code
I2C_FAMILY=$(subst stm32f0,stm32l,$(CHIP_FAMILY))
chip-y=dma.o hwtimer.o system.o uart.o
chip-y+=jtag-$(CHIP_FAMILY).o clock-$(CHIP_FAMILY).o gpio-$(CHIP_FAMILY).o
chip-$(CONFIG_SPI)+=spi.o
chip-$(CONFIG_I2C)+=i2c-$(CHIP_FAMILY).o
chip-$(CONFIG_I2C)+=i2c-$(I2C_FAMILY).o
chip-$(CONFIG_WATCHDOG)+=watchdog.o
chip-$(HAS_TASK_KEYSCAN)+=keyboard_raw.o
chip-$(HAS_TASK_POWERLED)+=power_led.o
chip-$(CONFIG_FLASH)+=flash-$(CHIP_FAMILY).o
chip-$(CONFIG_FLASH)+=flash-$(FLASH_FAMILY).o
chip-$(CONFIG_ADC)+=adc-$(CHIP_FAMILY).o
chip-$(CONFIG_PWM)+=pwm.o

View File

@@ -0,0 +1,61 @@
/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
/* Clocks and power management settings */
#include "chipset.h"
#include "clock.h"
#include "common.h"
#include "console.h"
#include "cpu.h"
#include "hooks.h"
#include "registers.h"
#include "util.h"
/* use 48Mhz USB-synchronized High-speed oscillator */
#define HSI48_CLOCK 48000000
int clock_get_freq(void)
{
return HSI48_CLOCK;
}
void clock_enable_module(enum module_id module, int enable)
{
}
/*
* system closk is HSI48 = 48MHz,
* no prescaler, no MCO, no PLL
* USB clock = HSI48
*/
BUILD_ASSERT(CPU_CLOCK == HSI48_CLOCK);
void clock_init(void)
{
/*
* The initial state :
* SYSCLK from HSI (=8MHz), no divider on AHB, APB1, APB2
* PLL unlocked, RTC enabled on LSE
*/
/* put 1 Wait-State for flash access to ensure proper reads at 48Mhz */
STM32_FLASH_ACR = 0x1001; /* 1 WS / Prefetch enabled */
/* Ensure that HSI48 is ON */
if (!(STM32_RCC_CR2 & (1 << 17))) {
/* Enable HSI */
STM32_RCC_CR2 |= 1 << 16;
/* Wait for HSI to be ready */
while (!(STM32_RCC_CR2 & (1 << 17)))
;
}
/* switch SYSCLK to HSI48 */
STM32_RCC_CFGR = 0x00000003;
/* wait until the HSI48 is the clock source */
while ((STM32_RCC_CFGR & 0xc) != 0xc)
;
}

View File

@@ -0,0 +1,42 @@
/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
/* Memory mapping */
#define CONFIG_FLASH_BASE 0x08000000
#define CONFIG_FLASH_PHYSICAL_SIZE 0x00020000
#define CONFIG_FLASH_SIZE CONFIG_FLASH_PHYSICAL_SIZE
#define CONFIG_FLASH_BANK_SIZE 0x1000
#define CONFIG_FLASH_ERASE_SIZE 0x0400 /* erase bank size */
#define CONFIG_FLASH_WRITE_SIZE 0x0002 /* minimum write size */
/* No page mode on STM32F, so no benefit to larger write sizes */
#define CONFIG_FLASH_WRITE_IDEAL_SIZE 0x0002
#define CONFIG_RAM_BASE 0x20000000
#define CONFIG_RAM_SIZE 0x00002000
/* Size of one firmware image in flash */
#define CONFIG_FW_IMAGE_SIZE (64 * 1024)
#define CONFIG_FW_RO_OFF 0
#define CONFIG_FW_RO_SIZE (CONFIG_FW_IMAGE_SIZE - CONFIG_FW_PSTATE_SIZE)
#define CONFIG_FW_RW_OFF CONFIG_FW_IMAGE_SIZE
#define CONFIG_FW_RW_SIZE CONFIG_FW_IMAGE_SIZE
#define CONFIG_FW_WP_RO_OFF CONFIG_FW_RO_OFF
#define CONFIG_FW_WP_RO_SIZE CONFIG_FW_IMAGE_SIZE
/*
* Put pstate after RO to give RW more space and make RO write protect region
* contiguous.
*/
#define CONFIG_FW_PSTATE_SIZE CONFIG_FLASH_BANK_SIZE
#define CONFIG_FW_PSTATE_OFF (CONFIG_FW_RO_OFF + CONFIG_FW_RO_SIZE)
/* Number of IRQ vectors on the NVIC */
#define CONFIG_IRQ_COUNT 32
/* Reduced history because of limited RAM */
#undef CONFIG_CONSOLE_HISTORY
#define CONFIG_CONSOLE_HISTORY 3

View File

@@ -6,8 +6,13 @@
#ifndef __CROS_EC_CONFIG_CHIP_H
#define __CROS_EC_CONFIG_CHIP_H
#ifdef CHIP_FAMILY_STM32F0
/* CPU core BFD configuration */
#include "core/cortex-m0/config_core.h"
#else
/* CPU core BFD configuration */
#include "core/cortex-m/config_core.h"
#endif
/* Default to UART 1 for EC console */
#define CONFIG_UART_CONSOLE 1
@@ -23,6 +28,9 @@
#elif defined(CHIP_VARIANT_STM32F10X)
/* STM32F101xx, STM32F102xx, STM32F103xx, STM32F105xx, and STM32F107xx */
#include "config-stm32f10x.h"
#elif defined(CHIP_VARIANT_STM32F07X)
/* STM32F07xx */
#include "config-stm32f07x.h"
#else
#error "Unsupported chip variant"
#endif

View File

@@ -238,6 +238,7 @@ void dma_clear_isr(enum dma_channel channel)
dma->ifcr |= STM32_DMA_ISR_ALL(channel);
}
#ifndef CHIP_FAMILY_STM32F0
void dma_event_interrupt_channel_4(void)
{
dma_clear_isr(STM32_DMAC_CH4);
@@ -269,3 +270,4 @@ void dma_event_interrupt_channel_7(void)
task_wake(id[STM32_DMAC_CH7]);
}
DECLARE_IRQ(STM32_IRQ_DMA_CHANNEL_7, dma_event_interrupt_channel_7, 3);
#endif /* !CHIP_FAMILY_STM32F0 */

245
chip/stm32/gpio-stm32f0.c Normal file
View File

@@ -0,0 +1,245 @@
/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
/* GPIO module for Chrome EC */
#include "common.h"
#include "console.h"
#include "gpio.h"
#include "hooks.h"
#include "registers.h"
#include "task.h"
#include "util.h"
/* Console output macros */
#define CPUTS(outstr) cputs(CC_GPIO, outstr)
#define CPRINTF(format, args...) cprintf(CC_GPIO, format, ## args)
/* For each EXTI bit, record which GPIO entry is using it */
static const struct gpio_info *exti_events[16];
static uint32_t expand_to_2bit_mask(uint32_t mask)
{
uint32_t mask_out = 0;
while (mask) {
int bit = get_next_bit(&mask);
mask_out |= 3 << (bit * 2);
}
return mask_out;
}
void gpio_set_flags_by_mask(uint32_t port, uint32_t mask, uint32_t flags)
{
/* Bitmask for registers with 2 bits per GPIO pin */
const uint32_t mask2 = expand_to_2bit_mask(mask);
uint32_t val;
/* Set up pullup / pulldown */
val = STM32_GPIO_PUPDR(port) & ~mask2;
if (flags & GPIO_PULL_UP)
val |= 0x55555555 & mask2; /* Pull Up = 01 */
else if (flags & GPIO_PULL_DOWN)
val |= 0xaaaaaaaa & mask2; /* Pull Down = 10 */
STM32_GPIO_PUPDR(port) = val;
/*
* Select open drain first, so that we don't glitch the signal when
* changing the line to an output.
*/
if (flags & GPIO_OPEN_DRAIN)
STM32_GPIO_OTYPER(port) |= mask;
val = STM32_GPIO_MODER(port) & ~mask2;
if (flags & GPIO_OUTPUT) {
/*
* Set pin level first to avoid glitching. This is harmless on
* STM32L because the set/reset register isn't connected to the
* output drivers until the pin is made an output.
*/
if (flags & GPIO_HIGH)
STM32_GPIO_BSRR(port) = mask;
else if (flags & GPIO_LOW)
STM32_GPIO_BSRR(port) = mask << 16;
/* General purpose, MODE = 01 */
val |= 0x55555555 & mask2;
STM32_GPIO_MODER(port) = val;
} else if (flags & GPIO_INPUT) {
/* Input, MODE=00 */
STM32_GPIO_MODER(port) = val;
}
/* Set up interrupts if necessary */
ASSERT(!(flags & (GPIO_INT_F_LOW | GPIO_INT_F_HIGH)));
if (flags & GPIO_INT_F_RISING)
STM32_EXTI_RTSR |= mask;
if (flags & GPIO_INT_F_FALLING)
STM32_EXTI_FTSR |= mask;
/* Interrupt is enabled by gpio_enable_interrupt() */
}
void gpio_pre_init(void)
{
const struct gpio_info *g = gpio_list;
int is_warm = 0;
int i;
/* Required to configure external IRQ lines (SYSCFG_EXTICRn) */
STM32_RCC_APB2ENR |= 1 << 0;
if ((STM32_RCC_AHBENR & 0x7e0000) == 0x7e0000) {
/* This is a warm reboot */
is_warm = 1;
} else {
/*
* Enable all GPIOs clocks
*
* TODO(crosbug.com/p/23770): only enable the banks we need to,
* and support disabling some of them in low-power idle.
*/
STM32_RCC_AHBENR |= 0x7e0000;
}
/* Set all GPIOs to defaults */
for (i = 0; i < GPIO_COUNT; i++, g++) {
int flags = g->flags;
if (flags & GPIO_DEFAULT)
continue;
/*
* If this is a warm reboot, don't set the output levels or
* we'll shut off the AP.
*/
if (is_warm)
flags &= ~(GPIO_LOW | GPIO_HIGH);
/* Set up GPIO based on flags */
gpio_set_flags_by_mask(g->port, g->mask, flags);
}
}
static void gpio_init(void)
{
/* Enable IRQs now that pins are set up */
task_enable_irq(STM32_IRQ_EXTI0_1);
task_enable_irq(STM32_IRQ_EXTI2_3);
task_enable_irq(STM32_IRQ_EXTI4_15);
}
DECLARE_HOOK(HOOK_INIT, gpio_init, HOOK_PRIO_DEFAULT);
void gpio_set_alternate_function(uint32_t port, uint32_t mask, int func)
{
int bit;
uint8_t half;
uint32_t afr;
uint32_t moder = STM32_GPIO_MODER(port);
if (func < 0) {
/* Return to normal GPIO function, defaulting to input. */
while (mask) {
bit = get_next_bit(&mask);
moder &= ~(0x3 << (bit * 2));
}
STM32_GPIO_MODER(port) = moder;
return;
}
/* Low half of the GPIO bank */
half = mask & 0xff;
afr = STM32_GPIO_AFRL(port);
while (half) {
bit = 31 - __builtin_clz(half);
afr &= ~(0xf << (bit * 4));
afr |= func << (bit * 4);
moder &= ~(0x3 << (bit * 2 + 0));
moder |= 0x2 << (bit * 2 + 0);
half &= ~(1 << bit);
}
STM32_GPIO_AFRL(port) = afr;
/* High half of the GPIO bank */
half = mask >> 8;
afr = STM32_GPIO_AFRH(port);
while (half) {
bit = 31 - __builtin_clz(half);
afr &= ~(0xf << (bit * 4));
afr |= func << (bit * 4);
moder &= ~(0x3 << (bit * 2 + 16));
moder |= 0x2 << (bit * 2 + 16);
half &= ~(1 << bit);
}
STM32_GPIO_AFRH(port) = afr;
STM32_GPIO_MODER(port) = moder;
}
test_mockable int gpio_get_level(enum gpio_signal signal)
{
return !!(STM32_GPIO_IDR(gpio_list[signal].port) &
gpio_list[signal].mask);
}
uint16_t *gpio_get_level_reg(enum gpio_signal signal, uint32_t *mask)
{
*mask = gpio_list[signal].mask;
return (uint16_t *)&STM32_GPIO_IDR(gpio_list[signal].port);
}
void gpio_set_level(enum gpio_signal signal, int value)
{
STM32_GPIO_BSRR(gpio_list[signal].port) =
gpio_list[signal].mask << (value ? 0 : 16);
}
int gpio_enable_interrupt(enum gpio_signal signal)
{
const struct gpio_info *g = gpio_list + signal;
uint32_t bit, group, shift, bank;
/* Fail if not implemented or no interrupt handler */
if (!g->mask || !g->irq_handler)
return EC_ERROR_INVAL;
bit = 31 - __builtin_clz(g->mask);
if (exti_events[bit]) {
CPRINTF("Overriding %s with %s on EXTI%d\n",
exti_events[bit]->name, g->name, bit);
}
exti_events[bit] = g;
group = bit / 4;
shift = (bit % 4) * 4;
bank = (g->port - STM32_GPIOA_BASE) / 0x400;
STM32_SYSCFG_EXTICR(group) = (STM32_SYSCFG_EXTICR(group) &
~(0xF << shift)) | (bank << shift);
STM32_EXTI_IMR |= g->mask;
return EC_SUCCESS;
}
/*****************************************************************************/
/* Interrupt handler */
void gpio_interrupt(void)
{
int bit;
const struct gpio_info *g;
uint32_t pending = STM32_EXTI_PR;
STM32_EXTI_PR = pending;
while (pending) {
bit = 31 - __builtin_clz(pending);
g = exti_events[bit];
if (g && g->irq_handler)
g->irq_handler(g - gpio_list);
pending &= ~(1 << bit);
}
}
DECLARE_IRQ(STM32_IRQ_EXTI0_1, gpio_interrupt, 1);
DECLARE_IRQ(STM32_IRQ_EXTI2_3, gpio_interrupt, 1);
DECLARE_IRQ(STM32_IRQ_EXTI4_15, gpio_interrupt, 1);

View File

@@ -21,7 +21,35 @@
* algorithmically. To avoid burning memory for a lookup table, use macros to
* compute the offset. This also has the benefit that compilation will fail if
* an unsupported master/slave pairing is used.
*
*/
#ifdef CHIP_FAMILY_STM32F0
/*
* Slave Master
* 1 15 2 3 17
* 2 1 15 3 14
* 3 1 2 15 14
* 15 2 3 16 17
* --------------------
* ts = 0 1 2 3
*/
#define STM32_TIM_TS_SLAVE_1_MASTER_15 0
#define STM32_TIM_TS_SLAVE_1_MASTER_2 1
#define STM32_TIM_TS_SLAVE_1_MASTER_3 2
#define STM32_TIM_TS_SLAVE_1_MASTER_17 3
#define STM32_TIM_TS_SLAVE_2_MASTER_1 0
#define STM32_TIM_TS_SLAVE_2_MASTER_15 1
#define STM32_TIM_TS_SLAVE_2_MASTER_3 2
#define STM32_TIM_TS_SLAVE_2_MASTER_14 3
#define STM32_TIM_TS_SLAVE_3_MASTER_1 0
#define STM32_TIM_TS_SLAVE_3_MASTER_2 1
#define STM32_TIM_TS_SLAVE_3_MASTER_15 2
#define STM32_TIM_TS_SLAVE_3_MASTER_14 3
#define STM32_TIM_TS_SLAVE_15_MASTER_2 0
#define STM32_TIM_TS_SLAVE_15_MASTER_3 1
#define STM32_TIM_TS_SLAVE_15_MASTER_16 2
#define STM32_TIM_TS_SLAVE_15_MASTER_17 3
#else /* !CHIP_FAMILY_STM32F0 */
/*
* Slave Master
* 1 15 2 3 4 (STM32F100 only)
* 2 9 10 3 4
@@ -51,6 +79,7 @@
#define STM32_TIM_TS_SLAVE_9_MASTER_3 1
#define STM32_TIM_TS_SLAVE_9_MASTER_10 2
#define STM32_TIM_TS_SLAVE_9_MASTER_11 3
#endif /* !CHIP_FAMILY_STM32F0 */
#define TSMAP(slave, master) \
CONCAT4(STM32_TIM_TS_SLAVE_, slave, _MASTER_, master)
@@ -64,7 +93,11 @@
#define IRQ_WD IRQ_TIM(TIM_WATCHDOG)
/* TIM1 has fancy names for its IRQs; remap count-up IRQ for the macro above */
#ifdef CHIP_FAMILY_STM32F0
#define STM32_IRQ_TIM1 STM32_IRQ_TIM1_BRK_UP_TRG
#else /* !CHIP_FAMILY_STM32F0 */
#define STM32_IRQ_TIM1 STM32_IRQ_TIM1_UP_TIM16
#endif /* !CHIP_FAMILY_STM32F0 */
#define TIM_BASE(n) CONCAT3(STM32_TIM, n, _BASE)
#define TIM_WD_BASE TIM_BASE(TIM_WATCHDOG)
@@ -169,7 +202,7 @@ void __hw_timer_enable_clock(int n, int enable)
* Mapping of timers to reg/mask is split into a few different ranges,
* some specific to individual chips.
*/
#if defined(CHIP_FAMILY_STM32F)
#if defined(CHIP_FAMILY_STM32F) || defined(CHIP_FAMILY_STM32F0)
if (n == 1) {
reg = &STM32_RCC_APB2ENR;
mask = STM32_RCC_PB2_TIM1;
@@ -181,6 +214,16 @@ void __hw_timer_enable_clock(int n, int enable)
}
#endif
#if defined(CHIP_FAMILY_STM32F0)
if (n >= 15 && n <= 17) {
reg = &STM32_RCC_APB2ENR;
mask = STM32_RCC_PB2_TIM15 << (n - 15);
}
if (n == 14) {
reg = &STM32_RCC_APB1ENR;
mask = STM32_RCC_PB1_TIM14;
}
#endif
if (n >= 2 && n <= 7) {
reg = &STM32_RCC_APB1ENR;
mask = STM32_RCC_PB1_TIM2 << (n - 2);

21
chip/stm32/jtag-stm32f0.c Normal file
View File

@@ -0,0 +1,21 @@
/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
/* Settings to enable JTAG debugging */
#include "jtag.h"
#include "registers.h"
void jtag_pre_init(void)
{
/*
* Stop all timers we might use (TIM1-3,14-17) and watchdogs when
* the JTAG stops the CPU.
*/
STM32_DBGMCU_APB1FZ |=
STM32_RCC_PB1_TIM2 | STM32_RCC_PB1_TIM3 | STM32_RCC_PB1_TIM6 |
STM32_RCC_PB1_TIM7 | STM32_RCC_PB1_WWDG | STM32_RCC_PB1_IWDG;
STM32_DBGMCU_APB2FZ |= STM32_RCC_PB2_TIM15 | STM32_RCC_PB2_TIM16 |
STM32_RCC_PB2_TIM17 | STM32_RCC_PB2_TIM1;
}

View File

@@ -63,7 +63,7 @@ static void pwm_configure(enum pwm_channel ch)
val = *gpio_cr & ~(mask * 0xf);
val |= mask * 0x9;
*gpio_cr = val;
#else /* stm32l */
#else /* stm32l or stm32f0 */
gpio_set_alternate_function(gpio->port, gpio->mask,
GPIO_ALT_TIM(pwm->tim.id));
#endif

View File

@@ -11,6 +11,40 @@
#include "common.h"
/* IRQ numbers */
#ifdef CHIP_FAMILY_STM32F0
#define STM32_IRQ_WWDG 0
#define STM32_IRQ_PVD 1
#define STM32_IRQ_RTC_WAKEUP 2
#define STM32_IRQ_FLASH 3
#define STM32_IRQ_RCC 4
#define STM32_IRQ_EXTI0_1 5
#define STM32_IRQ_EXTI2_3 6
#define STM32_IRQ_EXTI4_15 7
#define STM32_IRQ_TSC 8
#define STM32_IRQ_DMA_CHANNEL_1 9
#define STM32_IRQ_DMA_CHANNEL_2_3 10
#define STM32_IRQ_DMA_CHANNEL_4_7 11
#define STM32_IRQ_ADC_COMP 12
#define STM32_IRQ_TIM1_BRK_UP_TRG 13
#define STM32_IRQ_TIM1_CC 14
#define STM32_IRQ_TIM2 15
#define STM32_IRQ_TIM3 16
#define STM32_IRQ_TIM6_DAC 17
#define STM32_IRQ_TIM7 18
#define STM32_IRQ_TIM14 19
#define STM32_IRQ_TIM15 20
#define STM32_IRQ_TIM16 21
#define STM32_IRQ_TIM17 22
#define STM32_IRQ_I2C1 23
#define STM32_IRQ_I2C2 24
#define STM32_IRQ_SPI1 25
#define STM32_IRQ_SPI2 26
#define STM32_IRQ_USART1 27
#define STM32_IRQ_USART2 28
#define STM32_IRQ_USART3_4 29
#define STM32_IRQ_CEC_CAN 30
#define STM32_IRQ_USB 31
#else /* !CHIP_FAMILY_STM32F0 */
#define STM32_IRQ_WWDG 0
#define STM32_IRQ_PVD 1
#define STM32_IRQ_TAMPER_STAMP 2
@@ -89,6 +123,7 @@
#define STM32_IRQ_DMA2_CHANNEL4_5 59 /* STM32F100 and STM32F10x */
/* if MISC_REMAP bits are set */
#define STM32_IRQ_DMA2_CHANNEL5 60 /* STM32F100 only */
#endif /* CHIP_FAMILY_STM32F0 */
/* --- USART --- */
#define STM32_USART1_BASE 0x40013800
@@ -101,6 +136,34 @@
#define STM32_USART_REG(n, offset) REG16(STM32_USART_BASE(n) + (offset))
#ifdef CHIP_FAMILY_STM32F0
#define STM32_USART_CR1(n) STM32_USART_REG(n, 0x00)
#define STM32_USART_CR1_UE (1 << 0)
#define STM32_USART_CR1_RE (1 << 2)
#define STM32_USART_CR1_TE (1 << 3)
#define STM32_USART_CR1_RXNEIE (1 << 5)
#define STM32_USART_CR1_TCIE (1 << 6)
#define STM32_USART_CR1_TXEIE (1 << 7)
#define STM32_USART_CR1_OVER8 (1 << 15)
#define STM32_USART_CR2(n) STM32_USART_REG(n, 0x04)
#define STM32_USART_CR3(n) STM32_USART_REG(n, 0x08)
#define STM32_USART_CR3_DMAR (1 << 6)
#define STM32_USART_CR3_DMAT (1 << 7)
#define STM32_USART_CR3_ONEBIT (1 << 11)
#define STM32_USART_BRR(n) STM32_USART_REG(n, 0x0C)
#define STM32_USART_GTPR(n) STM32_USART_REG(n, 0x10)
#define STM32_USART_RTOR(n) STM32_USART_REG(n, 0x14)
#define STM32_USART_RQR(n) STM32_USART_REG(n, 0x18)
#define STM32_USART_ISR(n) STM32_USART_REG(n, 0x1C)
#define STM32_USART_ICR(n) STM32_USART_REG(n, 0x20)
#define STM32_USART_RDR(n) STM32_USART_REG(n, 0x24)
#define STM32_USART_TDR(n) STM32_USART_REG(n, 0x28)
/* register alias */
#define STM32_USART_SR(n) STM32_USART_ISR(n)
#define STM32_USART_SR_RXNE (1 << 5)
#define STM32_USART_SR_TC (1 << 6)
#define STM32_USART_SR_TXE (1 << 7)
#else /* !CHIP_FAMILY_STM32F0 */
#define STM32_USART_SR(n) STM32_USART_REG(n, 0x00)
#define STM32_USART_SR_RXNE (1 << 5)
#define STM32_USART_SR_TC (1 << 6)
@@ -121,6 +184,10 @@
#define STM32_USART_CR3_DMAT (1 << 7)
#define STM32_USART_CR3_ONEBIT (1 << 11) /* STM32L only */
#define STM32_USART_GTPR(n) STM32_USART_REG(n, 0x18)
/* register aliases */
#define STM32_USART_TDR(n) STM32_USART_DR(n)
#define STM32_USART_RDR(n) STM32_USART_DR(n)
#endif /* !CHIP_FAMILY_STM32F0 */
#define STM32_IRQ_USART(n) CONCAT2(STM32_IRQ_USART, n)
@@ -248,6 +315,28 @@ typedef volatile struct timer_ctlr timer_ctlr_t;
#define GPIO_ALT_RI 0xE
#define GPIO_ALT_EVENTOUT 0xF
#elif defined(CHIP_FAMILY_STM32F0)
#define STM32_GPIOA_BASE 0x48000000
#define STM32_GPIOB_BASE 0x48000400
#define STM32_GPIOC_BASE 0x48000800
#define STM32_GPIOD_BASE 0x48000C00
#define STM32_GPIOE_BASE 0x48001000
#define STM32_GPIOF_BASE 0x48001400
#define STM32_GPIO_MODER(b) REG32((b) + 0x00)
#define STM32_GPIO_OTYPER(b) REG16((b) + 0x04)
#define STM32_GPIO_OSPEEDR(b) REG32((b) + 0x08)
#define STM32_GPIO_PUPDR(b) REG32((b) + 0x0C)
#define STM32_GPIO_IDR(b) REG16((b) + 0x10)
#define STM32_GPIO_ODR(b) REG16((b) + 0x14)
#define STM32_GPIO_BSRR(b) REG32((b) + 0x18)
#define STM32_GPIO_LCKR(b) REG32((b) + 0x1C)
#define STM32_GPIO_AFRL(b) REG32((b) + 0x20)
#define STM32_GPIO_AFRH(b) REG32((b) + 0x24)
#define STM32_GPIO_BRR(b) REG32((b) + 0x28)
#define GPIO_ALT_TIM(x) (0 /*TODO(fixme)*/)
#elif defined(CHIP_FAMILY_STM32F)
#define STM32_GPIOA_BASE 0x40010800
#define STM32_GPIOB_BASE 0x40010c00
@@ -360,7 +449,7 @@ typedef volatile struct timer_ctlr timer_ctlr_t;
#define STM32_SYSCFG_PMC REG32(STM32_SYSCFG_BASE + 0x04)
#define STM32_SYSCFG_EXTICR(n) REG32(STM32_SYSCFG_BASE + 8 + 4 * (n))
#elif defined(CHIP_FAMILY_STM32F)
#elif defined(CHIP_FAMILY_STM32F) || defined(CHIP_FAMILY_STM32F0)
#define STM32_RCC_BASE 0x40021000
#define STM32_RCC_CR REG32(STM32_RCC_BASE + 0x00)
@@ -374,9 +463,21 @@ typedef volatile struct timer_ctlr timer_ctlr_t;
#define STM32_RCC_BDCR REG32(STM32_RCC_BASE + 0x20)
#define STM32_RCC_CSR REG32(STM32_RCC_BASE + 0x24)
#define STM32_RCC_CFGR2 REG32(STM32_RCC_BASE + 0x2c) /* STM32F100 */
#define STM32_RCC_CFGR3 REG32(STM32_RCC_BASE + 0x30) /* STM32F0XX */
#define STM32_RCC_CR2 REG32(STM32_RCC_BASE + 0x34) /* STM32F0XX */
#define STM32_RCC_HB_DMA1 (1 << 0)
#define STM32_RCC_PB2_TIM1 (1 << 11)
#define STM32_RCC_PB2_TIM15 (1 << 16) /* STM32F0XX */
#define STM32_RCC_PB2_TIM16 (1 << 17) /* STM32F0XX */
#define STM32_RCC_PB2_TIM17 (1 << 18) /* STM32F0XX */
#define STM32_RCC_PB1_TIM14 (1 << 8) /* STM32F0XX */
#define STM32_SYSCFG_BASE 0x40010000
#define STM32_SYSCFG_CFGR1 REG32(STM32_SYSCFG_BASE + 0x00)
#define STM32_SYSCFG_EXTICR(n) REG32(STM32_SYSCFG_BASE + 8 + 4 * (n))
#define STM32_SYSCFG_CFGR2 REG32(STM32_SYSCFG_BASE + 0x18)
#else
#error Unsupported chip variant
@@ -425,7 +526,7 @@ typedef volatile struct timer_ctlr timer_ctlr_t;
#define STM32_RTC_BASE 0x40002800
#if defined(CHIP_FAMILY_STM32L)
#if defined(CHIP_FAMILY_STM32L) || defined(CHIP_FAMILY_STM32F0)
#define STM32_RTC_TR REG32(STM32_RTC_BASE + 0x00)
#define STM32_RTC_DR REG32(STM32_RTC_BASE + 0x04)
#define STM32_RTC_CR REG32(STM32_RTC_BASE + 0x08)
@@ -512,7 +613,11 @@ typedef volatile struct stm32_spi_regs stm32_spi_regs_t;
/* --- Debug --- */
#ifdef CHIP_FAMILY_STM32F0
#define STM32_DBGMCU_BASE 0x40015800
#else
#define STM32_DBGMCU_BASE 0xE0042000
#endif
#define STM32_DBGMCU_IDCODE REG32(STM32_DBGMCU_BASE + 0x00)
#define STM32_DBGMCU_CR REG32(STM32_DBGMCU_BASE + 0x04)
@@ -560,7 +665,7 @@ typedef volatile struct stm32_spi_regs stm32_spi_regs_t;
#define STM32_OPTB_WRP3L 0x18
#define STM32_OPTB_WRP3H 0x1c
#elif defined(CHIP_FAMILY_STM32F)
#elif defined(CHIP_FAMILY_STM32F) || defined(CHIP_FAMILY_STM32F0)
#define STM32_FLASH_REGS_BASE 0x40022000
#define STM32_FLASH_ACR REG32(STM32_FLASH_REGS_BASE + 0x00)
@@ -618,6 +723,17 @@ typedef volatile struct stm32_spi_regs stm32_spi_regs_t;
#define STM32_ADC_JSQR REG32(STM32_ADC1_BASE + 0x38)
#define STM32_ADC_JDR(n) REG32(STM32_ADC1_BASE + 0x3C + ((n)&3) * 4)
#define STM32_ADC_DR REG32(STM32_ADC1_BASE + 0x4C)
#elif defined(CHIP_FAMILY_STM32F0)
#define STM32_ADC_ISR REG32(STM32_ADC1_BASE + 0x00)
#define STM32_ADC_IER REG32(STM32_ADC1_BASE + 0x04)
#define STM32_ADC_CR REG32(STM32_ADC1_BASE + 0x08)
#define STM32_ADC_CFGR1 REG32(STM32_ADC1_BASE + 0x0C)
#define STM32_ADC_CFGR2 REG32(STM32_ADC1_BASE + 0x10)
#define STM32_ADC_SMPR REG32(STM32_ADC1_BASE + 0x14)
#define STM32_ADC_TR REG32(STM32_ADC1_BASE + 0x20)
#define STM32_ADC_CHSELR REG32(STM32_ADC1_BASE + 0x28)
#define STM32_ADC_DR REG32(STM32_ADC1_BASE + 0x40)
#define STM32_ADC_CCR REG32(STM32_ADC1_BASE + 0x308)
#elif defined(CHIP_FAMILY_STM32L)
#define STM32_ADC_SR REG32(STM32_ADC1_BASE + 0x00)
#define STM32_ADC_CR1 REG32(STM32_ADC1_BASE + 0x04)
@@ -653,7 +769,7 @@ typedef volatile struct stm32_spi_regs stm32_spi_regs_t;
#if defined(CHIP_FAMILY_STM32L)
#define STM32_DMA1_BASE 0x40026000
#elif defined(CHIP_FAMILY_STM32F)
#elif defined(CHIP_FAMILY_STM32F) || defined(CHIP_FAMILY_STM32F0)
#define STM32_DMA1_BASE 0x40020000
#else
#error Unsupported chip variant

View File

@@ -158,7 +158,7 @@ void system_pre_init(void)
/* Enable RTC and use LSI as clock source */
STM32_RCC_CSR = (STM32_RCC_CSR & ~0x00C30000) | 0x00420000;
}
#elif defined(CHIP_FAMILY_STM32F)
#elif defined(CHIP_FAMILY_STM32F) || defined(CHIP_FAMILY_STM32F0)
if ((STM32_RCC_BDCR & 0x00018300) != 0x00008200) {
/* the RTC settings are bad, we need to reset it */
STM32_RCC_BDCR |= 0x00010000;

View File

@@ -24,7 +24,7 @@
/* DMA channel options; assumes UART1 */
static const struct dma_option dma_tx_option = {
STM32_DMAC_USART1_TX, (void *)&STM32_USART_DR(UARTN),
STM32_DMAC_USART1_TX, (void *)&STM32_USART_TDR(UARTN),
STM32_DMA_CCR_MSIZE_8_BIT | STM32_DMA_CCR_PSIZE_8_BIT
};
@@ -35,7 +35,7 @@ static const struct dma_option dma_tx_option = {
#ifdef CONFIG_UART_RX_DMA
/* DMA channel options; assumes UART1 */
static const struct dma_option dma_rx_option = {
STM32_DMAC_USART1_RX, (void *)&STM32_USART_DR(UARTN),
STM32_DMAC_USART1_RX, (void *)&STM32_USART_RDR(UARTN),
STM32_DMA_CCR_MSIZE_8_BIT | STM32_DMA_CCR_PSIZE_8_BIT |
STM32_DMA_CCR_CIRC
};
@@ -130,12 +130,12 @@ void uart_write_char(char c)
while (!uart_tx_ready())
;
STM32_USART_DR(UARTN) = c;
STM32_USART_TDR(UARTN) = c;
}
int uart_read_char(void)
{
return STM32_USART_DR(UARTN);
return STM32_USART_RDR(UARTN);
}
void uart_disable_interrupt(void)
@@ -192,7 +192,7 @@ static void uart_freq_change(void)
{
int div = DIV_ROUND_NEAREST(clock_get_freq(), CONFIG_UART_BAUD_RATE);
#ifdef CHIP_FAMILY_STM32L
#if defined(CHIP_FAMILY_STM32L) || defined(CHIP_FAMILY_STM32F0)
if (div / 16 > 0) {
/*
* CPU clock is high enough to support x16 oversampling.
@@ -222,7 +222,7 @@ void uart_init(void)
#if (UARTN == 1)
STM32_RCC_APB2ENR |= STM32_RCC_PB2_USART1;
#else
STM32_RCC_APB1ENR |= STM32_RCC_PB1_USART ## UARTN;
STM32_RCC_APB1ENR |= CONCAT2(STM32_RCC_PB1_USART, UARTN);
#endif
/* Configure GPIOs */

View File

@@ -57,6 +57,7 @@ struct stm32_def {
{0x427, "STM32L15xxC", 0x08000000, 0x40000, 256},
{0x420, "STM32F100xx", 0x08000000, 0x20000, 1024},
{0x410, "STM32F102R8", 0x08000000, 0x10000, 1024},
{0x448, "STM32F07xB", 0x08000000, 0x20000, 1024},
{ 0 }
};