1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2025-12-25 06:23:53 +01:00

Merge pull request #11227 from maribu/leonardo

boards: Add support for the Arduino-Leonardo
This commit is contained in:
Martine Lenders 2019-05-24 18:24:21 +02:00 committed by GitHub
commit 0f3ccb2a33
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
170 changed files with 922 additions and 286 deletions

View File

@ -0,0 +1,5 @@
MODULE = board
DIRS = $(RIOTBOARD)/common/arduino-atmega
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,3 @@
include $(RIOTBOARD)/common/arduino-atmega/Makefile.features
include $(RIOTCPU)/atmega32u4/Makefile.features

View File

@ -0,0 +1,17 @@
# define the cpu used by the arduino uno board
export CPU = atmega32u4
# export needed for flash rule
PORT_LINUX ?= /dev/ttyUSB0
AVRDUDE_PORT ?= /dev/ttyACM0
PORT_DARWIN ?= $(firstword $(sort $(wildcard /dev/tty.usbmodem*)))
BAUD ?= 9600
# PROGRAMMER defaults to avr109 which is the internal flasher via USB. Can be
# overridden for debugging (which requires changes that require to use an ISP)
PROGRAMMER ?= avr109
BOOTLOADER_SIZE ?= 4K
ROM_RESERVED ?= $(BOOTLOADER_SIZE)
include $(RIOTBOARD)/common/arduino-atmega/Makefile.include

View File

@ -0,0 +1,42 @@
/*
* Copyright (C) 2017 Thomas Perrot <thomas.perrot@tupi.fr>
*
* 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_arduino-leonardo
* @{
*
* @file
* @brief Board specific initialization for Arduino Leonardo
*
* @author Thomas Perrot <thomas.perrot@tupi.fr>
*
* @}
*/
#include "board.h"
#include "cpu.h"
#include "irq.h"
#include "periph/gpio.h"
#ifndef CPU_ATMEGA_CLK_SCALE_INIT
#define CPU_ATMEGA_CLK_SCALE_INIT CPU_ATMEGA_CLK_SCALE_DIV1
#endif
void led_init(void);
void board_init(void)
{
/* disable usb interrupt */
PRR1 |= 1<<PRUSB;
atmega_set_prescaler(CPU_ATMEGA_CLK_SCALE_INIT);
atmega_stdio_init();
cpu_init();
led_init();
irq_enable();
}

View File

@ -0,0 +1,62 @@
/**
@defgroup boards_arduino-leonardo Arduino Leonardo
@ingroup boards
@brief Support for the Arduino Leonardo board
## Overview
The Arduino Leonardo is a microcontroller board based on the ATmega32u4.
Similar to an Arduino UNO, can be recognized by computer as a mouse or keyboard.
Otherwise it's the same. Brief descriptions of both boards are available at
the official [Arduino web site.](https://www.arduino.cc/en/Main/Boards)
It has 20 digital input/output pins (of which 7 can be used as PWM outputs and
12 as analog inputs), a 16 MHz crystal oscillator, a micro USB connection, a
power jack, an ICSP header, and a reset button. It contains everything needed
to support the microcontroller; simply connect it to a computer with a USB
cable or power it with a AC-to-DC adapter or battery to get started.
For details, please look at the [Leonardo page.](@ref boards_arduino-leonardo)
## Using the shell
The shell is using the TTL (5V) serial because the USB (CDC) communication is
not currently supported.
The TTL serial cable must be connected as described below:
- FTDI RX goes to PIN1 (TX)
- FTDI TX goes to PIN0 (RX)
- FTDI GND goes to GND
Keep in mind that the Arduino Leonardo is not automatically restarted upon
`make BOARD=arduino-leonardo`, so you'll need to hit the reset button. Please
be patient, as the bootloader waits a few seconds before starting your code.
## Flashing the device
Flashing RIOT on the Arduino Leonardo is bit different compared to the other
Arduinos, as the device cannot be restarted automatically to enter the
bootloader. Therefore, you'll need to press the reset button in time to allow
avrdude (the tool used to flash the firmware) to connect to the bootloader.
### On a Fast Host
1. Type `make BOARD=arduino-leonardo flash` but do not hit enter yet
2. Press the reset button on the Arduino Leonardo
3. Hit enter
In case the compilation takes longer than the bootloader waits before starting
the user program, flashing will fail. See below to work arround
### On a Slow Host
1. Run `make BOARD=arduino-leonardo`
2. Type `make BOARD=arduino-leonardo flash-only` without hitting enter yet
3. Press the reset button on the Arduino Leonardo
4. Hit enter
## Mac Users
Mac Users have export the environment variable both `PORT` and `AVRDUDE_PORT`
to point to the device file of the TTL adapter (`PORT`) and the device file of
the Arduino Leonardo (`AVRDUDE_PORT`).
*/

View File

@ -0,0 +1,35 @@
/*
* Copyright (C) 2017 Thomas Perrot <thomas.perrot@tupi.fr>
*
* 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_arduino-leonardo Arduino Leonardo
* @ingroup boards
* @brief Support for the Arduino Leonardo board
* @{
*
* @file
* @brief Board specific definitions for the Arduino Leonardo board
*
* @author Thomas Perrot <thomas.perrot@tupi.fr>
*/
#ifndef BOARD_H
#define BOARD_H
#include "board_common.h"
#ifdef __cplusplus
extern "C" {
#endif
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H */
/** @} */

View File

@ -0,0 +1,34 @@
/*
* Copyright (C) 2017 Thomas Perrot <thomas.perrot@tupi.fr>
*
* 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_arduino-leonardo
* @{
*
* @file
* @brief Board specific led initialization for Arduino Leonardo
*
* @author Thomas Perrot <thomas.perrot@tupi.fr>
*
* @}
*/
#include "board.h"
#include "cpu.h"
#include "periph/gpio.h"
void led_init(void)
{
/* initialize the on-board LEDs */
gpio_init(LED0_PIN, GPIO_OUT);
LED0_OFF;
gpio_init(LED1_PIN, GPIO_OUT);
LED2_OFF;
gpio_init(LED2_PIN, GPIO_OUT);
LED2_OFF;
}

View File

@ -1,5 +1,6 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
* 2017 Thomas Perrot <thomas.perrot@tupi.fr>
*
* 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
@ -15,6 +16,7 @@
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Laurent Navet <laurent.navet@gmail.com>
* @author Thomas Perrot <thomas.perrot@tupi.fr>
*/
#ifndef ARDUINO_BOARD_H
@ -55,18 +57,24 @@ static const gpio_t arduino_pinmap[] = {
ARDUINO_PIN_17,
ARDUINO_PIN_18,
ARDUINO_PIN_19,
#ifdef CPU_ATMEGA2560
#if defined(CPU_ATMEGA2560) || defined(CPU_ATMEGA32U4)
ARDUINO_PIN_20,
ARDUINO_PIN_21,
ARDUINO_PIN_22,
ARDUINO_PIN_23,
#endif
#ifdef CPU_ATMEGA2560
ARDUINO_PIN_24,
ARDUINO_PIN_25,
ARDUINO_PIN_26,
ARDUINO_PIN_27,
ARDUINO_PIN_28,
ARDUINO_PIN_29,
#endif
#if defined(CPU_ATMEGA2560) || defined(CPU_ATMEGA32U4)
ARDUINO_PIN_30,
#endif
#ifdef CPU_ATMEGA2560
ARDUINO_PIN_31,
ARDUINO_PIN_32,
ARDUINO_PIN_33,

View File

@ -1,6 +1,7 @@
/*
* Copyright (C) 2015 Freie Universität Berlin
* 2016 Laurent Navet <laurent.navet@gmail.com>
* 2017 Thomas Perrot <thomas.perrot@tupi.fr>
*
* 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
@ -20,6 +21,7 @@
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Daniel Nordahl <nordahl.d@gmail.com>
* @author Laurent Navet <laurent.navet@gmail.com>
* @author Thomas Perrot <thomas.perrot@tupi.fr>
*/
#ifndef ARDUINO_PINMAP_H
@ -71,6 +73,51 @@ extern "C" {
#define ARDUINO_PIN_A5 ARDUINO_PIN_19
#endif
#ifdef CPU_ATMEGA32U4
/* Digital pins */
#define ARDUINO_PIN_0 GPIO_PIN(PORT_D, 2)
#define ARDUINO_PIN_1 GPIO_PIN(PORT_D, 3)
#define ARDUINO_PIN_2 GPIO_PIN(PORT_D, 1)
#define ARDUINO_PIN_3 GPIO_PIN(PORT_D, 0)
#define ARDUINO_PIN_5 GPIO_PIN(PORT_C, 6)
#define ARDUINO_PIN_7 GPIO_PIN(PORT_E, 6)
#define ARDUINO_PIN_11 GPIO_PIN(PORT_B, 7)
#define ARDUINO_PIN_13 GPIO_PIN(PORT_C, 7)
#define ARDUINO_PIN_14 GPIO_PIN(PORT_B, 3)
#define ARDUINO_PIN_15 GPIO_PIN(PORT_B, 1)
#define ARDUINO_PIN_16 GPIO_PIN(PORT_B, 2)
#define ARDUINO_PIN_17 GPIO_PIN(PORT_B, 0)
#define ARDUINO_PIN_30 GPIO_PIN(PORT_D, 5)
/* Analog pins */
#define ARDUINO_PIN_4 GPIO_PIN(PORT_D, 4)
#define ARDUINO_PIN_6 GPIO_PIN(PORT_D, 7)
#define ARDUINO_PIN_8 GPIO_PIN(PORT_B, 4)
#define ARDUINO_PIN_9 GPIO_PIN(PORT_B, 5)
#define ARDUINO_PIN_10 GPIO_PIN(PORT_B, 6)
#define ARDUINO_PIN_12 GPIO_PIN(PORT_D, 6)
#define ARDUINO_PIN_18 GPIO_PIN(PORT_F, 7)
#define ARDUINO_PIN_19 GPIO_PIN(PORT_F, 6)
#define ARDUINO_PIN_20 GPIO_PIN(PORT_F, 5)
#define ARDUINO_PIN_21 GPIO_PIN(PORT_F, 4)
#define ARDUINO_PIN_22 GPIO_PIN(PORT_F, 3)
#define ARDUINO_PIN_23 GPIO_PIN(PORT_F, 2)
/* Analog input */
#define ARDUINO_PIN_A0 ARDUINO_PIN_18
#define ARDUINO_PIN_A1 ARDUINO_PIN_19
#define ARDUINO_PIN_A2 ARDUINO_PIN_20
#define ARDUINO_PIN_A3 ARDUINO_PIN_21
#define ARDUINO_PIN_A4 ARDUINO_PIN_22
#define ARDUINO_PIN_A5 ARDUINO_PIN_23
#define ARDUINO_PIN_A6 ARDUINO_PIN_4
#define ARDUINO_PIN_A7 ARDUINO_PIN_6
#define ARDUINO_PIN_A8 ARDUINO_PIN_8
#define ARDUINO_PIN_A9 ARDUINO_PIN_9
#define ARDUINO_PIN_A10 ARDUINO_PIN_10
#define ARDUINO_PIN_A11 ARDUINO_PIN_12
#endif
#ifdef CPU_ATMEGA2560
#define ARDUINO_PIN_0 GPIO_PIN(PORT_E, 0)
#define ARDUINO_PIN_1 GPIO_PIN(PORT_E, 1)

View File

@ -1,6 +1,7 @@
/*
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
* 2016 Laurent Navet <laurent.navet@gmail.com>
* 2017 Thomas Perrot <thomas.perrot@tupi.fr>
*
* 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
@ -18,6 +19,7 @@
*
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
* @author Laurent Navet <laurent.navet@gmail.com>
* @author Thomas Perrot <thomas.perrot@tupi.fr>
*/
#ifndef BOARD_COMMON_H
@ -49,14 +51,35 @@ extern "C" {
#define LED0_MASK (1 << DDB5)
#endif
#ifdef CPU_ATMEGA32U4
#define LED0_PIN GPIO_PIN(2, 7) /**< BUILTIN LED */
#define LED0_MASK (1 << DDC7)
#define LED1_PIN GPIO_PIN(1, 0) /**< RX LED */
#define LED1_MASK (1 << DDB0)
#define LED2_PIN GPIO_PIN(3, 5) /**< TX LED */
#define LED2_MASK (1 << DDD5)
#endif
#ifdef CPU_ATMEGA2560
#define LED0_PIN GPIO_PIN(1, 7)
#define LED0_MASK (1 << DDB7)
#endif
#define LED0_ON (PORTB |= LED0_MASK)
#define LED0_OFF (PORTB &= ~LED0_MASK)
#define LED0_TOGGLE (PORTB ^= LED0_MASK)
#ifdef CPU_ATMEGA32U4
#define LED0_ON (PORTC |= LED0_MASK) /**< BUILTIN LED */
#define LED0_OFF (PORTC &= ~LED0_MASK)
#define LED0_TOGGLE (PORTC ^= LED0_MASK)
#define LED1_OFF (PORTB |= LED1_MASK) /**< RX LED */
#define LED1_ON (PORTB &= ~LED1_MASK)
#define LED1_TOGGLE (PORTB ^= LED1_MASK)
#define LED2_OFF (PORTD |= LED2_MASK) /**< TX LED */
#define LED2_ON (PORTD &= ~LED2_MASK)
#define LED2_TOGGLE (PORTD ^= LED2_MASK)
#else
#define LED0_ON (PORTD |= LED0_MASK)
#define LED0_OFF (PORTD &= ~LED0_MASK)
#define LED0_TOGGLE (PORTD ^= LED0_MASK)
#endif
/** @} */
/**

View File

@ -31,6 +31,10 @@ void led_init(void);
void board_init(void)
{
#ifdef CPU_ATMEGA32U4
/* disable usb interrupt on Atmega32U4 */
PRR1 |= 1<<PRUSB;
#endif
atmega_set_prescaler(CPU_ATMEGA_CLK_SCALE_INIT);

View File

@ -93,10 +93,35 @@ extern "C" {
* The timer driver only supports the four 16-bit timers (Timer1, Timer3,
* Timer4, Timer5), so those are the only onces we can use here.
*
*
* ATmega32U4
* ==========
* The ATmega32U4 has 4 timers. Timer0 and Timer2 are 8 Bit Timers.
*
* The timer driver only supports the two 16-bit timers (Timer1 and
* Timer3), so those are the only ones we can use here.
*
* @{
*/
#ifndef TIMER_NUMOF
#if defined(CPU_ATMEGA256RFR2)
#if defined(CPU_ATMEGA32U4)
#define TIMER_NUMOF (2U)
#define TIMER_CHANNELS (3)
#define TIMER_0 MEGA_TIMER1
#define TIMER_0_MASK &TIMSK1
#define TIMER_0_FLAG &TIFR1
#define TIMER_0_ISRA TIMER1_COMPA_vect
#define TIMER_0_ISRB TIMER1_COMPB_vect
#define TIMER_0_ISRC TIMER1_COMPC_vect
#define TIMER_1 MEGA_TIMER3
#define TIMER_1_MASK &TIMSK3
#define TIMER_1_FLAG &TIFR3
#define TIMER_1_ISRA TIMER3_COMPA_vect
#define TIMER_1_ISRB TIMER3_COMPB_vect
#define TIMER_1_ISRC TIMER3_COMPC_vect
#elif defined(CPU_ATMEGA256RFR2)
#define TIMER_NUMOF (3U)
#define TIMER_CHANNELS (3)
@ -192,6 +217,11 @@ extern "C" {
#define UART_0 MEGA_UART0
#define UART_0_ISR USART_RX_vect
#elif defined(CPU_ATMEGA32U4)
#define UART_NUMOF (1U)
#define UART_0 MEGA_UART1
#define UART_0_ISR USART1_RX_vect
#else
#define UART_NUMOF (0U)
#endif
@ -205,23 +235,33 @@ extern "C" {
* All currently supported ATmega MCUs have only one hardware SPI with fixed pin
* configuration, so all we can do here, is to enable or disable it...
*
* The fixed pins ATmega328p are:
* MOSI - PB3
* MISO - PB4
* SCK - PB5
* SS - PB2 -> this pin is configured as output, but not used
* The fixed pins ATmega328P are:
*
* The fixed pins for the ATmega128rp are:
* MOSI - PB5
* MISO - PB6
* SCK - PB7
* SS - PB4 -> this pin is configured as output, but not used
* | Function | Pin |
* |:-------- |:--- |
* | MOSI | PB3 |
* | MISO | PB4 |
* | SCK | PB5 |
* | SS | PB2 |
*
* The fixed pins for the ATmega1281, ATmega256rfr2, and ATmega2560 are:
* MOSI - PB2
* MISO - PB3
* SCK - PB1
* SS - PB0 -> this pin is configured as output, but not used
* The fixed pins for the ATmega1284P are:
*
* | Function | Pin |
* |:-------- |:--- |
* | MOSI | PB5 |
* | MISO | PB6 |
* | SCK | PB7 |
* | SS | PB4 |
*
* The fixed pins for the ATmega1281, ATmega256RFR2, ATmega2560, and ATmega32U4
* are:
*
* | Function | Pin |
* |:-------- |:--- |
* | MOSI | PB2 |
* | MISO | PB3 |
* | SCK | PB1 |
* | SS | PB0 |
*
* The SS pin must be configured as output for the SPI device to work as
* master correctly, though we do not use it for now (as we handle the chip
@ -255,7 +295,7 @@ extern "C" {
* @{
*/
#ifndef ADC_NUMOF
#if defined(CPU_ATMEGA256RFR2) || defined(CPU_ATMEGA328P) || defined(CPU_ATMEGA1281) || defined(CPU_ATMEGA1284P)
#if defined(CPU_ATMEGA256RFR2) || defined(CPU_ATMEGA328P) || defined(CPU_ATMEGA1281) || defined(CPU_ATMEGA1284P) || defined(CPU_ATMEGA32U4)
#define ADC_NUMOF (8U)
#elif defined (CPU_ATMEGA2560)
#define ADC_NUMOF (16U)
@ -287,22 +327,26 @@ extern "C" {
#elif defined(CPU_ATMEGA2560)
#define PWM_PINS_CH0 { GPIO_PIN(PORT_B, 7), GPIO_PIN(PORT_G, 5) }
#define PWM_PINS_CH1 { GPIO_PIN(PORT_B, 4), GPIO_PIN(PORT_H, 6) }
#elif defined(CPU_ATMEGA32U4)
#define PWM_PINS_CH0 { GPIO_PIN(PORT_B, 7), GPIO_PIN(PORT_D, 0) }
#else
#define PWM_NUMOF (0U)
#endif
#if defined(CPU_ATMEGA328P) || defined(CPU_ATMEGA1281) || defined(CPU_ATMEGA2560)
#if defined(CPU_ATMEGA328P) || defined(CPU_ATMEGA1281) || defined(CPU_ATMEGA2560) || defined(CPU_ATMEGA32U4)
static const pwm_conf_t pwm_conf[] = {
{
.dev = MINI_TIMER0,
.pin_ch = PWM_PINS_CH0,
.div = MINI_TIMER0_DIV,
},
#ifndef CPU_ATMEGA32U4
{
.dev = MINI_TIMER2,
.pin_ch = PWM_PINS_CH1,
.div = MINI_TIMER2_DIV,
}
#endif
};
#define PWM_NUMOF (sizeof(pwm_conf) / sizeof(pwm_conf[0]))

6
cpu/atmega32u4/Makefile Normal file
View File

@ -0,0 +1,6 @@
# define the module that is build
MODULE = cpu
# add a list of subdirectories, that should also be build
DIRS = $(ATMEGA_COMMON)
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1 @@
-include $(RIOTCPU)/atmega_common/Makefile.features

View File

@ -0,0 +1,14 @@
# this CPU implementation is using the new core/CPU interface
export CFLAGS += -DCOREIF_NG=1
# tell the build system that the CPU depends on the atmega common files
USEMODULE += atmega_common
# define path to atmega common module, which is needed for this CPU
export ATMEGA_COMMON = $(RIOTCPU)/atmega_common/
RAM_LEN = 2560
ROM_LEN = 32K
# CPU depends on the atmega common module, so include it
include $(ATMEGA_COMMON)Makefile.include

30
cpu/atmega32u4/cpu.c Normal file
View File

@ -0,0 +1,30 @@
/*
* Copyright (C) 2017 Thomas Perrot <thomas.perrot@tupi.fr>
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup cpu_atmega32u4
* @{
*
* @file
* @brief Implementation of the CPU initialization
*
* @author Thomas Perrot <thomas.perrot@tupi.fr>
* @}
*/
#include "cpu.h"
#include "periph/init.h"
/**
* @brief Initialize the CPU, set IRQ priorities
*/
void cpu_init(void)
{
/* trigger static peripheral initialization */
periph_init();
}

10
cpu/atmega32u4/doc.txt Normal file
View File

@ -0,0 +1,10 @@
/**
* @defgroup cpu_atmega32u4 Atmel ATmega32u4
* @ingroup cpu
* @brief Implementation of Atmel's ATmega32u4 MCU
*/
/**
* @defgroup cpu_atmega32u4_definitions Atmel ATmega32u4 Definitions
* @ingroup cpu_atmega32u4
*/

View File

@ -0,0 +1,50 @@
/*
* Copyright (C) 2017 Thomas Perrot <thomas.perrot@tupi.fr>
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup cpu_atmega32u4
* @{
*
* @file
* @brief Implementation specific CPU configuration options
*
* @author Thomas Perrot <thomas.perrot@tupi.fr>
*
*/
#ifndef CPU_CONF_H
#define CPU_CONF_H
#include "atmega_regs_common.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @name Kernel configuration
*
* Since printf seems to get memory allocated by the linker/avr-libc the stack
* size tested successfully even with pretty small stacks.k
* @{
*/
#define THREAD_EXTRA_STACKSIZE_PRINTF (128)
#ifndef THREAD_STACKSIZE_DEFAULT
#define THREAD_STACKSIZE_DEFAULT (256)
#endif
#define THREAD_STACKSIZE_IDLE (128)
/** @} */
#ifdef __cplusplus
}
#endif
#endif /* CPU_CONF_H */
/** @} */

View File

@ -0,0 +1,71 @@
/*
* Copyright (C) 2017 Thomas Perrot <thomas.perrot@tupi.fr>
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup cpu_atmega32u4
* @{
*
* @file
* @brief CPU specific definitions for internal peripheral handling
*
* @author Thomas Perrot <thomas.perrot@tupi.fr>
*
*/
#ifndef PERIPH_CPU_H
#define PERIPH_CPU_H
#include "periph_cpu_common.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Available ports on the ATmega32u4 family
*/
enum {
PORT_B = 1, /**< port B */
PORT_C = 2, /**< port C */
PORT_D = 3, /**< port D */
PORT_E = 4, /**< port E */
PORT_F = 5 /**< port F */
};
/**
* @brief Available external interrupt pins on the ATmega32u4 family
*
* In order of their interrupt number.
*/
#define CPU_ATMEGA_EXT_INTS { GPIO_PIN(PORT_D, 0), \
GPIO_PIN(PORT_D, 1), \
GPIO_PIN(PORT_D, 2), \
GPIO_PIN(PORT_D, 3), \
GPIO_PIN(PORT_E, 7) }
/**
* @name Defines for the I2C interface
* @{
*/
#define I2C_PORT_REG PORTD
#define I2C_PIN_MASK (1 << PORTD0) | (1 << PORTD1)
/** @} */
/**
* @name EEPROM configuration
* @{
*/
#define EEPROM_SIZE (1024U) /* 1kB */
/** @} */
#ifdef __cplusplus
}
#endif
#endif /* PERIPH_CPU_H */
/** @} */

View File

@ -1,6 +1,7 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
* 2016 INRIA
* 2017 Thomas Perrot <thomas.perrot@tupi.fr>
*
* 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
@ -16,6 +17,8 @@
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Francisco Acosta <francisco.acosta@inria.fr>
* @author Thomas Perrot <thomas.perrot@tupi.fr>
*
*/
#ifndef ATMEGA_REGS_COMMON_H
@ -66,7 +69,11 @@ typedef struct {
REG8 CSRA; /**< control and status register A */
REG8 CSRB; /**< control and status register B */
REG8 CSRC; /**< control and status register C */
#ifdef CPU_ATMEGA32U4
REG8 CSRD; /**< control and status register D */
#else
REG8 reserved; /**< reserved */
#endif
REG16 BRR; /**< baud rate register */
REG8 DR; /**< data register */
} mega_uart_t;

View File

@ -111,7 +111,7 @@ int adc_sample(adc_t line, adc_res_t res)
_prep();
/* set conversion channel */
#if defined(CPU_ATMEGA328P) || defined(CPU_ATMEGA1281) || defined(CPU_ATMEGA1284P)
#if defined(CPU_ATMEGA328P) || defined(CPU_ATMEGA1281) || defined(CPU_ATMEGA1284P) || defined(CPU_ATMEGA32U4)
ADMUX &= 0xf0;
ADMUX |= line;
#elif defined(CPU_ATMEGA2560) || defined(CPU_ATMEGA256RFR2)

View File

@ -2,6 +2,7 @@
* Copyright (C) 2015 Daniel Amkaer Sorensen
* 2016 Freie Universität Berlin
* 2017 Hamburg University of Applied Sciences
* 2017 Thomas Perrot <thomas.perrot@tupi.fr>
*
* 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
@ -19,6 +20,7 @@
* @author Daniel Amkaer Sorensen <daniel.amkaer@gmail.com>
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Dimitri Nahm <dimitri.nahm@haw-hamburg.de>
* @author Thomas Perrot <thomas.perrot@tupi.fr>
*
* @}
*/
@ -71,6 +73,9 @@ void spi_init_pins(spi_t bus)
* */
DDRB |= ((1 << DDB2) | (1 << DDB1));
#endif
#ifdef CPU_ATMEGA32U4
DDRB |= ((1 << DDB0) | (1 << DDB1) | (1 << DDB2));
#endif
}
int spi_acquire(spi_t bus, spi_cs_t cs, spi_mode_t mode, spi_clk_t clk)

View File

@ -1,5 +1,6 @@
/*
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
* 2017 Thomas Perrot <thomas.perrot@tupi.fr>
*
* 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
@ -16,6 +17,7 @@
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
* @author Thomas Perrot <thomas.perrot@tupi.fr>
*
*
* Support static BAUD rate calculation using STDIO_UART_BAUDRATE.
@ -78,11 +80,16 @@ static mega_uart_t *dev[] = {
*/
static uart_isr_ctx_t isr_ctx[UART_NUMOF];
static void _update_brr(uart_t uart, uint16_t brr, bool double_speed)
{
dev[uart]->BRR = brr;
if (double_speed) {
#ifdef CPU_ATMEGA32U4
dev[uart]->CSRA |= (1 << U2X1);
#else
dev[uart]->CSRA |= (1 << U2X0);
#endif
}
}
@ -119,20 +126,35 @@ int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg)
isr_ctx[uart].arg = arg;
/* disable and reset UART */
#ifdef CPU_ATMEGA32U4
dev[uart]->CSRD = 0;
#endif
dev[uart]->CSRB = 0;
dev[uart]->CSRA = 0;
/* configure UART to 8N1 mode */
#ifdef CPU_ATMEGA32U4
dev[uart]->CSRC = (1 << UCSZ10) | (1 << UCSZ11);
#else
dev[uart]->CSRC = (1 << UCSZ00) | (1 << UCSZ01);
#endif
/* set clock divider */
_set_brr(uart, baudrate);
/* enable RX and TX and the RX interrupt */
if (rx_cb) {
#ifdef CPU_ATMEGA32U4
dev[uart]->CSRB = ((1 << RXCIE1) | (1 << RXEN1) | (1 << TXEN1));
#else
dev[uart]->CSRB = ((1 << RXCIE0) | (1 << RXEN0) | (1 << TXEN0));
#endif
}
else {
#ifdef CPU_ATMEGA32U4
dev[uart]->CSRB = (1 << TXEN1);
#else
dev[uart]->CSRB = (1 << TXEN0);
#endif
}
return UART_OK;
@ -141,7 +163,11 @@ int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg)
void uart_write(uart_t uart, const uint8_t *data, size_t len)
{
for (size_t i = 0; i < len; i++) {
#ifdef CPU_ATMEGA32U4
while (!(dev[uart]->CSRA & (1 << UDRE1))) {};
#else
while (!(dev[uart]->CSRA & (1 << UDRE0))) {}
#endif
dev[uart]->DR = data[i];
}
}

View File

@ -1,5 +1,6 @@
/*
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
* 2017 Thomas Perrot <thomas.perrot@tupi.fr>
* 2018 RWTH Aachen, Josua Arndt <jarndt@ias.rwth-aachen.de>
*
* This file is subject to the terms and conditions of the GNU Lesser
@ -15,6 +16,7 @@
* @brief Implementation of the kernel's architecture dependent thread interface
*
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
* @author Thomas Perrot <thomas.perrot@tupi.fr>
* @author Josua Arndt <jarndt@ias.rwth-aachen.de>
*
* @}
@ -122,7 +124,7 @@ char *thread_stack_init(thread_task_func_t task_func, void *arg,
stk--;
*stk = (uint8_t)0x00;
#endif
#if defined(RAMPZ)
#if defined(RAMPZ) && !defined(__AVR_ATmega32U4__)
stk--;
*stk = (uint8_t)0x00;
#endif
@ -262,7 +264,7 @@ __attribute__((always_inline)) static inline void __context_save(void)
"in __tmp_reg__, __SREG__ \n\t"
"cli \n\t"
"push __tmp_reg__ \n\t"
#if defined(RAMPZ)
#if defined(RAMPZ) && !defined(__AVR_ATmega32U4__)
"in __tmp_reg__, __RAMPZ__ \n\t"
"push __tmp_reg__ \n\t"
#endif
@ -354,7 +356,8 @@ __attribute__((always_inline)) static inline void __context_restore(void)
"pop __tmp_reg__ \n\t"
"out 0x3c, __tmp_reg__ \n\t"
#endif
#if defined(RAMPZ)
#if defined(RAMPZ) && !defined(__AVR_ATmega32U4__)
"pop __tmp_reg__ \n\t"
"out __RAMPZ__, __tmp_reg__ \n\t"
#endif

View File

@ -0,0 +1 @@
SUBSYSTEM=="usb", ATTR{idVendor}=="2341", ATTR{idProduct}=="0036", MODE="0666", OWNER="vagrant"

View File

@ -9,11 +9,10 @@ RIOTBASE ?= $(CURDIR)/../..
# Not all boards have enough memory to build the default configuration of this
# example...
BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560 \
arduino-nano arduino-uno chronos hifive1 \
i-nucleo-lrwan1 \
mega-xplained microbit msb-430 msb-430h nrf51dk \
nrf51dongle nrf6310 \
BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno chronos \
hifive1 i-nucleo-lrwan1 mega-xplained microbit \
msb-430 msb-430h nrf51dk nrf51dongle nrf6310 \
nucleo-f030r8 nucleo-f031k6 nucleo-f042k6 \
nucleo-f070rb nucleo-f072rb nucleo-f303k8 \
nucleo-f334r8 nucleo-l031k6 nucleo-l053r8 \

View File

@ -7,9 +7,9 @@ BOARD ?= native
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../..
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
arduino-uno chronos hifive1 i-nucleo-lrwan1 \
mega-xplained msb-430 \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno chronos \
hifive1 i-nucleo-lrwan1 mega-xplained msb-430 \
msb-430h nucleo-f030r8 nucleo-l053r8 \
nucleo-f031k6 nucleo-f042k6 nucleo-f303k8 \
nucleo-f334r8 nucleo-l031k6 stm32f0discovery \

View File

@ -7,9 +7,9 @@ BOARD ?= native
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../..
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
arduino-uno chronos hifive1 i-nucleo-lrwan1 \
msb-430 msb-430h \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno chronos \
hifive1 i-nucleo-lrwan1 msb-430 msb-430h \
nucleo-f030r8 nucleo-l053r8 nucleo-f031k6 \
nucleo-f042k6 nucleo-f303k8 nucleo-f334r8 \
nucleo-l031k6 mega-xplained stm32f0discovery \

View File

@ -7,7 +7,8 @@ BOARD ?= native
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../..
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno
# Uncomment these lines if you want to use platform support from external
# repositories:
@ -31,7 +32,6 @@ QUIET ?= 1
# Modules to include:
USEMODULE += shell
USEMODULE += shell_commands
USEMODULE += ps
# include and auto-initialize all available sensors
USEMODULE += saul_default

View File

@ -8,7 +8,8 @@ BOARD ?= native
RIOTBASE ?= $(CURDIR)/../..
# TinyDTLS only has support for 32-bit architectures ATM
BOARD_BLACKLIST := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_BLACKLIST := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno chronos jiminy-mega256rfr2 mega-xplained \
msb-430 msb-430h telosb waspmote-pro wsn430-v1_3b \
wsn430-v1_4 z1

View File

@ -7,13 +7,14 @@ BOARD ?= native
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../..
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
arduino-uno chronos hifive1 i-nucleo-lrwan1 \
msb-430 msb-430h \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno chronos \
hifive1 i-nucleo-lrwan1 msb-430 msb-430h \
nucleo-f031k6 nucleo-f042k6 nucleo-f303k8 \
nucleo-l031k6 nucleo-f030r8 nucleo-f070rb \
nucleo-f072rb nucleo-f302r8 nucleo-f334r8 nucleo-l053r8 \
stm32f0discovery telosb waspmote-pro wsn430-v1_3b \
nucleo-f072rb nucleo-f302r8 nucleo-f334r8 \
nucleo-l053r8 stm32f0discovery telosb \
waspmote-pro wsn430-v1_3b \
wsn430-v1_4 z1 mega-xplained
# Include packages that pull up and auto-init the link layer.

View File

@ -15,8 +15,8 @@ BOARD_BLACKLIST := chronos \
z1 \
#
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno nucleo-f031k6
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../..

View File

@ -9,9 +9,9 @@ BOARD ?= native
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../..
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
arduino-uno chronos i-nucleo-lrwan1 \
mega-xplained msb-430 \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno chronos \
i-nucleo-lrwan1 mega-xplained msb-430 \
msb-430h nucleo-f031k6 nucleo-f042k6 \
nucleo-l031k6 nucleo-f030r8 nucleo-f303k8 \
nucleo-f334r8 nucleo-l053r8 stm32f0discovery \

View File

@ -7,8 +7,9 @@ BOARD ?= samr21-xpro
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../..
BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560 \
arduino-nano arduino-uno b-l072z-lrwan1 blackpill \
BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno \
b-l072z-lrwan1 blackpill \
bluepill calliope-mini cc2650-launchpad cc2650stk \
hifive1 i-nucleo-lrwan1 lsn50 maple-mini mega-xplained microbit msb-430 \
msb-430h nrf51dk nrf51dongle nrf6310 \

View File

@ -7,8 +7,8 @@ BOARD ?= native
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../..
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno nucleo-f031k6
# Comment this out to disable code in RIOT that does safety checking
# which is not needed in a production environment but helps in the

View File

@ -7,7 +7,8 @@ BOARD ?= native
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../..
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno blackpill bluepill calliope-mini \
chronos hifive1 i-nucleo-lrwan1 mega-xplained \
microbit msb-430 msb-430h \

View File

@ -7,11 +7,12 @@ BOARD ?= native
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../..
BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560 \
arduino-nano arduino-uno b-l072z-lrwan1 blackpill \
bluepill calliope-mini \
chronos hifive1 i-nucleo-lrwan1 mega-xplained microbit \
msb-430 msb-430h nrf51dk nrf51dongle nrf6310 nucleo-f031k6 \
BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno \
b-l072z-lrwan1 blackpill bluepill calliope-mini \
chronos hifive1 i-nucleo-lrwan1 mega-xplained \
microbit msb-430 msb-430h nrf51dk \
nrf51dongle nrf6310 nucleo-f031k6 \
nucleo-f042k6 nucleo-f303k8 nucleo-l031k6 \
nucleo-f030r8 nucleo-f070rb nucleo-f072rb \
nucleo-f103rb nucleo-f302r8 nucleo-f334r8 \

View File

@ -4,8 +4,8 @@ APPLICATION = ipc_pingpong
# If no BOARD is found in the environment, use this default:
BOARD ?= native
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno nucleo-f031k6
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../..

View File

@ -17,8 +17,8 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon b-l072z-lrwan1 blackpill bluepill call
nucleo-l031k6 opencm904 saml10-xpro saml11-xpro \
spark-core stm32f0discovery yunjia-nrf51822
BOARD_BLACKLIST := arduino-duemilanove arduino-mega2560 arduino-nano \
arduino-uno chronos \
BOARD_BLACKLIST := arduino-duemilanove arduino-leonardo arduino-mega2560 \
arduino-nano arduino-uno chronos \
msb-430 msb-430h telosb waspmote-pro wsn430-v1_3b \
wsn430-v1_4 z1 pic32-wifire pic32-clicker jiminy-mega256rfr2 \
mega-xplained

View File

@ -28,7 +28,8 @@ BOARD_INSUFFICIENT_MEMORY := blackpill bluepill calliope-mini cc2650-launchpad \
yunjia-nrf51822 esp8266-esp-12x esp8266-olimex-mod \
esp8266-sparkfun-thing firefly
BOARD_BLACKLIST := arduino-duemilanove arduino-mega2560 arduino-nano arduino-uno \
BOARD_BLACKLIST := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno \
chronos hifive1 jiminy-mega256rfr2 mega-xplained mips-malta \
msb-430 msb-430h pic32-clicker pic32-wifire telosb \
waspmote-pro wsn430-v1_3b wsn430-v1_4 z1

View File

@ -16,7 +16,8 @@ BOARD_INSUFFICIENT_MEMORY := blackpill bluepill calliope-mini cc2650-launchpad \
nucleo-l053r8 opencm904 saml10-xpro saml11-xpro \
spark-core stm32f0discovery
BOARD_BLACKLIST := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_BLACKLIST := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno chronos hifive1 jiminy-mega256rfr2 \
mega-xplained mips-malta msb-430 msb-430h pic32-clicker \
pic32-wifire telosb waspmote-pro wsn430-v1_3b wsn430-v1_4 z1

View File

@ -7,8 +7,9 @@ BOARD ?= native
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../..
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
arduino-uno chronos i-nucleo-lrwan1 msb-430 msb-430h \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno \
chronos i-nucleo-lrwan1 msb-430 msb-430h \
nucleo-f031k6 nucleo-f042k6 nucleo-l031k6 \
nucleo-f030r8 nucleo-f303k8 nucleo-l053r8 \
stm32f0discovery telosb waspmote-pro wsn430-v1_3b \

View File

@ -7,7 +7,8 @@ BOARD ?= native
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../../
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno chronos i-nucleo-lrwan1 mega-xplained \
msb-430 msb-430h nucleo-f042k6 nucleo-f031k6 \
nucleo-l031k6 nucleo-f030r8 nucleo-l053r8 \

View File

@ -7,9 +7,9 @@ BOARD ?= native
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../..
BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560 \
arduino-nano arduino-uno chronos i-nucleo-lrwan1 \
mega-xplained msb-430 msb-430h \
BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno chronos \
i-nucleo-lrwan1 mega-xplained msb-430 msb-430h \
nrf51dk nrf51dongle nrf6310 \
nucleo-f031k6 nucleo-f042k6 nucleo-l031k6 \
nucleo-f030r8 nucleo-f070rb nucleo-f072rb \

View File

@ -7,7 +7,8 @@ BOARD ?= native
# This has to be the absolute path to the RIOT base directory:
RIOTBASE ?= $(CURDIR)/../..
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno
# we want to use SAUL:
USEMODULE += saul_default

View File

@ -9,7 +9,7 @@ DEBUGGER = $(DIST_PATH)/debug.sh $(DEBUGSERVER_FLAGS) $(DIST_PATH) $(DEBUGSERVER
PROGRAMMER_FLAGS = -p $(subst atmega,m,$(CPU))
# Set flasher port only for programmers that require it
ifneq (,$(filter $(PROGRAMMER),arduino buspirate stk500v1 stk500v2 wiring))
ifneq (,$(filter $(PROGRAMMER),arduino avr109 buspirate stk500v1 stk500v2 wiring))
# make the flasher port configurable (e.g. with atmelice the port is usb)
# defaults to terminal's serial port if not configured
AVRDUDE_PORT ?= $(PORT)

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno
# Modules that will have an impact on the size of the TCB (thread_t):
#

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno
# These boards only have a single timer in their periph_conf.h, needs special
# CFLAGS configuration to build properly

View File

@ -1,8 +1,8 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
chronos msb-430 msb-430h telosb wsn430-v1_3b \
wsn430-v1_4 z1
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno chronos msb-430 msb-430h telosb \
wsn430-v1_3b wsn430-v1_4 z1
USEMODULE += hashes
USEMODULE += bloom

View File

@ -1,7 +1,8 @@
export APPLICATION = can_trx
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno
USEMODULE += shell
USEMODULE += shell_commands

View File

@ -1,9 +1,10 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := i-nucleo-lrwan1 nucleo32-f031 nucleo32-f042 \
nucleo32-l031 nucleo-f030 nucleo-l053 stm32f0discovery \
arduino-duemilanove arduino-nano arduino-uno \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno i-nucleo-lrwan1 nucleo32-f031 \
nucleo32-f042 nucleo32-l031 nucleo-f030 \
nucleo-f030r8 nucleo-f031k6 nucleo-f042k6 \
nucleo-l031k6 nucleo-l053r8
nucleo-l031k6 nucleo-l053 nucleo-l053r8 \
stm32f0discovery
include $(RIOTBASE)/Makefile.include

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno chronos hifive1 i-nucleo-lrwan1 \
msb-430 msb-430h \
nucleo-f031k6 nucleo-f042k6 nucleo-f303k8 \

View File

@ -1,7 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno nucleo-f031k6
USEMODULE += shell
USEMODULE += at

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno
USEMODULE += at30tse75x
USEMODULE += shell

View File

@ -1,8 +1,8 @@
include ../Makefile.tests_common
# exclude boards with insufficient memory
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno nucleo-f031k6
DISABLE_MODULE += auto_init

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno
USEMODULE += ata8520e
USEMODULE += shell

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno
# include and auto-initialize all available sensors
USEMODULE += saul_default

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno
# chronos : USART_1 undeclared
BOARD_BLACKLIST += chronos

View File

@ -1,11 +1,12 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno i-nucleo-lrwan1 msb-430 msb-430h \
nucleo-f334r8 nucleo-l053r8 nucleo-f031k6 nucleo-f042k6 \
nucleo-f303k8 nucleo-l031k6 mega-xplained \
stm32f0discovery telosb waspmote-pro wsn430-v1_3b \
wsn430-v1_4 z1
nucleo-f334r8 nucleo-l053r8 nucleo-f031k6 \
nucleo-f042k6 nucleo-f303k8 nucleo-l031k6 \
mega-xplained stm32f0discovery telosb \
waspmote-pro wsn430-v1_3b wsn430-v1_4 z1
USEMODULE += auto_init_gnrc_netif
USEMODULE += enc28j60

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno i-nucleo-lrwan1 msb-430 msb-430h \
nucleo-l053r8 nucleo-f031k6 nucleo-f042k6 \
nucleo-l031k6 stm32f0discovery telosb \

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno
# chronos : USART_1 undeclared
BOARD_BLACKLIST += chronos

View File

@ -1,7 +1,8 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
arduino-uno i-nucleo-lrwan1 nucleo-f031k6 nucleo-f042k6 \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno \
i-nucleo-lrwan1 nucleo-f031k6 nucleo-f042k6 \
nucleo-l031k6 nucleo-f334r8 nucleo-l053r8 \
stm32f0discovery waspmote-pro

View File

@ -1,7 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY += arduino-uno arduino-nano arduino-duemilanove
BOARD_INSUFFICIENT_MEMORY += arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno
BOARD ?= msba2
USEMODULE += fmt

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano\
arduino-uno
USEMODULE += mpu9150
USEMODULE += xtimer

View File

@ -1,8 +1,8 @@
include ../Makefile.tests_common
# exclude boards with insufficient memory
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano\
arduino-uno nucleo-f031k6
USEMODULE += shell
USEMODULE += shell_commands

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano\
arduino-uno
USEMODULE += nvram_spi
USEMODULE += xtimer

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano\
arduino-uno
USEMODULE += shell
USEMODULE += pcd8544

View File

@ -1,7 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano\
arduino-uno nucleo-f031k6
USEMODULE += pir

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano\
arduino-uno
DRIVER ?= rn2483

View File

@ -1,8 +1,8 @@
include ../Makefile.tests_common
# exclude boards with insufficient memory
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano\
arduino-uno nucleo-f031k6
USEMODULE += sdcard_spi
USEMODULE += auto_init_storage

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano\
arduino-uno
DRIVER ?= sht11
BOARD ?= msba2

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano\
arduino-uno
USEMODULE += xtimer
USEMODULE += srf02

View File

@ -2,8 +2,8 @@ BOARD ?= b-l072z-lrwan1
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano\
arduino-uno nucleo-f031k6
USEMODULE += od
USEMODULE += shell

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano\
arduino-uno
USEMODULE += tsl4531x
USEMODULE += xtimer

View File

@ -1,8 +1,9 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6 nucleo-f042k6 nucleo-f030r8 \
nucleo-f334r8 stm32f0discovery waspmote-pro
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno nucleo-f031k6 nucleo-f042k6 \
nucleo-f030r8 nucleo-f334r8 stm32f0discovery \
waspmote-pro
USEMODULE += xbee
USEMODULE += gnrc_txtsnd

View File

@ -6,9 +6,10 @@ include ../Makefile.tests_common
BOARD_BLACKLIST := msb-430 msb-430h pic32-clicker pic32-wifire \
telosb wsn430-v1_3b wsn430-v1_4 z1
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
arduino-uno i-nucleo-lrwan1 msb-430 msb-430h \
nucleo-l031k6 nucleo-f031k6 nucleo-f042k6 nucleo-l053r8 \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno \
i-nucleo-lrwan1 msb-430 msb-430h nucleo-l031k6 \
nucleo-f031k6 nucleo-f042k6 nucleo-l053r8 \
stm32f0discovery telosb waspmote-pro wsn430-v1_3b \
wsn430-v1_4 z1

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano\
arduino-uno
FORCE_ASSERTS = 1
USEMODULE += event_callback

View File

@ -1,7 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6 nucleo-f042k6
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano\
arduino-uno nucleo-f031k6 nucleo-f042k6
USEMODULE += evtimer

View File

@ -1,7 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6 nucleo-f042k6
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano\
arduino-uno nucleo-f031k6 nucleo-f042k6
USEMODULE += evtimer

View File

@ -2,7 +2,8 @@ DEVELHELP := 1
# name of your application
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno hifive1 i-nucleo-lrwan1 mega-xplained \
msb-430 msb-430h nucleo-f030r8 nucleo-f031k6 \
nucleo-f042k6 nucleo-f070rb nucleo-f072rb \

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno chronos nucleo-f031k6 nucleo-f042k6 \
nucleo-l031k6 telosb waspmote-pro wsn430-v1_3b \
wsn430-v1_4

View File

@ -1,8 +1,9 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
arduino-uno chronos i-nucleo-lrwan1 nucleo-f030r8 \
nucleo-l053r8 nucleo-f031k6 nucleo-l031k6 nucleo-f042k6 \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno chronos \
i-nucleo-lrwan1 nucleo-f030r8 nucleo-l053r8 \
nucleo-f031k6 nucleo-l031k6 nucleo-f042k6 \
stm32f0discovery telosb waspmote-pro wsn430-v1_3b \
wsn430-v1_4

View File

@ -1,10 +1,11 @@
APPLICATION = gnrc_mac_timeout
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
arduino-uno chronos i-nucleo-lrwan1 nucleo-f030r8 \
nucleo-f031k6 nucleo-f042k6 nucleo-l031k6 nucleo-l053r8 \
stm32f0discovery waspmote-pro
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno \
chronos i-nucleo-lrwan1 nucleo-f030r8 \
nucleo-f031k6 nucleo-f042k6 nucleo-l031k6 \
nucleo-l053r8 stm32f0discovery waspmote-pro
USEMODULE += gnrc_mac

View File

@ -1,8 +1,9 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
arduino-uno chronos i-nucleo-lrwan1 nucleo-f030r8 \
nucleo-f031k6 nucleo-f042k6 nucleo-l031k6 nucleo-l053r8 \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno chronos \
i-nucleo-lrwan1 nucleo-f030r8 nucleo-f031k6 \
nucleo-f042k6 nucleo-l031k6 nucleo-l053r8 \
stm32f0discovery telosb waspmote-pro wsn430-v1_3b \
wsn430-v1_4

View File

@ -1,11 +1,12 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560 \
arduino-nano arduino-uno b-l072z-lrwan1 blackpill \
bluepill calliope-mini cc2650-launchpad cc2650stk \
chronos hifive1 i-nucleo-lrwan1 lsn50 maple-mini \
mega-xplained microbit \
msb-430 msb-430h nrf51dk nrf51dongle nrf6310 \
BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno \
b-l072z-lrwan1 blackpill bluepill calliope-mini \
cc2650-launchpad cc2650stk chronos hifive1 \
i-nucleo-lrwan1 lsn50 maple-mini \
mega-xplained microbit msb-430 msb-430h \
nrf51dk nrf51dongle nrf6310 \
nucleo-f030r8 nucleo-f070rb nucleo-f072rb \
nucleo-f103rb nucleo-f302r8 nucleo-f334r8 \
nucleo-l053r8 nucleo-l073rz nucleo-f031k6 \

View File

@ -2,7 +2,8 @@ DEVELHELP := 1
# name of your application
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno hifive1 i-nucleo-lrwan1 mega-xplained \
msb-430 msb-430h nucleo-f030r8 nucleo-f031k6 \
nucleo-f042k6 nucleo-f070rb nucleo-f072rb \

View File

@ -1,9 +1,9 @@
# name of your application
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
arduino-uno chronos hifive1 i-nucleo-lrwan1 \
msb-430 msb-430h \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano arduino-uno chronos \
hifive1 i-nucleo-lrwan1 msb-430 msb-430h \
nucleo-f030r8 nucleo-f031k6 nucleo-f042k6 \
nucleo-f070rb nucleo-f070rb nucleo-f072rb \
nucleo-f303k8 nucleo-f334r8 nucleo-l031k6 \

View File

@ -1,7 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno nucleo-f031k6
USEMODULE += gnrc_sixlowpan_frag
USEMODULE += embunit

View File

@ -2,7 +2,8 @@ include ../Makefile.tests_common
RIOTBASE ?= $(CURDIR)/../..
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno chronos hifive1 i-nucleo-lrwan1 \
mega-xplained msb-430 msb-430h \
nucleo-f042k6 nucleo-f031k6 \

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-nano arduino-uno \
chronos nucleo-f031k6 nucleo-f042k6 nucleo-l031k6
USEMODULE += gnrc_sock_ip

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno chronos nucleo-f031k6 nucleo-f042k6 \
nucleo-l031k6 waspmote-pro

View File

@ -13,7 +13,8 @@ TCP_CLIENT_ADDR ?= 2001:db8::affe:0002
TCP_TEST_CYCLES ?= 3
# Mark Boards with insufficient memory
BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560 \
BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove \
arduino-leonardo arduino-mega2560 \
arduino-nano arduino-uno calliope-mini chronos \
hifive1 i-nucleo-lrwan1 mega-xplained microbit \
msb-430 msb-430h nrf51dk nrf51dongle nrf6310 \

View File

@ -12,7 +12,8 @@ TCP_SERVER_PORT ?= 80
TCP_TEST_CYCLES ?= 3
# Mark Boards with insufficient memory
BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560 \
BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove \
arduino-leonardo arduino-mega2560 \
arduino-nano arduino-uno calliope-mini chronos \
hifive1 i-nucleo-lrwan1 mega-xplained microbit \
msb-430 msb-430h \

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno calliope-mini chronos hifive1 \
i-nucleo-lrwan1 \
mega-xplained microbit msb-430 msb-430h \

View File

@ -1,7 +1,7 @@
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno nucleo-f031k6
USEMODULE += auto_init
USEMODULE += xtimer

View File

@ -1,8 +1,8 @@
APPLICATION = isr_yield_higher
include ../Makefile.tests_common
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-nano arduino-uno \
nucleo-f031k6
BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-leonardo arduino-nano \
arduino-uno nucleo-f031k6
USEMODULE += xtimer

View File

@ -1,6 +1,7 @@
include ../Makefile.tests_common
BOARD_BLACKLIST := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_BLACKLIST := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno jiminy-mega256rfr2 mega-xplained waspmote-pro
# arduino-mega2560: builds locally but breaks travis (possibly because of
# differences in the toolchain)

View File

@ -2,7 +2,8 @@ include ../Makefile.tests_common
# lwIP's memory management doesn't seem to work on non 32-bit platforms at the
# moment.
BOARD_BLACKLIST := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_BLACKLIST := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno chronos esp8266-esp-12x esp8266-olimex-mod \
esp8266-sparkfun-thing jiminy-mega256rfr2 mega-xplained \
msb-430 msb-430h telosb waspmote-pro \

View File

@ -2,7 +2,8 @@ include ../Makefile.tests_common
# lwIP's memory management doesn't seem to work on non 32-bit platforms at the
# moment.
BOARD_BLACKLIST := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_BLACKLIST := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno chronos esp8266-esp-12x esp8266-olimex-mod \
esp8266-sparkfun-thing jiminy-mega256rfr2 mega-xplained \
msb-430 msb-430h telosb waspmote-pro \

View File

@ -2,7 +2,8 @@ include ../Makefile.tests_common
# lwIP's memory management doesn't seem to work on non 32-bit platforms at the
# moment.
BOARD_BLACKLIST := arduino-duemilanove arduino-mega2560 arduino-nano \
BOARD_BLACKLIST := arduino-duemilanove arduino-leonardo \
arduino-mega2560 arduino-nano \
arduino-uno chronos esp8266-esp-12x esp8266-olimex-mod \
esp8266-sparkfun-thing jiminy-mega256rfr2 mega-xplained \
msb-430 msb-430h telosb waspmote-pro \

Some files were not shown because too many files have changed in this diff Show More