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

stm32f2: add initial support for stm32f2

This commit is contained in:
DipSwitch 2015-12-13 11:00:06 +01:00
parent 8518843a40
commit 4064858e8d
21 changed files with 10105 additions and 0 deletions

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
include $(RIOTBASE)/Makefile.base

View File

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

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

@ -0,0 +1,92 @@
/*
* 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;
/* PLL configuration: PLLCLK = SOURCE_CLOCK / SOURCE_CLOCK_DIV * SOURCE_CLOCK_MUL */
RCC->PLLCFGR &= ~((uint32_t)(RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLP | RCC_PLLCFGR_PLLQ));
RCC->PLLCFGR |= (uint32_t)(RCC_PLL_SOURCE | CLOCK_PLL_DIV | (CLOCK_PLL_MUL << 6));
/* 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,58 @@
/*
* 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 "stm32f2xx.h"
#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
/** @} */
/**
* @brief Length for reading CPU_ID
*/
#define CPUID_ID_LEN (12)
/**
* @brief Configure the CPU's clock system
*
* @param[in] source source clock frequency
* @param[in] target target clock frequency
* @param[in] prescale prescaler to use
*/
void cpu_clock_scale(uint32_t source, uint32_t target, uint32_t *prescale);
#ifdef __cplusplus
}
#endif
#endif /* __CPU_CONF_H */
/** @} */

View File

@ -0,0 +1,212 @@
/*
* 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 CPU specific definitions for internal peripheral handling
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
*/
#ifndef PERIPH_CPU_H
#define PERIPH_CPU_H
#include "cpu.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Overwrite the default gpio_t type definition
* @{
*/
#define HAVE_GPIO_T
typedef uint32_t gpio_t;
/** @} */
/**
* @brief Definition of a fitting UNDEF value
*/
#define GPIO_UNDEF (0xffffffff)
/**
* @brief Define a CPU specific GPIO pin generator macro
*/
#define GPIO_PIN(x, y) ((GPIOA_BASE + (x << 10)) | y)
/**
* @brief declare needed generic SPI functions
* @{
*/
#define PERIPH_SPI_NEEDS_TRANSFER_BYTES
#define PERIPH_SPI_NEEDS_TRANSFER_REG
#define PERIPH_SPI_NEEDS_TRANSFER_REGS
/** @} */
/**
* @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;
/**
* @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_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 */
} uart_conf_t;
/** @} */
/**
* @brief Configure the alternate function for the given pin
*
* @note This is meant for internal use in STM32F4 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 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:
return (1 << 5);
case 1:
return (1 << 11);
case 2:
return (1 << 21);
case 3:
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

View File

@ -0,0 +1,27 @@
/*
* 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 STM32F215RG
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
*
* @}
*/
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K
ram (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
}
INCLUDE cortexm_base.ld

View File

@ -0,0 +1,27 @@
/*
* 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 STM32F215RG
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
*
* @}
*/
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
ram (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
}
INCLUDE cortexm_base.ld

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

@ -0,0 +1,71 @@
/*
* 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 */
break;
case LPM_IDLE: /* STM Sleep mode */
break;
case LPM_SLEEP: /* STM Stop mode */
break;
case LPM_POWERDOWN: /* STM Standby mode */
/* Fall-through */
case LPM_OFF: /* STM Standby mode */
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

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

@ -0,0 +1,185 @@
/*
* 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 ADC driver implementation
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
*
* @}
*/
#include "cpu.h"
#include "periph/adc.h"
#include "periph_conf.h"
/* guard in case that no ADC device is defined */
#if ADC_NUMOF
typedef struct {
int max_value;
} adc_config_t;
adc_config_t adc_config[ADC_NUMOF];
int adc_init(adc_t dev, adc_precision_t precision)
{
ADC_TypeDef *adc = 0;
adc_poweron(dev);
switch (dev) {
#if ADC_0_EN
case ADC_0:
adc = ADC_0_DEV;
ADC_0_PORT_CLKEN();
ADC_0_PORT->MODER |= (3 << (ADC_0_CH0_PIN * 2) | 3 << (ADC_0_CH1_PIN * 2));
break;
#endif
#if ADC_1_EN
case ADC_1:
adc = ADC_1_DEV;
ADC_1_PORT_CLKEN();
ADC_1_PORT->MODER |= (3 << (ADC_1_CH0_PIN * 2) | 3 << (ADC_1_CH1_PIN * 2));
break;
#endif
default:
return -1;
}
/* reset control registers */
adc->CR1 = 0;
adc->CR2 = 0;
adc->SQR1 = 0;
/* set precision */
switch (precision) {
case ADC_RES_6BIT:
adc->CR1 |= ADC_CR1_RES_0 | ADC_CR1_RES_1;
adc_config[dev].max_value = 0x3f;
break;
case ADC_RES_8BIT:
adc->CR1 |= ADC_CR1_RES_1;
adc_config[dev].max_value = 0xff;
break;
case ADC_RES_10BIT:
adc->CR1 |= ADC_CR1_RES_0;
adc_config[dev].max_value = 0x3ff;
break;
case ADC_RES_12BIT:
adc_config[dev].max_value = 0xfff;
break;
case ADC_RES_14BIT:
case ADC_RES_16BIT:
adc_poweroff(dev);
return -1;
break;
}
/* set clock prescaler */
ADC->CCR = (3 << 16); /* ADC clock = 10,5MHz */
/* enable the ADC module */
adc->CR2 |= ADC_CR2_ADON;
return 0;
}
int adc_sample(adc_t dev, int channel)
{
ADC_TypeDef *adc = 0;
switch (dev) {
#if ADC_0_EN
case ADC_0:
adc = ADC_0_DEV;
switch (channel) {
case 0:
adc->SQR3 = ADC_0_CH0 & 0x1f;
break;
case 1:
adc->SQR3 = ADC_0_CH1 & 0x1f;
break;
default:
return -1;
}
break;
#endif
#if ADC_1_EN
case ADC_1:
adc = ADC_1_DEV;
switch (channel) {
case 0:
adc->SQR3 = ADC_1_CH0 & 0x1f;
break;
case 1:
adc->SQR3 = ADC_1_CH1 & 0x1f;
break;
default:
return -1;
}
break;
#endif
}
/* start single conversion */
adc->CR2 |= ADC_CR2_SWSTART;
/* wait until conversion is complete */
while (!(adc->SR & ADC_SR_EOC));
/* read and return result */
return (int)adc->DR;
}
void adc_poweron(adc_t dev)
{
switch (dev) {
#if ADC_0_EN
case ADC_0:
ADC_0_CLKEN();
break;
#endif
#if ADC_1_EN
case ADC_1:
ADC_1_CLKEN();
break;
#endif
}
}
void adc_poweroff(adc_t dev)
{
switch (dev) {
#if ADC_0_EN
case ADC_0:
ADC_0_CLKDIS();
break;
#endif
#if ADC_1_EN
case ADC_1:
ADC_1_CLKDIS();
break;
#endif
}
}
int adc_map(adc_t dev, int value, int min, int max)
{
return (int)adc_mapf(dev, value, (float)min, (float)max);
}
float adc_mapf(adc_t dev, int value, float min, float max)
{
return ((max - min) / ((float)adc_config[dev].max_value)) * value;
}
#endif /* ADC_NUMOF */

View File

@ -0,0 +1,28 @@
/*
* Copyright (C) 2015 Engineering-Spirit
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @addtogroup driver_periph
* @{
*
* @file
* @brief Low-level CPUID driver implementation
*
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
*/
#include <string.h>
#include "periph/cpuid.h"
void cpuid_get(void *id)
{
memcpy(id, (void *)(0x1fff7a10), CPUID_ID_LEN);
}
/** @} */

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

@ -0,0 +1,166 @@
/*
* 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
#define DAC_MAX_12BIT 0x0fff
typedef struct {
uint8_t shift_mod;
} dac_config_t;
dac_config_t dac_config[DAC_NUMOF];
int8_t dac_init(dac_t dev, dac_precision_t precision)
{
DAC_TypeDef *dac = 0;
dac_poweron(dev);
switch (dev) {
#if DAC_0_EN
case DAC_0:
dac = DAC_0_DEV;
DAC_0_PORT_CLKEN();
/* Set Mode to analoge out, disable Pullup Pulldown Resistors for both channels */
DAC_0_PORT->MODER |= (3 << (DAC_0_CH0_PIN * 2) | 3 << (DAC_0_CH1_PIN * 2));
DAC_0_PORT->PUPDR &= ~(3 << (DAC_0_CH0_PIN * 2) | 3 << (DAC_0_CH1_PIN * 2));
break;
#endif
default:
/* Unknown Device */
return -1;
}
/* Select Shift value to normalize given Value */
switch(precision) {
case DAC_RES_6BIT:
dac_config[dev].shift_mod = 0x06; /* 2^6 << 6 = 2^12 */
break;
case DAC_RES_8BIT:
dac_config[dev].shift_mod = 0x04; /* 2^8 << 4 = 2^12 */
break;
case DAC_RES_10BIT:
dac_config[dev].shift_mod = 0x02; /* 2^10 << 2 = 2^12 */
break;
case DAC_RES_12BIT:
dac_config[dev].shift_mod = 0x00; /* 2^12 << 0 = 2^12 */
break;
/* Not Supported Resolutions */
case DAC_RES_14BIT:
case DAC_RES_16BIT:
default:
dac_poweroff(dev);
return -2;
break;
}
/* Enable Channels, Clear Output */
dac->CR = 0;
dac->CR |= (DAC_CR_EN1 | DAC_CR_EN2);
dac->DHR12R1 = 0;
dac->DHR12R2 = 0;
return 0;
}
int8_t dac_write(dac_t dev, uint8_t channel, uint16_t value)
{
DAC_TypeDef* __attribute__((unused)) dac = 0;
uint16_t __attribute__((unused)) val = value << dac_config[dev].shift_mod;
switch(dev){
#if DAC_0_EN
case DAC_0:
dac = DAC_0_DEV;
if( DAC_MAX_12BIT < val ){
/* Value out of Range */
return -3;
}
switch(channel){
case 0:
dac->DHR12R1 = val;
break;
case 1:
dac->DHR12R2 = val;
break;
/* Invalid Channel */
default:
return -2;
}
break;
#endif
/* Unknown Device */
default:
return -1;
}
return 0;
}
int8_t dac_poweron(dac_t dev)
{
switch (dev){
#if DAC_0_EN
case DAC_0:
DAC_0_CLKEN();
break;
#endif
default:
/* Unknown Device */
return -1;
}
return 0;
}
int8_t dac_poweroff(dac_t dev)
{
switch (dev) {
#if DAC_0_EN
case DAC_0:
DAC_0_CLKDIS();
break;
#endif
default:
/* Unknown Device */
return -1;
}
return 0;
}
uint16_t dac_map(dac_t dev, int value, int min, int max)
{
return dac_mapf(dev, (int) value, (int) min, (int) max);
}
uint16_t dac_mapf(dac_t dev, float value, float min, float max)
{
uint16_t val_12_bit = ((value - min) * DAC_MAX_12BIT)/(max-min);
return val_12_bit >> dac_config[dev].shift_mod;
}
#undef DAC_MAX_12BIT
#endif /* DAC_NUMOF */

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

@ -0,0 +1,221 @@
/*
* 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 GPIO driver implementation
*
* @author Hauke Petersen <mail@haukepetersen.de>
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
*
* @}
*/
#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 Datastructure to hold an interrupt context
*/
typedef struct {
void (*cb)(void *arg); /**< interrupt callback routine */
void *arg; /**< optional argument */
} exti_ctx_t;
/**
* @brief Hold one callback function pointer for each interrupt line
*/
static exti_ctx_t exti_chan[GPIO_ISR_CHAN_NUMOF];
/**
* @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_dir_t dir, gpio_pp_t pullup)
{
GPIO_TypeDef *port = _port(pin);
int pin_num = _pin_num(pin);
/* enable clock */
RCC->AHB1ENR |= (RCC_AHB1ENR_GPIOAEN << _port_num(pin));
/* configure pull register */
port->PUPDR &= ~(3 << (2 * pin_num));
port->PUPDR |= (pullup << (2 * pin_num));
/* set direction */
if (dir == GPIO_DIR_OUT) {
port->MODER &= ~(3 << (2 * pin_num)); /* set pin to output mode */
port->MODER |= (1 << (2 * pin_num));
port->OTYPER &= ~(1 << pin_num); /* set to push-pull */
port->OSPEEDR |= (3 << (2 * pin_num)); /* set to high speed */
port->ODR &= ~(1 << pin_num); /* set pin to low signal */
}
else {
port->MODER &= ~(3 << (2 * pin_num)); /* configure pin as input */
}
return 0;
}
int gpio_init_int(gpio_t pin,
gpio_pp_t pullup, 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, GPIO_DIR_IN, pullup);
/* 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_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)->BSRRL = (1 << _pin_num(pin));
}
void gpio_clear(gpio_t pin)
{
_port(pin)->BSRRH = (1 << _pin_num(pin));
}
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)
{
for (unsigned i = 0; i < GPIO_ISR_CHAN_NUMOF; i++) {
if (EXTI->PR & (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();
}
}

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

@ -0,0 +1,576 @@
/*
* 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 Peter Kietzmann <peter.kietzmann@haw-hamburg.de>
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @auhtor Thomas Eichinge <thomas.eichinger@fu-berlin.de>
*
* @}
*/
#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
/* static function definitions */
static void _i2c_init(I2C_TypeDef *i2c, int ccr);
static void _toggle_pins(GPIO_TypeDef *port_scl, GPIO_TypeDef *port_sda, int pin_scl, int pin_sda);
static void _pin_config(GPIO_TypeDef *port_scl, GPIO_TypeDef *port_sda, int pin_scl, int pin_sda);
static void _start(I2C_TypeDef *dev, uint8_t address, uint8_t rw_flag);
static inline void _clear_addr(I2C_TypeDef *dev);
static inline void _write(I2C_TypeDef *dev, char *data, int length);
static inline void _stop(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
};
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);
/* make sure the analog filters don't hang -> see errata sheet 2.14.7 */
if (i2c->SR2 & I2C_SR2_BUSY) {
DEBUG("LINE BUSY AFTER RESET -> toggle pins now\n");
/* disable peripheral */
i2c->CR1 &= ~I2C_CR1_PE;
/* toggle both pins to reset analog filter */
_toggle_pins(port_scl, port_sda, pin_scl, pin_sda);
/* reset pins for alternate function */
_pin_config(port_scl, port_sda, pin_scl, pin_sda);
/* make peripheral soft reset */
i2c->CR1 |= I2C_CR1_SWRST;
i2c->CR1 &= ~I2C_CR1_SWRST;
/* enable 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 = 0; /* makes 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_scl->PUPDR |= (1 << (2 * pin_scl));
port_sda->PUPDR &= ~(3 << (2 * pin_sda));
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)));
}
}
static void _toggle_pins(GPIO_TypeDef *port_scl, GPIO_TypeDef *port_sda, int pin_scl, int pin_sda)
{
/* Set GPIOs to General purpose output mode mode */
port_scl->MODER &= ~(3 << (2 * pin_scl));
port_scl->MODER |= (1 << (2 * pin_scl));
port_sda->MODER &= ~(3 << (2 * pin_sda));
port_sda->MODER |= (1 << (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);
/* set both to high */
port_scl->ODR |= (1 << pin_scl);
port_sda->ODR |= (1 << pin_sda);
/* set SDA to low */
port_sda->ODR &= ~(1 << pin_sda);
/* set SCL to low */
port_scl->ODR &= ~(1 << pin_scl);
/* set SCL to high */
port_scl->ODR |= (1 << pin_scl);
/* set SDA to high */
port_sda->ODR |= (1 << pin_sda);
}
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)
{
unsigned int state;
int i = 0;
I2C_TypeDef *i2c;
switch (dev) {
#if I2C_0_EN
case I2C_0:
i2c = I2C_0_DEV;
break;
#endif
default:
return -1;
}
switch (length) {
case 1:
DEBUG("Send Slave address and wait for ADDR == 1\n");
_start(i2c, address, I2C_FLAG_READ);
DEBUG("Set ACK = 0\n");
i2c->CR1 &= ~(I2C_CR1_ACK);
DEBUG("Clear ADDR and set STOP = 1\n");
state = disableIRQ();
_clear_addr(i2c);
i2c->CR1 |= (I2C_CR1_STOP);
restoreIRQ(state);
DEBUG("Wait for RXNE == 1\n");
while (!(i2c->SR1 & I2C_SR1_RXNE));
DEBUG("Read received data\n");
*data = (char)i2c->DR;
/* wait until STOP is cleared by hardware */
while (i2c->CR1 & I2C_CR1_STOP);
/* 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");
_start(i2c, address, I2C_FLAG_READ);
DEBUG("Set POS bit\n");
i2c->CR1 |= (I2C_CR1_POS | I2C_CR1_ACK);
DEBUG("Crit block: Clear ADDR bit and clear ACK flag\n");
state = disableIRQ();
_clear_addr(i2c);
i2c->CR1 &= ~(I2C_CR1_ACK);
restoreIRQ(state);
DEBUG("Wait for transfer to be completed\n");
while (!(i2c->SR1 & I2C_SR1_BTF));
DEBUG("Crit block: set STOP and read first byte\n");
state = disableIRQ();
i2c->CR1 |= (I2C_CR1_STOP);
data[0] = (char)i2c->DR;
restoreIRQ(state);
DEBUG("read second byte\n");
data[1] = (char)i2c->DR;
DEBUG("wait for STOP bit to be cleared again\n");
while (i2c->CR1 & I2C_CR1_STOP);
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");
_start(i2c, address, I2C_FLAG_READ);
_clear_addr(i2c);
while (i < (length - 3)) {
DEBUG("Wait until byte was received\n");
while (!(i2c->SR1 & I2C_SR1_RXNE));
DEBUG("Copy byte from DR\n");
data[i++] = (char)i2c->DR;
}
DEBUG("Reading the last 3 bytes, waiting for BTF flag\n");
while (!(i2c->SR1 & I2C_SR1_BTF));
DEBUG("Disable ACK\n");
i2c->CR1 &= ~(I2C_CR1_ACK);
DEBUG("Crit block: set STOP and read N-2 byte\n");
state = disableIRQ();
data[i++] = (char)i2c->DR;
i2c->CR1 |= (I2C_CR1_STOP);
restoreIRQ(state);
DEBUG("Read N-1 byte\n");
data[i++] = (char)i2c->DR;
while (!(i2c->SR1 & I2C_SR1_RXNE));
DEBUG("Read last byte\n");
data[i++] = (char)i2c->DR;
DEBUG("wait for STOP bit to be cleared again\n");
while (i2c->CR1 & I2C_CR1_STOP);
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;
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");
_start(i2c, address, I2C_FLAG_WRITE);
_clear_addr(i2c);
DEBUG("Write reg into DR\n");
i2c->DR = reg;
_stop(i2c);
DEBUG("Now start a read transaction\n");
return i2c_read_bytes(dev, address, data, length);
}
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;
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");
_start(i2c, address, I2C_FLAG_WRITE);
_clear_addr(i2c);
/* send out data bytes */
_write(i2c, data, length);
/* end transmission */
DEBUG("Ending transmission\n");
_stop(i2c);
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;
switch (dev) {
#if I2C_0_EN
case I2C_0:
i2c = I2C_0_DEV;
break;
#endif
default:
return -1;
}
/* start transmission and send slave address */
_start(i2c, address, I2C_FLAG_WRITE);
_clear_addr(i2c);
/* send register address and wait for complete transfer to be finished*/
_write(i2c, (char *)(&reg), 1);
/* write data to register */
_write(i2c, data, length);
/* finish transfer */
_stop(i2c);
/* 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)
{
switch (dev) {
#if I2C_0_EN
case I2C_0:
while (I2C_0_DEV->SR2 & I2C_SR2_BUSY);
I2C_0_CLKDIS();
break;
#endif
}
}
static void _start(I2C_TypeDef *dev, uint8_t address, uint8_t rw_flag)
{
/* wait for device to be ready */
DEBUG("Wait for device to be ready\n");
while (dev->SR2 & I2C_SR2_BUSY);
/* 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));
/* 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");
while (!(dev->SR1 & I2C_SR1_ADDR));
}
static inline void _clear_addr(I2C_TypeDef *dev)
{
dev->SR1;
dev->SR2;
DEBUG("Cleared address\n");
}
static inline void _write(I2C_TypeDef *dev, char *data, int length)
{
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 */
while (!(dev->SR1 & I2C_SR1_TXE));
DEBUG("DR is now empty again\n");
}
}
static inline void _stop(I2C_TypeDef *dev)
{
/* make sure last byte was send */
DEBUG("Wait if last byte hasn't been sent\n");
while (!(dev->SR1 & I2C_SR1_BTF));
/* send STOP condition */
dev->CR1 |= I2C_CR1_STOP;
}
#if I2C_0_EN
void I2C_0_ERR_ISR(void)
{
unsigned state = I2C_0_DEV->SR1;
DEBUG("\n\n### I2C ERROR OCCURED ###\n");
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");
}
while (1);
}
#endif /* I2C_0_EN */
#endif /* I2C_NUMOF */

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

@ -0,0 +1,278 @@
/*
* 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 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>
*
* @}
*/
#include <stdint.h>
#include <string.h>
#include "cpu.h"
#include "periph/pwm.h"
#include "periph_conf.h"
/* ignore file in case no PWM devices are defined */
#if PWM_0_EN || PWM_1_EN
int pwm_init(pwm_t dev, pwm_mode_t mode, unsigned int frequency, unsigned int resolution)
{
TIM_TypeDef *tim = NULL;
GPIO_TypeDef *port = NULL;
uint32_t pins[PWM_MAX_CHANNELS];
uint32_t af = 0;
uint32_t pwm_clk = 0;
int channels = 0;
pwm_poweron(dev);
switch (dev) {
#if PWM_0_EN
case PWM_0:
tim = PWM_0_DEV;
port = PWM_0_PORT;
pins[0] = PWM_0_PIN_CH0;
#if (PWM_0_CHANNELS > 1)
pins[1] = PWM_0_PIN_CH1;
#endif
#if (PWM_0_CHANNELS > 2)
pins[2] = PWM_0_PIN_CH2;
#endif
#if (PWM_0_CHANNELS > 3)
pins[3] = PWM_0_PIN_CH3;
#endif
af = PWM_0_PIN_AF;
channels = PWM_0_CHANNELS;
pwm_clk = PWM_0_CLK;
PWM_0_PORT_CLKEN();
break;
#endif
#if PWM_1_EN
case PWM_1:
tim = PWM_1_DEV;
port = PWM_1_PORT;
pins[0] = PWM_1_PIN_CH0;
#if (PWM_1_CHANNELS > 1)
pins[1] = PWM_1_PIN_CH1;
#endif
#if (PWM_1_CHANNELS > 2)
pins[2] = PWM_1_PIN_CH2;
#endif
#if (PWM_1_CHANNELS > 3)
pins[3] = PWM_1_PIN_CH3;
#endif
af = PWM_1_PIN_AF;
channels = PWM_1_CHANNELS;
pwm_clk = PWM_1_CLK;
PWM_1_PORT_CLKEN();
break;
#endif
}
/* 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] |= (af << (pins[i] * 4));
} else {
port->AFR[1] &= ~(0xf << ((pins[i] - 8) * 4));
port->AFR[1] |= (af << ((pins[i] - 8) * 4));
}
}
/* Reset C/C and timer configuration register */
switch (channels) {
case 4:
tim->CCR4 = 0;
/* Fall through */
case 3:
tim->CCR3 = 0;
tim->CR2 = 0;
/* Fall through */
case 2:
tim->CCR2 = 0;
/* Fall through */
case 1:
tim->CCR1 = 0;
tim->CR1 = 0;
break;
}
/* set prescale and auto-reload registers to matching values for resolution and frequency */
if (resolution > 0xffff || (resolution * frequency) > pwm_clk) {
return -2;
}
tim->PSC = (pwm_clk / (resolution * frequency)) - 1;
tim->ARR = resolution - 1;
/* calculate the actual PWM frequency */
frequency = (pwm_clk / (resolution * (tim->PSC + 1)));
/* set PWM mode */
switch (mode) {
case PWM_LEFT:
tim->CCMR1 = (TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_2 |
TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2M_2);
if (channels > 2) {
tim->CCMR2 = (TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3M_2 |
TIM_CCMR2_OC4M_1 | TIM_CCMR2_OC4M_2);
}
break;
case PWM_RIGHT:
tim->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) {
tim->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:
tim->CCMR1 = 0;
if (channels > 2) {
tim->CCMR2 = 0;
}
tim->CR1 |= (TIM_CR1_CMS_0 | TIM_CR1_CMS_1);
break;
}
/* enable output on PWM pins */
tim->CCER = (TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E | TIM_CCER_CC4E);
/* enable PWM outputs */
tim->BDTR = TIM_BDTR_MOE;
/* enable timer ergo the PWM generation */
pwm_start(dev);
return frequency;
}
int pwm_set(pwm_t dev, int channel, unsigned int value)
{
TIM_TypeDef *tim = NULL;
switch (dev) {
#if PWM_0_EN
case PWM_0:
tim = PWM_0_DEV;
if (channel >= PWM_0_CHANNELS) {
return -1;
}
break;
#endif
#if PWM_1_EN
case PWM_1:
tim = PWM_1_DEV;
if (channel >= PWM_1_CHANNELS) {
return -1;
}
break;
#endif
}
/* norm value to maximum possible value */
if (value > tim->ARR) {
value = (unsigned int) tim->ARR;
}
switch (channel) {
case 0:
tim->CCR1 = value;
break;
case 1:
tim->CCR2 = value;
break;
case 2:
tim->CCR3 = value;
break;
case 3:
tim->CCR4 = value;
break;
default:
return -1;
}
return 0;
}
void pwm_start(pwm_t dev)
{
switch (dev) {
#if PWM_0_EN
case PWM_0:
PWM_0_DEV->CR1 |= TIM_CR1_CEN;
break;
#endif
#if PWM_1_EN
case PWM_1:
PWM_1_DEV->CR1 |= TIM_CR1_CEN;
break;
#endif
}
}
void pwm_stop(pwm_t dev)
{
switch (dev) {
#if PWM_0_EN
case PWM_0:
PWM_0_DEV->CR1 &= ~(TIM_CR1_CEN);
break;
#endif
#if PWM_1_EN
case PWM_1:
PWM_1_DEV->CR1 &= ~(TIM_CR1_CEN);
break;
#endif
}
}
void pwm_poweron(pwm_t dev)
{
switch (dev) {
#if PWM_0_EN
case PWM_0:
PWM_0_CLKEN();
break;
#endif
#if PWM_1_EN
case PWM_1:
PWM_1_CLKEN();
break;
#endif
}
}
void pwm_poweroff(pwm_t dev)
{
switch (dev) {
#if PWM_0_EN
case PWM_0:
PWM_0_CLKDIS();
break;
#endif
#if PWM_1_EN
case PWM_1:
PWM_1_CLKDIS();
break;
#endif
}
}
#endif /* PWM_0_EN || PWM_1_EN */

View File

@ -0,0 +1,66 @@
/*
* Copyright (C) 2014 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 random number generator driver implementation
*
* @author Hauke Petersen <mail@haukepetersen.de>
*
* @}
*/
#include "cpu.h"
#include "periph/random.h"
#include "periph_conf.h"
/* ignore file in case no RNG device is defined */
#if RANDOM_NUMOF
void random_init(void)
{
random_poweron();
}
int random_read(char *buf, unsigned int num)
{
/* cppcheck-suppress variableScope */
uint32_t tmp;
unsigned int count = 0;
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++] = (char)tmp;
tmp = tmp >> 8;
}
}
return (int)count;
}
void random_poweron(void)
{
RCC->AHB2ENR |= RCC_AHB2ENR_RNGEN;
RNG->CR = RNG_CR_RNGEN;
}
void random_poweroff(void)
{
RNG->CR = 0;
RCC->AHB2ENR &= ~RCC_AHB2ENR_RNGEN;
}
#endif /* RANDOM_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 */

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

@ -0,0 +1,313 @@
/*
* Copyright (C) 2014 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 timer driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
#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);
/** Type for timer state */
typedef struct {
void (*cb)(int);
} timer_conf_t;
/** Timer state memory */
timer_conf_t config[TIMER_NUMOF];
int timer_init(tim_t dev, unsigned int ticks_per_us, void (*callback)(int))
{
TIM_TypeDef *timer;
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
/* enable timer peripheral clock */
TIMER_0_CLKEN();
/* set timer's IRQ priority */
NVIC_SetPriority(TIMER_0_IRQ_CHAN, TIMER_IRQ_PRIO);
/* select timer */
timer = TIMER_0_DEV;
timer->PSC = TIMER_0_PRESCALER * ticks_per_us;
break;
#endif
#if TIMER_1_EN
case TIMER_1:
/* enable timer peripheral clock */
TIMER_1_CLKEN();
/* set timer's IRQ priority */
NVIC_SetPriority(TIMER_1_IRQ_CHAN, TIMER_IRQ_PRIO);
/* select timer */
timer = TIMER_1_DEV;
timer->PSC = TIMER_1_PRESCALER * ticks_per_us;
break;
#endif
case TIMER_UNDEFINED:
default:
return -1;
}
/* set callback function */
config[dev].cb = callback;
/* set timer to run in counter mode */
timer->CR1 = 0;
timer->CR2 = 0;
/* set auto-reload and prescaler values and load new values */
timer->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 - 1);
}
int timer_set_absolute(tim_t dev, int channel, unsigned int value)
{
TIM_TypeDef *timer;
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
timer = TIMER_0_DEV;
break;
#endif
#if TIMER_1_EN
case TIMER_1:
timer = TIMER_1_DEV;
break;
#endif
case TIMER_UNDEFINED:
default:
return -1;
}
switch (channel) {
case 0:
timer->CCR1 = value;
timer->SR &= ~TIM_SR_CC1IF;
timer->DIER |= TIM_DIER_CC1IE;
break;
case 1:
timer->CCR2 = value;
timer->SR &= ~TIM_SR_CC2IF;
timer->DIER |= TIM_DIER_CC2IE;
break;
case 2:
timer->CCR3 = value;
timer->SR &= ~TIM_SR_CC3IF;
timer->DIER |= TIM_DIER_CC3IE;
break;
case 3:
timer->CCR4 = value;
timer->SR &= ~TIM_SR_CC4IF;
timer->DIER |= TIM_DIER_CC4IE;
break;
default:
return -1;
}
return 0;
}
int timer_clear(tim_t dev, int channel)
{
TIM_TypeDef *timer;
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
timer = TIMER_0_DEV;
break;
#endif
#if TIMER_1_EN
case TIMER_1:
timer = TIMER_1_DEV;
break;
#endif
case TIMER_UNDEFINED:
default:
return -1;
}
switch (channel) {
case 0:
timer->DIER &= ~TIM_DIER_CC1IE;
break;
case 1:
timer->DIER &= ~TIM_DIER_CC2IE;
break;
case 2:
timer->DIER &= ~TIM_DIER_CC3IE;
break;
case 3:
timer->DIER &= ~TIM_DIER_CC4IE;
break;
default:
return -1;
}
return 0;
}
unsigned int timer_read(tim_t dev)
{
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
return TIMER_0_DEV->CNT;
break;
#endif
#if TIMER_1_EN
case TIMER_1:
return TIMER_1_DEV->CNT;
break;
#endif
case TIMER_UNDEFINED:
default:
return 0;
}
}
void timer_start(tim_t dev)
{
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
TIMER_0_DEV->CR1 |= TIM_CR1_CEN;
break;
#endif
#if TIMER_1_EN
case TIMER_1:
TIMER_1_DEV->CR1 |= TIM_CR1_CEN;
break;
#endif
case TIMER_UNDEFINED:
break;
}
}
void timer_stop(tim_t dev)
{
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
TIMER_0_DEV->CR1 &= ~TIM_CR1_CEN;
break;
#endif
#if TIMER_1_EN
case TIMER_1:
TIMER_1_DEV->CR1 &= ~TIM_CR1_CEN;
break;
#endif
case TIMER_UNDEFINED:
break;
}
}
void timer_irq_enable(tim_t dev)
{
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
NVIC_EnableIRQ(TIMER_0_IRQ_CHAN);
break;
#endif
#if TIMER_1_EN
case TIMER_1:
NVIC_EnableIRQ(TIMER_1_IRQ_CHAN);
break;
#endif
case TIMER_UNDEFINED:
break;
}
}
void timer_irq_disable(tim_t dev)
{
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
NVIC_DisableIRQ(TIMER_0_IRQ_CHAN);
break;
#endif
#if TIMER_1_EN
case TIMER_1:
NVIC_DisableIRQ(TIMER_1_IRQ_CHAN);
break;
#endif
case TIMER_UNDEFINED:
break;
}
}
void TIMER_0_ISR(void)
{
irq_handler(TIMER_0, TIMER_0_DEV);
}
void TIMER_1_ISR(void)
{
irq_handler(TIMER_1, TIMER_1_DEV);
}
static inline void irq_handler(tim_t timer, TIM_TypeDef *dev)
{
if (dev->SR & TIM_SR_CC1IF) {
dev->DIER &= ~TIM_DIER_CC1IE;
dev->SR &= ~TIM_SR_CC1IF;
config[timer].cb(0);
}
else if (dev->SR & TIM_SR_CC2IF) {
dev->DIER &= ~TIM_DIER_CC2IE;
dev->SR &= ~TIM_SR_CC2IF;
config[timer].cb(1);
}
else if (dev->SR & TIM_SR_CC3IF) {
dev->DIER &= ~TIM_DIER_CC3IE;
dev->SR &= ~TIM_SR_CC3IF;
config[timer].cb(2);
}
else if (dev->SR & TIM_SR_CC4IF) {
dev->DIER &= ~TIM_DIER_CC4IE;
dev->SR &= ~TIM_SR_CC4IF;
config[timer].cb(3);
}
if (sched_context_switch_request) {
thread_yield();
}
}

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

@ -0,0 +1,232 @@
/*
* Copyright (C) 2014-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 UART driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Fabian Nack <nack@inf.fu-berlin.de>
*
* @}
*/
#include "cpu.h"
#include "thread.h"
#include "sched.h"
#include "mutex.h"
#include "periph/uart.h"
#include "periph/gpio.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];
/**
* @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;
/* check if given UART device does exist */
if (uart < 0 || uart >= UART_NUMOF) {
return -1;
}
/* 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]);
/* configure pins */
gpio_init(uart_config[uart].rx_pin, GPIO_DIR_IN, GPIO_NOPULL);
gpio_init(uart_config[uart].tx_pin, GPIO_DIR_OUT, GPIO_NOPULL);
gpio_init_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 */
if (_bus(uart) == 1) {
divider = CLOCK_APB1 / (16 * baudrate);
}
else {
divider = CLOCK_APB2 / (16 * baudrate);
}
mantissa = (uint16_t)divider;
fraction = (uint8_t)((divider - mantissa) * 16);
dev->BRR = ((mantissa & 0x0fff) << 4) | (0x0f & fraction);
/* configure UART to 8N1 and enable receive and transmit mode */
dev->CR3 = USART_CR3_DMAT;
dev->CR2 = 0;
dev->CR1 = USART_CR1_UE | USART_CR1_TE | USART_CR1_RE;
/* 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 (inISR()) {
/* 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 {
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]);
}
}
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 */
dma_base(stream)->IFCR[dma_hl(stream)] = 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);
}
#endif
#ifdef UART_3_ISR
void UART_3_ISR(void)
{
irq_handler(3, uart_config[3].dev);
}
#endif
#ifdef UART_4_ISR
void UART_4_ISR(void)
{
irq_handler(4, uart_config[4].dev);
}
#endif
#ifdef UART_5_ISR
void UART_5_ISR(void)
{
irq_handler(5, uart_config[5].dev);
}
#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);
/* STM32F4 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-M4 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 */
};