diff --git a/cpu/stm32_common/cpu_common.c b/cpu/stm32_common/cpu_common.c index 06e410112c..2f8f33b765 100644 --- a/cpu/stm32_common/cpu_common.c +++ b/cpu/stm32_common/cpu_common.c @@ -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); diff --git a/cpu/stm32_common/include/periph_cpu_common.h b/cpu/stm32_common/include/periph_cpu_common.h index 2422473b03..367c03c426 100644 --- a/cpu/stm32_common/include/periph_cpu_common.h +++ b/cpu/stm32_common/include/periph_cpu_common.h @@ -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) diff --git a/cpu/stm32l0/Makefile b/cpu/stm32l0/Makefile new file mode 100644 index 0000000000..7610bbb5e2 --- /dev/null +++ b/cpu/stm32l0/Makefile @@ -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 diff --git a/cpu/stm32l0/Makefile.include b/cpu/stm32l0/Makefile.include new file mode 100644 index 0000000000..8814ecd405 --- /dev/null +++ b/cpu/stm32l0/Makefile.include @@ -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 diff --git a/cpu/stm32l0/cpu.c b/cpu/stm32l0/cpu.c new file mode 100644 index 0000000000..a78f9767a1 --- /dev/null +++ b/cpu/stm32l0/cpu.c @@ -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 + * @author Alexandre Abadie + * + * @} + */ + +#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) {} +} diff --git a/cpu/stm32l0/include/cpu_conf.h b/cpu/stm32l0/include/cpu_conf.h new file mode 100644 index 0000000000..ac622b2af8 --- /dev/null +++ b/cpu/stm32l0/include/cpu_conf.h @@ -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 + * @author Alexandre Abadie +*/ + +#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 */ +/** @} */ diff --git a/cpu/stm32l0/include/periph_cpu.h b/cpu/stm32l0/include/periph_cpu.h new file mode 100644 index 0000000000..c109006f27 --- /dev/null +++ b/cpu/stm32l0/include/periph_cpu.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 + * @author Alexandre Abadie + * + */ + +#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 */ +/** @} */ diff --git a/cpu/stm32l0/include/stm32l073xx.h b/cpu/stm32l0/include/stm32l073xx.h new file mode 100644 index 0000000000..23d232eaa5 --- /dev/null +++ b/cpu/stm32l0/include/stm32l073xx.h @@ -0,0 +1,7841 @@ +/** + ****************************************************************************** + * @file stm32l073xx.h + * @author MCD Application Team + * @version V1.7.0 + * @date 31-May-2016 + * @brief CMSIS Cortex-M0+ Device Peripheral Access Layer Header File. + * This file contains all the peripheral register's definitions, bits + * definitions and memory mapping for stm32l073xx devices. + * + * This file contains: + * - Data structures and the address mapping for all peripherals + * - Peripheral's registers declarations and bits definition + * - Macros to access peripheral's registers hardware + * + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2015 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32l073xx + * @{ + */ + +#ifndef __STM32L073xx_H +#define __STM32L073xx_H + +#ifdef __cplusplus + extern "C" { +#endif + + +/** @addtogroup Configuration_section_for_CMSIS + * @{ + */ +/** + * @brief Configuration of the Cortex-M0+ Processor and Core Peripherals + */ +#define __CM0PLUS_REV 0 /*!< Core Revision r0p0 */ +#define __MPU_PRESENT 0 /*!< STM32L0xx provides an MPU */ +#define __VTOR_PRESENT 1 /*!< Vector Table Register supported */ +#define __NVIC_PRIO_BITS 2 /*!< STM32L0xx uses 2 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ + +/** + * @} + */ + +/** @addtogroup Peripheral_interrupt_number_definition + * @{ + */ + +/** + * @brief stm32l073xx Interrupt Number Definition, according to the selected device + * in @ref Library_configuration_section + */ + +/*!< Interrupt Number Definition */ +typedef enum +{ +/****** Cortex-M0 Processor Exceptions Numbers ******************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + HardFault_IRQn = -13, /*!< 3 Cortex-M0+ Hard Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M0+ SV Call Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M0+ Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M0+ System Tick Interrupt */ + +/****** STM32L-0 specific Interrupt Numbers *********************************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ + PVD_IRQn = 1, /*!< PVD through EXTI Line detect Interrupt */ + RTC_IRQn = 2, /*!< RTC through EXTI Line Interrupt */ + FLASH_IRQn = 3, /*!< FLASH Interrupt */ + RCC_CRS_IRQn = 4, /*!< RCC and CRS Interrupts */ + EXTI0_1_IRQn = 5, /*!< EXTI Line 0 and 1 Interrupts */ + EXTI2_3_IRQn = 6, /*!< EXTI Line 2 and 3 Interrupts */ + EXTI4_15_IRQn = 7, /*!< EXTI Line 4 to 15 Interrupts */ + TSC_IRQn = 8, /*!< TSC Interrupt */ + DMA1_Channel1_IRQn = 9, /*!< DMA1 Channel 1 Interrupt */ + DMA1_Channel2_3_IRQn = 10, /*!< DMA1 Channel 2 and Channel 3 Interrupts */ + DMA1_Channel4_5_6_7_IRQn = 11, /*!< DMA1 Channel 4, Channel 5, Channel 6 and Channel 7 Interrupts */ + ADC1_COMP_IRQn = 12, /*!< ADC1, COMP1 and COMP2 Interrupts */ + LPTIM1_IRQn = 13, /*!< LPTIM1 Interrupt */ + USART4_5_IRQn = 14, /*!< USART4 and USART5 Interrupt */ + TIM2_IRQn = 15, /*!< TIM2 Interrupt */ + TIM3_IRQn = 16, /*!< TIM3 Interrupt */ + TIM6_DAC_IRQn = 17, /*!< TIM6 and DAC Interrupts */ + TIM7_IRQn = 18, /*!< TIM7 Interrupt */ + TIM21_IRQn = 20, /*!< TIM21 Interrupt */ + I2C3_IRQn = 21, /*!< I2C3 Interrupt */ + TIM22_IRQn = 22, /*!< TIM22 Interrupt */ + I2C1_IRQn = 23, /*!< I2C1 Interrupt */ + I2C2_IRQn = 24, /*!< I2C2 Interrupt */ + SPI1_IRQn = 25, /*!< SPI1 Interrupt */ + SPI2_IRQn = 26, /*!< SPI2 Interrupt */ + USART1_IRQn = 27, /*!< USART1 Interrupt */ + USART2_IRQn = 28, /*!< USART2 Interrupt */ + RNG_LPUART1_IRQn = 29, /*!< RNG and LPUART1 Interrupts */ + LCD_IRQn = 30, /*!< LCD Interrupt */ + USB_IRQn = 31, /*!< USB global Interrupt */ +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm0plus.h" +#include + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t ISR; /*!< ADC Interrupt and Status register, Address offset:0x00 */ + __IO uint32_t IER; /*!< ADC Interrupt Enable register, Address offset:0x04 */ + __IO uint32_t CR; /*!< ADC Control register, Address offset:0x08 */ + __IO uint32_t CFGR1; /*!< ADC Configuration register 1, Address offset:0x0C */ + __IO uint32_t CFGR2; /*!< ADC Configuration register 2, Address offset:0x10 */ + __IO uint32_t SMPR; /*!< ADC Sampling time register, Address offset:0x14 */ + uint32_t RESERVED1; /*!< Reserved, 0x18 */ + uint32_t RESERVED2; /*!< Reserved, 0x1C */ + __IO uint32_t TR; /*!< ADC watchdog threshold register, Address offset:0x20 */ + uint32_t RESERVED3; /*!< Reserved, 0x24 */ + __IO uint32_t CHSELR; /*!< ADC channel selection register, Address offset:0x28 */ + uint32_t RESERVED4[5]; /*!< Reserved, 0x2C */ + __IO uint32_t DR; /*!< ADC data register, Address offset:0x40 */ + uint32_t RESERVED5[28]; /*!< Reserved, 0x44 - 0xB0 */ + __IO uint32_t CALFACT; /*!< ADC data register, Address offset:0xB4 */ +} ADC_TypeDef; + +typedef struct +{ + __IO uint32_t CCR; +} ADC_Common_TypeDef; + + +/** + * @brief Comparator + */ + +typedef struct +{ + __IO uint32_t CSR; /*!< COMP comparator control and status register, Address offset: 0x18 */ +} COMP_TypeDef; + +typedef struct +{ + __IO uint32_t CSR; /*!< COMP control and status register, used for bits common to several COMP instances, Address offset: 0x00 */ +} COMP_Common_TypeDef; + + +/** +* @brief CRC calculation unit +*/ + +typedef struct +{ +__IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ +__IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ +uint8_t RESERVED0; /*!< Reserved, 0x05 */ +uint16_t RESERVED1; /*!< Reserved, 0x06 */ +__IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ +uint32_t RESERVED2; /*!< Reserved, 0x0C */ +__IO uint32_t INIT; /*!< Initial CRC value register, Address offset: 0x10 */ +__IO uint32_t POL; /*!< CRC polynomial register, Address offset: 0x14 */ +} CRC_TypeDef; + +/** + * @brief Clock Recovery System + */ + +typedef struct +{ +__IO uint32_t CR; /*!< CRS ccontrol register, Address offset: 0x00 */ +__IO uint32_t CFGR; /*!< CRS configuration register, Address offset: 0x04 */ +__IO uint32_t ISR; /*!< CRS interrupt and status register, Address offset: 0x08 */ +__IO uint32_t ICR; /*!< CRS interrupt flag clear register, Address offset: 0x0C */ +} CRS_TypeDef; + +/** + * @brief Digital to Analog Converter + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ + __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ + __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ + __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ + __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ + __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ + __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ + __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ + __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ + __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ + __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ + __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ + __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ + __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ +} DAC_TypeDef; + +/** + * @brief Debug MCU + */ + +typedef struct +{ + __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ + __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ + __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ + __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ +}DBGMCU_TypeDef; + +/** + * @brief DMA Controller + */ + +typedef struct +{ + __IO uint32_t CCR; /*!< DMA channel x configuration register */ + __IO uint32_t CNDTR; /*!< DMA channel x number of data register */ + __IO uint32_t CPAR; /*!< DMA channel x peripheral address register */ + __IO uint32_t CMAR; /*!< DMA channel x memory address register */ +} DMA_Channel_TypeDef; + +typedef struct +{ + __IO uint32_t ISR; /*!< DMA interrupt status register, Address offset: 0x00 */ + __IO uint32_t IFCR; /*!< DMA interrupt flag clear register, Address offset: 0x04 */ +} DMA_TypeDef; + +typedef struct +{ + __IO uint32_t CSELR; /*!< DMA channel selection register, Address offset: 0xA8 */ +} DMA_Request_TypeDef; + +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ + __IO uint32_t IMR; /*! + * + * @} + */ + +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 diff --git a/cpu/stm32l0/periph/Makefile b/cpu/stm32l0/periph/Makefile new file mode 100644 index 0000000000..1be36f440e --- /dev/null +++ b/cpu/stm32l0/periph/Makefile @@ -0,0 +1,5 @@ +# define the module name +MODULE = periph + +# include RIOTs generic Makefile +include $(RIOTBASE)/Makefile.base diff --git a/cpu/stm32l0/periph/gpio.c b/cpu/stm32l0/periph/gpio.c new file mode 100644 index 0000000000..46f57690a0 --- /dev/null +++ b/cpu/stm32l0/periph/gpio.c @@ -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 + * @author Alexandre Abadie + * + * @} + */ + +#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(); +} diff --git a/cpu/stm32l0/vectors.c b/cpu/stm32l0/vectors.c new file mode 100644 index 0000000000..daeec03c24 --- /dev/null +++ b/cpu/stm32l0/vectors.c @@ -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 + * @author Alexandre Abadie + * + * @} + */ + +#include +#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 */ +};