Merge pull request #6433 from aabadie/nucleo_l073

boards/nucleo-l073: initial support
pr/rotary
Francisco Acosta 7 years ago committed by GitHub
commit 29753d6018

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

@ -0,0 +1 @@
include $(RIOTBOARD)/nucleo-common/Makefile.dep

@ -0,0 +1,13 @@
# Put defined MCU peripherals here (in alphabetical order)
FEATURES_PROVIDED += periph_cpuid
FEATURES_PROVIDED += periph_gpio
FEATURES_PROVIDED += periph_pwm
FEATURES_PROVIDED += periph_spi
FEATURES_PROVIDED += periph_timer
FEATURES_PROVIDED += periph_uart
# load the common Makefile.features for Nucleo boards
include $(RIOTBOARD)/nucleo-common/Makefile.features
# The board MPU family (used for grouping by the CI system)
FEATURES_MCU_GROUP = cortex_m0_1

@ -0,0 +1,6 @@
## the cpu to build for
export CPU = stm32l0
export CPU_MODEL = stm32l073rz
# load the common Makefile.include for Nucleo boards
include $(RIOTBOARD)/nucleo-common/Makefile.include

@ -0,0 +1,34 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
* 2016 Inria
*
* 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-l073
* @{
*
* @file
* @brief Board specific implementations for the nucleo-l073 board
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Alexandre Abadie <alexandre.abadie@inria.fr>
*
* @}
*/
#include "board.h"
#include "periph/gpio.h"
void board_init(void)
{
/* initialize the boards LED */
gpio_init(LED0_PIN, GPIO_OUT);
/* initialize the CPU */
cpu_init();
}

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

@ -0,0 +1,47 @@
/*
* Copyright (C) 2017 Freie Universität Berlin
* 2017 Inria
*
* 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-l073 Nucleo-L073
* @ingroup boards
* @brief Board specific files for the nucleo-l073 board
* @{
*
* @file
* @brief Board specific definitions for the nucleo-l073 board
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Alexandre Aabdie <alexandre.abadie@inria.fr>
*/
#ifndef BOARD_H
#define BOARD_H
#include <stdint.h>
#include "board_common.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @name xtimer configuration
* @{
*/
#define XTIMER_DEV TIMER_DEV(0)
#define XTIMER_CHAN (0)
#define XTIMER_WIDTH (16)
/** @} */
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H */
/** @} */

@ -0,0 +1,193 @@
/*
* Copyright (C) 2017 Freie Universität Berlin
* 2017 Inria
*
* 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-l073
* @{
*
* @file
* @brief Peripheral MCU configuration for the nucleo-l073 board
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Alexandre Aabdie <alexandre.abadie@inria.fr>
*/
#ifndef PERIPH_CONF_H
#define PERIPH_CONF_H
#include "periph_cpu.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @name Clock system configuration
* @{
*/
#define CLOCK_HSI (16000000U) /* internal oscillator */
#define CLOCK_CORECLOCK (32000000U) /* desired core clock frequency */
/* configuration of PLL prescaler and multiply values */
/* CORECLOCK := HSI / CLOCK_PLL_DIV * CLOCK_PLL_MUL */
#define CLOCK_PLL_DIV RCC_CFGR_PLLDIV2
#define CLOCK_PLL_MUL RCC_CFGR_PLLMUL4
/* configuration of peripheral bus clock prescalers */
#define CLOCK_AHB_DIV RCC_CFGR_HPRE_DIV1 /* AHB clock -> 32MHz */
#define CLOCK_APB2_DIV RCC_CFGR_PPRE2_DIV1 /* APB2 clock -> 32MHz */
#define CLOCK_APB1_DIV RCC_CFGR_PPRE1_DIV1 /* APB1 clock -> 32MHz */
/* configuration of flash access cycles */
#define CLOCK_FLASH_LATENCY FLASH_ACR_LATENCY
/* bus clocks for simplified peripheral initialization, UPDATE MANUALLY! */
#define CLOCK_AHB (CLOCK_CORECLOCK / 1)
#define CLOCK_APB2 (CLOCK_CORECLOCK / 1)
#define CLOCK_APB1 (CLOCK_CORECLOCK / 1)
/** @} */
/**
* @brief Timer configuration
* @{
*/
static const timer_conf_t timer_config[] = {
{
.dev = TIM2,
.max = 0x0000ffff,
.rcc_mask = RCC_APB1ENR_TIM2EN,
.bus = APB1,
.irqn = TIM2_IRQn
}
};
#define TIMER_0_ISR isr_tim2
#define TIMER_NUMOF (sizeof(timer_config) / sizeof(timer_config[0]))
/** @} */
/**
* @brief UART configuration
* @{
*/
static const uart_conf_t uart_config[] = {
{
.dev = USART2,
.rcc_mask = RCC_APB1ENR_USART2EN,
.rx_pin = GPIO_PIN(PORT_A, 3),
.tx_pin = GPIO_PIN(PORT_A, 2),
.rx_af = GPIO_AF4,
.tx_af = GPIO_AF4,
.bus = APB1,
.irqn = USART2_IRQn
},
{
.dev = USART4,
.rcc_mask = RCC_APB1ENR_USART4EN,
.rx_pin = GPIO_PIN(PORT_C, 11),
.tx_pin = GPIO_PIN(PORT_C, 10),
.rx_af = GPIO_AF6,
.tx_af = GPIO_AF6,
.bus = APB1,
.irqn = USART4_5_IRQn
},
};
#define UART_0_ISR (isr_usart2)
#define UART_1_ISR (isr_usart4_5)
#define UART_NUMOF (sizeof(uart_config) / sizeof(uart_config[0]))
/** @} */
/**
* @brief PWM configuration
* @{
*/
static const pwm_conf_t pwm_config[] = {
{
.dev = TIM3,
.rcc_mask = RCC_APB1ENR_TIM3EN,
.chan = { { .pin = GPIO_PIN(PORT_B, 4) /* D5 */, .cc_chan = 0 },
{ .pin = GPIO_PIN(PORT_C, 7) /* D9 */, .cc_chan = 1 },
{ .pin = GPIO_PIN(PORT_C, 8) , .cc_chan = 2 },
{ .pin = GPIO_UNDEF, .cc_chan = 0 } },
.af = GPIO_AF2,
.bus = APB1
}
};
#define PWM_NUMOF (sizeof(pwm_config) / sizeof(pwm_config[0]))
/** @} */
/**
* @name SPI configuration
*
* @note The spi_divtable is auto-generated from
* `cpu/stm32_common/dist/spi_divtable/spi_divtable.c`
* @{
*/
static const uint8_t spi_divtable[2][5] = {
{ /* for APB1 @ 32000000Hz */
7, /* -> 125000Hz */
5, /* -> 500000Hz */
4, /* -> 1000000Hz */
2, /* -> 4000000Hz */
1 /* -> 8000000Hz */
},
{ /* for APB2 @ 32000000Hz */
7, /* -> 125000Hz */
5, /* -> 500000Hz */
4, /* -> 1000000Hz */
2, /* -> 4000000Hz */
1 /* -> 8000000Hz */
}
};
static const spi_conf_t spi_config[] = {
{
.dev = SPI1,
.mosi_pin = GPIO_PIN(PORT_A, 7),
.miso_pin = GPIO_PIN(PORT_A, 6),
.sclk_pin = GPIO_PIN(PORT_A, 5),
.cs_pin = GPIO_UNDEF,
.af = GPIO_AF0,
.rccmask = RCC_APB2ENR_SPI1EN,
.apbbus = APB2
}
};
#define SPI_NUMOF (sizeof(spi_config) / sizeof(spi_config[0]))
/** @} */
/**
* @brief ADC configuration
* @{
*/
#define ADC_NUMOF (0)
/** @} */
/**
* @brief DAC configuration
* @{
*/
#define DAC_NUMOF (0)
/** @} */
/**
* @name RTC configuration
* @{
*/
#define RTC_NUMOF (0U)
/** @} */
#ifdef __cplusplus
}
#endif
#endif /* PERIPH_CONF_H */
/** @} */

@ -43,7 +43,14 @@ void periph_clk_en(bus_t bus, uint32_t mask)
case APB2:
RCC->APB2ENR |= mask;
break;
#if defined(CPU_FAM_STM32L0) || defined(CPU_FAM_STM32L1) || defined(CPU_FAM_STM32F1) \
#if defined(CPU_FAM_STM32L0)
case AHB:
RCC->AHBENR |= mask;
break;
case IOP:
RCC->IOPENR |= mask;
break;
#elif defined(CPU_FAM_STM32L1) || defined(CPU_FAM_STM32F1) \
|| defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F3)
case AHB:
RCC->AHBENR |= mask;
@ -76,7 +83,14 @@ void periph_clk_dis(bus_t bus, uint32_t mask)
case APB2:
RCC->APB2ENR &= ~(mask);
break;
#if defined(CPU_FAM_STM32L0) || defined(CPU_FAM_STM32L1) || defined(CPU_FAM_STM32F1) \
#if defined(CPU_FAM_STM32L0)
case AHB:
RCC->AHBENR &= ~(mask);
break;
case IOP:
RCC->IOPENR &= ~(mask);
break;
#elif defined(CPU_FAM_STM32L1) || defined(CPU_FAM_STM32F1) \
|| defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F3)
case AHB:
RCC->AHBENR &= ~(mask);

@ -57,7 +57,10 @@ extern "C" {
typedef enum {
APB1, /**< APB1 bus */
APB2, /**< APB2 bus */
#if defined(CPU_FAM_STM32L0) || defined(CPU_FAM_STM32L1) || defined(CPU_FAM_STM32F1)\
#if defined(CPU_FAM_STM32L0)
AHB, /**< AHB bus */
IOP, /**< IOP bus */
#elif defined(CPU_FAM_STM32L1) || defined(CPU_FAM_STM32F1)\
|| defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F3)
AHB, /**< AHB bus */
#elif defined(CPU_FAM_STM32F2) || defined(CPU_FAM_STM32F4)

@ -104,7 +104,7 @@ void uart_write(uart_t uart, const uint8_t *data, size_t len)
assert(uart < UART_NUMOF);
for (size_t i = 0; i < len; i++) {
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F3)
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32L0) || defined(CPU_FAM_STM32F3)
while (!(dev(uart)->ISR & USART_ISR_TXE)) {}
dev(uart)->TDR = data[i];
#else
@ -115,7 +115,7 @@ void uart_write(uart_t uart, const uint8_t *data, size_t len)
/* make sure the function is synchronous by waiting for the transfer to
* finish */
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F3)
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32L0) || defined(CPU_FAM_STM32F3)
while (!(dev(uart)->ISR & USART_ISR_TC)) {}
#else
while (!(dev(uart)->SR & USART_SR_TC)) {}
@ -136,7 +136,7 @@ void uart_poweroff(uart_t uart)
static inline void irq_handler(uart_t uart)
{
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F3)
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32L0) || defined(CPU_FAM_STM32F3)
uint32_t status = dev(uart)->ISR;

@ -0,0 +1,10 @@
# 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
# (file triggers compiler bug. see #5775)
SRC_NOLTO += vectors.c
include $(RIOTBASE)/Makefile.base

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

@ -0,0 +1,121 @@
/*
* Copyright (C) 2014 Freie Universität Berlin
* 2017 Inria
*
* 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_stm32l0
* @{
*
* @file
* @brief Implementation of the CPU initialization
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Alexandre Abadie <alexandre.abadie@inria.fr>
*
* @}
*/
#include "cpu.h"
#include "periph_conf.h"
#include "periph/init.h"
/* Check the source to be used for the PLL */
#if defined(CLOCK_HSI) && defined(CLOCK_HSE)
#error "Only provide one of two CLOCK_HSI/CLOCK_HSE"
#elif CLOCK_HSI
#define CLOCK_CR_SOURCE RCC_CR_HSION
#define CLOCK_CR_SOURCE_RDY RCC_CR_HSIRDY
#define CLOCK_PLL_SOURCE RCC_CFGR_PLLSRC_HSI
#elif CLOCK_HSE
#define CLOCK_CR_SOURCE RCC_CR_HSEON
#define CLOCK_CR_SOURCE_RDY RCC_CR_HSERDY
#define CLOCK_PLL_SOURCE RCC_CFGR_PLLSRC_HSE
#else
#error "Please provide CLOCK_HSI or CLOCK_HSE in boards/NAME/includes/perhip_cpu.h"
#endif
static void clk_init(void);
/**
* @brief Initialize the CPU, set IRQ priorities
*/
void cpu_init(void)
{
/* initialize the Cortex-M core */
cortexm_init();
/* initialize the clock system */
clk_init();
/* trigger static peripheral initialization */
periph_init();
}
/**
* @brief Configure the controllers clock system
*
* The clock initialization make the following assumptions:
* - the external HSE clock from an external oscillator is used as base clock
* - the internal PLL circuit is used for clock refinement
*
* Use the following formulas to calculate the needed values:
*
* SYSCLK = ((HSE_VALUE / CLOCK_PLL_M) * CLOCK_PLL_N) / CLOCK_PLL_P
* USB, SDIO and RNG Clock = ((HSE_VALUE / CLOCK_PLL_M) * CLOCK_PLL_N) / CLOCK_PLL_Q
*
* The actual used values are specified in the board's `periph_conf.h` file.
*
* NOTE: currently there is not timeout for initialization of PLL and other locks
* -> when wrong values are chosen, the initialization could stall
*/
static void clk_init(void)
{
/* Reset the RCC clock configuration to the default reset state(for debug purpose) */
/* Set MSION bit */
RCC->CR |= RCC_CR_MSION;
/* Reset SW, HPRE, PPRE1, PPRE2, MCOSEL and MCOPRE bits */
RCC->CFGR &= ~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLDIV | RCC_CFGR_PLLMUL);
/* Reset HSION, HSEON, CSSON and PLLON bits */
RCC->CR &= ~(RCC_CR_HSION | RCC_CR_HSEON | RCC_CR_HSEBYP | RCC_CR_CSSON | RCC_CR_PLLON);
/* Disable all interrupts */
RCC->CICR = 0x0;
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration */
/* Enable high speed clock source */
RCC->CR |= CLOCK_CR_SOURCE;
/* Wait till the high speed clock source is ready
* NOTE: the MCU will stay here forever if you use an external clock source and it's not connected */
while (!(RCC->CR & CLOCK_CR_SOURCE_RDY)) {}
/* Enable Prefetch Buffer */
FLASH->ACR |= FLASH_ACR_PRFTEN;
/* Flash 1 wait state */
FLASH->ACR |= CLOCK_FLASH_LATENCY;
/* Power enable */
periph_clk_en(APB1, RCC_APB1ENR_PWREN);
/* Select the Voltage Range 1 (1.8 V) */
PWR->CR = PWR_CR_VOS_0;
/* Wait Until the Voltage Regulator is ready */
while((PWR->CSR & PWR_CSR_VOSF) != 0) {}
/* 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 = CLOCK_SOURCE / PLL_DIV * PLL_MUL */
RCC->CFGR &= ~((uint32_t)(RCC_CFGR_PLLSRC | RCC_CFGR_PLLDIV | RCC_CFGR_PLLMUL));
RCC->CFGR |= (uint32_t)(CLOCK_PLL_SOURCE | CLOCK_PLL_DIV | CLOCK_PLL_MUL);
/* 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) {}
}

@ -0,0 +1,49 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
* 2017 Inria
*
* 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_stm32l0 STM32L0
* @brief STM32L0 specific code
* @ingroup cpu
* @{
*
* @file
* @brief Implementation specific CPU configuration options
*
* @author Hauke Petersen <hauke.pertersen@fu-berlin.de>
* @author Alexandre Abadie <alexandre.abadie@inria.fr>
*/
#ifndef STM32L0_CPU_CONF_H
#define STM32L0_CPU_CONF_H
#include "cpu_conf_common.h"
#ifdef CPU_MODEL_STM32L073RZ
#include "stm32l073xx.h"
#endif
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief ARM Cortex-M specific CPU configuration
* @{
*/
#define CPU_DEFAULT_IRQ_PRIO (1U)
#define CPU_IRQ_NUMOF (31U)
/** @} */
#ifdef __cplusplus
}
#endif
#endif /* STM32F0_CPU_CONF_H */
/** @} */

@ -0,0 +1,119 @@
/*
* Copyright (C) 2015-2017 Freie Universität Berlin
* 2017 Inria
*
* 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_stm32l0
* @{
*
* @file
* @brief CPU specific definitions for internal peripheral handling
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Alexandre Abadie <alexandre.abadie@inria.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))
#ifndef DOXYGEN
/**
* @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 Override flank configuration values
* @{
*/
#define HAVE_GPIO_FLANK_T
typedef enum {
GPIO_RISING = 1, /**< emit interrupt on rising flank */
GPIO_FALLING = 2, /**< emit interrupt on falling flank */
GPIO_BOTH = 3 /**< emit interrupt on both flanks */
} gpio_flank_t;
/** @} */
#endif /* ndef DOXYGEN */
/**
* @brief Available ports on the STM32F0 family
*/
enum {
PORT_A = 0, /**< port A */
PORT_B = 1, /**< port B */
PORT_C = 2, /**< port C */
PORT_D = 3, /**< port D */
PORT_F = 5, /**< port F */
};
#ifndef DOXYGEN
/**
* @brief Override ADC resolution values
* @{
*/
#define HAVE_ADC_RES_T
typedef enum {
ADC_RES_6BIT = (0x3 << 3), /**< ADC resolution: 6 bit */
ADC_RES_8BIT = (0x2 << 3), /**< ADC resolution: 8 bit */
ADC_RES_10BIT = (0x1 << 3), /**< ADC resolution: 10 bit */
ADC_RES_12BIT = (0x0 << 3), /**< ADC resolution: 12 bit */
ADC_RES_14BIT = (0xfe), /**< not applicable */
ADC_RES_16BIT = (0xff) /**< not applicable */
} adc_res_t;
/** @} */
#endif /* ndef DOXYGEN */
/**
* @brief ADC line configuration values
*/
typedef struct {
gpio_t pin; /**< pin to use */
uint8_t chan; /**< internal channel the pin is connected to */
} adc_conf_t;
/**
* @brief DAC line configuration data
*/
typedef struct {
gpio_t pin; /**< pin connected to the line */
uint8_t chan; /**< DAC device used for this line */
} dac_conf_t;
#ifdef __cplusplus
}
#endif
#endif /* PERIPH_CPU_H */
/** @} */

File diff suppressed because it is too large Load Diff

@ -0,0 +1,30 @@
/*
* Copyright (C) 2017 Inria
*
* 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_stm32l0
* @{
*
* @file
* @brief Memory definitions for the STM32L073RZ
*
* @author Alexandre Abadie <alexandre.abadie@inria.fr>
*
* @}
*/
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 192K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
cpuid (r) : ORIGIN = 0x1ff80050, LENGTH = 12
}
_cpuid_address = ORIGIN(cpuid);
INCLUDE cortexm_base.ld

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

@ -0,0 +1,220 @@
/*
* Copyright (C) 2014 Freie Universität Berlin
* 2017 Inria
*
* 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_stm32l0
* @{
*
* @file
* @brief Low-level GPIO driver implementation
*
* @author Hauke Petersen <mail@haukepetersen.de>
* @author Alexandre Abadie <alexandre.abadie@inria.fr>
*
* @}
*/
#include "cpu.h"
#include "periph/gpio.h"
#include "periph_conf.h"
/**
* @brief The STM32L0 family has 16 external interrupt lines
*/
#define EXTI_NUMOF (16U)
/**
* @brief Allocate memory for one callback and argument per EXTI channel
*/
static gpio_isr_ctx_t isr_ctx[EXTI_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 */
periph_clk_en(IOP, (RCC_IOPENR_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);
/* finally set pin speed to maximum and reset output */
port->OSPEEDR |= (3 << (2 * pin_num));
port->BRR = (1 << pin_num);
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);
/* set callback */
isr_ctx[pin_num].cb = cb;
isr_ctx[pin_num].arg = arg;
/* enable clock of the SYSCFG module for EXTI configuration */
periph_clk_en(APB2, RCC_APB2ENR_SYSCFGEN);
/* initialize pin as input */
gpio_init(pin, mode);
/* enable global pin interrupt */
if (pin_num < 2) {
NVIC_EnableIRQ(EXTI0_1_IRQn);
}
else if (pin_num < 4) {
NVIC_EnableIRQ(EXTI2_3_IRQn);
}
else {
NVIC_EnableIRQ(EXTI4_15_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, needed as this function can be used without calling
* gpio_init first */
periph_clk_en(IOP, (RCC_IOPENR_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)
{
if (_port(pin)->MODER & (0x3 << (_pin_num(pin) * 2))) {
return _port(pin)->ODR & (1 << _pin_num(pin));
}
else {
return _port(pin)->IDR & (1 << _pin_num(pin));
}
}
void gpio_set(gpio_t pin)
{
_port(pin)->BSRR = (1 << _pin_num(pin));
}
void gpio_clear(gpio_t pin)
{
_port(pin)->BRR = (1 << _pin_num(pin));
}
void gpio_toggle(gpio_t pin)
{
if (gpio_read(pin)) {
_port(pin)->BRR = (1 << _pin_num(pin));
} else {
_port(pin)->BSRR = (1 << _pin_num(pin));
}
}
void gpio_write(gpio_t pin, int value)
{
if (value) {
_port(pin)->BSRR = (1 << _pin_num(pin));
} else {
_port(pin)->BRR = (1 << _pin_num(pin));
}
}
void isr_exti(void)
{
/* only generate interrupts against lines which have their IMR set */
uint32_t pending_isr = (EXTI->PR & EXTI->IMR);
for (size_t i = 0; i < EXTI_NUMOF; i++) {
if (pending_isr & (1 << i)) {
EXTI->PR = (1 << i); /* clear by writing a 1 */
isr_ctx[i].cb(isr_ctx[i].arg);
}
}
cortexm_isr_end();
}

@ -0,0 +1,125 @@
/*
* Copyright (C) 2014-2017 Freie Universität Berlin
* 2017 Inria
*
* 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_stm32l0
* @{
*
* @file
* @brief Interrupt vector definitions
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Alexandre Abadie <alexandre.abadie@inria.fr>
*
* @}
*/
#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);
/* STM32L0 specific interrupt vectors */
WEAK_DEFAULT void isr_wwdg(void);
WEAK_DEFAULT void isr_pvd(void);
WEAK_DEFAULT void isr_rtc(void);
WEAK_DEFAULT void isr_flash(void);
WEAK_DEFAULT void isr_rcc(void);
WEAK_DEFAULT void isr_exti(void);
WEAK_DEFAULT void isr_ts(void);
WEAK_DEFAULT void isr_dma1_ch1(void);
WEAK_DEFAULT void isr_dma1_ch2_3(void);
WEAK_DEFAULT void isr_dma1_ch4_5_6_7(void);
WEAK_DEFAULT void isr_adc1_comp(void);
WEAK_DEFAULT void isr_lptim1(void);
WEAK_DEFAULT void isr_usart4_5(void);
WEAK_DEFAULT void isr_tim2(void);
WEAK_DEFAULT void isr_tim3(void);
WEAK_DEFAULT void isr_tim6_dac(void);
WEAK_DEFAULT void isr_tim7(void);
WEAK_DEFAULT void isr_tim21(void);
WEAK_DEFAULT void isr_i2c3(void);
WEAK_DEFAULT void isr_tim22(void);
WEAK_DEFAULT void isr_i2c1(void);
WEAK_DEFAULT void isr_i2c2(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_rng_lpuart1(void);
WEAK_DEFAULT void isr_lcd(void);
WEAK_DEFAULT void isr_usb(void);
/* interrupt vector table */
ISR_VECTORS const void *interrupt_vector[] = {
/* Exception stack pointer */
(void*) (&_estack), /* pointer to the top of the stack */
/* Cortex-M0 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*) (0UL), /* reserved */
(void*) (0UL), /* reserved */
(void*) (0UL), /* reserved */
(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*) (0UL), /* reserved */
(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, /* windowed watchdog */
(void*) isr_pvd, /* power control */
(void*) isr_rtc, /* real time clock */
(void*) isr_flash, /* flash memory controller */
(void*) isr_rcc, /* reset and clock control */
(void*) isr_exti, /* external interrupt lines 0 and 1 */
(void*) isr_exti, /* external interrupt lines 2 and 3 */
(void*) isr_exti, /* external interrupt lines 4 to 15 */
(void*) isr_ts, /* touch sensing input*/
(void*) isr_dma1_ch1, /* direct memory access controller 1, channel 1*/
(void*) isr_dma1_ch2_3, /* direct memory access controller 1, channel 2 and 3*/
(void*) isr_dma1_ch4_5_6_7, /* direct memory access controller 1, channel 4, 5, 6 and 7*/
(void*) isr_adc1_comp, /* analog digital converter */
(void*) isr_lptim1, /* low power timer 1 */
(void*) isr_usart4_5, /* usart 4 to 5 */
(void*) isr_tim2, /* timer 2 */
(void*) isr_tim3, /* timer 3 */
(void*) isr_tim6_dac, /* timer 6 and digital to analog converter */
(void*) isr_tim7, /* timer 7 */
(void*) (0UL), /* reserved */
(void*) isr_tim21, /* timer 21 */
(void*) isr_i2c3, /* I2C 3 */
(void*) isr_tim22, /* timer 22 */
(void*) isr_i2c1, /* I2C 1 */
(void*) isr_i2c2, /* I2C 2 */
(void*) isr_spi1, /* SPI 1 */
(void*) isr_spi2, /* SPI 2 */
(void*) isr_usart1, /* USART 1 */
(void*) isr_usart2, /* USART 2 */
(void*) isr_rng_lpuart1, /* Low power UART 1 */
(void*) isr_lcd, /* LCD */
(void*) isr_usb /* USB */
};

@ -839,7 +839,8 @@ EXCLUDE_PATTERNS = */board/*/tools/* \
*/cpu/stm32f2/include/stm32f2*.h \
*/cpu/stm32f4/include/stm32f4*.h \
*/cpu/stm32f*/include/stm32f* \
*/cpu/stm32l1/include/stm32l1xx.h \
*/cpu/stm32l1/include/stm32l*.h \
*/cpu/stm32l0/include/stm32l* \
*/cpu/x86/include/x86_pci.h \
*/drivers/kw2xrf/include/overwrites.h \
*/drivers/nrf24l01p/include/nrf24l01p_settings.h \

@ -18,7 +18,7 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon nrf51dongle nrf6310 nucleo-f103 \
stm32f0discovery weio yunjia-nrf51822 nucleo-f072 \
cc2650stk nucleo-f030 nucleo-f070 microbit \
calliope-mini nucleo32-f042 nucleo32-f303 opencm9-04 \
maple-mini nucleo32-f031
maple-mini nucleo32-f031 nucleo-l073
# Include packages that pull up and auto-init the link layer.
# NOTE: 6LoWPAN will be included if IEEE802.15.4 devices are present

@ -12,7 +12,8 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon cc2650stk maple-mini msb-430 msb-430h
spark-core stm32f0discovery telosb \
weio wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 nucleo-f072 \
nucleo-f030 nucleo-f070 microbit calliope-mini \
nucleo32-f042 nucleo32-f303 opencm9-04 nucleo32-f031
nucleo32-f042 nucleo32-f303 opencm9-04 nucleo32-f031 \
nucleo-l073
BOARD_BLACKLIST += mips-malta # No UART available.

@ -6,7 +6,8 @@ BOARD_INSUFFICIENT_MEMORY := cc2650stk chronos maple-mini msb-430 msb-430h \
yunjia-nrf51822 spark-core airfy-beacon nucleo-f103 \
nucleo-f334 nrf51dongle nrf6310 weio nucleo-f072 \
nucleo-f030 nucleo-f070 microbit calliope-mini \
nucleo32-f042 nucleo32-f303 opencm9-04 nucleo32-f031
nucleo32-f042 nucleo32-f303 opencm9-04 nucleo32-f031 \
nucleo-l073
DISABLE_MODULE += auto_init

@ -14,7 +14,7 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon cc2650stk chronos ek-lm4f120xl \
slwstk6220a ek-lm4f120xl stm32f3discovery \
slwstk6220a nucleo32-f042 nucleo32-f303 opencm9-04 \
seeeduino_arch-pro remote-pa remote-revb remote-reva \
nucleo32-f031
nucleo32-f031 nucleo-l073
USEMODULE += embunit
@ -33,7 +33,7 @@ ARM_CORTEX_M_BOARDS := airfy-beacon arduino-due cc2538dk ek-lm4f120xl f4vi1 fox
pba-d-01-kw2x pca10000 pca10005 remote saml21-xpro samr21-xpro slwstk6220a \
spark-core stm32f0discovery stm32f3discovery stm32f4discovery udoo weio \
yunjia-nrf51822 sodaq-autonomo arduino-zero nucleo-f030 nucleo-f070 \
nucleo32-f303 opencm9-04 nucleo-f411 nucleo32-f031
nucleo32-f303 opencm9-04 nucleo-f411 nucleo32-f031 nucleo-l073
DISABLE_TEST_FOR_ARM_CORTEX_M := tests-relic

Loading…
Cancel
Save