From 177ef5bfa9f82aee1be9475ab592f3cd44b603b3 Mon Sep 17 00:00:00 2001 From: Leandro Lanzieri Date: Tue, 18 Sep 2018 18:07:07 +0200 Subject: [PATCH] boards/lobaro-lorabox: Add initial support for Lobaro Lorabox board --- boards/lobaro-lorabox/Makefile | 3 + boards/lobaro-lorabox/Makefile.dep | 3 + boards/lobaro-lorabox/Makefile.features | 9 + boards/lobaro-lorabox/Makefile.include | 26 +++ boards/lobaro-lorabox/board.c | 29 +++ boards/lobaro-lorabox/doc.txt | 91 ++++++++ boards/lobaro-lorabox/include/board.h | 92 ++++++++ boards/lobaro-lorabox/include/gpio_params.h | 48 ++++ boards/lobaro-lorabox/include/periph_conf.h | 232 ++++++++++++++++++++ examples/javascript/Makefile | 15 +- examples/lua_REPL/Makefile | 6 +- examples/lua_basic/Makefile | 12 +- tests/unittests/Makefile | 1 + 13 files changed, 551 insertions(+), 16 deletions(-) create mode 100644 boards/lobaro-lorabox/Makefile create mode 100644 boards/lobaro-lorabox/Makefile.dep create mode 100644 boards/lobaro-lorabox/Makefile.features create mode 100644 boards/lobaro-lorabox/Makefile.include create mode 100644 boards/lobaro-lorabox/board.c create mode 100644 boards/lobaro-lorabox/doc.txt create mode 100644 boards/lobaro-lorabox/include/board.h create mode 100644 boards/lobaro-lorabox/include/gpio_params.h create mode 100644 boards/lobaro-lorabox/include/periph_conf.h diff --git a/boards/lobaro-lorabox/Makefile b/boards/lobaro-lorabox/Makefile new file mode 100644 index 0000000000..f8fcbb53a0 --- /dev/null +++ b/boards/lobaro-lorabox/Makefile @@ -0,0 +1,3 @@ +MODULE = board + +include $(RIOTBASE)/Makefile.base diff --git a/boards/lobaro-lorabox/Makefile.dep b/boards/lobaro-lorabox/Makefile.dep new file mode 100644 index 0000000000..5472bf8b8d --- /dev/null +++ b/boards/lobaro-lorabox/Makefile.dep @@ -0,0 +1,3 @@ +ifneq (,$(filter saul_default,$(USEMODULE))) + USEMODULE += saul_gpio +endif diff --git a/boards/lobaro-lorabox/Makefile.features b/boards/lobaro-lorabox/Makefile.features new file mode 100644 index 0000000000..19f672f277 --- /dev/null +++ b/boards/lobaro-lorabox/Makefile.features @@ -0,0 +1,9 @@ +# Put defined MCU peripherals here (in alphabetical order) +FEATURES_PROVIDED += periph_gpio +FEATURES_PROVIDED += periph_i2c +FEATURES_PROVIDED += periph_rtc +FEATURES_PROVIDED += periph_spi +FEATURES_PROVIDED += periph_timer +FEATURES_PROVIDED += periph_uart + +-include $(RIOTCPU)/stm32l1/Makefile.features diff --git a/boards/lobaro-lorabox/Makefile.include b/boards/lobaro-lorabox/Makefile.include new file mode 100644 index 0000000000..b2bfe76781 --- /dev/null +++ b/boards/lobaro-lorabox/Makefile.include @@ -0,0 +1,26 @@ +## the cpu to build for +export CPU = stm32l1 +export CPU_MODEL = stm32l151cb + +# add the common header files to the include path +INCLUDES += -I$(RIOTBOARD)/lobaro-lorabox/include + +# configure the serial terminal +PORT_LINUX ?= /dev/ttyUSB0 +PORT_DARWIN ?= $(firstword $(sort $(wildcard /dev/tty.usbmodem*))) + +# setup serial terminal +include $(RIOTMAKE)/tools/serial.inc.mk + +FLASHER = $(RIOTTOOLS)/stm32loader/stm32loader.py + +# needed for now so the build system generates the .bin file +HEXFILE = $(BINFILE) + +# -e: erase +# -u: use sector by sector erase +# -S: swap RTS and DTR +# -l 0x1ff: amount of sectors to erase +FFLAGS += -e -u -S -l 0x1ff -w $(BINFILE) + +TERMFLAGS += --set-rts 0 diff --git a/boards/lobaro-lorabox/board.c b/boards/lobaro-lorabox/board.c new file mode 100644 index 0000000000..529f63975b --- /dev/null +++ b/boards/lobaro-lorabox/board.c @@ -0,0 +1,29 @@ +/* + * Copyright (C) 2018 HAW Hamburg + * + * 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_lobaro_lorabox + * @{ + * + * @file + * @brief Board initialization code for Lobaro LoraBox + * + * @author Leandro Lanzieri + * @} + */ + +#include "board.h" +#include "periph/gpio.h" + +void board_init(void) +{ + /* initialize the CPU */ + cpu_init(); + gpio_init(LED0_PIN, GPIO_OUT); + gpio_init(EN3V3_PIN, GPIO_OUT); +} diff --git a/boards/lobaro-lorabox/doc.txt b/boards/lobaro-lorabox/doc.txt new file mode 100644 index 0000000000..61d3f81af4 --- /dev/null +++ b/boards/lobaro-lorabox/doc.txt @@ -0,0 +1,91 @@ +/** +@defgroup boards_lobaro_lorabox Lobaro Lorabox +@ingroup boards +@brief Support for the Lobaro LoraBox with stm32l151cb-a + +## Hardware + +![LoraBox](https://www.lobaro.com/wp/wp-content/uploads/2017/03/Lobaro_wMBUS_LoRaWAN_Bridge.jpg) + + +### MCU +| MCU | stm32l151cb-a | +|:------------- |:--------------------- | +| Family | ARM Cortex-M3 | +| Vendor | ST Microelectronics | +| RAM | 16Kb | +| Flash | 128Kb | +| Frequency | 32MHz (no external oscilator connected) | +| FPU | no | +| Timers | 10 (8x 16-bit, 2x watchdog timers) | +| ADCs | 1x 24-channel 12-bit | +| UARTs | 3 | +| SPIs | 2 | +| I2Cs | 2 | +| Vcc | 1.65V - 3.6V | +| Datasheet | [Datasheet](https://www.st.com/resource/en/datasheet/stm32l151cb-a.pdf) | +| Reference Manual | [Reference Manual](https://www.st.com/content/ccc/resource/technical/document/reference_manual/cc/f9/93/b2/f0/82/42/57/CD00240193.pdf/files/CD00240193.pdf/jcr:content/translations/en.CD00240193.pdf) | +| Programming Manual | [Programming Manual](https://www.st.com/content/ccc/resource/technical/document/programming_manual/5b/ca/8d/83/56/7f/40/08/CD00228163.pdf/files/CD00228163.pdf/jcr:content/translations/en.CD00228163.pdf) | +| Board Manual | [Board Manual](https://www.lobaro.com/download/7250/)| + +### User Interface + +1 LEDs: + +| NAME | LED0 | +| ----- | ----- | +| Color | green | +| Pin | P1 | + + +## Flashing +### Connections +To flash using the STM32 ROM bootloader on the board, use the provided UART-USB +bridge and connect it to the *Config* port. The *Config* port pinout is the +following: + +``` +--------------- --------------- +| 1 2 3 4 5 6 | | x x x x x x | +--------------- --------------- + Config Addon + +1: RST +2: VCC +3: RX1 +4: TX1 +5: Boot0 +6: GND +``` + +### STM32 Loader +To flash RIOT on the board, after connection the UART-USB bridge, just run: +``` +BOARD=lobaro-lorabox make flash +``` +This uses the stm32loader script to erase the memory and flash it interfacing +with the STM32 ROM bootloader. + +### Lobaro Tool +Another way of interfacing with the STM32 ROM bootloader is using the **Lobaro Maintenance Tool** provided +[online](https://www.lobaro.com/lobaro-maintenance-tool/) for free for Linux, +Mac & Windows. It allows flashing and accessing the UART. + +![LobaroTool](https://www.lobaro.com/wp/wp-content/uploads/2018/03/Lobaro_Tool_FirmwareUpdateFeature.png) + +## Connecting via Serial +The default UART port is the USART1, the same that is used for flashing, so it +is available on the *Config* port. The default port is /dev/ttyUSB0. To access +the port run: +``` +BOARD=lobaro-lorabox make term +``` +**Note:** If you want to access the port with a different application please +keep in mind that RTS must be set to '0' and DTR to '1' as the provided UART-USB +bridge seems to invert this lines. + */ + +## SX1272 radio +Please note that the board has a Semtech SX1272 radio. This means that when the +semtech-loramac package or the sx127x driver are used the correct driver version +(sx1272) must be selected. \ No newline at end of file diff --git a/boards/lobaro-lorabox/include/board.h b/boards/lobaro-lorabox/include/board.h new file mode 100644 index 0000000000..08606abbed --- /dev/null +++ b/boards/lobaro-lorabox/include/board.h @@ -0,0 +1,92 @@ +/* + * Copyright (C) 2018 HAW Hamburg + * + * 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_lobaro_lorabox + * @brief Support for Lobaro LoraBox + * @{ + * + * @file + * @brief Common pin definitions and board configuration options + * + * @author Leandro Lanzieri + */ + +#ifndef BOARD_H +#define BOARD_H + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @name LED pin definitions and handlers + * @{ + */ +#define AUTO_INIT_LED0 +#define LED0_PORT GPIOA +#define LED0_PIN GPIO_PIN(PORT_A, 1) +#define LED0_MASK (1 << 1) + +#define LED0_ON (LED0_PORT->BSRR = (LED0_MASK << 16)) +#define LED0_OFF (LED0_PORT->BSRR = LED0_MASK) +#define LED0_TOGGLE (LED0_PORT->ODR ^= LED0_MASK) + +#define EN3V3_PORT GPIOA +#define EN3V3_PIN GPIO_PIN(PORT_A, 11) +#define EN3V3_MASK (1 << 11) + +#define EN3V3_ON (EN3V3_PORT->BSRR = EN3V3_MASK) +#define EN3V3_OFF (EN3V3_PORT->BSRR = (EN3V3_MASK << 16)) +#define EN3V3_TOGGLE (EN3V3_PORT->ODR ^= EN3V3_MASK) +/** @} */ + +/** + * @name SX127X + * + * SX127X configuration. + * @{ + */ +#define SX127X_PARAM_SPI (SPI_DEV(0)) + +#define SX127X_PARAM_SPI_NSS GPIO_PIN(PORT_B, 0) + +#define SX127X_PARAM_RESET GPIO_PIN(PORT_A, 4) + +#define SX127X_PARAM_DIO0 GPIO_PIN(PORT_B, 1) + +#define SX127X_PARAM_DIO1 GPIO_PIN(PORT_B, 10) + +#define SX127X_PARAM_DIO2 GPIO_PIN(PORT_B, 11) + +#define SX127X_PARAM_DIO3 GPIO_PIN(PORT_B, 7) + +#define SX127X_PARAM_PASELECT (SX127X_PA_RFO) + +#define SX127X_PARAMS { .spi = SX127X_PARAM_SPI, \ + .nss_pin = SX127X_PARAM_SPI_NSS, \ + .reset_pin = SX127X_PARAM_RESET, \ + .dio0_pin = SX127X_PARAM_DIO0, \ + .dio1_pin = SX127X_PARAM_DIO1, \ + .dio2_pin = SX127X_PARAM_DIO2, \ + .dio3_pin = SX127X_PARAM_DIO3, \ + .paselect = SX127X_PARAM_PASELECT \ + } +/** @} */ + +/** + * @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/lobaro-lorabox/include/gpio_params.h b/boards/lobaro-lorabox/include/gpio_params.h new file mode 100644 index 0000000000..6795149d37 --- /dev/null +++ b/boards/lobaro-lorabox/include/gpio_params.h @@ -0,0 +1,48 @@ +/* + * Copyright (C) 2018 HAW Hamburg + * + * 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_lobaro_lorabox + * @{ + * + * @file + * @brief Board specific configuration of direct mapped GPIOs + * + * @author Leandro Lanzieri + */ + +#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[] = +{ +#ifdef AUTO_INIT_LED0 + { + .name = "LED(green)", + .pin = LED0_PIN, + .mode = GPIO_OUT + }, +#endif +}; + +#ifdef __cplusplus +} +#endif + +#endif /* GPIO_PARAMS_H */ +/** @} */ diff --git a/boards/lobaro-lorabox/include/periph_conf.h b/boards/lobaro-lorabox/include/periph_conf.h new file mode 100644 index 0000000000..f1e71fa3bc --- /dev/null +++ b/boards/lobaro-lorabox/include/periph_conf.h @@ -0,0 +1,232 @@ +/* + * Copyright (C) 2014-2016 Freie Universität Berlin + * 2018 HAW Hamburg + * + * 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_lobaro_lorabox + * @brief Support for the Lobaro lorabox with stm32l151cb + * @{ + * + * @file + * @brief Peripheral MCU configuration for the Lobaro lorabox board + * + * @author Thomas Eichinger + * @author Hauke Petersen + * @author Kevin Weiss + * @author Leandro Lanzieri + */ + +#ifndef PERIPH_CONF_H +#define PERIPH_CONF_H + +#include "periph_cpu.h" + +#ifdef __cplusplus +extern "C" { +#endif + + +/** + * @name xtimer configuration + * @{ + */ +#define XTIMER_WIDTH (16) +#define XTIMER_BACKOFF (50) +#define XTIMER_ISR_BACKOFF (40) +/** @} */ + +/** + * @name Clock system configuration + * @{ + **/ +#define CLOCK_HSI (16000000U) /* frequency of internal oscillator */ +#define CLOCK_CORECLOCK (32000000U) /* targeted core clock frequency */ +/* + * 0: no external low speed crystal available, + * 1: external crystal available (always 32.768kHz) + */ +#ifndef CLOCK_LSE +#define CLOCK_LSE (1) +#endif +/* 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) +/** @} */ + +/** + * @name 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])) +/** @} */ + +/** + * @name Real time counter configuration + * @{ + */ +#define RTC_NUMOF (1U) +/** @} */ + +/** + * @name UART configuration + * @{ + */ +static const uart_conf_t uart_config[] = { + { + .dev = USART1, + .rcc_mask = RCC_APB2ENR_USART1EN, + .rx_pin = GPIO_PIN(PORT_A, 10), + .tx_pin = GPIO_PIN(PORT_A, 9), + .rx_af = GPIO_AF7, + .tx_af = GPIO_AF7, + .bus = APB2, + .irqn = USART1_IRQn + }, + { + .dev = USART2, + .rcc_mask = RCC_APB1ENR_USART2EN, + .rx_pin = GPIO_PIN(PORT_A, 3), + .tx_pin = GPIO_PIN(PORT_A, 2), + .rx_af = GPIO_AF7, + .tx_af = GPIO_AF7, + .bus = APB1, + .irqn = USART2_IRQn + } +}; + +#define UART_0_ISR (isr_usart1) +#define UART_1_ISR (isr_usart2) + +#define UART_NUMOF (sizeof(uart_config) / sizeof(uart_config[0])) +/** @} */ + +/** + * @name PWM configuration + * @{ + */ +#define PWM_NUMOF 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_PIN(PORT_B, 0), + .af = GPIO_AF5, + .rccmask = RCC_APB2ENR_SPI1EN, + .apbbus = APB2 + }, + { + .dev = SPI2, + .mosi_pin = GPIO_PIN(PORT_B, 14), + .miso_pin = GPIO_PIN(PORT_B, 15), + .sclk_pin = GPIO_PIN(PORT_B, 13), + .cs_pin = GPIO_PIN(PORT_B, 12), + .af = GPIO_AF5, + .rccmask = RCC_APB1ENR_SPI2EN, + .apbbus = APB1 + } +}; + +#define SPI_NUMOF (sizeof(spi_config) / sizeof(spi_config[0])) +/** @} */ + +/** + * @name I2C configuration + * @{ + */ +static const i2c_conf_t i2c_config[] = { + { + .dev = I2C1, + .speed = I2C_SPEED_NORMAL, + .scl_pin = GPIO_PIN(PORT_B, 8), + .sda_pin = GPIO_PIN(PORT_B, 9), + .scl_af = GPIO_AF4, + .sda_af = GPIO_AF4, + .bus = APB1, + .rcc_mask = RCC_APB1ENR_I2C1EN, + .clk = CLOCK_APB1, + .irqn = I2C1_EV_IRQn + } +}; + +#define I2C_0_ISR isr_i2c1_ev + +#define I2C_NUMOF (sizeof(i2c_config) / sizeof(i2c_config[0])) +/** @} */ + +/** + * @name ADC configuration + * @{ + */ +#define ADC_NUMOF (0U) +/** @} */ + +/** + * @name DAC configuration + * @{ + */ +#define DAC_NUMOF 0 +/** @} */ + +#ifdef __cplusplus +} +#endif + +#endif /* PERIPH_CONF_H */ +/** @} */ diff --git a/examples/javascript/Makefile b/examples/javascript/Makefile index 16e5b41eff..4493616696 100644 --- a/examples/javascript/Makefile +++ b/examples/javascript/Makefile @@ -8,13 +8,14 @@ BOARD ?= native RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := airfy-beacon b-l072z-lrwan1 bluepill calliope-mini \ - cc2650-launchpad cc2650stk hifive1 maple-mini \ - microbit nrf51dongle nrf6310 nucleo-f030r8 nucleo-f070rb \ - nucleo-f072rb nucleo-f103rb nucleo-f302r8 nucleo-f334r8 nucleo-f410rb \ - nucleo-l053r8 nucleo-l073rz nucleo-f031k6 nucleo-f042k6 \ - nucleo-f303k8 nucleo-l031k6 opencm904 \ - spark-core stm32f0discovery stm32mindev \ - yunjia-nrf51822 + cc2650-launchpad cc2650stk hifive1 lobaro-lorabox \ + maple-mini microbit nrf51dongle nrf6310 \ + nucleo-f030r8 nucleo-f070rb nucleo-f072rb \ + nucleo-f103rb nucleo-f302r8 nucleo-f334r8 \ + nucleo-f410rb nucleo-l053r8 nucleo-l073rz \ + nucleo-f031k6 nucleo-f042k6 nucleo-f303k8 \ + nucleo-l031k6 opencm904 spark-core stm32f0discovery \ + stm32mindev yunjia-nrf51822 BOARD_BLACKLIST := arduino-duemilanove arduino-mega2560 arduino-uno chronos \ msb-430 msb-430h telosb waspmote-pro wsn430-v1_3b \ diff --git a/examples/lua_REPL/Makefile b/examples/lua_REPL/Makefile index 67ecf11d95..9a42189453 100644 --- a/examples/lua_REPL/Makefile +++ b/examples/lua_REPL/Makefile @@ -16,9 +16,9 @@ BOARD_INSUFFICIENT_MEMORY := bluepill calliope-mini cc2650-launchpad \ stm32mindev airfy-beacon arduino-mkr1000 \ arduino-mkrfox1200 arduino-mkrzero arduino-zero \ b-l072z-lrwan1 cc2538dk ek-lm4f120xl feather-m0 \ - ikea-tradfri limifrog-v1 mbed_lpc1768 nrf6310 \ - nucleo-f091rc nucleo-l073rz nz32-sc151 \ - openmote-cc2538 openmote-b pba-d-01-kw2x \ + ikea-tradfri limifrog-v1 lobaro-lorabox \ + mbed_lpc1768 nrf6310 nucleo-f091rc nucleo-l073rz \ + nz32-sc151 openmote-cc2538 openmote-b pba-d-01-kw2x \ remote-pa remote-reva remote-revb samd21-xpro \ saml21-xpro samr21-xpro seeeduino_arch-pro \ sensebox_samd21 slstk3401a sltb001a slwstk6220a \ diff --git a/examples/lua_basic/Makefile b/examples/lua_basic/Makefile index 91a55145f5..5782ca4b04 100644 --- a/examples/lua_basic/Makefile +++ b/examples/lua_basic/Makefile @@ -7,12 +7,12 @@ BOARD ?= native RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := bluepill calliope-mini cc2650-launchpad \ - cc2650stk maple-mini microbit nrf51dongle \ - nucleo-f030r8 nucleo-f031k6 nucleo-f042k6 \ - nucleo-f070rb nucleo-f072rb nucleo-f103rb \ - nucleo-f302r8 nucleo-f303k8 nucleo-f334r8 \ - nucleo-f410rb nucleo-l031k6 nucleo-l053r8 \ - opencm904 spark-core stm32f0discovery \ + cc2650stk lobaro-lorabox maple-mini microbit \ + nrf51dongle nucleo-f030r8 nucleo-f031k6 \ + nucleo-f042k6 nucleo-f070rb nucleo-f072rb \ + nucleo-f103rb nucleo-f302r8 nucleo-f303k8 \ + nucleo-f334r8 nucleo-f410rb nucleo-l031k6 \ + nucleo-l053r8 opencm904 spark-core stm32f0discovery \ stm32mindev BOARD_BLACKLIST := arduino-duemilanove arduino-mega2560 arduino-uno \ diff --git a/tests/unittests/Makefile b/tests/unittests/Makefile index 608a274e71..a3be68a7ef 100644 --- a/tests/unittests/Makefile +++ b/tests/unittests/Makefile @@ -21,6 +21,7 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon \ feather-m0 \ ikea-tradfri \ limifrog-v1 maple-mini \ + lobaro-lorabox \ mbed_lpc1768 \ mega-xplained \ microbit \