1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2024-12-29 04:50:03 +01:00

Merge pull request #5397 from OTAkeys/pr/stm32f2xx

cpu: add stm32f2xx family support (based on #4497)
This commit is contained in:
Kaspar Schleiser 2016-08-31 21:14:37 +02:00 committed by GitHub
commit 26e4004de4
36 changed files with 34833 additions and 0 deletions

View File

@ -0,0 +1,3 @@
MODULE = board
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,15 @@
# Put defined MCU peripherals here (in alphabetical order)
FEATURES_PROVIDED += periph_cpuid
FEATURES_PROVIDED += periph_gpio
FEATURES_PROVIDED += periph_i2c
FEATURES_PROVIDED += periph_pwm
FEATURES_PROVIDED += periph_rtc
FEATURES_PROVIDED += periph_spi
FEATURES_PROVIDED += periph_timer
FEATURES_PROVIDED += periph_uart
# Various other features (if any)
FEATURES_PROVIDED += cpp
# The board MPU family (used for grouping by the CI system)
FEATURES_MCU_GROUP = cortex-m3

View File

@ -0,0 +1,6 @@
# define the cpu used by the nucleo-f207 board
export CPU = stm32f2
export CPU_MODEL = stm32f207zg
# load the common Makefile.include for Nucleo boards
include $(RIOTBOARD)/nucleo-common/Makefile.include

View File

@ -0,0 +1,33 @@
/*
* 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.
*/
/**
* @ingroup boards_nucleo-f207
* @{
*
* @file
* @brief Board specific implementations for the nucleo-f207 board
*
* @author Vincent Dupont <vincent@otakeys.com>
*
* @}
*/
#include "board.h"
#include "periph/gpio.h"
void board_init(void)
{
/* initialize the CPU */
cpu_init();
/* initialize the boards LEDs */
gpio_init(LED0_PIN, GPIO_OUT);
gpio_init(LED1_PIN, GPIO_OUT);
gpio_init(LED2_PIN, GPIO_OUT);
}

7
boards/nucleo-f207/dist/openocd.cfg vendored Normal file
View File

@ -0,0 +1,7 @@
source [find interface/stlink-v2-1.cfg]
transport select hla_swd
source [find target/stm32f2x.cfg]
reset_config srst_only

View File

@ -0,0 +1,79 @@
/*
* 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.
*/
/**
* @defgroup boards_nucleo-f207 Nucleo-F207
* @ingroup boards
* @brief Board specific files for the nucleo-f207 board
* @{
*
* @file
* @brief Board specific definitions for the nucleo-f207 board
*
* @author Vincent Dupont <vincent@otakeys.com
* @author Toon Stegen <toon.stegen@altran.com>
*/
#ifndef BOARD_H_
#define BOARD_H_
#include "board_common.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief LED pin definitions and handlers
* @{
*/
#undef LED0_PIN
#undef LED0_MASK
#undef LED0_ON
#undef LED0_OFF
#undef LED0_TOGGLE
#define LED0_PIN GPIO_PIN(PORT_B, 0)
#define LED0_MASK (1 << 0)
#define LED0_ON (GPIOB->BSRR = LED0_MASK)
#define LED0_OFF (GPIOB->BSRR = (LED0_MASK << 16))
#define LED0_TOGGLE (GPIOB->ODR ^= LED0_MASK)
#define LED1_PIN GPIO_PIN(PORT_B, 7)
#define LED1_MASK (1 << 7)
#define LED1_ON (GPIOB->BSRR = LED1_MASK)
#define LED1_OFF (GPIOB->BSRR = (LED1_MASK << 16))
#define LED1_TOGGLE (GPIOB->ODR ^= LED1_MASK)
#define LED2_PIN GPIO_PIN(PORT_B, 14)
#define LED2_MASK (1 << 14)
#define LED2_ON (GPIOB->BSRR = LED2_MASK)
#define LED2_OFF (GPIOB->BSRR = (LED2_MASK << 16))
#define LED2_TOGGLE (GPIOB->ODR ^= LED2_MASK)
/** @} */
/**
* @brief Use the 1st UART for STDIO on this board
*/
#define UART_STDIO_DEV UART_DEV(0)
/**
* @brief User button
*/
#define BTN_B1_PIN GPIO_PIN(PORT_C, 13)
/**
* @brief Initialize board specific hardware, including clock, LEDs and std-IO
*/
void board_init(void);
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H_ */
/** @} */

View File

@ -0,0 +1,320 @@
/*
* 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.
*/
/**
* @ingroup boards_nucleo-f207
* @{
*
* @file
* @name Peripheral MCU configuration for the nucleo-f207 board
*
* @author Vincent Dupont <vincent@otakeys.com>
* @author Aurelien Gonce <aurelien.gonce@altran.fr>
* @author Toon Stegen <toon.stegen@altran.com>
*/
#ifndef PERIPH_CONF_H_
#define PERIPH_CONF_H_
#include "periph_cpu.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @name Clock system configuration
* @{
*/
#define CLOCK_HSE (8000000U) /* external oscillator */
#define CLOCK_CORECLOCK (120000000U) /* desired core clock frequency */
/* the actual PLL values are automatically generated */
#define CLOCK_PLL_M (CLOCK_HSE / 1000000)
#define CLOCK_PLL_N ((CLOCK_CORECLOCK / 1000000) * 2)
#define CLOCK_PLL_P (2U)
#define CLOCK_PLL_Q (CLOCK_PLL_N / 48)
#define CLOCK_AHB_DIV RCC_CFGR_HPRE_DIV1
#define CLOCK_APB1_DIV RCC_CFGR_PPRE1_DIV4
#define CLOCK_APB2_DIV RCC_CFGR_PPRE2_DIV2
#define CLOCK_FLASH_LATENCY FLASH_ACR_LATENCY_5WS
/* bus clocks for simplified peripheral initialization, UPDATE MANUALLY! */
#define CLOCK_AHB (CLOCK_CORECLOCK / 1)
#define CLOCK_APB1 (CLOCK_CORECLOCK / 4)
#define CLOCK_APB2 (CLOCK_CORECLOCK / 2)
/** @} */
/**
* @name PWM configuration
* @{
*/
#define PWM_NUMOF (1U)
#define PWM_0_EN 1
static const pwm_conf_t pwm_config[PWM_NUMOF] = {
{
.tim = 2,
.port = GPIOC,
.bus = AHB1,
.rcc_mask = RCC_AHB1ENR_GPIOCEN,
.CH0 = 6,
.CH1 = 7,
.CH2 = 8,
.CH3 = 9,
.AF = 2
}
};
/** @} */
/**
* @name Timer configuration
* @{
*/
#define TIMER_NUMOF (4U)
#define TIMER_0_EN 1
#define TIMER_1_EN 1
#define TIMER_2_EN 1
#define TIMER_3_EN 1
#define TIMER_IRQ_PRIO 1
static const timer_conf_t timer_config[TIMER_NUMOF] = {
{
.dev = TIM2,
.channels = 4,
.freq = (CLOCK_APB1 * 2),
.rcc_mask = RCC_APB1ENR_TIM2EN,
.bus = APB1,
.irqn = TIM2_IRQn,
.priority = TIMER_IRQ_PRIO
},
{
.dev = TIM5,
.channels = 4,
.freq = (CLOCK_APB1 * 2),
.rcc_mask = RCC_APB1ENR_TIM5EN,
.bus = APB1,
.irqn = TIM5_IRQn,
.priority = TIMER_IRQ_PRIO
},
{
.dev = TIM3,
.channels = 4,
.freq = (CLOCK_APB1 * 2),
.rcc_mask = RCC_APB1ENR_TIM3EN,
.bus = APB1,
.irqn = TIM3_IRQn,
.priority = TIMER_IRQ_PRIO
},
{
.dev = TIM4,
.channels = 4,
.freq = (CLOCK_APB1 * 2),
.rcc_mask = RCC_APB1ENR_TIM4EN,
.bus = APB1,
.irqn = TIM4_IRQn,
.priority = TIMER_IRQ_PRIO
}
};
#define TIMER_0_ISR isr_tim2
#define TIMER_1_ISR isr_tim5
#define TIMER_2_ISR isr_tim3
#define TIMER_3_ISR isr_tim4
/** @} */
/**
* @brief UART configuration
* @{
*/
static const uart_conf_t uart_config[] = {
{
.dev = USART3,
.rcc_mask = RCC_APB1ENR_USART3EN,
.rx_pin = GPIO_PIN(PORT_D, 9),
.tx_pin = GPIO_PIN(PORT_D, 8),
.rts_pin = GPIO_PIN(PORT_D, 12),
.cts_pin = GPIO_PIN(PORT_D, 11),
.rx_mode = GPIO_IN,
.tx_mode = GPIO_OUT,
.af = GPIO_AF7,
.irqn = USART3_IRQn,
.dma_stream = 3,
.dma_chan = 4,
.hw_flow_ctrl = 0
},
{
.dev = USART2,
.rcc_mask = RCC_APB1ENR_USART2EN,
.rx_pin = GPIO_PIN(PORT_D, 6),
.tx_pin = GPIO_PIN(PORT_D, 5),
.rts_pin = GPIO_PIN(PORT_D, 4),
.cts_pin = GPIO_PIN(PORT_D, 3),
.rx_mode = GPIO_IN,
.tx_mode = GPIO_OUT,
.rts_mode = GPIO_OUT,
.cts_mode = GPIO_IN,
.af = GPIO_AF7,
.irqn = USART2_IRQn,
.dma_stream = 6,
.dma_chan = 4,
.hw_flow_ctrl = 1
},
{
.dev = USART1,
.rcc_mask = RCC_APB2ENR_USART1EN,
.rx_pin = GPIO_PIN(PORT_A, 10),
.tx_pin = GPIO_PIN(PORT_A, 9),
.rts_pin = GPIO_PIN(PORT_A, 12),
.cts_pin = GPIO_PIN(PORT_A, 11),
.rx_mode = GPIO_IN,
.tx_mode = GPIO_OUT,
.rts_mode = GPIO_OUT,
.cts_mode = GPIO_IN,
.af = GPIO_AF7,
.irqn = USART1_IRQn,
.dma_stream = 7,
.dma_chan = 4,
.hw_flow_ctrl = 1
}
};
/* assign ISR vector names */
#define UART_0_ISR isr_usart3
#define UART_0_DMA_ISR isr_dma1_stream3
#define UART_1_ISR isr_usart2
#define UART_1_DMA_ISR isr_dma1_stream6
#define UART_2_ISR isr_usart1
#define UART_2_DMA_ISR isr_dma1_stream7
/* deduct number of defined UART interfaces */
#define UART_NUMOF (sizeof(uart_config) / sizeof(uart_config[0]))
/** @} */
/**
* @name SPI configuration
* @{
*/
#define SPI_NUMOF (2U)
#define SPI_0_EN 1
#define SPI_1_EN 1
#define SPI_IRQ_PRIO 1
/* SPI 0 device config */
#define SPI_0_DEV SPI1
#define SPI_0_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_SPI1EN)
#define SPI_0_CLKDIS() (RCC->APB2ENR &= ~RCC_APB2ENR_SPI1EN)
#define SPI_0_BUS_DIV 1 /* 1 -> SPI bus runs with half CPU clock, 0 -> quarter CPU clock */
#define SPI_0_IRQ SPI1_IRQn
#define SPI_0_IRQ_HANDLER isr_spi1
/* SPI 0 pin configuration */
#define SPI_0_SCK_PORT GPIOA /* A5 pin is shared with the green LED. */
#define SPI_0_SCK_PIN 5
#define SPI_0_SCK_AF 5
#define SPI_0_SCK_PORT_CLKEN() (RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN)
#define SPI_0_MISO_PORT GPIOA
#define SPI_0_MISO_PIN 6
#define SPI_0_MISO_AF 5
#define SPI_0_MISO_PORT_CLKEN() (RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN)
#define SPI_0_MOSI_PORT GPIOA
#define SPI_0_MOSI_PIN 7
#define SPI_0_MOSI_AF 5
#define SPI_0_MOSI_PORT_CLKEN() (RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN)
/* SPI 1 device config */
#define SPI_1_DEV SPI2
#define SPI_1_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_SPI2EN)
#define SPI_1_CLKDIS() (RCC->APB1ENR &= ~RCC_APB1ENR_SPI2EN)
#define SPI_1_BUS_DIV 0 /* 1 -> SPI bus runs with half CPU clock, 0 -> quarter CPU clock */
#define SPI_1_IRQ SPI2_IRQn
#define SPI_1_IRQ_HANDLER isr_spi2
/* SPI 1 pin configuration */
#define SPI_1_SCK_PORT GPIOB
#define SPI_1_SCK_PIN 3
#define SPI_1_SCK_AF 5
#define SPI_1_SCK_PORT_CLKEN() (RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN)
#define SPI_1_MISO_PORT GPIOB
#define SPI_1_MISO_PIN 4
#define SPI_1_MISO_AF 5
#define SPI_1_MISO_PORT_CLKEN() (RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN)
#define SPI_1_MOSI_PORT GPIOB
#define SPI_1_MOSI_PIN 5
#define SPI_1_MOSI_AF 5
#define SPI_1_MOSI_PORT_CLKEN() (RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN)
/** @} */
/**
* @name I2C configuration
* @{
*/
#define I2C_NUMOF (1U)
#define I2C_0_EN 1
#define I2C_IRQ_PRIO 1
#define I2C_APBCLK (CLOCK_APB1)
/* I2C 0 device configuration */
#define I2C_0_DEV I2C1
#define I2C_0_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_I2C1EN)
#define I2C_0_CLKDIS() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C1EN))
#define I2C_0_EVT_IRQ I2C1_EV_IRQn
#define I2C_0_EVT_ISR isr_i2c1_ev
#define I2C_0_ERR_IRQ I2C1_ER_IRQn
#define I2C_0_ERR_ISR isr_i2c1_er
/* I2C 0 pin configuration */
#define I2C_0_SCL_PORT GPIOB
#define I2C_0_SCL_PIN 8
#define I2C_0_SCL_AF 4
#define I2C_0_SCL_PULLUP 0
#define I2C_0_SCL_CLKEN() (RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN)
#define I2C_0_SDA_PORT GPIOB
#define I2C_0_SDA_PIN 9
#define I2C_0_SDA_AF 4
#define I2C_0_SDA_PULLUP 0
#define I2C_0_SDA_CLKEN() (RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN)
/** @} */
/**
* @brief ADC configuration
*
* We need to define the following fields:
* PIN, device (ADCx), channel
* @{
*/
#define ADC_CONFIG { \
{GPIO_PIN(PORT_A, 4), 0, 0}, \
{GPIO_PIN(PORT_A, 5), 1, 0} \
}
#define ADC_NUMOF (2)
/** @} */
/**
* @brief DAC configuration
* @{
*/
#define DAC_NUMOF (0)
/** @} */
/**
* @brief RTC configuration
* @{
*/
#define RTC_NUMOF (1)
/** @} */
#ifdef __cplusplus
}
#endif
#endif /* PERIPH_CONF_H_ */
/** @} */

7
cpu/stm32f2/Makefile Normal file
View File

@ -0,0 +1,7 @@
# define the module that is build
MODULE = cpu
# add a list of subdirectories, that should also be build
DIRS = periph $(RIOTCPU)/cortexm_common $(RIOTCPU)/stm32_common
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,5 @@
export CPU_ARCH = cortex-m3
export CPU_FAM = stm32f2
include $(RIOTCPU)/stm32_common/Makefile.include
include $(RIOTCPU)/Makefile.include.cortexm_common

103
cpu/stm32f2/cpu.c Normal file
View File

@ -0,0 +1,103 @@
/*
* 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.
*/
/**
* @ingroup cpu_stm32f2
* @{
*
* @file
* @brief Implementation of the kernel cpu functions
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
* @}
*/
#include "cpu.h"
#include "periph_conf.h"
#ifdef HSI_VALUE
# define RCC_CR_SOURCE RCC_CR_HSION
# define RCC_CR_SOURCE_RDY RCC_CR_HSIRDY
# define RCC_PLL_SOURCE RCC_PLLCFGR_PLLSRC_HSI
#else
# define RCC_CR_SOURCE RCC_CR_HSEON
# define RCC_CR_SOURCE_RDY RCC_CR_HSERDY
# define RCC_PLL_SOURCE RCC_PLLCFGR_PLLSRC_HSE
#endif
static void clk_init(void);
void cpu_init(void)
{
/* initialize the Cortex-M core */
cortexm_init();
/* initialize system clocks */
clk_init();
}
/**
* @brief Configure the clock system of the stm32f2
*
*/
static void clk_init(void)
{
/* Reset the RCC clock configuration to the default reset state(for debug purpose) */
/* Set HSION bit */
RCC->CR |= 0x00000001U;
/* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */
RCC->CFGR = 0x00000000U;
/* Reset HSEON, CSSON and PLLON bits */
RCC->CR &= 0xFEF6FFFFU;
/* Reset PLLCFGR register */
RCC->PLLCFGR = 0x24003010U;
/* Reset HSEBYP bit */
RCC->CR &= 0xFFFBFFFFU;
/* Disable all interrupts and clear pending bits */
RCC->CIR = 0x00000000U;
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration */
/* Enable the high speed clock source */
RCC->CR |= RCC_CR_SOURCE;
/* Wait till hish speed clock source is ready,
* NOTE: the MCU will stay here forever if no HSE clock is connected */
while ((RCC->CR & RCC_CR_SOURCE_RDY) == 0);
/* Configure Flash prefetch, Instruction cache, Data cache and wait state */
FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN | FLASH_ACR_DCEN;
/* Flash 2 wait state */
FLASH->ACR &= ~((uint32_t)FLASH_ACR_LATENCY);
FLASH->ACR |= (uint32_t)CLOCK_FLASH_LATENCY;
/* HCLK = SYSCLK */
RCC->CFGR |= (uint32_t)CLOCK_AHB_DIV;
/* PCLK2 = HCLK */
RCC->CFGR |= (uint32_t)CLOCK_APB2_DIV;
/* PCLK1 = HCLK */
RCC->CFGR |= (uint32_t)CLOCK_APB1_DIV;
/* reset PLL config register */
RCC->PLLCFGR &= ~((uint32_t)(RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLP | RCC_PLLCFGR_PLLQ));
/* 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 */
while ((RCC->CR & RCC_CR_PLLRDY) == 0);
/* Select PLL as system clock source */
RCC->CFGR &= ~((uint32_t)(RCC_CFGR_SW));
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
/* Wait till PLL is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL);
}

View File

@ -0,0 +1,54 @@
/*
* 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.
*/
/**
* @defgroup cpu_stm32f2 STM32F2
* @ingroup cpu
* @brief CPU specific implementations for the STM32F2
* @{
*
* @file
* @brief Implementation specific CPU configuration options
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl
*/
#ifndef __CPU_CONF_H
#define __CPU_CONF_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" {
#endif
/**
* @brief ARM Cortex-M specific CPU configuration
* @{
*/
#define CPU_DEFAULT_IRQ_PRIO (1U)
#define CPU_IRQ_NUMOF (81U)
#define CPU_FLASH_BASE FLASH_BASE
/** @} */
#ifdef __cplusplus
}
#endif
#endif /* __CPU_CONF_H */
/** @} */

View File

@ -0,0 +1,304 @@
/*
* 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.
*/
/**
* @ingroup cpu_stm32f2
* @{
*
* @file
* @brief CPU specific definitions for internal peripheral handling
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
* @author Aurelien Gonce <aurelien.gonce@altran.fr>
*/
#ifndef PERIPH_CPU_H
#define PERIPH_CPU_H
#include "periph_cpu_common.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @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_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;
/** @} */
/**
* @brief Available peripheral buses
*/
enum {
AHB1, /**< AHB1 bus */
AHB2, /**< AHB2 bus */
AHB3 /**< AHB3 bus */
};
/**
* @brief Available ports on the STM32F2 family
*/
enum {
PORT_A = 0, /**< port A */
PORT_B = 1, /**< port B */
PORT_C = 2, /**< port C */
PORT_D = 3, /**< port D */
PORT_E = 4, /**< port E */
PORT_F = 5, /**< port F */
PORT_G = 6, /**< port G */
PORT_H = 7, /**< port H */
PORT_I = 8 /**< port I */
};
/**
* @brief Available MUX values for configuring a pin's alternate function
*/
typedef enum {
GPIO_AF0 = 0, /**< use alternate function 0 */
GPIO_AF1, /**< use alternate function 1 */
GPIO_AF2, /**< use alternate function 2 */
GPIO_AF3, /**< use alternate function 3 */
GPIO_AF4, /**< use alternate function 4 */
GPIO_AF5, /**< use alternate function 5 */
GPIO_AF6, /**< use alternate function 6 */
GPIO_AF7, /**< use alternate function 7 */
GPIO_AF8, /**< use alternate function 8 */
GPIO_AF9, /**< use alternate function 9 */
GPIO_AF10, /**< use alternate function 10 */
GPIO_AF11, /**< use alternate function 11 */
GPIO_AF12, /**< use alternate function 12 */
GPIO_AF13, /**< use alternate function 13 */
GPIO_AF14 /**< use alternate function 14 */
} gpio_af_t;
/**
* @name PWM configuration
* @{
*/
typedef struct {
uint8_t tim; /**< timer used */
GPIO_TypeDef *port; /**< pwm device */
uint8_t bus; /**< AHBx bus */
uint32_t rcc_mask; /**< corresponding bit in the RCC register */
uint8_t CH0; /**< channel 0 */
uint8_t CH1; /**< channel 1 */
uint8_t CH2; /**< channel 2 */
uint8_t CH3; /**< channel 3 */
uint8_t AF; /**< alternate function */
} pwm_conf_t;
/**
* @brief Timer configuration
* @{
*/
typedef struct {
TIM_TypeDef *dev; /**< timer device */
uint8_t channels; /**< number of channel */
uint32_t freq; /**< frequency */
uint32_t rcc_mask; /**< corresponding bit in the RCC register */
uint8_t bus; /**< APBx bus the timer is clock from */
uint8_t irqn; /**< global IRQ channel */
uint8_t priority; /**< priority */
} timer_conf_t;
/** @} */
/**
* @brief Structure for UART configuration data
* @{
*/
typedef struct {
USART_TypeDef *dev; /**< UART device base register address */
uint32_t rcc_mask; /**< bit in clock enable register */
gpio_t rx_pin; /**< RX pin */
gpio_t tx_pin; /**< TX pin */
gpio_mode_t rx_mode; /**< RX pin mode */
gpio_mode_t tx_mode; /**< TX pin mode */
gpio_t rts_pin; /**< RTS pin */
gpio_t cts_pin; /**< CTS pin */
gpio_mode_t rts_mode; /**< RTS pin mode */
gpio_mode_t cts_mode; /**< CTS pin mode */
gpio_af_t af; /**< alternate pin function to use */
uint8_t irqn; /**< IRQ channel */
uint8_t dma_stream; /**< DMA stream used for TX */
uint8_t dma_chan; /**< DMA channel used for TX */
uint8_t hw_flow_ctrl; /**< Support for hardware flow control */
} uart_conf_t;
/** @} */
/**
* @brief Available number of ADC devices
*/
#define ADC_DEVS (2U)
/**
* @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 Override the ADC resolution configuration
* @{
*/
#define HAVE_ADC_RES_T
typedef enum {
ADC_RES_6BIT = 0x03000000, /**< ADC resolution: 6 bit */
ADC_RES_8BIT = 0x02000000, /**< ADC resolution: 8 bit */
ADC_RES_10BIT = 0x01000000, /**< ADC resolution: 10 bit */
ADC_RES_12BIT = 0x00000000, /**< ADC resolution: 12 bit */
ADC_RES_14BIT = 1, /**< ADC resolution: 14 bit (not supported) */
ADC_RES_16BIT = 2 /**< ADC resolution: 16 bit (not supported)*/
} adc_res_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 STM32F2 peripheral drivers only
*
* @param[in] pin pin to configure
* @param[in] af alternate function to use
*/
void gpio_init_af(gpio_t pin, gpio_af_t af);
/**
* @brief Configure the given pin to be used as ADC input
*
* @param[in] pin pin to configure
*/
void gpio_init_analog(gpio_t pin);
/**
* @brief Power on the DMA device the given stream belongs to
*
* @param[in] stream logical DMA stream
*/
static inline void dma_poweron(int stream)
{
if (stream < 8) {
RCC->AHB1ENR |= RCC_AHB1ENR_DMA1EN;
} else {
RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN;
}
}
/**
* @brief Get DMA base register
*
* For simplifying DMA stream handling, we map the DMA channels transparently to
* one integer number, such that DMA1 stream0 equals 0, DMA2 stream0 equals 8,
* DMA2 stream 7 equals 15 and so on.
*
* @param[in] stream logical DMA stream
*/
static inline DMA_TypeDef *dma_base(int stream)
{
return (stream < 8) ? DMA1 : DMA2;
}
/**
* @brief Get the DMA stream base address
*
* @param[in] stream logical DMA stream
*
* @return base address for the selected DMA stream
*/
static inline DMA_Stream_TypeDef *dma_stream(int stream)
{
uint32_t base = (uint32_t)dma_base(stream);
return (DMA_Stream_TypeDef *)(base + (0x10 + (0x18 * (stream & 0x7))));
}
/**
* @brief Select high or low DMA interrupt register based on stream number
*
* @param[in] stream logical DMA stream
*
* @return 0 for streams 0-3, 1 for streams 3-7
*/
static inline int dma_hl(int stream)
{
return ((stream & 0x4) >> 2);
}
/**
* @brief Get the interrupt flag clear bit position in the DMA LIFCR register
*
* @param[in] stream logical DMA stream
*/
static inline uint32_t dma_ifc(int stream)
{
switch (stream & 0x3) {
case 0: /* 0 and 4 */
return (1 << 5);
case 1: /* 1 and 5 */
return (1 << 11);
case 2: /* 2 and 6 */
return (1 << 21);
case 3: /* 3 and 7 */
return (1 << 27);
default:
return 0;
}
}
static inline void dma_isr_enable(int stream)
{
if (stream < 7) {
NVIC_EnableIRQ((IRQn_Type)((int)DMA1_Stream0_IRQn + stream));
}
else if (stream == 7) {
NVIC_EnableIRQ(DMA1_Stream7_IRQn);
}
else if (stream < 13) {
NVIC_EnableIRQ((IRQn_Type)((int)DMA2_Stream0_IRQn + (stream - 8)));
}
else if (stream < 16) {
NVIC_EnableIRQ((IRQn_Type)((int)DMA2_Stream5_IRQn + (stream - 13)));
}
}
#ifdef __cplusplus
}
#endif
#endif /* PERIPH_CPU_H */
/** @} */

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

File diff suppressed because it is too large Load Diff

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 STM32F205RG
*
* @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,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

@ -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 STM32F215RG
*
* @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 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

98
cpu/stm32f2/lpm_arch.c Normal file
View File

@ -0,0 +1,98 @@
/*
* 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.
*/
/**
* @ingroup cpu_stm32f2
* @{
*
* @file
* @brief Implementation of the kernels power management interface
*
* @author Nick v. IJzendoorn <nijzndoorn@engineering-spirit.nl>
*
* @}
*/
#include "cpu.h"
#include "arch/lpm_arch.h"
static enum lpm_mode current_mode = LPM_UNKNOWN;
void lpm_arch_init(void)
{
current_mode = LPM_ON;
}
enum lpm_mode lpm_arch_set(enum lpm_mode target)
{
enum lpm_mode last_mode = current_mode;
switch (target) {
case LPM_ON: /* STM Run mode */
current_mode = LPM_ON;
break;
case LPM_IDLE: /* STM Sleep mode */
current_mode = LPM_IDLE;
/* Reset SLEEPDEEP bit of system control block */
SCB->SCR &= ~(SCB_SCR_SLEEPDEEP_Msk);
/* Enter sleep mode */
__WFI();
break;
case LPM_SLEEP: /* STM Stop mode */
current_mode = LPM_SLEEP;
/* Clear PDDS and LPDS bits to enter stop mode on */
/* deepsleep with voltage regulator on */
PWR->CR &= ~(PWR_CR_PDDS | PWR_CR_LPDS);
/* Set SLEEPDEEP bit of system control block */
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
/* Enter stop mode */
__WFI();
break;
case LPM_POWERDOWN: /* STM Standby mode */
/* Fall-through */
case LPM_OFF: /* STM Standby mode */
current_mode = LPM_POWERDOWN;
/* Set PDDS to enter standby mode on deepsleep and clear flags */
PWR->CR |= (PWR_CR_PDDS | PWR_CR_CWUF | PWR_CR_CSBF);
/* Enable WKUP pin to use for wakeup from standby mode */
PWR->CSR |= PWR_CSR_EWUP;
/* Set SLEEPDEEP bit of system control block */
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
#if defined ( __CC_ARM )
/* Ensure that store operations are completed */
__force_stores();
#endif
/* Enter standby mode */
__WFI();
break;
default:
break;
}
return last_mode;
}
enum lpm_mode lpm_arch_get(void)
{
return current_mode;
}
void lpm_arch_awake(void)
{
if (current_mode == LPM_SLEEP) {
/* After stop mode, the clock system needs to be reconfigured */
cpu_init();
}
current_mode = LPM_ON;
}
/** Not provided */
inline void lpm_arch_begin_awake(void) { }
/** Not provided */
inline void lpm_arch_end_awake(void) { }

View File

@ -0,0 +1,5 @@
# define the module name
MODULE = periph
# include RIOTs generic Makefile
include $(RIOTBASE)/Makefile.base

138
cpu/stm32f2/periph/adc.c Normal file
View File

@ -0,0 +1,138 @@
/*
* Copyright (C) 2016 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.
*/
/**
* @ingroup cpu_stm32f2
* @{
*
* @file
* @brief Low-level ADC driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
*
* @}
*/
#include "cpu.h"
#include "mutex.h"
#include "periph/adc.h"
#include "periph_conf.h"
/**
* @brief Maximum allowed ADC clock speed
*/
#define MAX_ADC_SPEED (12000000U)
/**
* @brief Load the ADC configuration
* @{
*/
#ifdef ADC_CONFIG
static const adc_conf_t adc_config[] = ADC_CONFIG;
#else
static const adc_conf_t adc_config[] = {};
#endif
/**
* @brief Allocate locks for all three available ADC devices
*/
static mutex_t locks[] = {
#if ADC_DEVS > 1
MUTEX_INIT,
#endif
#if ADC_DEVS > 2
MUTEX_INIT,
#endif
MUTEX_INIT
};
static inline ADC_TypeDef *dev(adc_t line)
{
return (ADC_TypeDef *)(ADC1_BASE + (adc_config[line].dev << 8));
}
static inline void prep(adc_t line)
{
mutex_lock(&locks[adc_config[line].dev]);
RCC->APB2ENR |= (RCC_APB2ENR_ADC1EN << adc_config[line].dev);
}
static inline void done(adc_t line)
{
RCC->APB2ENR &= ~(RCC_APB2ENR_ADC1EN << adc_config[line].dev);
mutex_unlock(&locks[adc_config[line].dev]);
}
int adc_init(adc_t line)
{
uint32_t clk_div = 2;
/* check if the line is valid */
if (line >= ADC_NUMOF) {
return -1;
}
/* lock and power-on the device */
prep(line);
/* configure the pin */
gpio_init_analog(adc_config[line].pin);
/* set clock prescaler to get the maximal possible ADC clock value */
for (clk_div = 2; clk_div < 8; clk_div += 2) {
if ((CLOCK_CORECLOCK / clk_div) <= MAX_ADC_SPEED) {
break;
}
}
ADC->CCR = ((clk_div / 2) - 1) << 16;
/* enable the ADC module */
dev(line)->CR2 = ADC_CR2_ADON;
/* check if this channel is an internal ADC channel, if so
* enable the internal temperature and Vref */
if (adc_config[line].chan == 16 || adc_config[line].chan == 17) {
/* check if the internal channels are configured to use ADC1 */
if (dev(line) != ADC1) {
return -3;
}
ADC->CCR |= ADC_CCR_TSVREFE;
}
/* free the device again */
done(line);
return 0;
}
int adc_sample(adc_t line, adc_res_t res)
{
int sample;
/* check if resolution is applicable */
if (res < 0xff) {
return -1;
}
/* lock and power on the ADC device */
prep(line);
/* set resolution and conversion channel */
dev(line)->CR1 = res;
dev(line)->SQR3 = adc_config[line].chan;
/* start conversion and wait for results */
dev(line)->CR2 |= ADC_CR2_SWSTART;
while (!(dev(line)->SR & ADC_SR_EOC)) {}
/* finally read sample and reset the STRT bit in the status register */
sample = (int)dev(line)->DR;
/* power off and unlock device again */
done(line);
return sample;
}

76
cpu/stm32f2/periph/dac.c Normal file
View File

@ -0,0 +1,76 @@
/*
* 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.
*/
/**
* @ingroup cpu_stm32f2
* @{
*
* @file
* @brief Low-level DAC driver implementation
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
*
* @}
*/
#include "cpu.h"
#include "periph/dac.h"
#include "periph_conf.h"
/* guard in case that no DAC device is defined */
#if DAC_NUMOF
/**
* @brief Get the DAC configuration from the board (if configured)
* @{
*/
#ifdef DAC_CONFIG
static const dac_conf_t dac_config[] = DAC_CONFIG;
#else
static const dac_conf_t dac_config[] = {};
#endif
/** @} */
int8_t dac_init(dac_t line)
{
if (line >= DAC_NUMOF) {
return -1;
}
/* configure pin */
gpio_init_analog(dac_config[line].pin);
/* enable the DAC's clock */
RCC->APB1ENR |= RCC_APB1ENR_DACEN;
/* reset output and enable the line's channel */
dac_set(line, 0);
dac_poweron(line);
return 0;
}
void dac_set(dac_t line, uint16_t value)
{
value = (value >> 4); /* scale to 12-bit */
if (dac_config[line].chan) {
DAC->DHR12R2 = value;
}
else {
DAC->DHR12R1 = value;
}
}
void dac_poweron(dac_t line)
{
DAC->CR |= (1 << (16 * dac_config[line].chan));
}
void dac_poweroff(dac_t line)
{
DAC->CR &= ~(1 << (16 * dac_config[line].chan));
}
#endif /* DAC_NUMOF */

221
cpu/stm32f2/periph/gpio.c Normal file
View File

@ -0,0 +1,221 @@
/*
* 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
* details.
*/
/**
* @ingroup cpu_stm32f2
* @{
*
* @file
* @brief Low-level GPIO driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Fabian Nack <nack@inf.fu-berlin.de>
*
* @}
*/
#include "cpu.h"
#include "sched.h"
#include "thread.h"
#include "periph/gpio.h"
#include "periph_conf.h"
/**
* @brief Number of available external interrupt lines
*/
#define GPIO_ISR_CHAN_NUMOF (16U)
/**
* @brief Hold one callback function pointer for each interrupt line
*/
static gpio_isr_ctx_t exti_chan[GPIO_ISR_CHAN_NUMOF];
/**
* @brief Extract the port base address from the given pin identifier
*/
static inline GPIO_TypeDef *_port(gpio_t pin)
{
return (GPIO_TypeDef *)(pin & ~(0x0f));
}
/**
* @brief Extract the port number form the given identifier
*
* The port number is extracted by looking at bits 10, 11, 12, 13 of the base
* register addresses.
*/
static inline int _port_num(gpio_t pin)
{
return ((pin >> 10) & 0x0f);
}
/**
* @brief Extract the pin number from the last 4 bit of the pin identifier
*/
static inline int _pin_num(gpio_t pin)
{
return (pin & 0x0f);
}
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));
/* 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_mode_t mode, gpio_flank_t flank,
gpio_cb_t cb, void *arg)
{
int pin_num = _pin_num(pin);
int port_num = _port_num(pin);
/* configure and save exti configuration struct */
exti_chan[pin_num].cb = cb;
exti_chan[pin_num].arg = arg;
/* enable the SYSCFG clock */
RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN;
/* initialize pin as input */
gpio_init(pin, mode);
/* enable global pin interrupt */
if (pin_num < 5) {
NVIC_EnableIRQ(EXTI0_IRQn + pin_num);
}
else if (pin_num < 10) {
NVIC_EnableIRQ(EXTI9_5_IRQn);
}
else {
NVIC_EnableIRQ(EXTI15_10_IRQn);
}
/* configure the active edge(s) */
switch (flank) {
case GPIO_RISING:
EXTI->RTSR |= (1 << pin_num);
EXTI->FTSR &= ~(1 << pin_num);
break;
case GPIO_FALLING:
EXTI->RTSR &= ~(1 << pin_num);
EXTI->FTSR |= (1 << pin_num);
break;
case GPIO_BOTH:
EXTI->RTSR |= (1 << pin_num);
EXTI->FTSR |= (1 << pin_num);
break;
}
/* enable specific pin as exti sources */
SYSCFG->EXTICR[pin_num >> 2] &= ~(0xf << ((pin_num & 0x03) * 4));
SYSCFG->EXTICR[pin_num >> 2] |= (port_num << ((pin_num & 0x03) * 4));
/* clear any pending requests */
EXTI->PR = (1 << pin_num);
/* enable interrupt for EXTI line */
EXTI->IMR |= (1 << pin_num);
return 0;
}
void gpio_init_af(gpio_t pin, gpio_af_t af)
{
GPIO_TypeDef *port = _port(pin);
uint32_t pin_num = _pin_num(pin);
/* set pin to AF mode */
port->MODER &= ~(3 << (2 * pin_num));
port->MODER |= (2 << (2 * pin_num));
/* set selected function */
port->AFR[(pin_num > 7) ? 1 : 0] &= ~(0xf << ((pin_num & 0x07) * 4));
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));
}
void gpio_irq_disable(gpio_t pin)
{
EXTI->IMR &= ~(1 << _pin_num(pin));
}
int gpio_read(gpio_t pin)
{
GPIO_TypeDef *port = _port(pin);
uint32_t pin_num = _pin_num(pin);
if (port->MODER & (3 << (pin_num * 2))) { /* if configured as output */
return port->ODR & (1 << pin_num); /* read output data reg */
} else {
return port->IDR & (1 << pin_num); /* else read input data reg */
}
}
void gpio_set(gpio_t pin)
{
_port(pin)->BSRR = (1 << _pin_num(pin));
}
void gpio_clear(gpio_t pin)
{
_port(pin)->BSRR = (1 << (_pin_num(pin) + 16));
}
void gpio_toggle(gpio_t pin)
{
if (gpio_read(pin)) {
gpio_clear(pin);
} else {
gpio_set(pin);
}
}
void gpio_write(gpio_t pin, int value)
{
if (value) {
gpio_set(pin);
} else {
gpio_clear(pin);
}
}
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 (pending_isr & (1 << i)) {
EXTI->PR = (1 << i); /* clear by writing a 1 */
exti_chan[i].cb(exti_chan[i].arg);
}
}
if (sched_context_switch_request) {
thread_yield();
}
}

View File

@ -0,0 +1,68 @@
/*
* Copyright (C) 2014 Freie Universität Berlin
* 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.
*/
/**
* @ingroup cpu_stm32f2
* @{
*
* @file
* @brief Low-level random number generator driver implementation
*
* @author Hauke Petersen <mail@haukepetersen.de>
* @author Aurelien Gonce <aurelien.gonce@altran.fr>
*
* @}
*/
#include "cpu.h"
#include "periph/hwrng.h"
#include "periph_conf.h"
/* ignore file in case no RNG device is defined */
#ifdef RNG
void hwrng_init(void)
{
/* enable RNG reset state */
RCC->AHB2ENR |= RCC_AHB2ENR_RNGEN;
/* release RNG from reset state */
RCC->AHB2ENR &= ~RCC_AHB2ENR_RNGEN;
}
void hwrng_read(uint8_t *buf, unsigned int num)
{
/* cppcheck-suppress variableScope */
uint32_t tmp;
unsigned int count = 0;
/* enable RNG reset state */
RCC->AHB2ENR |= RCC_AHB2ENR_RNGEN;
/* enable the RNG */
RNG->CR |= RNG_CR_RNGEN;
while (count < num) {
/* wait for random data to be ready to read */
while (!(RNG->SR & RNG_SR_DRDY));
/* read next 4 bytes */
tmp = RNG->DR;
/* copy data into result vector */
for (int i = 0; i < 4 && count < num; i++) {
buf[count++] = (uint8_t)tmp;
tmp = tmp >> 8;
}
}
/* disable the RNG */
RNG->CR &= ~RNG_CR_RNGEN;
/* release RNG from reset state */
RCC->AHB2ENR &= ~RCC_AHB2ENR_RNGEN;
}
#endif /* RANDOM_NUMOF */

730
cpu/stm32f2/periph/i2c.c Normal file
View File

@ -0,0 +1,730 @@
/*
* Copyright (C) 2014 FU 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 details.
*/
/**
* @addtogroup driver_periph
* @{
*
* @file
* @brief Low-level I2C driver implementation
*
* @note This implementation only implements the 7-bit addressing mode.
*
* @author Toon Stegen <toon.stegen@altran.com>
* @author Vincent Dupont <vincent@otakeys.com>
*
* @}
*/
#include <stdint.h>
#include "cpu.h"
#include "irq.h"
#include "mutex.h"
#include "periph_conf.h"
#include "periph/i2c.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
/* guard file in case no I2C device is defined */
#if I2C_NUMOF
#define I2C_MAX_LOOP_CNT 10000
/* static function definitions */
static int _read_bytes(I2C_TypeDef *i2c, uint8_t address, char *data, int length, char *err);
static void _i2c_init(I2C_TypeDef *i2c, int ccr);
static void _pin_config(GPIO_TypeDef *port_scl, GPIO_TypeDef *port_sda, int pin_scl, int pin_sda);
static int _start(I2C_TypeDef *dev, uint8_t address, uint8_t rw_flag, char *err);
static inline void _clear_addr(I2C_TypeDef *dev);
static inline int _write(I2C_TypeDef *dev, char *data, int length, char *err);
static inline int _stop(I2C_TypeDef *dev, char *err);
static inline int _wait_ready(I2C_TypeDef *dev);
/**
* @brief Array holding one pre-initialized mutex for each I2C device
*/
static mutex_t locks[] = {
#if I2C_0_EN
[I2C_0] = MUTEX_INIT,
#endif
#if I2C_1_EN
[I2C_1] = MUTEX_INIT,
#endif
#if I2C_2_EN
[I2C_2] = MUTEX_INIT,
#endif
#if I2C_3_EN
[I2C_3] = MUTEX_INIT
#endif
};
static char err_flag[] = {
#if I2C_0_EN
[I2C_0] = 0x00,
#endif
#if I2C_1_EN
[I2C_1] = 0x00,
#endif
#if I2C_2_EN
[I2C_2] = 0x00,
#endif
#if I2C_3_EN
[I2C_3] = 0x00
#endif
};
int i2c_init_master(i2c_t dev, i2c_speed_t speed)
{
I2C_TypeDef *i2c;
GPIO_TypeDef *port_scl;
GPIO_TypeDef *port_sda;
int pin_scl = 0, pin_sda = 0;
int ccr;
/* read speed configuration */
switch (speed) {
case I2C_SPEED_NORMAL:
ccr = I2C_APBCLK / 200000;
break;
case I2C_SPEED_FAST:
ccr = I2C_APBCLK / 800000;
break;
default:
return -2;
}
/* read static device configuration */
switch (dev) {
#if I2C_0_EN
case I2C_0:
i2c = I2C_0_DEV;
port_scl = I2C_0_SCL_PORT;
pin_scl = I2C_0_SCL_PIN;
port_sda = I2C_0_SDA_PORT;
pin_sda = I2C_0_SDA_PIN;
I2C_0_CLKEN();
I2C_0_SCL_CLKEN();
I2C_0_SDA_CLKEN();
NVIC_SetPriority(I2C_0_ERR_IRQ, I2C_IRQ_PRIO);
NVIC_EnableIRQ(I2C_0_ERR_IRQ);
break;
#endif
default:
return -1;
}
/* configure pins */
_pin_config(port_scl, port_sda, pin_scl, pin_sda);
/* configure device */
_i2c_init(i2c, ccr);
return 0;
}
static void _i2c_init(I2C_TypeDef *i2c, int ccr)
{
/* disable device and set ACK bit */
i2c->CR1 = I2C_CR1_ACK;
/* configure I2C clock */
i2c->CR2 = (I2C_APBCLK / 1000000) | I2C_CR2_ITERREN;
i2c->CCR = ccr;
i2c->TRISE = (I2C_APBCLK / 1000000) + 1;
/* configure device */
i2c->OAR1 |= (1 << 14); /* datasheet: bit 14 should be kept 1 */
i2c->OAR1 &= ~I2C_OAR1_ADDMODE; /* make sure we are in 7-bit address mode */
/* enable device */
i2c->CR1 |= I2C_CR1_PE;
}
static void _pin_config(GPIO_TypeDef *port_scl, GPIO_TypeDef *port_sda, int pin_scl, int pin_sda)
{
/* Set GPIOs to AF mode */
port_scl->MODER &= ~(3 << (2 * pin_scl));
port_scl->MODER |= (2 << (2 * pin_scl));
port_sda->MODER &= ~(3 << (2 * pin_sda));
port_sda->MODER |= (2 << (2 * pin_sda));
/* Set speed high*/
port_scl->OSPEEDR |= (3 << (2 * pin_scl));
port_sda->OSPEEDR |= (3 << (2 * pin_sda));
/* Set to push-pull configuration open drain*/
port_scl->OTYPER |= (1 << pin_scl);
port_sda->OTYPER |= (1 << pin_sda);
/* Enable pull-up resistors */
port_scl->PUPDR &= ~(3 << (2 * pin_scl));
port_sda->PUPDR &= ~(3 << (2 * pin_sda));
if (I2C_0_SCL_PULLUP) {
port_scl->PUPDR |= (1 << (2 * pin_scl));
}
if (I2C_0_SDA_PULLUP) {
port_sda->PUPDR |= (1 << (2 * pin_sda));
}
/* Configure GPIOs to for the I2C alternate function */
if (pin_scl < 8) {
port_scl->AFR[0] &= ~(0xf << (4 * pin_scl));
port_scl->AFR[0] |= (I2C_0_SCL_AF << (4 * pin_scl));
}
else {
port_scl->AFR[1] &= ~(0xf << (4 * (pin_scl - 8)));
port_scl->AFR[1] |= (I2C_0_SCL_AF << (4 * (pin_scl - 8)));
}
if (pin_sda < 8) {
port_sda->AFR[0] &= ~(0xf << (4 * pin_sda));
port_sda->AFR[0] |= (I2C_0_SDA_AF << (4 * pin_sda));
}
else {
port_sda->AFR[1] &= ~(0xf << (4 * (pin_sda - 8)));
port_sda->AFR[1] |= (I2C_0_SDA_AF << (4 * (pin_sda - 8)));
}
}
int i2c_acquire(i2c_t dev)
{
if (dev >= I2C_NUMOF) {
return -1;
}
mutex_lock(&locks[dev]);
return 0;
}
int i2c_release(i2c_t dev)
{
if (dev >= I2C_NUMOF) {
return -1;
}
mutex_unlock(&locks[dev]);
return 0;
}
int i2c_read_byte(i2c_t dev, uint8_t address, char *data)
{
return i2c_read_bytes(dev, address, data, 1);
}
int i2c_read_bytes(i2c_t dev, uint8_t address, char *data, int length)
{
I2C_TypeDef *i2c;
switch (dev) {
#if I2C_0_EN
case I2C_0:
i2c = I2C_0_DEV;
break;
#endif
default:
return -1;
}
int res = _wait_ready(i2c);
if (res != 0) {
return res;
}
return _read_bytes(i2c, address, data, length, &err_flag[dev]);
}
static inline int _wait_ready(I2C_TypeDef *dev)
{
/* wait for device to be ready */
DEBUG("Wait for device to be ready\n");
int cnt = 0;
while ((dev->SR2 & I2C_SR2_BUSY) && cnt++ < I2C_MAX_LOOP_CNT) {}
if (cnt == I2C_MAX_LOOP_CNT) {
return -3;
}
return 0;
}
static int _read_bytes(I2C_TypeDef *i2c, uint8_t address, char *data, int length, char *err)
{
unsigned int state;
int i = 0;
int cnt = 0;
int res;
switch (length) {
case 1:
DEBUG("Send Slave address and wait for ADDR == 1\n");
res = _start(i2c, address, I2C_FLAG_READ, err);
if (res != 0) {
return res;
}
if (*err) {
return -3;
}
DEBUG("Set ACK = 0\n");
i2c->CR1 &= ~(I2C_CR1_ACK);
DEBUG("Clear ADDR and set STOP = 1\n");
state = irq_disable();
_clear_addr(i2c);
i2c->CR1 |= (I2C_CR1_STOP);
irq_restore(state);
DEBUG("Wait for RXNE == 1\n");
cnt = 0;
*err = 0;
while (!(i2c->SR1 & I2C_SR1_RXNE) && cnt++ < I2C_MAX_LOOP_CNT && !(*err)) {}
if (cnt == I2C_MAX_LOOP_CNT || *err) {
return -3;
}
DEBUG("Read received data\n");
*data = (char)i2c->DR;
/* wait until STOP is cleared by hardware */
cnt = 0;
*err = 0;
while ((i2c->CR1 & I2C_CR1_STOP) && cnt++ < I2C_MAX_LOOP_CNT && !(*err)) {}
if (cnt == I2C_MAX_LOOP_CNT) {
return -3;
}
/* reset ACK to be able to receive new data */
i2c->CR1 |= (I2C_CR1_ACK);
break;
case 2:
DEBUG("Send Slave address and wait for ADDR == 1\n");
res = _start(i2c, address, I2C_FLAG_READ, err);
if (res != 0) {
return res;
}
if (*err) {
return -3;
}
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 = irq_disable();
_clear_addr(i2c);
i2c->CR1 &= ~(I2C_CR1_ACK);
irq_restore(state);
DEBUG("Wait for transfer to be completed\n");
cnt = 0;
*err = 0;
while (!(i2c->SR1 & I2C_SR1_BTF) && cnt++ < I2C_MAX_LOOP_CNT && !(*err)) {}
if (cnt == I2C_MAX_LOOP_CNT || *err) {
return -3;
}
DEBUG("Crit block: set STOP and read first byte\n");
state = irq_disable();
i2c->CR1 |= (I2C_CR1_STOP);
data[0] = (char)i2c->DR;
irq_restore(state);
DEBUG("read second byte\n");
data[1] = (char)i2c->DR;
DEBUG("wait for STOP bit to be cleared again\n");
cnt = 0;
*err = 0;
while ((i2c->CR1 & I2C_CR1_STOP) && cnt++ < I2C_MAX_LOOP_CNT && !(*err)) {}
if (cnt == I2C_MAX_LOOP_CNT || *err) {
return -3;
}
DEBUG("reset POS = 0 and ACK = 1\n");
i2c->CR1 &= ~(I2C_CR1_POS);
i2c->CR1 |= (I2C_CR1_ACK);
break;
default:
DEBUG("Send Slave address and wait for ADDR == 1\n");
res = _start(i2c, address, I2C_FLAG_READ, err);
if (res != 0) {
return res;
}
_clear_addr(i2c);
while (i < (length - 3)) {
DEBUG("Wait until byte was received\n");
cnt = 0;
*err = 0;
while (!(i2c->SR1 & I2C_SR1_RXNE) && cnt++ < I2C_MAX_LOOP_CNT && !(*err)) {}
if (cnt == I2C_MAX_LOOP_CNT || *err) {
return -3;
}
DEBUG("Copy byte from DR\n");
data[i++] = (char)i2c->DR;
}
DEBUG("Reading the last 3 bytes, waiting for BTF flag\n");
cnt = 0;
*err = 0;
while (!(i2c->SR1 & I2C_SR1_BTF) && cnt++ < I2C_MAX_LOOP_CNT && !(*err));
if (cnt == I2C_MAX_LOOP_CNT || *err) {
return -3;
}
DEBUG("Disable ACK\n");
i2c->CR1 &= ~(I2C_CR1_ACK);
DEBUG("Crit block: set STOP and read N-2 byte\n");
state = irq_disable();
data[i++] = (char)i2c->DR;
i2c->CR1 |= (I2C_CR1_STOP);
irq_restore(state);
DEBUG("Read N-1 byte\n");
data[i++] = (char)i2c->DR;
cnt = 0;
*err = 0;
while (!(i2c->SR1 & I2C_SR1_RXNE) && cnt++ < I2C_MAX_LOOP_CNT && !(*err)) {}
if (cnt == I2C_MAX_LOOP_CNT || *err) {
return -3;
}
DEBUG("Read last byte\n");
data[i++] = (char)i2c->DR;
DEBUG("wait for STOP bit to be cleared again\n");
cnt = 0;
*err = 0;
while ((i2c->CR1 & I2C_CR1_STOP) && cnt++ < I2C_MAX_LOOP_CNT && !(*err)) {}
if (cnt == I2C_MAX_LOOP_CNT || *err) {
return -3;
}
DEBUG("reset POS = 0 and ACK = 1\n");
i2c->CR1 &= ~(I2C_CR1_POS);
i2c->CR1 |= (I2C_CR1_ACK);
}
return length;
}
int i2c_read_reg(i2c_t dev, uint8_t address, uint8_t reg, char *data)
{
return i2c_read_regs(dev, address, reg, data, 1);
}
int i2c_read_regs(i2c_t dev, uint8_t address, uint8_t reg, char *data, int length)
{
I2C_TypeDef *i2c;
int res;
switch (dev) {
#if I2C_0_EN
case I2C_0:
i2c = I2C_0_DEV;
break;
#endif
default:
return -1;
}
/* send start condition and slave address */
DEBUG("Send slave address and clear ADDR flag\n");
res = _wait_ready(i2c);
if (res != 0) {
return res;
}
res = _start(i2c, address, I2C_FLAG_WRITE, &err_flag[dev]);
if (res != 0) {
return res;
}
if (err_flag[dev]) {
return -3;
}
_clear_addr(i2c);
DEBUG("Write reg into DR\n");
i2c->DR = reg;
DEBUG("Now start a read transaction\n");
return _read_bytes(i2c, address, data, length, &err_flag[dev]);
}
int i2c_write_byte(i2c_t dev, uint8_t address, char data)
{
return i2c_write_bytes(dev, address, &data, 1);
}
int i2c_write_bytes(i2c_t dev, uint8_t address, char *data, int length)
{
I2C_TypeDef *i2c;
int res;
switch (dev) {
#if I2C_0_EN
case I2C_0:
i2c = I2C_0_DEV;
break;
#endif
default:
return -1;
}
/* start transmission and send slave address */
DEBUG("sending start sequence\n");
res = _wait_ready(i2c);
if (res != 0) {
return res;
}
res = _start(i2c, address, I2C_FLAG_WRITE, &err_flag[dev]);
if (res != 0) {
return res;
}
if (err_flag[dev]) {
return -3;
}
_clear_addr(i2c);
/* send out data bytes */
res = _write(i2c, data, length, &err_flag[dev]);
if (res != 0) {
return res;
}
if (err_flag[dev]) {
return -3;
}
/* end transmission */
DEBUG("Ending transmission\n");
res = _stop(i2c, &err_flag[dev]);
if (res != 0) {
return res;
}
if (err_flag[dev]) {
return -3;
}
DEBUG("STOP condition was send out\n");
return length;
}
int i2c_write_reg(i2c_t dev, uint8_t address, uint8_t reg, char data)
{
return i2c_write_regs(dev, address, reg, &data, 1);
}
int i2c_write_regs(i2c_t dev, uint8_t address, uint8_t reg, char *data, int length)
{
I2C_TypeDef *i2c;
int res;
switch (dev) {
#if I2C_0_EN
case I2C_0:
i2c = I2C_0_DEV;
break;
#endif
default:
return -1;
}
/* start transmission and send slave address */
res = _wait_ready(i2c);
if (res != 0) {
return res;
}
res = _start(i2c, address, I2C_FLAG_WRITE, &err_flag[dev]);
if (res != 0) {
return res;
}
if (err_flag[dev]) {
return -3;
}
_clear_addr(i2c);
/* send register address and wait for complete transfer to be finished*/
res = _write(i2c, (char *)(&reg), 1, &err_flag[dev]);
if (res != 0) {
return res;
}
if (err_flag[dev]) {
return -3;
}
/* write data to register */
res = _write(i2c, data, length, &err_flag[dev]);
if (res != 0) {
return res;
}
if (err_flag[dev]) {
return -3;
}
/* finish transfer */
res = _stop(i2c, &err_flag[dev]);
if (res != 0) {
return res;
}
if (err_flag[dev]) {
return -3;
}
/* return number of bytes send */
return length;
}
void i2c_poweron(i2c_t dev)
{
switch (dev) {
#if I2C_0_EN
case I2C_0:
I2C_0_CLKEN();
break;
#endif
}
}
void i2c_poweroff(i2c_t dev)
{
int cnt = 0;
switch (dev) {
#if I2C_0_EN
case I2C_0:
while ((I2C_0_DEV->SR2 & I2C_SR2_BUSY) && cnt++ < I2C_MAX_LOOP_CNT) {}
I2C_0_CLKDIS();
break;
#endif
}
}
static int _start(I2C_TypeDef *dev, uint8_t address, uint8_t rw_flag, char *err)
{
int cnt = 0;
*err = 0;
/* generate start condition */
DEBUG("Generate start condition\n");
dev->CR1 |= I2C_CR1_START;
DEBUG("Wait for SB flag to be set\n");
while (!(dev->SR1 & I2C_SR1_SB) && cnt++ < I2C_MAX_LOOP_CNT && !(*err));
if (cnt == I2C_MAX_LOOP_CNT || *err) {
return -3;
}
/* send address and read/write flag */
DEBUG("Send address\n");
dev->DR = (address << 1) | rw_flag;
/* clear ADDR flag by reading first SR1 and then SR2 */
DEBUG("Wait for ADDR flag to be set\n");
cnt = 0;
*err = 0;
while (!(dev->SR1 & I2C_SR1_ADDR) && cnt++ < I2C_MAX_LOOP_CNT && !(*err)) {}
if (cnt == I2C_MAX_LOOP_CNT) {
return -3;
}
return 0;
}
static inline void _clear_addr(I2C_TypeDef *dev)
{
dev->SR1;
dev->SR2;
DEBUG("Cleared address\n");
}
static inline int _write(I2C_TypeDef *dev, char *data, int length, char *err)
{
DEBUG("Looping through bytes\n");
for (int i = 0; i < length; i++) {
/* write data to data register */
dev->DR = (uint8_t)data[i];
DEBUG("Written %i byte to data reg, now waiting for DR to be empty again\n", i);
/* wait for transfer to finish */
int cnt = 0;
*err = 0;
while (!(dev->SR1 & I2C_SR1_TXE) && cnt++ < I2C_MAX_LOOP_CNT && !(*err)) {}
if (cnt == I2C_MAX_LOOP_CNT || *err) {
return -3;
}
DEBUG("DR is now empty again\n");
}
return 0;
}
static inline int _stop(I2C_TypeDef *dev, char *err)
{
/* make sure last byte was send */
DEBUG("Wait if last byte hasn't been sent\n");
int cnt = 0;
*err = 0;
while (!(dev->SR1 & I2C_SR1_BTF) && cnt++ < I2C_MAX_LOOP_CNT && !(*err)) {}
if (cnt == I2C_MAX_LOOP_CNT) {
return -3;
}
/* send STOP condition */
dev->CR1 |= I2C_CR1_STOP;
return 0;
}
static inline void i2c_irq_handler(i2c_t i2c_dev, I2C_TypeDef *dev)
{
unsigned volatile state = dev->SR1;
/* record and clear errors */
err_flag[i2c_dev] = (state >> 8);
dev->SR1 &= 0x00ff;
DEBUG("\n\n### I2C %d ERROR OCCURED ###\n", i2c_dev);
DEBUG("status: %08x\n", state);
if (state & I2C_SR1_OVR) {
DEBUG("OVR\n");
}
if (state & I2C_SR1_AF) {
DEBUG("AF\n");
}
if (state & I2C_SR1_ARLO) {
DEBUG("ARLO\n");
}
if (state & I2C_SR1_BERR) {
DEBUG("BERR\n");
}
if (state & I2C_SR1_PECERR) {
DEBUG("PECERR\n");
}
if (state & I2C_SR1_TIMEOUT) {
DEBUG("TIMEOUT\n");
}
if (state & I2C_SR1_SMBALERT) {
DEBUG("SMBALERT\n");
}
}
#if I2C_0_EN
void I2C_0_ERR_ISR(void)
{
i2c_irq_handler(I2C_0, I2C_0_DEV);
}
#endif
#endif /* I2C_NUMOF */

219
cpu/stm32f2/periph/pwm.c Normal file
View File

@ -0,0 +1,219 @@
/*
* 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.
*/
/**
* @ingroup cpu_stm32f2
* @{
*
* @file
* @brief Low-level PWM driver implementation
*
* @author Hauke Petersen <mail@haukepetersen.de>
* @author Fabian Nack <nack@inf.fu-berlin.de>
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
* @author Aurelien Gonce <aurelien.gonce@altran.fr>
*
* @}
*/
#include <stdint.h>
#include <string.h>
#include "cpu.h"
#include "periph/pwm.h"
#include "periph_conf.h"
#include "periph/timer.h"
/* ignore file in case no PWM devices are defined */
#if (PWM_NUMOF > 0)
/**
* @brief Get the timer device
*/
static inline TIM_TypeDef *get_tim_dev(pwm_t tim)
{
return timer_config[tim].dev;
}
/**
* @brief Get the pwm device
*/
static inline GPIO_TypeDef *get_pwm_port(pwm_t pwm)
{
return pwm_config[pwm].port;
}
uint32_t pwm_init(pwm_t dev, pwm_mode_t mode, uint32_t freq, uint16_t res)
{
GPIO_TypeDef *port = get_pwm_port(dev);
tim_t tim = pwm_config[dev].tim;
TIM_TypeDef *timer_dev = get_tim_dev(tim);
uint8_t channels = pwm_channels(tim);
uint32_t pins[channels];
/* enable timer peripheral clock */
pwm_poweron(tim);
/* pins configuration */
pins[0] = pwm_config[dev].CH0;
if (channels > 1) {
pins[1] = pwm_config[dev].CH1;
}
if (channels > 2) {
pins[2] = pwm_config[dev].CH2;
}
if (channels > 3) {
pins[3] = pwm_config[dev].CH3;
}
/* enable pwm peripheral */
if (pwm_config[dev].bus == AHB1) {
RCC->AHB1ENR |= pwm_config[dev].rcc_mask;
} else if (pwm_config[dev].bus == AHB2) {
RCC->AHB2ENR |= pwm_config[dev].rcc_mask;
} else {
RCC->AHB3ENR |= pwm_config[dev].rcc_mask;
}
/* setup pins: alternate function */
for (int i = 0; i < channels; i++) {
port->MODER &= ~(3 << (pins[i] * 2));
port->MODER |= (2 << (pins[i] * 2));
if (pins[i] < 8) {
port->AFR[0] &= ~(0xf << (pins[i] * 4));
port->AFR[0] |= (pwm_config[dev].AF << (pins[i] * 4));
} else {
port->AFR[1] &= ~(0xf << ((pins[i] - 8) * 4));
port->AFR[1] |= (pwm_config[dev].AF << ((pins[i] - 8) * 4));
}
}
/* Reset C/C and timer configuration register */
switch (channels) {
case 4:
timer_dev->CCR4 = 0;
/* Fall through */
case 3:
timer_dev->CCR3 = 0;
timer_dev->CR2 = 0;
/* Fall through */
case 2:
timer_dev->CCR2 = 0;
/* Fall through */
case 1:
timer_dev->CCR1 = 0;
timer_dev->CR1 = 0;
break;
}
/* set prescale and auto-reload registers to matching values for resolution and frequency */
if (res > 0xffff || (res * freq) > timer_config[tim].freq) {
return 0;
}
timer_dev->PSC = (timer_config[tim].freq / (res * freq)) - 1;
timer_dev->ARR = res - 1;
/* calculate the actual PWM frequency */
freq = (timer_config[tim].freq / (res * (timer_dev->PSC + 1)));
/* set PWM mode */
switch (mode) {
case PWM_LEFT:
timer_dev->CCMR1 = (TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_2 |
TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2M_2);
if (channels > 2) {
timer_dev->CCMR2 = (TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3M_2 |
TIM_CCMR2_OC4M_1 | TIM_CCMR2_OC4M_2);
}
break;
case PWM_RIGHT:
timer_dev->CCMR1 = (TIM_CCMR1_OC1M_0 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_2 |
TIM_CCMR1_OC2M_0 | TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2M_2);
if (channels > 2) {
timer_dev->CCMR2 = (TIM_CCMR2_OC3M_0 | TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3M_2 |
TIM_CCMR2_OC4M_0 | TIM_CCMR2_OC4M_1 | TIM_CCMR2_OC4M_2);
}
break;
case PWM_CENTER:
timer_dev->CCMR1 = 0;
if (channels > 2) {
timer_dev->CCMR2 = 0;
}
timer_dev->CR1 |= (TIM_CR1_CMS_0 | TIM_CR1_CMS_1);
break;
}
/* enable output on PWM pins */
timer_dev->CCER = (TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E | TIM_CCER_CC4E);
/* enable PWM outputs */
timer_dev->BDTR = TIM_BDTR_MOE;
/* enable timer ergo the PWM generation */
pwm_start(tim);
return freq;
}
uint8_t pwm_channels(pwm_t dev) {
return (timer_config[dev].channels);
}
void pwm_set(pwm_t dev, uint8_t channel, uint16_t value)
{
tim_t tim = pwm_config[dev].tim;
TIM_TypeDef *timer_dev = get_tim_dev(tim);
if (channel >= pwm_channels(tim)) {
return;
}
/* norm value to maximum possible value */
if (value > timer_dev->ARR) {
value = (uint16_t) timer_dev->ARR;
}
switch (channel) {
case 0:
timer_dev->CCR1 = value;
break;
case 1:
timer_dev->CCR2 = value;
break;
case 2:
timer_dev->CCR3 = value;
break;
case 3:
timer_dev->CCR4 = value;
break;
default:
break;
}
}
void pwm_start(pwm_t dev)
{
get_tim_dev(dev)->CR1 |= TIM_CR1_CEN;
}
void pwm_stop(pwm_t dev)
{
get_tim_dev(dev)->CR1 &= ~(TIM_CR1_CEN);
}
void pwm_poweron(pwm_t dev)
{
periph_clk_en(timer_config[dev].bus, timer_config[dev].rcc_mask);
}
void pwm_poweroff(pwm_t dev)
{
periph_clk_dis(timer_config[dev].bus, timer_config[dev].rcc_mask);
}
#endif /* PWM_NUMOF > 0*/

280
cpu/stm32f2/periph/rtc.c Normal file
View File

@ -0,0 +1,280 @@
/*
* 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.
*/
/**
* @ingroup cpu_stm32f2
* @{
* @file
* @brief Low-level RTC driver implementation
* @author Vincent Dupont <vincent@otakeys.com>
* @}
*/
#include <time.h>
#include "cpu.h"
#include "periph/rtc.h"
#include "periph_conf.h"
#include "sched.h"
#include "thread.h"
/* guard file in case no RTC device was specified */
#if RTC_NUMOF
#define RTC_WRITE_PROTECTION_KEY1 (0xCA)
#define RTC_WRITE_PROTECTION_KEY2 (0x53)
#define RTC_SYNC_PRESCALER (0xff) /**< prescaler for 32.768 kHz oscillator */
#define RTC_ASYNC_PRESCALER (0x7f) /**< prescaler for 32.768 kHz oscillator */
#define MCU_YEAR_OFFSET (100) /**< struct tm counts years since 1900
but RTC has only two-digit year
hence the offset of 100 years. */
typedef struct {
rtc_alarm_cb_t cb; /**< callback called from RTC interrupt */
void *arg; /**< argument passed to the callback */
} rtc_state_t;
static rtc_state_t rtc_callback;
static uint8_t byte2bcd(uint8_t value);
/**
* @brief Initializes the RTC to use LSE (external 32.768 kHz oscillator) as a
* clocl source. Verify that your board has this oscillator. If other clock
* source is used, then also the prescaler constants should be changed.
*/
void rtc_init(void)
{
/* Enable write access to RTC registers */
RCC->APB1ENR |= RCC_APB1ENR_PWREN;
PWR->CR |= PWR_CR_DBP;
/* Reset RTC domain */
RCC->BDCR |= RCC_BDCR_BDRST;
RCC->BDCR &= ~(RCC_BDCR_BDRST);
/* Enable the LSE clock (external 32.768 kHz oscillator) */
RCC->BDCR &= ~(RCC_BDCR_LSEON);
RCC->BDCR &= ~(RCC_BDCR_LSEBYP);
RCC->BDCR |= RCC_BDCR_LSEON;
while ((RCC->BDCR & RCC_BDCR_LSERDY) == 0) {
}
/* Switch RTC to LSE clock source */
RCC->BDCR &= ~(RCC_BDCR_RTCSEL);
RCC->BDCR |= RCC_BDCR_RTCSEL_0;
/* Enable the RTC */
RCC->BDCR |= RCC_BDCR_RTCEN;
/* Unlock RTC write protection */
RTC->WPR = RTC_WRITE_PROTECTION_KEY1;
RTC->WPR = RTC_WRITE_PROTECTION_KEY2;
/* Enter RTC Init mode */
RTC->ISR = 0;
RTC->ISR |= RTC_ISR_INIT;
while ((RTC->ISR & RTC_ISR_INITF) == 0) {
}
/* Set 24-h clock */
RTC->CR &= ~RTC_CR_FMT;
/* Timestamps enabled */
RTC->CR |= RTC_CR_TSE;
/* Configure the RTC PRER */
RTC->PRER = RTC_SYNC_PRESCALER;
RTC->PRER |= (RTC_ASYNC_PRESCALER << 16);
/* Exit RTC init mode */
RTC->ISR &= (uint32_t) ~RTC_ISR_INIT;
/* Enable RTC write protection */
RTC->WPR = 0xff;
}
int rtc_set_time(struct tm *time)
{
/* Enable write access to RTC registers */
RCC->APB1ENR |= RCC_APB1ENR_PWREN;
PWR->CR |= PWR_CR_DBP;
/* Unlock RTC write protection */
RTC->WPR = RTC_WRITE_PROTECTION_KEY1;
RTC->WPR = RTC_WRITE_PROTECTION_KEY2;
/* Enter RTC Init mode */
RTC->ISR |= RTC_ISR_INIT;
while ((RTC->ISR & RTC_ISR_INITF) == 0) {
}
/* Set 24-h clock */
RTC->CR &= ~RTC_CR_FMT;
RTC->DR = ((((uint32_t)byte2bcd(time->tm_year - MCU_YEAR_OFFSET) << 16) & (RTC_DR_YT | RTC_DR_YU)) |
(((uint32_t)byte2bcd(time->tm_mon + 1) << 8) & (RTC_DR_MT | RTC_DR_MU)) |
(((uint32_t)byte2bcd(time->tm_mday) << 0) & (RTC_DR_DT | RTC_DR_DU)));
RTC->TR = ((((uint32_t)byte2bcd(time->tm_hour) << 16) & (RTC_TR_HT | RTC_TR_HU)) |
(((uint32_t)byte2bcd(time->tm_min) << 8) & (RTC_TR_MNT | RTC_TR_MNU)) |
(((uint32_t)byte2bcd(time->tm_sec) << 0) & (RTC_TR_ST | RTC_TR_SU)));
/* Exit RTC init mode */
RTC->ISR &= (uint32_t) ~RTC_ISR_INIT;
/* Enable RTC write protection */
RTC->WPR = 0xFF;
return 0;
}
int rtc_get_time(struct tm *time)
{
time->tm_year = MCU_YEAR_OFFSET;
time->tm_year += (((RTC->DR & RTC_DR_YT) >> 20) * 10) + ((RTC->DR & RTC_DR_YU) >> 16);
time->tm_mon = (((RTC->DR & RTC_DR_MT) >> 12) * 10) + ((RTC->DR & RTC_DR_MU) >> 8) - 1;
time->tm_mday = (((RTC->DR & RTC_DR_DT) >> 4) * 10) + ((RTC->DR & RTC_DR_DU) >> 0);
time->tm_hour = (((RTC->TR & RTC_TR_HT) >> 20) * 10) + ((RTC->TR & RTC_TR_HU) >> 16);
if (RTC->TR & RTC_TR_PM) {
/* 12PM is noon */
if (time->tm_hour != 12) {
time->tm_hour += 12;
}
}
else if ((RTC->CR & RTC_CR_FMT) && time->tm_hour == 12) {
/* 12AM is midnight */
time->tm_hour -= 12;
}
time->tm_min = (((RTC->TR & RTC_TR_MNT) >> 12) * 10) + ((RTC->TR & RTC_TR_MNU) >> 8);
time->tm_sec = (((RTC->TR & RTC_TR_ST) >> 4) * 10) + ((RTC->TR & RTC_TR_SU) >> 0);
return 0;
}
int rtc_set_alarm(struct tm *time, rtc_alarm_cb_t cb, void *arg)
{
/* Enable write access to RTC registers */
RCC->APB1ENR |= RCC_APB1ENR_PWREN;
PWR->CR |= PWR_CR_DBP;
/* Unlock RTC write protection */
RTC->WPR = RTC_WRITE_PROTECTION_KEY1;
RTC->WPR = RTC_WRITE_PROTECTION_KEY2;
/* Enter RTC Init mode */
RTC->ISR |= RTC_ISR_INIT;
while ((RTC->ISR & RTC_ISR_INITF) == 0) {
}
RTC->CR &= ~(RTC_CR_ALRAE);
while ((RTC->ISR & RTC_ISR_ALRAWF) == 0) {
}
RTC->ALRMAR &= ~(RTC_ALRMAR_MSK1 | RTC_ALRMAR_MSK2 | RTC_ALRMAR_MSK3 | RTC_ALRMAR_MSK4);
RTC->ALRMAR = ((((uint32_t)byte2bcd(time->tm_mday) << 24) & (RTC_ALRMAR_DT | RTC_ALRMAR_DU)) |
(((uint32_t)byte2bcd(time->tm_hour) << 16) & (RTC_ALRMAR_HT | RTC_ALRMAR_HU)) |
(((uint32_t)byte2bcd(time->tm_min) << 8) & (RTC_ALRMAR_MNT | RTC_ALRMAR_MNU)) |
(((uint32_t)byte2bcd(time->tm_sec) << 0) & (RTC_ALRMAR_ST | RTC_ALRMAR_SU)));
/* Enable Alarm A */
RTC->CR |= RTC_CR_ALRAE;
RTC->CR |= RTC_CR_ALRAIE;
RTC->ISR &= ~(RTC_ISR_ALRAF);
/* Exit RTC init mode */
RTC->ISR &= (uint32_t) ~RTC_ISR_INIT;
/* Enable RTC write protection */
RTC->WPR = 0xFF;
EXTI->IMR |= EXTI_IMR_MR17;
EXTI->RTSR |= EXTI_RTSR_TR17;
NVIC_SetPriority(RTC_Alarm_IRQn, 10);
NVIC_EnableIRQ(RTC_Alarm_IRQn);
rtc_callback.cb = cb;
rtc_callback.arg = arg;
return 0;
}
int rtc_get_alarm(struct tm *time)
{
time->tm_year = MCU_YEAR_OFFSET;
time->tm_year += (((RTC->DR & RTC_DR_YT) >> 20) * 10) + ((RTC->DR & RTC_DR_YU) >> 16);
time->tm_mon = (((RTC->DR & RTC_DR_MT) >> 12) * 10) + ((RTC->DR & RTC_DR_MU) >> 8) - 1;
time->tm_mday = (((RTC->ALRMAR & RTC_ALRMAR_DT) >> 28) * 10) + ((RTC->ALRMAR & RTC_ALRMAR_DU) >> 24);
time->tm_hour = (((RTC->ALRMAR & RTC_ALRMAR_HT) >> 20) * 10) + ((RTC->ALRMAR & RTC_ALRMAR_HU) >> 16);
if ((RTC->ALRMAR & RTC_ALRMAR_PM) && (RTC->CR & RTC_CR_FMT)) {
time->tm_hour += 12;
}
time->tm_min = (((RTC->ALRMAR & RTC_ALRMAR_MNT) >> 12) * 10) + ((RTC->ALRMAR & RTC_ALRMAR_MNU) >> 8);
time->tm_sec = (((RTC->ALRMAR & RTC_ALRMAR_ST) >> 4) * 10) + ((RTC->ALRMAR & RTC_ALRMAR_SU) >> 0);
return 0;
}
void rtc_clear_alarm(void)
{
/* Disable Alarm A */
RTC->CR &= RTC_CR_ALRAE;
RTC->CR &= RTC_CR_ALRAIE;
rtc_callback.cb = NULL;
rtc_callback.arg = NULL;
}
void rtc_poweron(void)
{
/* RTC on STM32F2 is online even on sleep modes. No need to power on. */
}
void rtc_poweroff(void)
{
/* Enable write access to RTC registers */
RCC->APB1ENR |= RCC_APB1ENR_PWREN;
PWR->CR |= PWR_CR_DBP;
/* Reset RTC domain */
RCC->BDCR |= RCC_BDCR_BDRST;
RCC->BDCR &= ~(RCC_BDCR_BDRST);
/* Disable the RTC */
RCC->BDCR &= ~RCC_BDCR_RTCEN;
/* Disable LSE clock */
RCC->BDCR &= ~(RCC_BDCR_LSEON);
}
void isr_rtc_alarm(void)
{
if (RTC->ISR & RTC_ISR_ALRAF) {
if (rtc_callback.cb != NULL) {
rtc_callback.cb(rtc_callback.arg);
}
RTC->ISR &= ~RTC_ISR_ALRAF;
}
EXTI->PR |= EXTI_PR_PR17;
if (sched_context_switch_request) {
thread_yield();
}
}
/**
* Convert a number from unsigned to BCD
*
* @param[in] value to be converted
* @return BCD representation of the value
*/
static uint8_t byte2bcd(uint8_t value)
{
uint8_t bcdhigh = 0;
while (value >= 10) {
bcdhigh++;
value -= 10;
}
return ((uint8_t)(bcdhigh << 4) | value);
}
#endif /* RTC_NUMOF */

455
cpu/stm32f2/periph/spi.c Normal file
View File

@ -0,0 +1,455 @@
/*
* Copyright (C) 2014 Hamburg University of Applied Sciences
*
* 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.
*/
/**
* @ingroup cpu_stm32f2
* @{
*
* @file
* @brief Low-level SPI driver implementation
*
* @author Peter Kietzmann <peter.kietzmann@haw-hamburg.de>
* @author Fabian Nack <nack@inf.fu-berlin.de>
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
#include <stdio.h>
#include "board.h"
#include "cpu.h"
#include "mutex.h"
#include "periph/spi.h"
#include "periph_conf.h"
#include "thread.h"
#include "sched.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
/* guard this file in case no SPI device is defined */
#if SPI_NUMOF
/**
* @brief Data-structure holding the state for a SPI device
*/
typedef struct {
char(*cb)(char data);
} spi_state_t;
static inline void irq_handler_transfer(SPI_TypeDef *spi, spi_t dev);
/**
* @brief Reserve memory for saving the SPI device's state
*/
static spi_state_t spi_config[SPI_NUMOF];
/* static bus div mapping */
static const uint8_t spi_bus_div_map[SPI_NUMOF] = {
#if SPI_0_EN
[SPI_0] = SPI_0_BUS_DIV,
#endif
#if SPI_1_EN
[SPI_1] = SPI_1_BUS_DIV,
#endif
#if SPI_2_EN
[SPI_2] = SPI_2_BUS_DIV,
#endif
};
/**
* @brief Array holding one pre-initialized mutex for each SPI device
*/
static mutex_t locks[] = {
#if SPI_0_EN
[SPI_0] = MUTEX_INIT,
#endif
#if SPI_1_EN
[SPI_1] = MUTEX_INIT,
#endif
#if SPI_2_EN
[SPI_2] = MUTEX_INIT
#endif
};
int spi_init_master(spi_t dev, spi_conf_t conf, spi_speed_t speed)
{
uint8_t speed_devider;
SPI_TypeDef *spi_port;
switch (speed) {
case SPI_SPEED_100KHZ:
return -2; /* not possible for stm32f2, APB2 minimum is 328 kHz */
break;
case SPI_SPEED_400KHZ:
speed_devider = 0x05 + spi_bus_div_map[dev]; /* makes 656 kHz */
break;
case SPI_SPEED_1MHZ:
speed_devider = 0x04 + spi_bus_div_map[dev]; /* makes 1.3 MHz */
break;
case SPI_SPEED_5MHZ:
speed_devider = 0x02 + spi_bus_div_map[dev]; /* makes 5.3 MHz */
break;
case SPI_SPEED_10MHZ:
speed_devider = 0x01 + spi_bus_div_map[dev]; /* makes 10.5 MHz */
break;
default:
return -1;
}
switch (dev) {
#if SPI_0_EN
case SPI_0:
spi_port = SPI_0_DEV;
/* enable clocks */
SPI_0_CLKEN();
SPI_0_SCK_PORT_CLKEN();
SPI_0_MISO_PORT_CLKEN();
SPI_0_MOSI_PORT_CLKEN();
break;
#endif /* SPI_0_EN */
#if SPI_1_EN
case SPI_1:
spi_port = SPI_1_DEV;
/* enable clocks */
SPI_1_CLKEN();
SPI_1_SCK_PORT_CLKEN();
SPI_1_MISO_PORT_CLKEN();
SPI_1_MOSI_PORT_CLKEN();
break;
#endif /* SPI_1_EN */
#if SPI_2_EN
case SPI_2:
spi_port = SPI_2_DEV;
/* enable clocks */
SPI_2_CLKEN();
SPI_2_SCK_PORT_CLKEN();
SPI_2_MISO_PORT_CLKEN();
SPI_2_MOSI_PORT_CLKEN();
break;
#endif /* SPI_2_EN */
default:
return -2;
}
/* configure SCK, MISO and MOSI pin */
spi_conf_pins(dev);
/**************** SPI-Init *****************/
spi_port->I2SCFGR &= ~(SPI_I2SCFGR_I2SMOD);/* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */
spi_port->CR1 = 0;
spi_port->CR2 = 0;
/* the NSS (chip select) is managed purely by software */
spi_port->CR1 |= SPI_CR1_SSM | SPI_CR1_SSI;
spi_port->CR1 |= (speed_devider << 3); /* Define serial clock baud rate. 001 leads to f_PCLK/4 */
spi_port->CR1 |= (SPI_CR1_MSTR); /* 1: master configuration */
spi_port->CR1 |= (conf);
/* enable SPI */
spi_port->CR1 |= (SPI_CR1_SPE);
return 0;
}
int spi_init_slave(spi_t dev, spi_conf_t conf, char(*cb)(char data))
{
SPI_TypeDef *spi_port;
switch (dev) {
#if SPI_0_EN
case SPI_0:
spi_port = SPI_0_DEV;
/* enable clocks */
SPI_0_CLKEN();
SPI_0_SCK_PORT_CLKEN();
SPI_0_MISO_PORT_CLKEN();
SPI_0_MOSI_PORT_CLKEN();
/* configure interrupt channel */
NVIC_SetPriority(SPI_0_IRQ, SPI_IRQ_PRIO); /* set SPI interrupt priority */
NVIC_EnableIRQ(SPI_0_IRQ); /* set SPI interrupt priority */
break;
#endif /* SPI_0_EN */
#if SPI_1_EN
case SPI_1:
spi_port = SPI_1_DEV;
/* enable clocks */
SPI_1_CLKEN();
SPI_1_SCK_PORT_CLKEN();
SPI_1_MISO_PORT_CLKEN();
SPI_1_MOSI_PORT_CLKEN();
/* configure interrupt channel */
NVIC_SetPriority(SPI_1_IRQ, SPI_IRQ_PRIO);
NVIC_EnableIRQ(SPI_1_IRQ);
break;
#endif /* SPI_1_EN */
#if SPI_2_EN
case SPI_2:
spi_port = SPI_2_DEV;
/* enable clocks */
SPI_2_CLKEN();
SPI_2_SCK_PORT_CLKEN();
SPI_2_MISO_PORT_CLKEN();
SPI_2_MOSI_PORT_CLKEN();
/* configure interrupt channel */
NVIC_SetPriority(SPI_2_IRQ, SPI_IRQ_PRIO);
NVIC_EnableIRQ(SPI_2_IRQ);
break;
#endif /* SPI_2_EN */
default:
return -1;
}
/* configure sck, miso and mosi pin */
spi_conf_pins(dev);
/***************** SPI-Init *****************/
spi_port->I2SCFGR &= ~(SPI_I2SCFGR_I2SMOD);
spi_port->CR1 = 0;
spi_port->CR2 = 0;
/* enable RXNEIE flag to enable rx buffer not empty interrupt */
spi_port->CR2 |= (SPI_CR2_RXNEIE); /*1:not masked */
spi_port->CR1 |= (conf);
/* the NSS (chip select) is managed by software and NSS is low (slave enabled) */
spi_port->CR1 |= SPI_CR1_SSM;
/* set callback */
spi_config[dev].cb = cb;
/* enable SPI device */
spi_port->CR1 |= SPI_CR1_SPE;
return 0;
}
int spi_conf_pins(spi_t dev)
{
GPIO_TypeDef *port[3];
int pin[3], af[3];
switch (dev) {
#if SPI_0_EN
case SPI_0:
port[0] = SPI_0_SCK_PORT;
pin[0] = SPI_0_SCK_PIN;
af[0] = SPI_0_SCK_AF;
port[1] = SPI_0_MOSI_PORT;
pin[1] = SPI_0_MOSI_PIN;
af[1] = SPI_0_MOSI_AF;
port[2] = SPI_0_MISO_PORT;
pin[2] = SPI_0_MISO_PIN;
af[2] = SPI_0_MISO_AF;
break;
#endif /* SPI_0_EN */
#if SPI_1_EN
case SPI_1:
port[0] = SPI_1_SCK_PORT;
pin[0] = SPI_1_SCK_PIN;
af[0] = SPI_1_SCK_AF;
port[1] = SPI_1_MOSI_PORT;
pin[1] = SPI_1_MOSI_PIN;
af[1] = SPI_1_MOSI_AF;
port[2] = SPI_1_MISO_PORT;
pin[2] = SPI_1_MISO_PIN;
af[2] = SPI_1_MISO_AF;
break;
#endif /* SPI_1_EN */
#if SPI_2_EN
case SPI_2:
port[0] = SPI_2_SCK_PORT;
pin[0] = SPI_2_SCK_PIN;
af[0] = SPI_2_SCK_AF;
port[1] = SPI_2_MOSI_PORT;
pin[1] = SPI_2_MOSI_PIN;
af[1] = SPI_2_MOSI_AF;
port[2] = SPI_2_MISO_PORT;
pin[2] = SPI_2_MISO_PIN;
af[2] = SPI_2_MISO_AF;
break;
#endif /* SPI_2_EN */
default:
return -1;
}
/***************** GPIO-Init *****************/
for (int i = 0; i < 3; i++) {
/* Set GPIOs to AF mode */
port[i]->MODER &= ~(3 << (2 * pin[i]));
port[i]->MODER |= (2 << (2 * pin[i]));
/* Set speed */
port[i]->OSPEEDR &= ~(3 << (2 * pin[i]));
port[i]->OSPEEDR |= (3 << (2 * pin[i]));
/* Set to push-pull configuration */
port[i]->OTYPER &= ~(1 << pin[i]);
/* Configure push-pull resistors */
port[i]->PUPDR &= ~(3 << (2 * pin[i]));
port[i]->PUPDR |= (2 << (2 * pin[i]));
/* Configure GPIOs for the SPI alternate function */
int hl = (pin[i] < 8) ? 0 : 1;
port[i]->AFR[hl] &= ~(0xf << ((pin[i] - (hl * 8)) * 4));
port[i]->AFR[hl] |= (af[i] << ((pin[i] - (hl * 8)) * 4));
}
return 0;
}
int spi_acquire(spi_t dev)
{
if (dev >= SPI_NUMOF) {
return -1;
}
mutex_lock(&locks[dev]);
return 0;
}
int spi_release(spi_t dev)
{
if (dev >= SPI_NUMOF) {
return -1;
}
mutex_unlock(&locks[dev]);
return 0;
}
int spi_transfer_byte(spi_t dev, char out, char *in)
{
SPI_TypeDef *spi_port;
switch (dev) {
#if SPI_0_EN
case SPI_0:
spi_port = SPI_0_DEV;
break;
#endif
#if SPI_1_EN
case SPI_1:
spi_port = SPI_1_DEV;
break;
#endif
#if SPI_2_EN
case SPI_2:
spi_port = SPI_2_DEV;
break;
#endif
default:
return -1;
}
while (!(spi_port->SR & SPI_SR_TXE));
spi_port->DR = out;
while (!(spi_port->SR & SPI_SR_RXNE));
if (in != NULL) {
*in = spi_port->DR;
}
else {
spi_port->DR;
}
return 1;
}
void spi_transmission_begin(spi_t dev, char reset_val)
{
switch (dev) {
#if SPI_0_EN
case SPI_0:
SPI_0_DEV->DR = reset_val;
break;
#endif
#if SPI_1_EN
case SPI_1:
SPI_1_DEV->DR = reset_val;
break;
#endif
#if SPI_2_EN
case SPI_2:
SPI_2_DEV->DR = reset_val;
break;
#endif
}
}
void spi_poweron(spi_t dev)
{
switch (dev) {
#if SPI_0_EN
case SPI_0:
SPI_0_CLKEN();
break;
#endif
#if SPI_1_EN
case SPI_1:
SPI_1_CLKEN();
break;
#endif
#if SPI_2_EN
case SPI_2:
SPI_2_CLKEN();
break;
#endif
}
}
void spi_poweroff(spi_t dev)
{
switch (dev) {
#if SPI_0_EN
case SPI_0:
while (SPI_0_DEV->SR & SPI_SR_BSY);
SPI_0_CLKDIS();
break;
#endif
#if SPI_1_EN
case SPI_1:
while (SPI_1_DEV->SR & SPI_SR_BSY);
SPI_1_CLKDIS();
break;
#endif
#if SPI_2_EN
case SPI_2:
while (SPI_2_DEV->SR & SPI_SR_BSY);
SPI_2_CLKDIS();
break;
#endif
}
}
static inline void irq_handler_transfer(SPI_TypeDef *spi, spi_t dev)
{
if (spi->SR & SPI_SR_RXNE) {
char data;
data = spi->DR;
data = spi_config[dev].cb(data);
spi->DR = data;
}
/* see if a thread with higher priority wants to run now */
if (sched_context_switch_request) {
thread_yield();
}
}
#if SPI_0_EN
void SPI_0_IRQ_HANDLER(void)
{
irq_handler_transfer(SPI_0_DEV, SPI_0);
}
#endif
#if SPI_1_EN
void SPI_1_IRQ_HANDLER(void)
{
irq_handler_transfer(SPI_1_DEV, SPI_1);
}
#endif
#if SPI_2_EN
void SPI_2_IRQ_HANDLER(void)
{
irq_handler_transfer(SPI_2_DEV, SPI_2);
}
#endif
#endif /* SPI_NUMOF */

203
cpu/stm32f2/periph/timer.c Normal file
View File

@ -0,0 +1,203 @@
/*
* Copyright (C) 2014 Freie Universität Berlin
* 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.
*/
/**
* @ingroup cpu_stm32f2
* @{
*
* @file
* @brief Low-level timer driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Aurelien Gonce <aurelien.gonce@altran.fr>
*
* @}
*/
#include <stdlib.h>
#include "cpu.h"
#include "board.h"
#include "sched.h"
#include "thread.h"
#include "periph_conf.h"
#include "periph/timer.h"
/** Unified IRQ handler for all timers */
static inline void irq_handler(tim_t timer, TIM_TypeDef *dev);
/** Timer state memory */
static timer_isr_ctx_t config[TIMER_NUMOF];
/**
* @brief Get the timer device
*/
static inline TIM_TypeDef *get_dev(tim_t tim)
{
return timer_config[tim].dev;
}
int timer_init(tim_t dev, unsigned long freq, timer_cb_t cb, void *arg)
{
/* check if device is valid */
if (dev >= TIMER_NUMOF) {
return -1;
}
/* enable timer peripheral clock */
periph_clk_en(timer_config[dev].bus, timer_config[dev].rcc_mask);
/* set timer's IRQ priority */
NVIC_SetPriority(timer_config[dev].irqn, timer_config[dev].priority);
/* set prescaler */
get_dev(dev)->PSC = (timer_config[dev].freq / freq) - 1;
/* set callback function */
config[dev].cb = cb;
config[dev].arg = arg;
/* set timer to run in counter mode */
get_dev(dev)->CR1 = 0;
get_dev(dev)->CR2 = 0;
/* set auto-reload and prescaler values and load new values */
get_dev(dev)->EGR |= TIM_EGR_UG;
/* enable the timer's interrupt */
timer_irq_enable(dev);
/* start the timer */
timer_start(dev);
return 0;
}
int timer_set(tim_t dev, int channel, unsigned int timeout)
{
int now = timer_read(dev);
return timer_set_absolute(dev, channel, now + timeout);
}
int timer_set_absolute(tim_t dev, int channel, unsigned int value)
{
if (channel >= timer_config[dev].channels || dev >= TIMER_NUMOF) {
return -1;
}
switch (channel) {
case 0:
get_dev(dev)->CCR1 = value;
get_dev(dev)->SR &= ~TIM_SR_CC1IF;
get_dev(dev)->DIER |= TIM_DIER_CC1IE;
break;
case 1:
get_dev(dev)->CCR2 = value;
get_dev(dev)->SR &= ~TIM_SR_CC2IF;
get_dev(dev)->DIER |= TIM_DIER_CC2IE;
break;
case 2:
get_dev(dev)->CCR3 = value;
get_dev(dev)->SR &= ~TIM_SR_CC3IF;
get_dev(dev)->DIER |= TIM_DIER_CC3IE;
break;
case 3:
get_dev(dev)->CCR4 = value;
get_dev(dev)->SR &= ~TIM_SR_CC4IF;
get_dev(dev)->DIER |= TIM_DIER_CC4IE;
break;
default:
return -1;
}
return 0;
}
int timer_clear(tim_t dev, int channel)
{
if (channel >= timer_config[dev].channels || dev >= TIMER_NUMOF) {
return -1;
}
get_dev(dev)->DIER &= ~(TIM_DIER_CC1IE << channel);
return 0;
}
unsigned int timer_read(tim_t dev)
{
return (unsigned int)get_dev(dev)->CNT;
}
void timer_start(tim_t dev)
{
get_dev(dev)->CR1 |= TIM_CR1_CEN;
}
void timer_stop(tim_t dev)
{
get_dev(dev)->CR1 &= ~TIM_CR1_CEN;
}
void timer_irq_enable(tim_t dev)
{
NVIC_EnableIRQ(timer_config[dev].irqn);
}
void timer_irq_disable(tim_t dev)
{
NVIC_DisableIRQ(timer_config[dev].irqn);
}
void TIMER_0_ISR(void)
{
irq_handler(TIMER_0, get_dev(TIMER_0));
}
void TIMER_1_ISR(void)
{
irq_handler(TIMER_1, get_dev(TIMER_1));
}
void TIMER_2_ISR(void)
{
irq_handler(TIMER_2, get_dev(TIMER_2));
}
void TIMER_3_ISR(void)
{
irq_handler(TIMER_3, get_dev(TIMER_3));
}
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(config[timer].arg, 0);
}
else if (dev->SR & TIM_SR_CC2IF) {
dev->DIER &= ~TIM_DIER_CC2IE;
dev->SR &= ~TIM_SR_CC2IF;
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(config[timer].arg, 2);
}
else if (dev->SR & TIM_SR_CC4IF) {
dev->DIER &= ~TIM_DIER_CC4IE;
dev->SR &= ~TIM_SR_CC4IF;
config[timer].cb(config[timer].arg, 3);
}
if (sched_context_switch_request) {
thread_yield();
}
}

293
cpu/stm32f2/periph/uart.c Normal file
View File

@ -0,0 +1,293 @@
/*
* Copyright (C) 2014-2015 Freie Universität Berlin
* Copyright (C) 2016 OTA keys
*
* 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.
*/
/**
* @ingroup cpu_stm32f2
* @{
*
* @file
* @brief Low-level UART driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Fabian Nack <nack@inf.fu-berlin.de>
* @author Hermann Lelong <hermann@otakeys.com>
* @author Toon Stegen <toon.stegen@altran.com>
*
* @}
*/
#include "cpu.h"
#include "thread.h"
#include "sched.h"
#include "mutex.h"
#include "periph/uart.h"
#include "periph/gpio.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
/**
* @brief Allocate memory to store the callback functions
*/
static uart_isr_ctx_t uart_ctx[UART_NUMOF];
/**
* @brief Get the base register for the given UART device
*/
static inline USART_TypeDef *_dev(uart_t uart)
{
return uart_config[uart].dev;
}
/**
* @brief Transmission locks
*/
static mutex_t tx_sync[UART_NUMOF];
static mutex_t tx_lock[UART_NUMOF];
/**
* @brief Find out which peripheral bus the UART device is connected to
*
* @return 1: APB1
* @return 2: APB2
*/
static inline int _bus(uart_t uart)
{
return (uart_config[uart].rcc_mask < RCC_APB1ENR_USART2EN) ? 2 : 1;
}
int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg)
{
USART_TypeDef *dev;
DMA_Stream_TypeDef *stream;
float divider;
uint16_t mantissa;
uint8_t fraction;
uint32_t max_clock;
uint8_t over8;
/* check if given UART device does exist */
if (uart < 0 || uart >= UART_NUMOF) {
return -1;
}
/* check if baudrate is reachable and choose the right oversampling method*/
max_clock = (_bus(uart) == 1) ? CLOCK_APB1 : CLOCK_APB2;
if (baudrate < (max_clock / 16)) {
over8 = 0;
}
else if (baudrate < (max_clock / 8)) {
over8 = 1;
}
else {
return -2;
}
/* get UART base address */
dev = _dev(uart);
/* remember callback addresses and argument */
uart_ctx[uart].rx_cb = rx_cb;
uart_ctx[uart].arg = arg;
/* init tx lock */
mutex_init(&tx_sync[uart]);
mutex_lock(&tx_sync[uart]);
mutex_init(&tx_lock[uart]);
/* configure pins */
gpio_init(uart_config[uart].rx_pin, uart_config[uart].rx_mode);
gpio_init(uart_config[uart].tx_pin, uart_config[uart].tx_mode);
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 */
uart_poweron(uart);
/* calculate and set baudrate */
divider = max_clock / (8 * (2 - over8) * baudrate);
mantissa = (uint16_t)divider;
fraction = (uint8_t)((divider - mantissa) * (8 * (2 - over8)));
dev->BRR = ((mantissa & 0x0fff) << 4) | (0x07 & fraction);
/* configure UART to 8N1 and enable receive and transmit mode*/
dev->CR1 = USART_CR1_UE | USART_CR1_TE | USART_CR1_RE;
if (over8) {
dev->CR1 |= USART_CR1_OVER8;
}
dev->CR3 = USART_CR3_DMAT;
dev->CR2 = 0;
if(uart_config[uart].hw_flow_ctrl) {
gpio_init(uart_config[uart].cts_pin, uart_config[uart].cts_mode);
gpio_init(uart_config[uart].rts_pin, uart_config[uart].rts_mode);
gpio_init_af(uart_config[uart].cts_pin, uart_config[uart].af);
gpio_init_af(uart_config[uart].rts_pin, uart_config[uart].af);
DEBUG("Init flow control on uart %u\n", uart);
/* configure hardware flow control */
dev->CR3 |= USART_CR3_RTSE | USART_CR3_CTSE;
}
/* configure the DMA stream for transmission */
dma_poweron(uart_config[uart].dma_stream);
stream = dma_stream(uart_config[uart].dma_stream);
stream->CR = ((uart_config[uart].dma_chan << 25) |
DMA_SxCR_PL_0 |
DMA_SxCR_MINC |
DMA_SxCR_DIR_0 |
DMA_SxCR_TCIE);
stream->PAR = (uint32_t)&(dev->DR);
stream->FCR = 0;
/* enable global and receive interrupts */
NVIC_EnableIRQ(uart_config[uart].irqn);
dma_isr_enable(uart_config[uart].dma_stream);
dev->CR1 |= USART_CR1_RXNEIE;
return 0;
}
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 (irq_is_in()) {
/* send data by active waiting on the TXE flag */
USART_TypeDef *dev = _dev(uart);
for (int i = 0; i < len; i++) {
while (!(dev->SR & USART_SR_TXE));
dev->DR = data[i];
}
}
else {
mutex_lock(&tx_lock[uart]);
DMA_Stream_TypeDef *stream = dma_stream(uart_config[uart].dma_stream);
/* configure and start DMA transfer */
stream->M0AR = (uint32_t)data;
stream->NDTR = (uint16_t)len;
stream->CR |= DMA_SxCR_EN;
/* wait for transfer to complete */
mutex_lock(&tx_sync[uart]);
mutex_unlock(&tx_lock[uart]);
}
}
void uart_poweron(uart_t uart)
{
if (_bus(uart) == 1) {
RCC->APB1ENR |= uart_config[uart].rcc_mask;
}
else {
RCC->APB2ENR |= uart_config[uart].rcc_mask;
}
}
void uart_poweroff(uart_t uart)
{
if (_bus(uart) == 1) {
RCC->APB1ENR &= ~(uart_config[uart].rcc_mask);
}
else {
RCC->APB2ENR &= ~(uart_config[uart].rcc_mask);
}
}
static inline void irq_handler(int uart, USART_TypeDef *dev)
{
if (dev->SR & USART_SR_RXNE) {
char data = (char)dev->DR;
uart_ctx[uart].rx_cb(uart_ctx[uart].arg, data);
}
if (sched_context_switch_request) {
thread_yield();
}
}
static inline void dma_handler(int uart, int stream)
{
/* clear DMA done flag */
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();
}
}
#ifdef UART_0_ISR
void UART_0_ISR(void)
{
irq_handler(0, uart_config[0].dev);
}
void UART_0_DMA_ISR(void)
{
dma_handler(0, uart_config[0].dma_stream);
}
#endif
#ifdef UART_1_ISR
void UART_1_ISR(void)
{
irq_handler(1, uart_config[1].dev);
}
void UART_1_DMA_ISR(void)
{
dma_handler(1, uart_config[1].dma_stream);
}
#endif
#ifdef UART_2_ISR
void UART_2_ISR(void)
{
irq_handler(2, uart_config[2].dev);
}
void UART_2_DMA_ISR(void)
{
dma_handler(2, uart_config[2].dma_stream);
}
#endif
#ifdef UART_3_ISR
void UART_3_ISR(void)
{
irq_handler(3, uart_config[3].dev);
}
void UART_3_DMA_ISR(void)
{
dma_handler(3, uart_config[3].dma_stream);
}
#endif
#ifdef UART_4_ISR
void UART_4_ISR(void)
{
irq_handler(4, uart_config[4].dev);
}
void UART_4_DMA_ISR(void)
{
dma_handler(4, uart_config[4].dma_stream);
}
#endif
#ifdef UART_5_ISR
void UART_5_ISR(void)
{
irq_handler(5, uart_config[5].dev);
}
void UART_5_DMA_ISR(void)
{
dma_handler(5, uart_config[5].dma_stream);
}
#endif

219
cpu/stm32f2/vectors.c Normal file
View File

@ -0,0 +1,219 @@
/*
* 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.
*/
/**
* @ingroup cpu_stm32f2
* @{
*
* @file
* @brief Interrupt vector definitions
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
*
* @}
*/
#include <stdint.h>
#include "vectors_cortexm.h"
/* get the start of the ISR stack as defined in the linkerscript */
extern uint32_t _estack;
/* define a local dummy handler as it needs to be in the same compilation unit
* as the alias definition */
void dummy_handler(void) {
dummy_handler_default();
}
/* Cortex-M common interrupt vectors */
WEAK_DEFAULT void isr_svc(void);
WEAK_DEFAULT void isr_pendsv(void);
WEAK_DEFAULT void isr_systick(void);
/* STM32F2 specific interrupt vectors */
WEAK_DEFAULT void isr_wwdg(void);
WEAK_DEFAULT void isr_pvd(void);
WEAK_DEFAULT void isr_tamp_stamp(void);
WEAK_DEFAULT void isr_rtc_wkup(void);
WEAK_DEFAULT void isr_flash(void);
WEAK_DEFAULT void isr_rcc(void);
WEAK_DEFAULT void isr_exti(void);
WEAK_DEFAULT void isr_dma1_stream0(void);
WEAK_DEFAULT void isr_dma1_stream1(void);
WEAK_DEFAULT void isr_dma1_stream2(void);
WEAK_DEFAULT void isr_dma1_stream3(void);
WEAK_DEFAULT void isr_dma1_stream4(void);
WEAK_DEFAULT void isr_dma1_stream5(void);
WEAK_DEFAULT void isr_dma1_stream6(void);
WEAK_DEFAULT void isr_adc(void);
WEAK_DEFAULT void isr_can1_tx(void);
WEAK_DEFAULT void isr_can1_rx0(void);
WEAK_DEFAULT void isr_can1_rx1(void);
WEAK_DEFAULT void isr_can1_sce(void);
WEAK_DEFAULT void isr_tim1_brk_tim9(void);
WEAK_DEFAULT void isr_tim1_up_tim10(void);
WEAK_DEFAULT void isr_tim1_trg_com_tim11(void);
WEAK_DEFAULT void isr_tim1_cc(void);
WEAK_DEFAULT void isr_tim2(void);
WEAK_DEFAULT void isr_tim3(void);
WEAK_DEFAULT void isr_tim4(void);
WEAK_DEFAULT void isr_i2c1_ev(void);
WEAK_DEFAULT void isr_i2c1_er(void);
WEAK_DEFAULT void isr_i2c2_ev(void);
WEAK_DEFAULT void isr_i2c2_er(void);
WEAK_DEFAULT void isr_spi1(void);
WEAK_DEFAULT void isr_spi2(void);
WEAK_DEFAULT void isr_usart1(void);
WEAK_DEFAULT void isr_usart2(void);
WEAK_DEFAULT void isr_usart3(void);
WEAK_DEFAULT void isr_rtc_alarm(void);
WEAK_DEFAULT void isr_otg_fs_wkup(void);
WEAK_DEFAULT void isr_tim8_brk_tim12(void);
WEAK_DEFAULT void isr_tim8_up_tim13(void);
WEAK_DEFAULT void isr_tim8_trg_com_tim14(void);
WEAK_DEFAULT void isr_tim8_cc(void);
WEAK_DEFAULT void isr_dma1_stream7(void);
WEAK_DEFAULT void isr_fsmc(void);
WEAK_DEFAULT void isr_sdio(void);
WEAK_DEFAULT void isr_tim5(void);
WEAK_DEFAULT void isr_spi3(void);
WEAK_DEFAULT void isr_uart4(void);
WEAK_DEFAULT void isr_uart5(void);
WEAK_DEFAULT void isr_tim6_dac(void);
WEAK_DEFAULT void isr_tim7(void);
WEAK_DEFAULT void isr_dma2_stream0(void);
WEAK_DEFAULT void isr_dma2_stream1(void);
WEAK_DEFAULT void isr_dma2_stream2(void);
WEAK_DEFAULT void isr_dma2_stream3(void);
WEAK_DEFAULT void isr_dma2_stream4(void);
WEAK_DEFAULT void isr_eth(void);
WEAK_DEFAULT void isr_eth_wkup(void);
WEAK_DEFAULT void isr_can2_tx(void);
WEAK_DEFAULT void isr_can2_rx0(void);
WEAK_DEFAULT void isr_can2_rx1(void);
WEAK_DEFAULT void isr_can2_sce(void);
WEAK_DEFAULT void isr_otg_fs(void);
WEAK_DEFAULT void isr_dma2_stream5(void);
WEAK_DEFAULT void isr_dma2_stream6(void);
WEAK_DEFAULT void isr_dma2_stream7(void);
WEAK_DEFAULT void isr_usart6(void);
WEAK_DEFAULT void isr_i2c3_ev(void);
WEAK_DEFAULT void isr_i2c3_er(void);
WEAK_DEFAULT void isr_otg_hs_ep1_out(void);
WEAK_DEFAULT void isr_otg_hs_ep1_in(void);
WEAK_DEFAULT void isr_otg_hs_wkup(void);
WEAK_DEFAULT void isr_otg_hs(void);
WEAK_DEFAULT void isr_dcmi(void);
WEAK_DEFAULT void isr_cryp(void);
WEAK_DEFAULT void isr_hash_rng(void);
/* interrupt vector table */
ISR_VECTORS const void *interrupt_vector[] = {
/* Exception stack pointer */
(void*) (&_estack), /* pointer to the top of the stack */
/* 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 */
(void*) mem_manage_default, /* memory manage exception */
(void*) bus_fault_default, /* bus fault exception */
(void*) usage_fault_default, /* usage fault exception */
(void*) (0UL), /* Reserved */
(void*) (0UL), /* Reserved */
(void*) (0UL), /* Reserved */
(void*) (0UL), /* Reserved */
(void*) isr_svc, /* system call interrupt, in RIOT used for
* switching into thread context on boot */
(void*) debug_mon_default, /* debug monitor exception */
(void*) (0UL), /* Reserved */
(void*) isr_pendsv, /* pendSV interrupt, in RIOT the actual
* context switching is happening here */
(void*) isr_systick, /* SysTick interrupt, not used in RIOT */
/* STM specific peripheral handlers */
(void*) isr_wwdg, /* Window WatchDog */
(void*) isr_pvd, /* PVD through EXTI Line detection */
(void*) isr_tamp_stamp, /* Tamper and TimeStamps through the EXTI line */
(void*) isr_rtc_wkup, /* RTC Wakeup through the EXTI line */
(void*) isr_flash, /* FLASH */
(void*) isr_rcc, /* RCC */
(void*) isr_exti, /* EXTI Line0 */
(void*) isr_exti, /* EXTI Line1 */
(void*) isr_exti, /* EXTI Line2 */
(void*) isr_exti, /* EXTI Line3 */
(void*) isr_exti, /* EXTI Line4 */
(void*) isr_dma1_stream0, /* DMA1 Stream 0 */
(void*) isr_dma1_stream1, /* DMA1 Stream 1 */
(void*) isr_dma1_stream2, /* DMA1 Stream 2 */
(void*) isr_dma1_stream3, /* DMA1 Stream 3 */
(void*) isr_dma1_stream4, /* DMA1 Stream 4 */
(void*) isr_dma1_stream5, /* DMA1 Stream 5 */
(void*) isr_dma1_stream6, /* DMA1 Stream 6 */
(void*) isr_adc, /* ADC1, ADC2 and ADC3s */
(void*) isr_can1_tx, /* CAN1 TX */
(void*) isr_can1_rx0, /* CAN1 RX0 */
(void*) isr_can1_rx1, /* CAN1 RX1 */
(void*) isr_can1_sce, /* CAN1 SCE */
(void*) isr_exti, /* External Line[9:5]s */
(void*) isr_tim1_brk_tim9, /* TIM1 Break and TIM9 */
(void*) isr_tim1_up_tim10, /* TIM1 Update and TIM10 */
(void*) isr_tim1_trg_com_tim11, /* TIM1 Trigger and Commutation and TIM11 */
(void*) isr_tim1_cc, /* TIM1 Capture Compare */
(void*) isr_tim2, /* TIM2 */
(void*) isr_tim3, /* TIM3 */
(void*) isr_tim4, /* TIM4 */
(void*) isr_i2c1_ev, /* I2C1 Event */
(void*) isr_i2c1_er, /* I2C1 Error */
(void*) isr_i2c2_ev, /* I2C2 Event */
(void*) isr_i2c2_er, /* I2C2 Error */
(void*) isr_spi1, /* SPI1 */
(void*) isr_spi2, /* SPI2 */
(void*) isr_usart1, /* USART1 */
(void*) isr_usart2, /* USART2 */
(void*) isr_usart3, /* USART3 */
(void*) isr_exti, /* External Line[15:10]s */
(void*) isr_rtc_alarm, /* RTC Alarm (A and B) through EXTI Line */
(void*) isr_otg_fs_wkup, /* USB OTG FS Wakeup through EXTI line */
(void*) isr_tim8_brk_tim12, /* TIM8 Break and TIM12 */
(void*) isr_tim8_up_tim13, /* TIM8 Update and TIM13 */
(void*) isr_tim8_trg_com_tim14, /* TIM8 Trigger and Commutation and TIM14 */
(void*) isr_tim8_cc, /* TIM8 Capture Compare */
(void*) isr_dma1_stream7, /* DMA1 Stream7 */
(void*) isr_fsmc, /* FSMC */
(void*) isr_sdio, /* SDIO */
(void*) isr_tim5, /* TIM5 */
(void*) isr_spi3, /* SPI3 */
(void*) isr_uart4, /* UART4 */
(void*) isr_uart5, /* UART5 */
(void*) isr_tim6_dac, /* TIM6 and DAC1&2 underrun errors */
(void*) isr_tim7, /* TIM7 */
(void*) isr_dma2_stream0, /* DMA2 Stream 0 */
(void*) isr_dma2_stream1, /* DMA2 Stream 1 */
(void*) isr_dma2_stream2, /* DMA2 Stream 2 */
(void*) isr_dma2_stream3, /* DMA2 Stream 3 */
(void*) isr_dma2_stream4, /* DMA2 Stream 4 */
(void*) isr_eth, /* Ethernet */
(void*) isr_eth_wkup, /* Ethernet Wakeup through EXTI line */
(void*) isr_can2_tx, /* CAN2 TX */
(void*) isr_can2_rx0, /* CAN2 RX0 */
(void*) isr_can2_rx1, /* CAN2 RX1 */
(void*) isr_can2_sce, /* CAN2 SCE */
(void*) isr_otg_fs, /* USB OTG FS */
(void*) isr_dma2_stream5, /* DMA2 Stream 5 */
(void*) isr_dma2_stream6, /* DMA2 Stream 6 */
(void*) isr_dma2_stream7, /* DMA2 Stream 7 */
(void*) isr_usart6, /* USART6 */
(void*) isr_i2c3_ev, /* I2C3 event */
(void*) isr_i2c3_er, /* I2C3 error */
(void*) isr_otg_hs_ep1_out, /* USB OTG HS End Point 1 Out */
(void*) isr_otg_hs_ep1_in, /* USB OTG HS End Point 1 In */
(void*) isr_otg_hs_wkup, /* USB OTG HS Wakeup through EXTI */
(void*) isr_otg_hs, /* USB OTG HS */
(void*) isr_dcmi, /* DCMI */
(void*) isr_cryp, /* CRYP crypto */
(void*) isr_hash_rng, /* Hash and Rng */
};

View File

@ -842,6 +842,7 @@ EXCLUDE_PATTERNS = */board/*/tools/* \
*/pkg/*/*/* \
*/pkg/tlsf/patch.txt \
*/sys/random/tinymt32/* \
*/cpu/stm32f2/include/stm32f2*.h \
# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names