diff --git a/boards/nucleo-l053/Makefile b/boards/nucleo-l053/Makefile new file mode 100644 index 0000000000..f8fcbb53a0 --- /dev/null +++ b/boards/nucleo-l053/Makefile @@ -0,0 +1,3 @@ +MODULE = board + +include $(RIOTBASE)/Makefile.base diff --git a/boards/nucleo-l053/Makefile.dep b/boards/nucleo-l053/Makefile.dep new file mode 100644 index 0000000000..76e2dc17b4 --- /dev/null +++ b/boards/nucleo-l053/Makefile.dep @@ -0,0 +1 @@ +include $(RIOTBOARD)/nucleo-common/Makefile.dep diff --git a/boards/nucleo-l053/Makefile.features b/boards/nucleo-l053/Makefile.features new file mode 100644 index 0000000000..ae8430d7d8 --- /dev/null +++ b/boards/nucleo-l053/Makefile.features @@ -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 diff --git a/boards/nucleo-l053/Makefile.include b/boards/nucleo-l053/Makefile.include new file mode 100644 index 0000000000..5128948a0e --- /dev/null +++ b/boards/nucleo-l053/Makefile.include @@ -0,0 +1,6 @@ +## the cpu to build for +export CPU = stm32l0 +export CPU_MODEL = stm32l053r8 + +# load the common Makefile.include for Nucleo boards +include $(RIOTBOARD)/nucleo-common/Makefile.include diff --git a/boards/nucleo-l053/board.c b/boards/nucleo-l053/board.c new file mode 100644 index 0000000000..7f18a5b107 --- /dev/null +++ b/boards/nucleo-l053/board.c @@ -0,0 +1,34 @@ +/* + * Copyright (C) 2016-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-l053 + * @{ + * + * @file + * @brief Board specific implementations for the nucleo-l053 board + * + * @author Hauke Petersen + * @author Alexandre Abadie + * + * @} + */ + +#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(); +} diff --git a/boards/nucleo-l053/dist/openocd.cfg b/boards/nucleo-l053/dist/openocd.cfg new file mode 100644 index 0000000000..b4c7706757 --- /dev/null +++ b/boards/nucleo-l053/dist/openocd.cfg @@ -0,0 +1,7 @@ +source [find interface/stlink-v2-1.cfg] + +transport select hla_swd + +source [find target/stm32l0.cfg] + +reset_config srst_only diff --git a/boards/nucleo-l053/include/board.h b/boards/nucleo-l053/include/board.h new file mode 100644 index 0000000000..d29f4f1c12 --- /dev/null +++ b/boards/nucleo-l053/include/board.h @@ -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-l053 Nucleo-L053 + * @ingroup boards + * @brief Board specific files for the nucleo-l053 board + * @{ + * + * @file + * @brief Board specific definitions for the nucleo-l053 board + * + * @author Hauke Petersen + * @author Alexandre Abadie + */ + +#ifndef BOARD_H +#define BOARD_H + +#include +#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 */ +/** @} */ diff --git a/boards/nucleo-l053/include/periph_conf.h b/boards/nucleo-l053/include/periph_conf.h new file mode 100644 index 0000000000..66c71e3b05 --- /dev/null +++ b/boards/nucleo-l053/include/periph_conf.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-l053 + * @{ + * + * @file + * @brief Peripheral MCU configuration for the nucleo-l053 board + * + * @author Hauke Petersen + * @author Alexandre Abadie + */ + +#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 = USART1, + .rcc_mask = RCC_APB2ENR_USART1EN, + .rx_pin = GPIO_PIN(PORT_A, 10), + .tx_pin = GPIO_PIN(PORT_A, 9), + .rx_af = GPIO_AF4, + .tx_af = GPIO_AF4, + .bus = APB2, + .irqn = USART1_IRQn + } +}; + +#define UART_0_ISR (isr_usart2) +#define UART_1_ISR (isr_usart1) + +#define UART_NUMOF (sizeof(uart_config) / sizeof(uart_config[0])) +/** @} */ + +/** + * @brief PWM configuration + * @{ + */ +static const pwm_conf_t pwm_config[] = { + { + .dev = TIM22, + .rcc_mask = RCC_APB2ENR_TIM22EN, + .chan = { { .pin = GPIO_PIN(PORT_B, 4) /* D5 */, .cc_chan = 0 }, + { .pin = GPIO_PIN(PORT_B, 5), .cc_chan = 1 }, + { .pin = GPIO_UNDEF, .cc_chan = 0 }, + { .pin = GPIO_UNDEF, .cc_chan = 0 } }, + .af = GPIO_AF4, + .bus = APB2 + } +}; + +#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 */ +/** @} */ diff --git a/cpu/stm32l0/include/cpu_conf.h b/cpu/stm32l0/include/cpu_conf.h index ac622b2af8..ad0c5fb69d 100644 --- a/cpu/stm32l0/include/cpu_conf.h +++ b/cpu/stm32l0/include/cpu_conf.h @@ -28,6 +28,9 @@ #ifdef CPU_MODEL_STM32L073RZ #include "stm32l073xx.h" #endif +#ifdef CPU_MODEL_STM32L053R8 +#include "stm32l053xx.h" +#endif #ifdef __cplusplus extern "C" { diff --git a/cpu/stm32l0/include/stm32l053xx.h b/cpu/stm32l0/include/stm32l053xx.h new file mode 100644 index 0000000000..3254b42d65 --- /dev/null +++ b/cpu/stm32l0/include/stm32l053xx.h @@ -0,0 +1,7504 @@ +/** + ****************************************************************************** + * @file stm32l053xx.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 stm32l053xx 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 stm32l053xx + * @{ + */ + +#ifndef __STM32L053xx_H +#define __STM32L053xx_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 stm32l053xx 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 */ + TIM2_IRQn = 15, /*!< TIM2 Interrupt */ + TIM6_DAC_IRQn = 17, /*!< TIM6 and DAC Interrupts */ + TIM21_IRQn = 20, /*!< TIM21 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 */ + uint32_t RESERVED0[6]; /*!< 0x14-0x28 */ + __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ + uint32_t RESERVED1; /*!< 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 = 64K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K + cpuid (r) : ORIGIN = 0x1ff80050, LENGTH = 12 +} + +_cpuid_address = ORIGIN(cpuid); + +INCLUDE cortexm_base.ld diff --git a/examples/dtls-echo/Makefile b/examples/dtls-echo/Makefile index 812629b1a5..b6cc11cb43 100644 --- a/examples/dtls-echo/Makefile +++ b/examples/dtls-echo/Makefile @@ -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 nucleo-l073 + maple-mini nucleo32-f031 nucleo-l073 nucleo-l053 # Include packages that pull up and auto-init the link layer. # NOTE: 6LoWPAN will be included if IEEE802.15.4 devices are present diff --git a/examples/emcute/Makefile b/examples/emcute/Makefile index a8b49a81d7..7987689d59 100644 --- a/examples/emcute/Makefile +++ b/examples/emcute/Makefile @@ -8,9 +8,9 @@ BOARD ?= native RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-uno \ - chronos msb-430 msb-430h nucleo-f030 nucleo-f070 \ - nucleo-f072 nucleo-f334 nucleo32-f031 nucleo32-f303 \ - nucleo32-f042 stm32f0discovery telosb \ + chronos msb-430 msb-430h nucleo-f030 nucleo-l053 \ + nucleo-f070 nucleo-f072 nucleo-f334 nucleo32-f031 \ + nucleo32-f303 nucleo32-f042 stm32f0discovery telosb \ waspmote-pro weio wsn430-v1_3b wsn430-v1_4 z1 # Include packages that pull up and auto-init the link layer. diff --git a/examples/gcoap/Makefile b/examples/gcoap/Makefile index 82bb6759ac..eda838c387 100644 --- a/examples/gcoap/Makefile +++ b/examples/gcoap/Makefile @@ -11,7 +11,7 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := chronos msb-430 msb-430h nucleo-f030 nucleo-f334 \ stm32f0discovery telosb weio wsn430-v1_3b wsn430-v1_4 \ - z1 nucleo32-f042 nucleo32-f031 + z1 nucleo32-f042 nucleo32-f031 nucleo-l053 # Must read nordic_softdevice_ble package before nanocoap package. However, # can't read it explicitly here because it is read later, as a dependency for diff --git a/examples/gnrc_border_router/Makefile b/examples/gnrc_border_router/Makefile index e8f60a1e6f..891e52325a 100644 --- a/examples/gnrc_border_router/Makefile +++ b/examples/gnrc_border_router/Makefile @@ -13,7 +13,7 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon cc2650stk maple-mini msb-430 msb-430h 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 \ - nucleo-l073 + nucleo-l073 nucleo-l053 BOARD_BLACKLIST += mips-malta # No UART available. diff --git a/examples/gnrc_networking/Makefile b/examples/gnrc_networking/Makefile index a10d81ca29..2dff6fd10a 100644 --- a/examples/gnrc_networking/Makefile +++ b/examples/gnrc_networking/Makefile @@ -11,7 +11,7 @@ BOARD_INSUFFICIENT_MEMORY := chronos msb-430 msb-430h nucleo-f103 nucleo-f334 \ spark-core stm32f0discovery telosb weio \ wsn430-v1_3b wsn430-v1_4 z1 nucleo-f072 nucleo-f030 \ nucleo-f070 microbit calliope-mini nucleo32-f042 \ - nucleo32-f303 nucleo32-f031 + nucleo32-f303 nucleo32-f031 nucleo-l053 # Include packages that pull up and auto-init the link layer. # NOTE: 6LoWPAN will be included if IEEE802.15.4 devices are present diff --git a/examples/gnrc_tftp/Makefile b/examples/gnrc_tftp/Makefile index 65947927a5..33e7061ba9 100644 --- a/examples/gnrc_tftp/Makefile +++ b/examples/gnrc_tftp/Makefile @@ -12,7 +12,7 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon chronos msb-430 msb-430h nrf51dongle \ 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 nucleo32-f031 + nucleo32-f303 nucleo32-f031 nucleo-l053 # Include packages that pull up and auto-init the link layer. # NOTE: 6LoWPAN will be included if IEEE802.15.4 devices are present diff --git a/examples/microcoap_server/Makefile b/examples/microcoap_server/Makefile index 014b531f1a..71f3f08722 100644 --- a/examples/microcoap_server/Makefile +++ b/examples/microcoap_server/Makefile @@ -9,7 +9,7 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := chronos msb-430 msb-430h nucleo-f030 nucleo32-f042 \ pca10000 pca10005 stm32f0discovery telosb weio z1 \ - nucleo32-f031 + nucleo32-f031 nucleo-l053 # Include packages that pull up and auto-init the link layer. # NOTE: 6LoWPAN will be included if IEEE802.15.4 devices are present diff --git a/examples/nanocoap_server/Makefile b/examples/nanocoap_server/Makefile index 43fcb0a429..41716d359f 100644 --- a/examples/nanocoap_server/Makefile +++ b/examples/nanocoap_server/Makefile @@ -8,7 +8,7 @@ BOARD ?= native RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := chronos msb-430 msb-430h nucleo-f030 nucleo32-f042 \ - stm32f0discovery telosb weio nucleo32-f031 + stm32f0discovery telosb weio nucleo32-f031 nucleo-l053 # blacklist this until #6022 is sorted out BOARD_BLACKLIST := nrf52dk diff --git a/examples/posix_sockets/Makefile b/examples/posix_sockets/Makefile index 45911f2333..aa00586ab7 100644 --- a/examples/posix_sockets/Makefile +++ b/examples/posix_sockets/Makefile @@ -10,7 +10,8 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := airfy-beacon chronos msb-430 msb-430h nrf51dongle nrf6310 \ nucleo-f334 pca10000 pca10005 stm32f0discovery telosb weio \ wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 nucleo-f072 \ - nucleo-f030 nucleo-f070 nucleo32-f042 nucleo32-f031 + nucleo-f030 nucleo-f070 nucleo32-f042 nucleo32-f031 \ + nucleo-l053 # Include packages that pull up and auto-init the link layer. # NOTE: 6LoWPAN will be included if IEEE802.15.4 devices are present diff --git a/tests/conn_ip/Makefile b/tests/conn_ip/Makefile index 8c71d1d673..651e76ddff 100644 --- a/tests/conn_ip/Makefile +++ b/tests/conn_ip/Makefile @@ -5,7 +5,7 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := chronos msb-430 msb-430h nucleo-f334 stm32f0discovery telosb \ weio wsn430-v1_3b wsn430-v1_4 z1 nucleo-f030 nucleo-f070 \ - nucleo32-f042 nucleo32-f031 + nucleo32-f042 nucleo32-f031 nucleo-l053 USEMODULE += gnrc_netdev_default USEMODULE += auto_init_gnrc_netif diff --git a/tests/driver_enc28j60/Makefile b/tests/driver_enc28j60/Makefile index ae89bc8b3e..40497edc9b 100644 --- a/tests/driver_enc28j60/Makefile +++ b/tests/driver_enc28j60/Makefile @@ -4,7 +4,7 @@ include ../Makefile.tests_common FEATURES_REQUIRED = periph_spi periph_gpio BOARD_INSUFFICIENT_MEMORY := msb-430h nucleo-f334 stm32f0discovery telosb \ - weio z1 msb-430 + weio z1 msb-430 nucleo-l053 USEMODULE += gnrc_netdev2 USEMODULE += gnrc_netdev_default diff --git a/tests/driver_encx24j600/Makefile b/tests/driver_encx24j600/Makefile index df2eac0808..f2a4bdff77 100644 --- a/tests/driver_encx24j600/Makefile +++ b/tests/driver_encx24j600/Makefile @@ -3,7 +3,8 @@ include ../Makefile.tests_common FEATURES_REQUIRED = periph_spi periph_gpio -BOARD_INSUFFICIENT_MEMORY := msb-430 msb-430h stm32f0discovery telosb weio z1 +BOARD_INSUFFICIENT_MEMORY := msb-430 msb-430h stm32f0discovery telosb weio z1 \ + nucleo-l053 USEMODULE += gnrc_netdev2 USEMODULE += gnrc_netdev_default diff --git a/tests/driver_kw2xrf/Makefile b/tests/driver_kw2xrf/Makefile index 24683ad5a6..4f08e2afcc 100644 --- a/tests/driver_kw2xrf/Makefile +++ b/tests/driver_kw2xrf/Makefile @@ -3,7 +3,7 @@ include ../Makefile.tests_common FEATURES_REQUIRED = periph_spi periph_gpio -BOARD_INSUFFICIENT_MEMORY := stm32f0discovery nucleo-f334 weio +BOARD_INSUFFICIENT_MEMORY := stm32f0discovery nucleo-f334 weio nucleo-l053 USEMODULE += auto_init_gnrc_netif USEMODULE += gnrc_netdev_default diff --git a/tests/emb6/Makefile b/tests/emb6/Makefile index 52db4bc3b0..4090610927 100644 --- a/tests/emb6/Makefile +++ b/tests/emb6/Makefile @@ -8,7 +8,7 @@ FEATURES_REQUIRED = periph_gpio periph_spi # for at86rf231 RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := msb-430 msb-430h stm32f0discovery telosb weio z1 \ - wsn430-v1_3b wsn430-v1_4 + wsn430-v1_3b wsn430-v1_4 nucleo-l053 USEPKG += emb6 diff --git a/tests/gnrc_ipv6_ext/Makefile b/tests/gnrc_ipv6_ext/Makefile index ae2fe798c4..d77ec02b5e 100644 --- a/tests/gnrc_ipv6_ext/Makefile +++ b/tests/gnrc_ipv6_ext/Makefile @@ -9,7 +9,7 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon chronos maple-mini msb-430 maple-mini nrf51dongle nrf6310 nucleo-f103 nucleo-f334 pca10000 pca10005 \ spark-core stm32f0discovery telosb weio wsn430-v1_3b \ wsn430-v1_4 yunjia-nrf51822 z1 nucleo-f030 nucleo32-f042 \ - nucleo32-f031 + nucleo32-f031 nucleo-l053 # Include packages that pull up and auto-init the link layer. # NOTE: 6LoWPAN will be included if IEEE802.15.4 devices are present diff --git a/tests/gnrc_sixlowpan/Makefile b/tests/gnrc_sixlowpan/Makefile index 45335a7c63..143ea20f3b 100644 --- a/tests/gnrc_sixlowpan/Makefile +++ b/tests/gnrc_sixlowpan/Makefile @@ -9,7 +9,7 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon chronos maple-mini msb-430 msb-430h nr nrf6310 nucleo-f103 nucleo-f334 pca10000 pca10005 spark-core \ stm32f0discovery telosb weio wsn430-v1_3b wsn430-v1_4 \ yunjia-nrf51822 z1 nucleo-f030 nucleo-f070 nucleo32-f042 \ - nucleo32-f031 + nucleo32-f031 nucleo-l053 # Include packages that pull up and auto-init the link layer. # NOTE: 6LoWPAN will be included if IEEE802.15.4 devices are present diff --git a/tests/gnrc_tcp_client/Makefile b/tests/gnrc_tcp_client/Makefile index c329a50c67..73d5f056d5 100644 --- a/tests/gnrc_tcp_client/Makefile +++ b/tests/gnrc_tcp_client/Makefile @@ -16,7 +16,8 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560\ nucleo32-f042 nucleo-f070 nucleo-f072 nucleo32-f303\ nucleo-f334 pca10000 pca10005 stm32f0discovery\ telosb weio wsn430-v1_3b wsn430-v1_4\ - yunjia-nrf51822 z1 msb-430 msb-430h nucleo32-f031 + yunjia-nrf51822 z1 msb-430 msb-430h nucleo32-f031\ + nucleo-l053 # This has to be the absolute path to the RIOT base directory: RIOTBASE ?= $(CURDIR)/../.. diff --git a/tests/gnrc_tcp_server/Makefile b/tests/gnrc_tcp_server/Makefile index 422eda392c..5333fbe0cb 100644 --- a/tests/gnrc_tcp_server/Makefile +++ b/tests/gnrc_tcp_server/Makefile @@ -14,7 +14,8 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560\ nucleo32-f042 nucleo-f070 nucleo-f072 nucleo32-f303\ nucleo-f334 pca10000 pca10005 stm32f0discovery\ telosb weio wsn430-v1_3b wsn430-v1_4\ - yunjia-nrf51822 z1 msb-430 msb-430h nucleo32-f031 + yunjia-nrf51822 z1 msb-430 msb-430h nucleo32-f031\ + nucleo-l053 # This has to be the absolute path to the RIOT base directory: RIOTBASE ?= $(CURDIR)/../.. diff --git a/tests/lwip/Makefile b/tests/lwip/Makefile index 27ed477931..a6b2174532 100644 --- a/tests/lwip/Makefile +++ b/tests/lwip/Makefile @@ -10,7 +10,7 @@ BOARD_BLACKLIST := arduino-mega2560 msb-430h telosb waspmote-pro z1 arduino-uno BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-mega2560 msb-430h nrf6310 \ nucleo-f334 pca10005 stm32f0discovery telosb \ weio yunjia-nrf51822 z1 nucleo-f030 nucleo-f072 \ - nucleo32-f031 + nucleo32-f031 nucleo-l053 # including lwip_ipv6_mld would currently break this test on at86rf2xx radios USEMODULE += lwip lwip_ipv6_autoconfig lwip_conn_ip lwip_netdev2 diff --git a/tests/lwip_sock_ip/Makefile b/tests/lwip_sock_ip/Makefile index 0f9b80dfa6..71db7795a9 100644 --- a/tests/lwip_sock_ip/Makefile +++ b/tests/lwip_sock_ip/Makefile @@ -7,7 +7,7 @@ BOARD_BLACKLIST := arduino-uno arduino-duemilanove arduino-mega2560 chronos \ msb-430 msb-430h telosb waspmote-pro wsn430-v1_3b \ wsn430-v1_4 z1 BOARD_INSUFFICIENT_MEMORY = nucleo-f030 nucleo32-f042 nucleo-f334 \ - stm32f0discovery weio nucleo32-f031 + stm32f0discovery weio nucleo32-f031 nucleo-l053 LWIP_IPV4 ?= 0 diff --git a/tests/lwip_sock_tcp/Makefile b/tests/lwip_sock_tcp/Makefile index 56d77ea0a9..5f9adad5c1 100644 --- a/tests/lwip_sock_tcp/Makefile +++ b/tests/lwip_sock_tcp/Makefile @@ -8,7 +8,7 @@ BOARD_BLACKLIST := arduino-uno arduino-duemilanove arduino-mega2560 chronos \ msb-430 msb-430h telosb waspmote-pro wsn430-v1_3b \ wsn430-v1_4 z1 BOARD_INSUFFICIENT_MEMORY = nucleo-f030 nucleo32-f031 nucleo32-f042 nucleo-f334 \ - stm32f0discovery weio + nucleo-l053 stm32f0discovery weio LWIP_IPV4 ?= 0 diff --git a/tests/lwip_sock_udp/Makefile b/tests/lwip_sock_udp/Makefile index 2b6540c5d6..36437d335a 100644 --- a/tests/lwip_sock_udp/Makefile +++ b/tests/lwip_sock_udp/Makefile @@ -8,7 +8,7 @@ BOARD_BLACKLIST := arduino-uno arduino-duemilanove arduino-mega2560 chronos \ msb-430 msb-430h telosb waspmote-pro wsn430-v1_3b \ wsn430-v1_4 z1 BOARD_INSUFFICIENT_MEMORY = nucleo32-f042 nucleo-f030 nucleo32-f031 nucleo-f042 \ - nucleo-f334 stm32f0discovery weio + nucleo-f334 nucleo-l053 stm32f0discovery weio LWIP_IPV4 ?= 0 diff --git a/tests/mutex_order/Makefile b/tests/mutex_order/Makefile index 471d87a7c7..1d4146a981 100644 --- a/tests/mutex_order/Makefile +++ b/tests/mutex_order/Makefile @@ -1,6 +1,7 @@ APPLICATION = mutex_order include ../Makefile.tests_common -BOARD_INSUFFICIENT_MEMORY := stm32f0discovery weio nucleo-f030 nucleo32-f042 nucleo32-f031 +BOARD_INSUFFICIENT_MEMORY := stm32f0discovery weio nucleo-f030 nucleo32-f042 nucleo32-f031 \ + nucleo-l053 include $(RIOTBASE)/Makefile.include diff --git a/tests/nhdp/Makefile b/tests/nhdp/Makefile index b774a21d80..d53455014f 100644 --- a/tests/nhdp/Makefile +++ b/tests/nhdp/Makefile @@ -5,7 +5,7 @@ BOARD_BLACKLIST := arduino-mega2560 chronos msb-430 msb-430h telosb \ wsn430-v1_3b wsn430-v1_4 z1 waspmote-pro arduino-uno \ arduino-duemilanove BOARD_INSUFFICIENT_MEMORY := nucleo-f334 stm32f0discovery weio nucleo-f030 \ - nucleo32-f042 nucleo32-f031 + nucleo32-f042 nucleo32-f031 nucleo-l053 USEMODULE += gnrc_ipv6 USEMODULE += gnrc_sock_udp diff --git a/tests/pkg_libcoap/Makefile b/tests/pkg_libcoap/Makefile index 41e4fb5b32..03da7ca284 100644 --- a/tests/pkg_libcoap/Makefile +++ b/tests/pkg_libcoap/Makefile @@ -6,7 +6,7 @@ BOARD_BLACKLIST := arduino-mega2560 chronos msb-430 msb-430h telosb wsn430-v1_3b wsn430-v1_4 z1 waspmote-pro arduino-uno arduino-duemilanove BOARD_INSUFFICIENT_MEMORY := chronos msb-430 msb-430h nucleo-f334 nucleo-f030 \ stm32f0discovery telosb weio wsn430-v1_3b wsn430-v1_4 z1 \ - nucleo-f070 nucleo32-f042 nucleo32-f031 + nucleo-f070 nucleo32-f042 nucleo32-f031 nucleo-l053 USEMODULE += gnrc_ipv6 USEMODULE += gnrc_sock_udp diff --git a/tests/posix_semaphore/Makefile b/tests/posix_semaphore/Makefile index 7a2f162b62..48f187e251 100644 --- a/tests/posix_semaphore/Makefile +++ b/tests/posix_semaphore/Makefile @@ -3,7 +3,8 @@ include ../Makefile.tests_common BOARD_INSUFFICIENT_MEMORY := msb-430 msb-430h mbed_lpc1768 chronos stm32f0discovery \ pca10000 pca10005 weio yunjia-nrf51822 nrf6310 spark-core \ - nucleo-f334 nucleo-f030 nucleo32-f042 nucleo32-f031 + nucleo-f334 nucleo-f030 nucleo32-f042 nucleo32-f031 \ + nucleo-l053 USEMODULE += fmt USEMODULE += posix_semaphore diff --git a/tests/pthread_rwlock/Makefile b/tests/pthread_rwlock/Makefile index 0606aab0bc..8763ac7f5c 100644 --- a/tests/pthread_rwlock/Makefile +++ b/tests/pthread_rwlock/Makefile @@ -13,6 +13,6 @@ CFLAGS += -DNATIVE_AUTO_EXIT BOARD_INSUFFICIENT_MEMORY += chronos mbed_lpc1768 msb-430 msb-430h stm32f0discovery \ pca10000 pca10005 yunjia-nrf51822 spark-core nucleo-f334 \ airfy-beacon nrf51dongle nrf6310 weio nucleo-f030 \ - nucleo32-f042 nucleo32-f031 + nucleo32-f042 nucleo32-f031 nucleo-l053 include $(RIOTBASE)/Makefile.include diff --git a/tests/rmutex/Makefile b/tests/rmutex/Makefile index ae7e5af420..9c813d6be1 100644 --- a/tests/rmutex/Makefile +++ b/tests/rmutex/Makefile @@ -2,6 +2,6 @@ APPLICATION = rmutex include ../Makefile.tests_common BOARD_INSUFFICIENT_MEMORY := stm32f0discovery weio nucleo-f030 nucleo32-f031 \ - nucleo32-f042 + nucleo32-f042 nucleo-l053 include $(RIOTBASE)/Makefile.include diff --git a/tests/slip/Makefile b/tests/slip/Makefile index 883dca84f7..7b7681b39a 100644 --- a/tests/slip/Makefile +++ b/tests/slip/Makefile @@ -2,7 +2,7 @@ APPLICATION = driver_slip include ../Makefile.tests_common BOARD_INSUFFICIENT_MEMORY := msb-430 msb-430h nucleo-f334 stm32f0discovery weio \ - nucleo-f030 nucleo32-f042 nucleo32-f031 + nucleo-f030 nucleo32-f042 nucleo32-f031 nucleo-l053 BOARD_BLACKLIST += mips-malta diff --git a/tests/thread_cooperation/Makefile b/tests/thread_cooperation/Makefile index 2fef46b772..f330b62299 100644 --- a/tests/thread_cooperation/Makefile +++ b/tests/thread_cooperation/Makefile @@ -7,7 +7,7 @@ BOARD_INSUFFICIENT_MEMORY := cc2650stk chronos maple-mini msb-430 msb-430h \ nucleo-f334 nrf51dongle nrf6310 weio nucleo-f072 \ nucleo-f030 nucleo-f070 microbit calliope-mini \ nucleo32-f042 nucleo32-f303 opencm9-04 nucleo32-f031 \ - nucleo-l073 + nucleo-l073 nucleo-l053 DISABLE_MODULE += auto_init diff --git a/tests/unittests/Makefile b/tests/unittests/Makefile index c3ec9460be..1ea3ed412c 100644 --- a/tests/unittests/Makefile +++ b/tests/unittests/Makefile @@ -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 nucleo-l073 + nucleo32-f031 nucleo-l073 nucleo-l053 USEMODULE += embunit @@ -33,7 +33,8 @@ 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 nucleo-l073 + nucleo32-f303 opencm9-04 nucleo-f411 nucleo32-f031 nucleo-l073 \ + nucleo-l053 DISABLE_TEST_FOR_ARM_CORTEX_M := tests-relic