1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2025-01-18 12:52:44 +01:00

stm32f2: Update with last api changes

* Update headers from ST
* Add linker scripts
This commit is contained in:
Vincent Dupont 2016-03-23 15:26:18 +01:00
parent 4064858e8d
commit 15b6814d9b
22 changed files with 30978 additions and 7016 deletions

View File

@ -2,6 +2,6 @@
MODULE = cpu
# add a list of subdirectories, that should also be build
DIRS += periph $(RIOTCPU)/cortexm_common
DIRS = periph $(RIOTCPU)/cortexm_common $(RIOTCPU)/stm32_common
include $(RIOTBASE)/Makefile.base

View File

@ -1,6 +1,5 @@
export CPU_ARCH = cortex-m3
export CPU_FAM = stm32f2
# use common periph functions
USEMODULE += periph_common
include $(RIOTCPU)/stm32_common/Makefile.include
include $(RIOTCPU)/Makefile.include.cortexm_common

View File

@ -77,9 +77,20 @@ static void clk_init(void)
RCC->CFGR |= (uint32_t)CLOCK_APB2_DIV;
/* PCLK1 = HCLK */
RCC->CFGR |= (uint32_t)CLOCK_APB1_DIV;
/* PLL configuration: PLLCLK = SOURCE_CLOCK / SOURCE_CLOCK_DIV * SOURCE_CLOCK_MUL */
/* reset PLL config register */
RCC->PLLCFGR &= ~((uint32_t)(RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLP | RCC_PLLCFGR_PLLQ));
RCC->PLLCFGR |= (uint32_t)(RCC_PLL_SOURCE | CLOCK_PLL_DIV | (CLOCK_PLL_MUL << 6));
/* set HSE as source for the PLL */
RCC->PLLCFGR |= RCC_PLL_SOURCE;
/* set division factor for main PLL input clock */
RCC->PLLCFGR |= (CLOCK_PLL_M & 0x3F);
/* set main PLL multiplication factor for VCO */
RCC->PLLCFGR |= (CLOCK_PLL_N & 0x1FF) << 6;
/* set main PLL division factor for main system clock */
RCC->PLLCFGR |= (((CLOCK_PLL_P & 0x03) >> 1) - 1) << 16;
/* set main PLL division factor for USB OTG FS, SDIO and RNG clocks */
RCC->PLLCFGR |= (CLOCK_PLL_Q & 0x0F) << 24;
/* Enable PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till PLL is ready */

View File

@ -21,7 +21,17 @@
#ifndef __CPU_CONF_H
#define __CPU_CONF_H
#include "stm32f2xx.h"
#include "cpu_conf_common.h"
#if defined(CPU_MODEL_STM32F205RG)
#include "stm32f205xx.h"
#elif defined(CPU_MODEL_STM32F207ZG)
#include "stm32f207xx.h"
#elif defined(CPU_MODEL_STM32F215RG) || defined(CPU_MODEL_STM32F215VG) || defined(CPU_MODEL_STM32F215VE)
#include "stm32f215xx.h"
#elif defined(CPU_MODEL_STM32F217ZG)
#include "stm32f217xx.h"
#endif
#ifdef __cplusplus
extern "C" {
@ -36,20 +46,6 @@ extern "C" {
#define CPU_FLASH_BASE FLASH_BASE
/** @} */
/**
* @brief Length for reading CPU_ID
*/
#define CPUID_ID_LEN (12)
/**
* @brief Configure the CPU's clock system
*
* @param[in] source source clock frequency
* @param[in] target target clock frequency
* @param[in] prescale prescaler to use
*/
void cpu_clock_scale(uint32_t source, uint32_t target, uint32_t *prescale);
#ifdef __cplusplus
}
#endif

View File

@ -19,37 +19,35 @@
#ifndef PERIPH_CPU_H
#define PERIPH_CPU_H
#include "cpu.h"
#include "periph_cpu_common.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Overwrite the default gpio_t type definition
* @brief Generate GPIO mode bitfields
*
* We use 5 bit to encode the mode:
* - bit 0+1: pin mode (input / output)
* - bit 2+3: pull resistor configuration
* - bit 4: output type (0: push-pull, 1: open-drain)
*/
#define GPIO_MODE(io, pr, ot) ((io << 0) | (pr << 2) | (ot << 4))
/**
* @brief Override GPIO mode options
* @{
*/
#define HAVE_GPIO_T
typedef uint32_t gpio_t;
/** @} */
/**
* @brief Definition of a fitting UNDEF value
*/
#define GPIO_UNDEF (0xffffffff)
/**
* @brief Define a CPU specific GPIO pin generator macro
*/
#define GPIO_PIN(x, y) ((GPIOA_BASE + (x << 10)) | y)
/**
* @brief declare needed generic SPI functions
* @{
*/
#define PERIPH_SPI_NEEDS_TRANSFER_BYTES
#define PERIPH_SPI_NEEDS_TRANSFER_REG
#define PERIPH_SPI_NEEDS_TRANSFER_REGS
#define HAVE_GPIO_MODE_T
typedef enum {
GPIO_IN = GPIO_MODE(0, 0, 0), /**< input w/o pull R */
GPIO_IN_PD = GPIO_MODE(0, 2, 0), /**< input with pull-down */
GPIO_IN_PU = GPIO_MODE(0, 1, 0), /**< input with pull-up */
GPIO_OUT = GPIO_MODE(1, 0, 0), /**< push-pull output */
GPIO_OD = GPIO_MODE(1, 0, 1), /**< open-drain w/o pull R */
GPIO_OD_PU = GPIO_MODE(1, 1, 1) /**< open-drain with pull-up */
} gpio_mode_t;
/** @} */
/**
@ -104,10 +102,27 @@ typedef struct {
} uart_conf_t;
/** @} */
/**
* @brief ADC channel configuration data
*/
typedef struct {
gpio_t pin; /**< pin connected to the channel */
uint8_t dev; /**< ADCx - 1 device used for the channel */
uint8_t chan; /**< CPU ADC channel connected to the pin */
} adc_conf_t;
/**
* @brief DAC line configuration data
*/
typedef struct {
gpio_t pin; /**< pin connected to the line */
uint8_t chan; /**< DAC device used for this line */
} dac_conf_t;
/**
* @brief Configure the alternate function for the given pin
*
* @note This is meant for internal use in STM32F4 peripheral drivers only
* @note This is meant for internal use in STM32F2 peripheral drivers only
*
* @param[in] pin pin to configure
* @param[in] af alternate function to use

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -1,5 +1,6 @@
/*
* Copyright (C) 2015 Engineering-Spirit
* Copyright (C) 2016 OTA keys S.A.
*
* 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
@ -11,17 +12,21 @@
* @{
*
* @file
* @brief Memory definitions for the STM32F215RG
* @brief Memory definitions for the STM32F205RG
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
* @author Vincent Dupont <vincent@otakeys.com>
*
* @}
*/
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K
rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
ram (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
cpuid (r) : ORIGIN = 0x1fff7a10, LENGTH = 12
}
_cpuid_address = ORIGIN(cpuid);
INCLUDE cortexm_base.ld

View File

@ -0,0 +1,30 @@
/*
* Copyright (C) 2015 Engineering-Spirit
*
* 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.
*/
/**
* @addtogroup cpu_stm32f2
* @{
*
* @file
* @brief Memory definitions for the STM32F207ZG
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
*
* @}
*/
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
ram (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
cpuid (r) : ORIGIN = 0x1fff7a10, LENGTH = 12
}
_cpuid_address = ORIGIN(cpuid);
INCLUDE cortexm_base.ld

View File

@ -1,5 +1,6 @@
/*
* Copyright (C) 2015 Engineering-Spirit
* Copyright (C) 2016 OTA keys S.A.
*
* 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
@ -14,6 +15,7 @@
* @brief Memory definitions for the STM32F215RG
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
* @author Vincent Dupont <vincent@otakeys.com>
*
* @}
*/
@ -22,6 +24,9 @@ MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
ram (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
cpuid (r) : ORIGIN = 0x1fff7a10, LENGTH = 12
}
_cpuid_address = ORIGIN(cpuid);
INCLUDE cortexm_base.ld

View File

@ -0,0 +1,32 @@
/*
* Copyright (C) 2015 Engineering-Spirit
* Copyright (C) 2016 OTA keys S.A.
*
* 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.
*/
/**
* @addtogroup cpu_stm32f2
* @{
*
* @file
* @brief Memory definitions for the STM32F215VG
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
* @author Vincent Dupont <vincent@otakeys.com>
*
* @}
*/
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K
ram (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
cpuid (r) : ORIGIN = 0x1fff7a10, LENGTH = 12
}
_cpuid_address = ORIGIN(cpuid);
INCLUDE cortexm_base.ld

View File

@ -0,0 +1,32 @@
/*
* Copyright (C) 2015 Engineering-Spirit
* Copyright (C) 2016 OTA keys S.A.
*
* 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.
*/
/**
* @addtogroup cpu_stm32f2
* @{
*
* @file
* @brief Memory definitions for the STM32F215VG
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
* @author Vincent Dupont <vincent@otakeys.com>
*
* @}
*/
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
ram (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
cpuid (r) : ORIGIN = 0x1fff7a10, LENGTH = 12
}
_cpuid_address = ORIGIN(cpuid);
INCLUDE cortexm_base.ld

View File

@ -0,0 +1,32 @@
/*
* Copyright (C) 2015 Engineering-Spirit
* Copyright (C) 2016 OTA keys S.A.
*
* 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.
*/
/**
* @addtogroup cpu_stm32f2
* @{
*
* @file
* @brief Memory definitions for the STM32F217ZG
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
* @author Vincent Dupont <vincent@otakeys.com>
*
* @}
*/
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
ram (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
cpuid (r) : ORIGIN = 0x1fff7a10, LENGTH = 12
}
_cpuid_address = ORIGIN(cpuid);
INCLUDE cortexm_base.ld

View File

@ -1,28 +0,0 @@
/*
* Copyright (C) 2015 Engineering-Spirit
*
* 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.
*/
/**
* @addtogroup driver_periph
* @{
*
* @file
* @brief Low-level CPUID driver implementation
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
*/
#include <string.h>
#include "periph/cpuid.h"
void cpuid_get(void *id)
{
memcpy(id, (void *)(0x1fff7a10), CPUID_ID_LEN);
}
/** @} */

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015 Engineering-Spirit
* Copyright (C) 2015 Freie Universität Berlin
*
* 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
@ -13,9 +13,8 @@
* @file
* @brief Low-level GPIO driver implementation
*
* @author Hauke Petersen <mail@haukepetersen.de>
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Fabian Nack <nack@inf.fu-berlin.de>
*
* @}
*/
@ -31,18 +30,10 @@
*/
#define GPIO_ISR_CHAN_NUMOF (16U)
/**
* @brief Datastructure to hold an interrupt context
*/
typedef struct {
void (*cb)(void *arg); /**< interrupt callback routine */
void *arg; /**< optional argument */
} exti_ctx_t;
/**
* @brief Hold one callback function pointer for each interrupt line
*/
static exti_ctx_t exti_chan[GPIO_ISR_CHAN_NUMOF];
static gpio_isr_ctx_t exti_chan[GPIO_ISR_CHAN_NUMOF];
/**
* @brief Extract the port base address from the given pin identifier
@ -71,32 +62,31 @@ static inline int _pin_num(gpio_t pin)
return (pin & 0x0f);
}
int gpio_init(gpio_t pin, gpio_dir_t dir, gpio_pp_t pullup)
int gpio_init(gpio_t pin, gpio_mode_t mode)
{
GPIO_TypeDef *port = _port(pin);
int pin_num = _pin_num(pin);
/* enable clock */
RCC->AHB1ENR |= (RCC_AHB1ENR_GPIOAEN << _port_num(pin));
/* configure pull register */
port->PUPDR &= ~(3 << (2 * pin_num));
port->PUPDR |= (pullup << (2 * pin_num));
/* set direction */
if (dir == GPIO_DIR_OUT) {
port->MODER &= ~(3 << (2 * pin_num)); /* set pin to output mode */
port->MODER |= (1 << (2 * pin_num));
port->OTYPER &= ~(1 << pin_num); /* set to push-pull */
port->OSPEEDR |= (3 << (2 * pin_num)); /* set to high speed */
port->ODR &= ~(1 << pin_num); /* set pin to low signal */
}
else {
port->MODER &= ~(3 << (2 * pin_num)); /* configure pin as input */
}
/* set mode */
port->MODER &= ~(0x3 << (2 * pin_num));
port->MODER |= ((mode & 0x3) << (2 * pin_num));
/* set pull resistor configuration */
port->PUPDR &= ~(0x3 << (2 * pin_num));
port->PUPDR |= (((mode >> 2) & 0x3) << (2 * pin_num));
/* set output mode */
port->OTYPER &= ~(1 << pin_num);
port->OTYPER |= (((mode >> 4) & 0x1) << pin_num);
/* reset speed value and clear pin */
port->OSPEEDR |= (3 << (2 * pin_num));
port->BSRR = (1 << (pin_num + 16));
return 0;
}
int gpio_init_int(gpio_t pin,
gpio_pp_t pullup, gpio_flank_t flank,
int gpio_init_int(gpio_t pin, gpio_mode_t mode, gpio_flank_t flank,
gpio_cb_t cb, void *arg)
{
int pin_num = _pin_num(pin);
@ -108,7 +98,7 @@ int gpio_init_int(gpio_t pin,
/* enable the SYSCFG clock */
RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN;
/* initialize pin as input */
gpio_init(pin, GPIO_DIR_IN, pullup);
gpio_init(pin, mode);
/* enable global pin interrupt */
if (pin_num < 5) {
NVIC_EnableIRQ(EXTI0_IRQn + pin_num);
@ -157,6 +147,14 @@ void gpio_init_af(gpio_t pin, gpio_af_t af)
port->AFR[(pin_num > 7) ? 1 : 0] |= (af << ((pin_num & 0x07) * 4));
}
void gpio_init_analog(gpio_t pin)
{
/* enable clock */
RCC->AHB1ENR |= (RCC_AHB1ENR_GPIOAEN << _port_num(pin));
/* set to analog mode */
_port(pin)->MODER |= (0x3 << (2 * _pin_num(pin)));
}
void gpio_irq_enable(gpio_t pin)
{
EXTI->IMR |= (1 << _pin_num(pin));
@ -181,12 +179,12 @@ int gpio_read(gpio_t pin)
void gpio_set(gpio_t pin)
{
_port(pin)->BSRRL = (1 << _pin_num(pin));
_port(pin)->BSRR = (1 << _pin_num(pin));
}
void gpio_clear(gpio_t pin)
{
_port(pin)->BSRRH = (1 << _pin_num(pin));
_port(pin)->BSRR = (1 << (_pin_num(pin) + 16));
}
void gpio_toggle(gpio_t pin)
@ -209,9 +207,11 @@ void gpio_write(gpio_t pin, int value)
void isr_exti(void)
{
/* only generate interrupts against lines which have their IMR set */
uint32_t pending_isr = (EXTI->PR & EXTI->IMR);
for (unsigned i = 0; i < GPIO_ISR_CHAN_NUMOF; i++) {
if (EXTI->PR & (1 << i)) {
EXTI->PR = (1 << i); /* clear by writing a 1 */
if (pending_isr & (1 << i)) {
EXTI->PR = (1 << i); /* clear by writing a 1 */
exti_chan[i].cb(exti_chan[i].arg);
}
}

View File

@ -19,23 +19,26 @@
*/
#include "cpu.h"
#include "periph/random.h"
#include "periph/hwrng.h"
#include "periph_conf.h"
/* ignore file in case no RNG device is defined */
#if RANDOM_NUMOF
#ifdef RNG
void random_init(void)
void hwrng_init(void)
{
random_poweron();
}
int random_read(char *buf, unsigned int num)
void hwrng_read(uint8_t *buf, unsigned int num)
{
/* cppcheck-suppress variableScope */
uint32_t tmp;
unsigned int count = 0;
RCC->AHB2ENR |= RCC_AHB2ENR_RNGEN;
RNG->CR = RNG_CR_RNGEN;
while (count < num) {
/* wait for random data to be ready to read */
while (!(RNG->SR & RNG_SR_DRDY));
@ -48,17 +51,6 @@ int random_read(char *buf, unsigned int num)
}
}
return (int)count;
}
void random_poweron(void)
{
RCC->AHB2ENR |= RCC_AHB2ENR_RNGEN;
RNG->CR = RNG_CR_RNGEN;
}
void random_poweroff(void)
{
RNG->CR = 0;
RCC->AHB2ENR &= ~RCC_AHB2ENR_RNGEN;
}

View File

@ -264,10 +264,10 @@ int i2c_read_bytes(i2c_t dev, uint8_t address, char *data, int length)
i2c->CR1 &= ~(I2C_CR1_ACK);
DEBUG("Clear ADDR and set STOP = 1\n");
state = disableIRQ();
state = irq_disable();
_clear_addr(i2c);
i2c->CR1 |= (I2C_CR1_STOP);
restoreIRQ(state);
irq_restore(state);
DEBUG("Wait for RXNE == 1\n");
@ -289,20 +289,20 @@ int i2c_read_bytes(i2c_t dev, uint8_t address, char *data, int length)
DEBUG("Set POS bit\n");
i2c->CR1 |= (I2C_CR1_POS | I2C_CR1_ACK);
DEBUG("Crit block: Clear ADDR bit and clear ACK flag\n");
state = disableIRQ();
state = irq_disable();
_clear_addr(i2c);
i2c->CR1 &= ~(I2C_CR1_ACK);
restoreIRQ(state);
irq_restore(state);
DEBUG("Wait for transfer to be completed\n");
while (!(i2c->SR1 & I2C_SR1_BTF));
DEBUG("Crit block: set STOP and read first byte\n");
state = disableIRQ();
state = irq_disable();
i2c->CR1 |= (I2C_CR1_STOP);
data[0] = (char)i2c->DR;
restoreIRQ(state);
irq_restore(state);
DEBUG("read second byte\n");
data[1] = (char)i2c->DR;
@ -338,10 +338,10 @@ int i2c_read_bytes(i2c_t dev, uint8_t address, char *data, int length)
i2c->CR1 &= ~(I2C_CR1_ACK);
DEBUG("Crit block: set STOP and read N-2 byte\n");
state = disableIRQ();
state = irq_disable();
data[i++] = (char)i2c->DR;
i2c->CR1 |= (I2C_CR1_STOP);
restoreIRQ(state);
irq_restore(state);
DEBUG("Read N-1 byte\n");
data[i++] = (char)i2c->DR;

View File

@ -7,7 +7,7 @@
*/
/**
* @ingroup cpu_stm32f2
* @ingroup cpu_stm32f4
* @{
*
* @file
@ -30,16 +30,11 @@
/** Unified IRQ handler for all timers */
static inline void irq_handler(tim_t timer, TIM_TypeDef *dev);
/** Type for timer state */
typedef struct {
void (*cb)(int);
} timer_conf_t;
/** Timer state memory */
timer_conf_t config[TIMER_NUMOF];
static timer_isr_ctx_t config[TIMER_NUMOF];
int timer_init(tim_t dev, unsigned int ticks_per_us, void (*callback)(int))
int timer_init(tim_t dev, unsigned long freq, timer_cb_t cb, void *arg)
{
TIM_TypeDef *timer;
@ -52,7 +47,7 @@ int timer_init(tim_t dev, unsigned int ticks_per_us, void (*callback)(int))
NVIC_SetPriority(TIMER_0_IRQ_CHAN, TIMER_IRQ_PRIO);
/* select timer */
timer = TIMER_0_DEV;
timer->PSC = TIMER_0_PRESCALER * ticks_per_us;
timer->PSC = (TIMER_0_FREQ / freq) - 1;
break;
#endif
#if TIMER_1_EN
@ -63,7 +58,7 @@ int timer_init(tim_t dev, unsigned int ticks_per_us, void (*callback)(int))
NVIC_SetPriority(TIMER_1_IRQ_CHAN, TIMER_IRQ_PRIO);
/* select timer */
timer = TIMER_1_DEV;
timer->PSC = TIMER_1_PRESCALER * ticks_per_us;
timer->PSC = (TIMER_1_FREQ / freq) - 1;
break;
#endif
case TIMER_UNDEFINED:
@ -72,7 +67,8 @@ int timer_init(tim_t dev, unsigned int ticks_per_us, void (*callback)(int))
}
/* set callback function */
config[dev].cb = callback;
config[dev].cb = cb;
config[dev].arg = arg;
/* set timer to run in counter mode */
timer->CR1 = 0;
@ -290,22 +286,22 @@ static inline void irq_handler(tim_t timer, TIM_TypeDef *dev)
if (dev->SR & TIM_SR_CC1IF) {
dev->DIER &= ~TIM_DIER_CC1IE;
dev->SR &= ~TIM_SR_CC1IF;
config[timer].cb(0);
config[timer].cb(config[timer].arg, 0);
}
else if (dev->SR & TIM_SR_CC2IF) {
dev->DIER &= ~TIM_DIER_CC2IE;
dev->SR &= ~TIM_SR_CC2IF;
config[timer].cb(1);
config[timer].cb(config[timer].arg, 1);
}
else if (dev->SR & TIM_SR_CC3IF) {
dev->DIER &= ~TIM_DIER_CC3IE;
dev->SR &= ~TIM_SR_CC3IF;
config[timer].cb(2);
config[timer].cb(config[timer].arg, 2);
}
else if (dev->SR & TIM_SR_CC4IF) {
dev->DIER &= ~TIM_DIER_CC4IE;
dev->SR &= ~TIM_SR_CC4IF;
config[timer].cb(3);
config[timer].cb(config[timer].arg, 3);
}
if (sched_context_switch_request) {
thread_yield();

View File

@ -78,8 +78,8 @@ int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg)
mutex_lock(&tx_sync[uart]);
/* configure pins */
gpio_init(uart_config[uart].rx_pin, GPIO_DIR_IN, GPIO_NOPULL);
gpio_init(uart_config[uart].tx_pin, GPIO_DIR_OUT, GPIO_NOPULL);
gpio_init(uart_config[uart].rx_pin, GPIO_IN);
gpio_init(uart_config[uart].tx_pin, GPIO_OUT);
gpio_init_af(uart_config[uart].rx_pin, uart_config[uart].af);
gpio_init_af(uart_config[uart].tx_pin, uart_config[uart].af);
/* enable UART clock */
@ -119,7 +119,7 @@ int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg)
void uart_write(uart_t uart, const uint8_t *data, size_t len)
{
/* in case we are inside an ISR, we need to send blocking */
if (inISR()) {
if (irq_is_in()) {
/* send data by active waiting on the TXE flag */
USART_TypeDef *dev = _dev(uart);
for (int i = 0; i < len; i++) {
@ -172,7 +172,12 @@ static inline void irq_handler(int uart, USART_TypeDef *dev)
static inline void dma_handler(int uart, int stream)
{
/* clear DMA done flag */
dma_base(stream)->IFCR[dma_hl(stream)] = dma_ifc(stream);
if (stream < 4) {
dma_base(stream)->LIFCR = dma_ifc(stream);
}
else {
dma_base(stream)->HIFCR = dma_ifc(stream);
}
mutex_unlock(&tx_sync[uart]);
if (sched_context_switch_request) {
thread_yield();

View File

@ -35,7 +35,7 @@ void dummy_handler(void) {
WEAK_DEFAULT void isr_svc(void);
WEAK_DEFAULT void isr_pendsv(void);
WEAK_DEFAULT void isr_systick(void);
/* STM32F4 specific interrupt vectors */
/* STM32F2 specific interrupt vectors */
WEAK_DEFAULT void isr_wwdg(void);
WEAK_DEFAULT void isr_pvd(void);
WEAK_DEFAULT void isr_tamp_stamp(void);
@ -116,7 +116,7 @@ WEAK_DEFAULT void isr_hash_rng(void);
ISR_VECTORS const void *interrupt_vector[] = {
/* Exception stack pointer */
(void*) (&_estack), /* pointer to the top of the stack */
/* Cortex-M4 handlers */
/* Cortex-M3 handlers */
(void*) reset_handler_default, /* entry point of the program */
(void*) nmi_default, /* non maskable interrupt handler */
(void*) hard_fault_default, /* hard fault exception */