From bf45254a8d07b500ccdd81ef813d1d3f570d1f52 Mon Sep 17 00:00:00 2001 From: Alexandre Abadie Date: Fri, 24 Feb 2017 17:22:40 +0100 Subject: [PATCH 1/5] cpu/stm32l0: add support for stm32l031k6 --- cpu/stm32l0/include/cpu_conf.h | 3 + cpu/stm32l0/include/vendor/stm32l031xx.h | 6092 ++++++++++++++++++++++ cpu/stm32l0/ldscripts/stm32l031k6.ld | 30 + 3 files changed, 6125 insertions(+) create mode 100644 cpu/stm32l0/include/vendor/stm32l031xx.h create mode 100644 cpu/stm32l0/ldscripts/stm32l031k6.ld diff --git a/cpu/stm32l0/include/cpu_conf.h b/cpu/stm32l0/include/cpu_conf.h index ff70564d0a..afd7d4be1a 100644 --- a/cpu/stm32l0/include/cpu_conf.h +++ b/cpu/stm32l0/include/cpu_conf.h @@ -31,6 +31,9 @@ #ifdef CPU_MODEL_STM32L053R8 #include "vendor/stm32l053xx.h" #endif +#ifdef CPU_MODEL_STM32L031K6 +#include "vendor/stm32l031xx.h" +#endif #ifdef __cplusplus extern "C" { diff --git a/cpu/stm32l0/include/vendor/stm32l031xx.h b/cpu/stm32l0/include/vendor/stm32l031xx.h new file mode 100644 index 0000000000..06cbdf4233 --- /dev/null +++ b/cpu/stm32l0/include/vendor/stm32l031xx.h @@ -0,0 +1,6092 @@ +/** + ****************************************************************************** + * @file stm32l031xx.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 stm32l031xx 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 stm32l031xx + * @{ + */ + +#ifndef __STM32L031xx_H +#define __STM32L031xx_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 no 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 stm32l031xx 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_IRQn = 4, /*!< RCC Interrupt */ + 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 */ + 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 */ + TIM21_IRQn = 20, /*!< TIM21 Interrupt */ + TIM22_IRQn = 22, /*!< TIM22 Interrupt */ + I2C1_IRQn = 23, /*!< I2C1 Interrupt */ + SPI1_IRQn = 25, /*!< SPI1 Interrupt */ + USART2_IRQn = 28, /*!< USART2 Interrupt */ + LPUART1_IRQn = 29, /*!< LPUART1 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 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 = 32K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K + cpuid (r) : ORIGIN = 0x1ff80050, LENGTH = 12 +} + +_cpuid_address = ORIGIN(cpuid); + +INCLUDE cortexm_base.ld From fb7fe334b637bbbc142072f443fd1605bb5db6f5 Mon Sep 17 00:00:00 2001 From: Alexandre Abadie Date: Fri, 24 Feb 2017 17:22:59 +0100 Subject: [PATCH 2/5] boards/nucleo32-l031: initial support --- boards/nucleo32-l031/Makefile | 3 + boards/nucleo32-l031/Makefile.dep | 3 + boards/nucleo32-l031/Makefile.features | 12 ++ boards/nucleo32-l031/Makefile.include | 13 ++ boards/nucleo32-l031/board.c | 34 ++++ boards/nucleo32-l031/dist/openocd.cfg | 7 + boards/nucleo32-l031/include/board.h | 64 ++++++++ boards/nucleo32-l031/include/gpio_params.h | 48 ++++++ boards/nucleo32-l031/include/periph_conf.h | 179 +++++++++++++++++++++ 9 files changed, 363 insertions(+) create mode 100644 boards/nucleo32-l031/Makefile create mode 100644 boards/nucleo32-l031/Makefile.dep create mode 100644 boards/nucleo32-l031/Makefile.features create mode 100644 boards/nucleo32-l031/Makefile.include create mode 100644 boards/nucleo32-l031/board.c create mode 100644 boards/nucleo32-l031/dist/openocd.cfg create mode 100644 boards/nucleo32-l031/include/board.h create mode 100644 boards/nucleo32-l031/include/gpio_params.h create mode 100644 boards/nucleo32-l031/include/periph_conf.h diff --git a/boards/nucleo32-l031/Makefile b/boards/nucleo32-l031/Makefile new file mode 100644 index 0000000000..f8fcbb53a0 --- /dev/null +++ b/boards/nucleo32-l031/Makefile @@ -0,0 +1,3 @@ +MODULE = board + +include $(RIOTBASE)/Makefile.base diff --git a/boards/nucleo32-l031/Makefile.dep b/boards/nucleo32-l031/Makefile.dep new file mode 100644 index 0000000000..5472bf8b8d --- /dev/null +++ b/boards/nucleo32-l031/Makefile.dep @@ -0,0 +1,3 @@ +ifneq (,$(filter saul_default,$(USEMODULE))) + USEMODULE += saul_gpio +endif diff --git a/boards/nucleo32-l031/Makefile.features b/boards/nucleo32-l031/Makefile.features new file mode 100644 index 0000000000..15648797fe --- /dev/null +++ b/boards/nucleo32-l031/Makefile.features @@ -0,0 +1,12 @@ +# Put defined MCU peripherals here (in alphabetical order) +FEATURES_PROVIDED += periph_cpuid +FEATURES_PROVIDED += periph_gpio +FEATURES_PROVIDED += periph_pwm +FEATURES_PROVIDED += periph_timer +FEATURES_PROVIDED += periph_uart + +# Various common features of Nucleo boards +FEATURES_PROVIDED += cpp + +# The board MPU family (used for grouping by the CI system) +FEATURES_MCU_GROUP = cortex_m0_1 diff --git a/boards/nucleo32-l031/Makefile.include b/boards/nucleo32-l031/Makefile.include new file mode 100644 index 0000000000..ac09741b51 --- /dev/null +++ b/boards/nucleo32-l031/Makefile.include @@ -0,0 +1,13 @@ +## the cpu to build for +export CPU = stm32l0 +export CPU_MODEL = stm32l031k6 + +# define the default port depending on the host OS +PORT_LINUX ?= /dev/ttyACM0 +PORT_DARWIN ?= $(firstword $(sort $(wildcard /dev/tty.usbmodem*))) + +# setup serial terminal +include $(RIOTBOARD)/Makefile.include.serial + +# this board uses openocd +include $(RIOTBOARD)/Makefile.include.openocd diff --git a/boards/nucleo32-l031/board.c b/boards/nucleo32-l031/board.c new file mode 100644 index 0000000000..bd93b1dced --- /dev/null +++ b/boards/nucleo32-l031/board.c @@ -0,0 +1,34 @@ +/* + * 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_nucleo32-l031 + * @{ + * + * @file + * @brief Board specific implementations for the nucleo32-l031 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/nucleo32-l031/dist/openocd.cfg b/boards/nucleo32-l031/dist/openocd.cfg new file mode 100644 index 0000000000..b4c7706757 --- /dev/null +++ b/boards/nucleo32-l031/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/nucleo32-l031/include/board.h b/boards/nucleo32-l031/include/board.h new file mode 100644 index 0000000000..f520bc1c22 --- /dev/null +++ b/boards/nucleo32-l031/include/board.h @@ -0,0 +1,64 @@ +/* + * 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_nucleo32-l031 Nucleo32-L031 + * @ingroup boards + * @brief Board specific files for the nucleo32-l031 board + * @{ + * + * @file + * @brief Board specific definitions for the nucleo32-l031 board + * + * @author Hauke Petersen + * @author Alexandre Aabdie + */ + +#ifndef BOARD_H +#define BOARD_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @name xtimer configuration + * @{ + */ +#define XTIMER_DEV TIMER_DEV(0) +#define XTIMER_CHAN (0) +#define XTIMER_WIDTH (16) +/** @} */ + +/** + * @name Macros for controlling the on-board LED. + * @{ + */ +#define LED0_PIN GPIO_PIN(PORT_B, 3) + +#define LED0_MASK (1 << 3) + +#define LED0_ON (GPIOB->BSRR = LED0_MASK) +#define LED0_OFF (GPIOB->BRR = LED0_MASK) +#define LED0_TOGGLE (GPIOB->ODR ^= LED0_MASK) +/** @} */ + +/** + * @brief Initialize board specific hardware, including clock, LEDs and std-IO + */ +void board_init(void); + +#ifdef __cplusplus +} +#endif + +#endif /* BOARD_H */ +/** @} */ diff --git a/boards/nucleo32-l031/include/gpio_params.h b/boards/nucleo32-l031/include/gpio_params.h new file mode 100644 index 0000000000..89d7278dd5 --- /dev/null +++ b/boards/nucleo32-l031/include/gpio_params.h @@ -0,0 +1,48 @@ +/* + * Copyright (C) 2017 Inria + * 2017 OTA keys + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @ingroup boards_nucleo32-l031 + * @{ + * + * @file + * @brief Board specific configuration of direct mapped GPIOs + * + * @author Alexandre Abadie + * @author Vincent Dupont + */ + +#ifndef GPIO_PARAMS_H +#define GPIO_PARAMS_H + +#include "board.h" +#include "saul/periph.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief GPIO pin configuration + */ +static const saul_gpio_params_t saul_gpio_params[] = +{ + { + .name = "LED(green)", + .pin = LED0_PIN, + .mode = GPIO_OUT + }, +}; + +#ifdef __cplusplus +} +#endif + +#endif /* GPIO_PARAMS_H */ +/** @} */ diff --git a/boards/nucleo32-l031/include/periph_conf.h b/boards/nucleo32-l031/include/periph_conf.h new file mode 100644 index 0000000000..7ad178181d --- /dev/null +++ b/boards/nucleo32-l031/include/periph_conf.h @@ -0,0 +1,179 @@ +/* + * 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_nucleo32-l031 + * @{ + * + * @file + * @brief Peripheral MCU configuration for the nucleo32-l031 board + * + * @author Hauke Petersen + * @author Alexandre Aabdie + */ + +#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, 15), + .tx_pin = GPIO_PIN(PORT_A, 2), + .rx_af = GPIO_AF4, + .tx_af = GPIO_AF4, + .bus = APB1, + .irqn = USART2_IRQn + } +}; + +#define UART_0_ISR (isr_usart2) + +#define UART_NUMOF (sizeof(uart_config) / sizeof(uart_config[0])) +/** @} */ + +/** + * @brief PWM configuration + * @{ + */ +static const pwm_conf_t pwm_config[] = { + { + .dev = TIM21, + .rcc_mask = RCC_APB2ENR_TIM21EN, + .chan = { { .pin = GPIO_PIN(PORT_B, 6) /* D5 */, .cc_chan = 0 }, + { .pin = GPIO_UNDEF, .cc_chan = 0 }, + { .pin = GPIO_UNDEF, .cc_chan = 0 }, + { .pin = GPIO_UNDEF, .cc_chan = 0 } }, + .af = GPIO_AF5, + .bus = APB2 + } +}; + +#define PWM_NUMOF (sizeof(pwm_config) / sizeof(pwm_config[0])) +/** @} */ + +/** + * @name SPI configuration + * @{ + */ +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_B, 5), + .miso_pin = GPIO_PIN(PORT_B, 4), + .sclk_pin = GPIO_PIN(PORT_B, 3), + .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 */ +/** @} */ From cc5034d67e1da2177efaa99cd0bb046bab2e2e62 Mon Sep 17 00:00:00 2001 From: Alexandre Abadie Date: Wed, 1 Mar 2017 09:13:43 +0100 Subject: [PATCH 3/5] examples: remove nucleo32-l031 from memory intensive examples --- examples/dtls-echo/Makefile | 4 ++-- examples/emcute/Makefile | 6 +++--- examples/gcoap/Makefile | 4 ++-- examples/gnrc_border_router/Makefile | 4 ++-- examples/gnrc_networking/Makefile | 4 ++-- examples/gnrc_tftp/Makefile | 4 ++-- examples/microcoap_server/Makefile | 2 +- examples/nanocoap_server/Makefile | 3 ++- examples/posix_sockets/Makefile | 8 ++++---- 9 files changed, 20 insertions(+), 19 deletions(-) diff --git a/examples/dtls-echo/Makefile b/examples/dtls-echo/Makefile index bb36b44e14..db3cd4268f 100644 --- a/examples/dtls-echo/Makefile +++ b/examples/dtls-echo/Makefile @@ -17,8 +17,8 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon calliope-mini cc2650stk maple-mini \ microbit nrf51dongle nrf6310 nucleo32-f031 \ nucleo32-f042 nucleo32-f303 nucleo-f030 nucleo-f070 \ nucleo-f072 nucleo-f103 nucleo-f334 nucleo-l053 \ - nucleo-l073 opencm904 pca10000 pca10005 spark-core \ - stm32f0discovery weio yunjia-nrf51822 + nucleo-l073 nucleo32-l031 opencm904 pca10000 pca10005 \ + spark-core stm32f0discovery weio yunjia-nrf51822 # 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 dd9090a725..a2ab0a5ccc 100644 --- a/examples/emcute/Makefile +++ b/examples/emcute/Makefile @@ -9,9 +9,9 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-uno \ chronos msb-430 msb-430h nucleo32-f031 nucleo32-f042 \ - nucleo32-f303 nucleo-f030 nucleo-f070 nucleo-f072 \ - nucleo-f334 nucleo-l053 stm32f0discovery telosb \ - waspmote-pro weio wsn430-v1_3b wsn430-v1_4 z1 + nucleo32-f303 nucleo32-l031 nucleo-f030 nucleo-f070 \ + nucleo-f072 nucleo-f334 nucleo-l053 stm32f0discovery \ + telosb waspmote-pro weio wsn430-v1_3b wsn430-v1_4 z1 # 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/gcoap/Makefile b/examples/gcoap/Makefile index 5cbb925ecb..1ccbb18908 100644 --- a/examples/gcoap/Makefile +++ b/examples/gcoap/Makefile @@ -10,8 +10,8 @@ BOARD ?= native RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := chronos msb-430 msb-430h nucleo32-f031 nucleo32-f042 \ - nucleo-f030 nucleo-f334 nucleo-l053 stm32f0discovery \ - telosb weio wsn430-v1_3b wsn430-v1_4 z1 + nucleo32-l031 nucleo-f030 nucleo-f334 nucleo-l053 \ + stm32f0discovery telosb weio wsn430-v1_3b wsn430-v1_4 z1 # 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 cde3e5c56c..060175adcb 100644 --- a/examples/gnrc_border_router/Makefile +++ b/examples/gnrc_border_router/Makefile @@ -9,8 +9,8 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := airfy-beacon calliope-mini cc2650stk maple-mini \ microbit msb-430 msb-430h nrf51dongle nrf6310 \ - nucleo32-f031 nucleo32-f042 nucleo32-f303 nucleo-f030 \ - nucleo-f070 nucleo-f072 nucleo-f103 nucleo-f334 \ + nucleo32-f031 nucleo32-f042 nucleo32-f303 nucleo32-l031 \ + nucleo-f030 nucleo-f070 nucleo-f072 nucleo-f103 nucleo-f334 \ nucleo-l053 nucleo-l073 opencm904 pca10000 pca10005 \ spark-core stm32f0discovery telosb weio wsn430-v1_3b \ wsn430-v1_4 yunjia-nrf51822 z1 diff --git a/examples/gnrc_networking/Makefile b/examples/gnrc_networking/Makefile index 823188642b..9c2b85e453 100644 --- a/examples/gnrc_networking/Makefile +++ b/examples/gnrc_networking/Makefile @@ -8,8 +8,8 @@ BOARD ?= native RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := calliope-mini chronos microbit msb-430 msb-430h \ - nucleo32-f031 nucleo32-f042 nucleo32-f303 nucleo-f030 \ - nucleo-f070 nucleo-f072 nucleo-f103 nucleo-f334 \ + nucleo32-f031 nucleo32-f042 nucleo32-f303 nucleo32-l031 \ + nucleo-f030 nucleo-f070 nucleo-f072 nucleo-f103 nucleo-f334 \ nucleo-l053 spark-core stm32f0discovery telosb weio \ wsn430-v1_3b wsn430-v1_4 z1 diff --git a/examples/gnrc_tftp/Makefile b/examples/gnrc_tftp/Makefile index e624b94916..4003de289a 100644 --- a/examples/gnrc_tftp/Makefile +++ b/examples/gnrc_tftp/Makefile @@ -9,8 +9,8 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := airfy-beacon calliope-mini chronos microbit msb-430 \ msb-430h nrf51dongle nrf6310 nucleo32-f031 \ - nucleo32-f042 nucleo32-f303 nucleo-f030 nucleo-f070 \ - nucleo-f072 nucleo-f103 nucleo-f334 nucleo-l053 \ + nucleo32-f042 nucleo32-f303 nucleo32-l031 nucleo-f030 \ + nucleo-f070 nucleo-f072 nucleo-f103 nucleo-f334 nucleo-l053 \ pca10000 pca10005 spark-core stm32f0discovery telosb \ weio wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 diff --git a/examples/microcoap_server/Makefile b/examples/microcoap_server/Makefile index 7164f612ea..bfe6946c01 100644 --- a/examples/microcoap_server/Makefile +++ b/examples/microcoap_server/Makefile @@ -8,7 +8,7 @@ BOARD ?= native RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := chronos msb-430 msb-430h nucleo32-f031 nucleo32-f042 \ - nucleo-f030 nucleo-l053 pca10000 pca10005 \ + nucleo32-l031 nucleo-f030 nucleo-l053 pca10000 pca10005 \ stm32f0discovery telosb weio z1 # Include packages that pull up and auto-init the link layer. diff --git a/examples/nanocoap_server/Makefile b/examples/nanocoap_server/Makefile index 4e5911869b..d3d6114613 100644 --- a/examples/nanocoap_server/Makefile +++ b/examples/nanocoap_server/Makefile @@ -8,7 +8,8 @@ BOARD ?= native RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := chronos msb-430 msb-430h nucleo32-f031 nucleo32-f042 \ - nucleo-f030 nucleo-l053 stm32f0discovery telosb weio + nucleo32-l031 nucleo-f030 nucleo-l053 stm32f0discovery \ + telosb weio # blacklist this until #6022 is sorted out BOARD_BLACKLIST := nrf52dk diff --git a/examples/posix_sockets/Makefile b/examples/posix_sockets/Makefile index d9e855ce84..877c3ee83e 100644 --- a/examples/posix_sockets/Makefile +++ b/examples/posix_sockets/Makefile @@ -8,10 +8,10 @@ BOARD ?= native RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := airfy-beacon chronos msb-430 msb-430h nrf51dongle \ - nrf6310 nucleo32-f031 nucleo32-f042 nucleo-f030 \ - nucleo-f070 nucleo-f072 nucleo-f334 nucleo-l053 \ - pca10000 pca10005 stm32f0discovery telosb weio \ - wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 + nrf6310 nucleo32-f031 nucleo32-f042 nucleo32-l031 \ + nucleo-f030 nucleo-f070 nucleo-f072 nucleo-f334 \ + nucleo-l053 pca10000 pca10005 stm32f0discovery telosb \ + weio wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 # Include packages that pull up and auto-init the link layer. # NOTE: 6LoWPAN will be included if IEEE802.15.4 devices are present From a0e45d1390139598a53a82a8f3ec96cc8f28b91f Mon Sep 17 00:00:00 2001 From: Alexandre Abadie Date: Wed, 1 Mar 2017 09:14:08 +0100 Subject: [PATCH 4/5] tests/unittest: remove nucleo32-l031 from unittest --- tests/unittests/Makefile | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/tests/unittests/Makefile b/tests/unittests/Makefile index d079099021..6119fe7835 100644 --- a/tests/unittests/Makefile +++ b/tests/unittests/Makefile @@ -5,8 +5,8 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560 \ arduino-uno arduino-zero calliope-mini cc2650stk \ chronos ek-lm4f120xl limifrog-v1 maple-mini microbit \ msb-430 msb-430h nrf51dongle nrf6310 nucleo32-f031 \ - nucleo32-f042 nucleo32-f303 nucleo-f030 nucleo-f070 \ - nucleo-f072 nucleo-f091 nucleo-f103 nucleo-f334 \ + nucleo32-f042 nucleo32-f303 nucleo32-l031 nucleo-f030 \ + nucleo-f070 nucleo-f072 nucleo-f091 nucleo-f103 nucleo-f334 \ nucleo-f410 nucleo-l053 nucleo-l073 opencm904 \ pba-d-01-kw2x pca10000 pca10005 remote-pa remote-reva \ remote-revb saml21-xpro samr21-xpro seeeduino_arch-pro \ @@ -27,7 +27,7 @@ DISABLE_TEST_FOR_ARM7 := tests-relic ARM_CORTEX_M_BOARDS := airfy-beacon arduino-due arduino-zero cc2538dk ek-lm4f120xl \ f4vi1 fox frdm-k64f iotlab-m3 limifrog-v1 mbed_lpc1768 msbiot \ - mulle nrf51dongle nrf6310 nucleo32-f031 nucleo32-f303 \ + mulle nrf51dongle nrf6310 nucleo32-f031 nucleo32-f303 nucleo32-l031 \ nucleo-f030 nucleo-f070 nucleo-f091 nucleo-f303 nucleo-f334 \ nucleo-f401 nucleo-f410 nucleo-f411 nucleo-l053 nucleo-l073 \ nucleo-l1 opencm904 openmote-cc2538 pba-d-01-kw2x pca10000 \ From b0128f9dd12febca2e024f16b877e7209f49773b Mon Sep 17 00:00:00 2001 From: Alexandre Abadie Date: Wed, 1 Mar 2017 11:36:05 +0100 Subject: [PATCH 5/5] tests: remove nucleo32-l031 from memory intensive tests --- tests/conn_ip/Makefile | 2 +- tests/gnrc_ipv6_ext/Makefile | 2 +- tests/gnrc_sixlowpan/Makefile | 4 ++-- tests/gnrc_tcp_client/Makefile | 6 +++--- tests/gnrc_tcp_server/Makefile | 6 +++--- tests/libfixmath_unittests/Makefile | 2 +- tests/lwip_sock_ip/Makefile | 4 ++-- tests/lwip_sock_tcp/Makefile | 4 ++-- tests/lwip_sock_udp/Makefile | 2 +- tests/mutex_order/Makefile | 4 ++-- tests/nhdp/Makefile | 4 ++-- tests/pkg_libcoap/Makefile | 2 +- tests/posix_semaphore/Makefile | 4 ++-- tests/pthread_rwlock/Makefile | 2 +- tests/rmutex/Makefile | 4 ++-- tests/slip/Makefile | 4 ++-- tests/thread_cooperation/Makefile | 6 +++--- 17 files changed, 31 insertions(+), 31 deletions(-) diff --git a/tests/conn_ip/Makefile b/tests/conn_ip/Makefile index 4e13f7abc5..5a59e80b25 100644 --- a/tests/conn_ip/Makefile +++ b/tests/conn_ip/Makefile @@ -4,7 +4,7 @@ include ../Makefile.tests_common RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := chronos msb-430 msb-430h nucleo32-f031 nucleo32-f042 \ - nucleo-f030 nucleo-f070 nucleo-f334 nucleo-l053 \ + nucleo32-l031 nucleo-f030 nucleo-f070 nucleo-f334 nucleo-l053 \ stm32f0discovery telosb weio wsn430-v1_3b wsn430-v1_4 \ z1 diff --git a/tests/gnrc_ipv6_ext/Makefile b/tests/gnrc_ipv6_ext/Makefile index 674dc60aef..1bdbf9a6cb 100644 --- a/tests/gnrc_ipv6_ext/Makefile +++ b/tests/gnrc_ipv6_ext/Makefile @@ -7,7 +7,7 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := airfy-beacon chronos maple-mini msb-430 msb-430h \ nrf51dongle nrf6310 nucleo32-f031 nucleo32-f042 \ - nucleo-f030 nucleo-f103 nucleo-f334 nucleo-l053 \ + nucleo32-l031 nucleo-f030 nucleo-f103 nucleo-f334 nucleo-l053 \ pca10000 pca10005 spark-core stm32f0discovery telosb \ weio wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 diff --git a/tests/gnrc_sixlowpan/Makefile b/tests/gnrc_sixlowpan/Makefile index 644ef12c91..11db6c36d8 100644 --- a/tests/gnrc_sixlowpan/Makefile +++ b/tests/gnrc_sixlowpan/Makefile @@ -7,8 +7,8 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := airfy-beacon chronos maple-mini msb-430 msb-430h \ nrf51dongle nrf6310 nucleo32-f031 nucleo32-f042 \ - nucleo-f030 nucleo-f070 nucleo-f103 nucleo-f334 \ - nucleo-l053 pca10000 pca10005 spark-core \ + nucleo32-l031 nucleo-f030 nucleo-f070 nucleo-f103 \ + nucleo-f334 nucleo-l053 pca10000 pca10005 spark-core \ stm32f0discovery telosb weio wsn430-v1_3b wsn430-v1_4 \ yunjia-nrf51822 z1 diff --git a/tests/gnrc_tcp_client/Makefile b/tests/gnrc_tcp_client/Makefile index 6003e2f05f..cf47660442 100644 --- a/tests/gnrc_tcp_client/Makefile +++ b/tests/gnrc_tcp_client/Makefile @@ -13,9 +13,9 @@ TCP_TEST_CYCLES ?= 10 BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560 \ arduino-uno calliope-mini chronos microbit msb-430 \ msb-430h nrf51dongle nrf6310 nucleo32-f031 \ - nucleo32-f042 nucleo32-f303 nucleo-f030 nucleo-f070 \ - nucleo-f072 nucleo-f334 nucleo-l053 pca10000 pca10005 \ - sb-430 sb-430h stm32f0discovery telosb weio \ + nucleo32-f042 nucleo32-f303 nucleo32-l031 nucleo-f030 \ + nucleo-f070 nucleo-f072 nucleo-f334 nucleo-l053 pca10000 \ + pca10005 sb-430 sb-430h stm32f0discovery telosb weio \ wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 # This has to be the absolute path to the RIOT base directory: diff --git a/tests/gnrc_tcp_server/Makefile b/tests/gnrc_tcp_server/Makefile index 3a38bd68b2..b7c893c97c 100644 --- a/tests/gnrc_tcp_server/Makefile +++ b/tests/gnrc_tcp_server/Makefile @@ -11,9 +11,9 @@ TCP_LOCAL_PORT ?= 80 BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560 \ arduino-uno calliope-mini chronos microbit msb-430 \ msb-430h nrf51dongle nrf6310 nucleo32-f031 \ - nucleo32-f042 nucleo32-f303 nucleo-f030 nucleo-f070 \ - nucleo-f072 nucleo-f334 nucleo-l053 pca10000 pca10005 \ - sb-430 sb-430h stm32f0discovery telosb weio \ + nucleo32-f042 nucleo32-f303 nucleo32-l031 nucleo-f030 \ + nucleo-f070 nucleo-f072 nucleo-f334 nucleo-l053 pca10000 \ + pca10005 sb-430 sb-430h stm32f0discovery telosb weio \ wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 # This has to be the absolute path to the RIOT base directory: diff --git a/tests/libfixmath_unittests/Makefile b/tests/libfixmath_unittests/Makefile index 7edfd4162f..8dfec84226 100644 --- a/tests/libfixmath_unittests/Makefile +++ b/tests/libfixmath_unittests/Makefile @@ -8,7 +8,7 @@ BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove # The MSP boards don't feature round(), exp(), and log(), which are used in the unittests BOARD_BLACKLIST += chronos msb-430 msb-430h telosb wsn430-v1_3b wsn430-v1_4 z1 -BOARD_INSUFFICIENT_MEMORY := nucleo32-f031 nucleo32-f042 weio +BOARD_INSUFFICIENT_MEMORY := nucleo32-f031 nucleo32-f042 nucleo32-l031 weio USEMODULE += libfixmath-unittests diff --git a/tests/lwip_sock_ip/Makefile b/tests/lwip_sock_ip/Makefile index 0ec1c6200b..6bb777f0cd 100644 --- a/tests/lwip_sock_ip/Makefile +++ b/tests/lwip_sock_ip/Makefile @@ -6,8 +6,8 @@ include ../Makefile.tests_common 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-f031 nucleo32-f042 nucleo-f030 nucleo-f334 \ - nucleo-l053 stm32f0discovery weio +BOARD_INSUFFICIENT_MEMORY = nucleo32-f031 nucleo32-f042 nucleo32-l031 nucleo-f030 \ + nucleo-f334 nucleo-l053 stm32f0discovery weio LWIP_IPV4 ?= 0 diff --git a/tests/lwip_sock_tcp/Makefile b/tests/lwip_sock_tcp/Makefile index d7e57cfcf8..20a5e691c6 100644 --- a/tests/lwip_sock_tcp/Makefile +++ b/tests/lwip_sock_tcp/Makefile @@ -7,8 +7,8 @@ include ../Makefile.tests_common 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-f031 nucleo32-f042 nucleo-f030 nucleo-f334 \ - nucleo-l053 stm32f0discovery weio +BOARD_INSUFFICIENT_MEMORY = nucleo32-f031 nucleo32-f042 nucleo32-l031 nucleo-f030 \ + nucleo-f334 nucleo-l053 stm32f0discovery weio LWIP_IPV4 ?= 0 diff --git a/tests/lwip_sock_udp/Makefile b/tests/lwip_sock_udp/Makefile index cc5ae2bb26..28d898944a 100644 --- a/tests/lwip_sock_udp/Makefile +++ b/tests/lwip_sock_udp/Makefile @@ -7,7 +7,7 @@ include ../Makefile.tests_common 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-f031 nucleo32-f042 nucleo-f030 nucleo-f042 \ +BOARD_INSUFFICIENT_MEMORY = nucleo32-f031 nucleo32-f042 nucleo32-l031 nucleo-f030 \ nucleo-f334 nucleo-l053 stm32f0discovery weio LWIP_IPV4 ?= 0 diff --git a/tests/mutex_order/Makefile b/tests/mutex_order/Makefile index 8f14282b41..12c8b1c9ad 100644 --- a/tests/mutex_order/Makefile +++ b/tests/mutex_order/Makefile @@ -1,8 +1,8 @@ APPLICATION = mutex_order include ../Makefile.tests_common -BOARD_INSUFFICIENT_MEMORY := nucleo32-f031 nucleo32-f042 nucleo-f030 nucleo-l053 \ - stm32f0discovery weio +BOARD_INSUFFICIENT_MEMORY := nucleo32-f031 nucleo32-f042 nucleo32-l031 nucleo-f030 \ + nucleo-l053 stm32f0discovery weio include $(RIOTBASE)/Makefile.include diff --git a/tests/nhdp/Makefile b/tests/nhdp/Makefile index 74684f6a51..db0f490259 100644 --- a/tests/nhdp/Makefile +++ b/tests/nhdp/Makefile @@ -4,8 +4,8 @@ include ../Makefile.tests_common 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 := nucleo32-f031 nucleo32-f042 nucleo-f030 nucleo-f334 \ - nucleo-l053 stm32f0discovery weio +BOARD_INSUFFICIENT_MEMORY := nucleo32-f031 nucleo32-f042 nucleo32-l031 nucleo-f030 \ + nucleo-f334 nucleo-l053 stm32f0discovery weio USEMODULE += gnrc_ipv6 USEMODULE += gnrc_sock_udp diff --git a/tests/pkg_libcoap/Makefile b/tests/pkg_libcoap/Makefile index acec4239a2..ddf90b27b1 100644 --- a/tests/pkg_libcoap/Makefile +++ b/tests/pkg_libcoap/Makefile @@ -5,7 +5,7 @@ include ../Makefile.tests_common 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 nucleo32-f031 nucleo32-f042 \ - nucleo-f030 nucleo-f070 nucleo-f334 nucleo-l053 \ + nucleo32-l031 nucleo-f030 nucleo-f070 nucleo-f334 nucleo-l053 \ stm32f0discovery telosb weio wsn430-v1_3b wsn430-v1_4 \ z1 diff --git a/tests/posix_semaphore/Makefile b/tests/posix_semaphore/Makefile index 1120d649d1..2a42f2ea0c 100644 --- a/tests/posix_semaphore/Makefile +++ b/tests/posix_semaphore/Makefile @@ -2,8 +2,8 @@ APPLICATION = posix_semaphore include ../Makefile.tests_common BOARD_INSUFFICIENT_MEMORY := chronos mbed_lpc1768 msb-430 msb-430h nrf6310 \ - nucleo32-f031 nucleo32-f042 nucleo-f030 nucleo-f334 \ - nucleo-l053 pca10000 pca10005 spark-core \ + nucleo32-f031 nucleo32-f042 nucleo32-l031 nucleo-f030 \ + nucleo-f334 nucleo-l053 pca10000 pca10005 spark-core \ stm32f0discovery weio yunjia-nrf51822 USEMODULE += fmt diff --git a/tests/pthread_rwlock/Makefile b/tests/pthread_rwlock/Makefile index 83ffb7db20..7c12698181 100644 --- a/tests/pthread_rwlock/Makefile +++ b/tests/pthread_rwlock/Makefile @@ -11,7 +11,7 @@ USEMODULE += random CFLAGS += -DNATIVE_AUTO_EXIT BOARD_INSUFFICIENT_MEMORY += airfy-beacon chronos mbed_lpc1768 msb-430 msb-430h \ - nrf51dongle nrf6310 nucleo32-f031 nucleo32-f042 \ + nrf51dongle nrf6310 nucleo32-f031 nucleo32-f042 nucleo32-l031 \ nucleo-f030 nucleo-f334 nucleo-l053 pca10000 pca10005 \ spark-core stm32f0discovery weio yunjia-nrf51822 diff --git a/tests/rmutex/Makefile b/tests/rmutex/Makefile index 90224f0696..1297308887 100644 --- a/tests/rmutex/Makefile +++ b/tests/rmutex/Makefile @@ -1,8 +1,8 @@ APPLICATION = rmutex include ../Makefile.tests_common -BOARD_INSUFFICIENT_MEMORY := nucleo32-f031 nucleo32-f042 nucleo-f030 nucleo-l053 \ - stm32f0discovery weio +BOARD_INSUFFICIENT_MEMORY := nucleo32-f031 nucleo32-f042 nucleo32-l031 nucleo-f030 \ + nucleo-l053 stm32f0discovery weio include $(RIOTBASE)/Makefile.include diff --git a/tests/slip/Makefile b/tests/slip/Makefile index 8f59c6d5a2..0ab7936cc1 100644 --- a/tests/slip/Makefile +++ b/tests/slip/Makefile @@ -2,8 +2,8 @@ APPLICATION = driver_slip include ../Makefile.tests_common BOARD_INSUFFICIENT_MEMORY := msb-430 msb-430h nucleo32-f031 nucleo32-f042 \ - nucleo-f030 nucleo-f334 nucleo-l053 stm32f0discovery \ - weio + nucleo32-l031 nucleo-f030 nucleo-f334 nucleo-l053 \ + stm32f0discovery weio BOARD_BLACKLIST += mips-malta diff --git a/tests/thread_cooperation/Makefile b/tests/thread_cooperation/Makefile index 1920dcd112..ec8944ddb0 100644 --- a/tests/thread_cooperation/Makefile +++ b/tests/thread_cooperation/Makefile @@ -4,9 +4,9 @@ include ../Makefile.tests_common BOARD_INSUFFICIENT_MEMORY := airfy-beacon calliope-mini cc2650stk chronos maple-mini \ mbed_lpc1768 microbit msb-430 msb-430h nrf51dongle \ nrf6310 nucleo32-f031 nucleo32-f042 nucleo32-f303 \ - nucleo-f030 nucleo-f070 nucleo-f072 nucleo-f103 \ - nucleo-f334 nucleo-l053 nucleo-l073 opencm904 pca10000 \ - pca10005 spark-core stm32f0discovery weio \ + nucleo32-l031 nucleo-f030 nucleo-f070 nucleo-f072 \ + nucleo-f103 nucleo-f334 nucleo-l053 nucleo-l073 opencm904 \ + pca10000 pca10005 spark-core stm32f0discovery weio \ yunjia-nrf51822 DISABLE_MODULE += auto_init