1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2024-12-29 04:50:03 +01:00

Merge pull request #8643 from Josar/jiminy_master

boards: Jiminy-mega256rfr2: initial support
This commit is contained in:
Peter Kietzmann 2018-03-02 15:24:39 +01:00 committed by GitHub
commit 215940b058
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
40 changed files with 874 additions and 30 deletions

View File

@ -0,0 +1,3 @@
MODULE = board
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,10 @@
include $(RIOTBOARD)/common/arduino-atmega/Makefile.features
# Put defined MCU peripherals here (in alphabetical order)
# Peripherals are defined in common/arduino-atmega/Makefile.features
# Add only additional Peripherals
# The board MPU family (used for grouping by the CI system)
FEATURES_MCU_GROUP = avr6
-include $(RIOTCPU)/atmega256rfr2/Makefile.features

View File

@ -0,0 +1,24 @@
# define the cpu used by the jiminy board
export CPU = atmega256rfr2
# export needed for flash rule
export PORT_LINUX ?= /dev/ttyACM0
export PORT_DARWIN ?= $(firstword $(sort $(wildcard /dev/tty.usbmodem*)))
# Serial Baud rate for Ffasher is configured to 500kBaud
# see /usr/include/asm-generic/termbits.h for availabel baudrates on your linux system
export PROGRAMMER_SPEED ?= 0010005
export FFLAGS += -p atmega256rfr2
# refine serial port information for pyterm
# For 8MHz F_CPU following Baudrate have good error rates
# 76923
# 38400
export BAUD = 38400
# PROGRAMMER defaults to arduino which is the internal flasher via USB. Can be
# overridden for debugging (which requires changes that require to use an ISP)
export PROGRAMMER ?= wiring
include $(RIOTBOARD)/common/arduino-atmega/Makefile.include

View File

@ -0,0 +1,80 @@
/*
* Copyright (C) 2016 RWTH Aachen, Josua Arndt
*
* 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_jiminy-mega256rfr2
* @{
*
* @file
* @brief Board specific implementations for the Jiminy Mega 256rfr2 board
* developed by the IAS of the RWTH Aachen University
*
* @author Josua Arndt <jarndt@ias.rwth-aachen.de>
*
* @}
*/
#include "board.h"
#include <stdio.h>
#include <avr/io.h>
#include "cpu.h"
#include "uart_stdio.h"
void SystemInit(void);
static int uart_putchar(char c, FILE *stream);
static int uart_getchar(FILE *stream);
static FILE uart_stdout = FDEV_SETUP_STREAM(uart_putchar, NULL, _FDEV_SETUP_WRITE);
static FILE uart_stdin = FDEV_SETUP_STREAM(NULL, uart_getchar, _FDEV_SETUP_READ);
void board_init(void)
{
/* initialize stdio via USART_0 */
SystemInit();
/* initialize the CPU */
cpu_init();
/* initialize the board LED (connected to pin PB7) */
/* Ports Pins as Output */
LED_PORT_DDR |= LED2_MASK | LED1_MASK | LED0_MASK;
/* All Pins Low so LEDs are off */
LED_PORT &= ~(LED2_MASK | LED1_MASK | LED0_MASK);
irq_enable();
}
/*Initialize the System, initialize IO via UART_0*/
void SystemInit(void)
{
/* initialize UART_0 for use as stdout */
uart_stdio_init();
stdout = &uart_stdout;
stdin = &uart_stdin;
/* Flush stdout */
puts("\f");
}
static int uart_putchar(char c, FILE *stream)
{
(void) stream;
uart_stdio_write(&c, 1);
return 0;
}
int uart_getchar(FILE *stream)
{
(void) stream;
char c;
uart_stdio_read(&c, 1);
return (int)c;
}

View File

@ -0,0 +1,113 @@
/*
* Copyright (C) 2016 RWTH Aachen, Josua Arndt
*
* 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_jiminy-mega256rfr2 Jiminy- Mega256rfr2
* @ingroup boards
* @brief Board specific files for the Jiminy Mega 256rfr2 board.
* @{
*
* @file
* @brief Board specific definitions for the Jiminy Mega 256rfr2 board.
*
* @author Josua Arndt <jarndt@ias.rwth-aachen.de>
* @author Steffen Robertz <steffen.robertz@rwth-aachen.de>
*/
#ifndef BOARD_H
#define BOARD_H
#include "cpu.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @name Baudrate for STDIO terminal
*
* The standard configuration for STDIO in spu/atmega_comman/periph/uart.c
* is to use double speed.
*
* For 8MHz F_CPU following Baudrate have good error rates
* 76923
* 38400
*
* Matches this with BAUD in Board/Makefile.include
*
* @{
*/
#ifndef UART_STDIO_BAUDRATE
#define UART_STDIO_BAUDRATE (38400U) /**< Sets Baudrate for e.g. Shell */
#endif
/** @} */
/**
* @name LED pin definitions and handlers
* @{
*/
#define LED_PORT PORTB
#define LED_PORT_DDR DDRB
#define LED0_PIN GPIO_PIN(1, 5)
#define LED1_PIN GPIO_PIN(1, 6)
#define LED2_PIN GPIO_PIN(1, 7)
#define LED0_MASK (1 << DDB5)
#define LED1_MASK (1 << DDB6)
#define LED2_MASK (1 << DDB7)
#define LED0_ON (LED_PORT |= LED0_MASK)
#define LED0_OFF (LED_PORT &= ~LED0_MASK)
#define LED0_TOGGLE (LED_PORT ^= LED0_MASK)
#define LED1_ON (LED_PORT |= LED1_MASK)
#define LED1_OFF (LED_PORT &= ~LED1_MASK)
#define LED1_TOGGLE (LED_PORT ^= LED1_MASK)
#define LED2_ON (LED_PORT |= LED2_MASK)
#define LED2_OFF (LED_PORT &= ~LED2_MASK)
#define LED2_TOGGLE (LED_PORT ^= LED2_MASK)
/** @} */
/**
* @name Context swap defines
* This emulates a software triggered interrupt
* @{
*/
#define AVR_CONTEXT_SWAP_INIT do { \
DDRE |= (1 << PE7); \
EICRB |= (1 << ISC70); \
EIMSK |= (1 << INT7); \
sei(); \
} while (0)
#define AVR_CONTEXT_SWAP_INTERRUPT_VECT INT7_vect
#define AVR_CONTEXT_SWAP_TRIGGER PORTE ^= (1 << PE7)
/** @} */
/**
* @name xtimer configuration values
* @{
*/
#define XTIMER_DEV TIMER_DEV(0)
#define XTIMER_CHAN (0)
#define XTIMER_WIDTH (16)
#define XTIMER_HZ (125000UL)
/** @} */
/**
* @brief Initialize board specific hardware, including clock, LEDs and std-IO
*/
void board_init(void);
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H */
/** @} */

View File

@ -0,0 +1,134 @@
/*
* Copyright (C) 2016 RWTH Aachen, Josua Arndt
*
* 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_jiminy-mega256rfr2
* @{
*
* @file
* @brief Peripheral MCU configuration for the Jiminy Mega 256rfr2 board
*
* @author Josua Arndt <jarndt@ias.rwth-aachen.de>
* @author Steffen Robertz <steffen.robertz@rwth-aachen.de>
*/
#ifndef PERIPH_CONF_H
#define PERIPH_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <avr/io.h>
#include "periph_cpu.h"
#include "atmega_regs_common.h"
#include "periph_cpu_common.h"
/**
* @name Clock configuration
* @{
*/
#define CLOCK_CORECLOCK (8000000UL)
/** @} */
/**
* @name Timer configuration
*
* ATTENTION RIOT Timer 0 is used for Xtimer which is system Timer
*
* The timer driver only supports the four 16-bit timers
* (Timer1, TST, Timer3, Timer4, Timer5), so those are the Timer we can use here.
* Timer 1, TST, PORT B5/6/7 Out, Port D4/6 In, Analog Comparator Input Capture, Output Compare Modulator, PWM
* Timer 3, TST, PORT E3/4/5 Out, Port E/6/7 In, Input or Output Compare and PWM Output
* Timer 4, TST, It can not be connected to any I/O Pin,
* Timer 5, TST, It can not be connected to any I/O Pin,
*
* Using Atmel Timer 4 and 5 seems to be the best choice
* Using Atmel Timer 4 as Xtimer
* and Atmel Timer 5 as timer available for the the application seems to be the best choice,
* as the special functions of the other timer are not lost.
* Atmel Timer1 to be used as PWM timer for RGB LED
* @{
*/
#define TIMER_NUMOF (3U)
#define TIMER_0 MEGA_TIMER4
#define TIMER_0_MASK &TIMSK4
#define TIMER_0_FLAG &TIFR4
#define TIMER_0_ISRA TIMER4_COMPA_vect
#define TIMER_0_ISRB TIMER4_COMPB_vect
#define TIMER_0_ISRC TIMER4_COMPC_vect
#define TIMER_1 MEGA_TIMER5
#define TIMER_1_MASK &TIMSK5
#define TIMER_1_FLAG &TIFR5
#define TIMER_1_ISRA TIMER5_COMPA_vect
#define TIMER_1_ISRB TIMER5_COMPB_vect
#define TIMER_1_ISRC TIMER5_COMPC_vect
#define TIMER_2 MEGA_TIMER1
#define TIMER_2_MASK &TIMSK1
#define TIMER_2_FLAG &TIFR1
#define TIMER_2_ISRA TIMER1_COMPA_vect
#define TIMER_2_ISRB TIMER1_COMPB_vect
#define TIMER_2_ISRC TIMER1_COMPC_vect
/** @} */
/**
* @name UART configuration
*
* The UART devices have fixed pin mappings, so all we need to do, is to specify
* which devices we would like to use and their corresponding RX interrupts. See
* the reference manual for the fixed pin mapping.
*
* @{
*/
#define UART_NUMOF (2U)
/* UART0 is used for stdio */
#define UART_0 MEGA_UART0
#define UART_0_ISR USART0_RX_vect
#define UART_1 MEGA_UART1
#define UART_1_ISR USART1_RX_vect
/** @} */
/**
* @name SPI configuration
*
* The atmega256rfr has only one hardware SPI with fixed pin configuration, so all
* we can do here, is to enable or disable it.
*
* PINS SS SCK MOSI MISO
* PB0 PB1 PB2 PB3
* @{
*/
#define SPI_NUMOF (1U) /* set to 0 to disable SPI */
/** @} */
/**
* @name I2C configuration
* @{
*/
#define I2C_NUMOF (1U)
/** @} */
/**
* @name ADC Configuration
* @{
*/
#define ADC_NUMOF (8U)
/** @} */
#ifdef __cplusplus
}
#endif
/** @} */
#endif /* PERIPH_CONF_H */

View File

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

View File

@ -0,0 +1,7 @@
include $(RIOTCPU)/atmega_common/Makefile.features
# common feature are defined in atmega_common/Makefile.features
# Only add Additional features
# Various other features (if any)
FEATURES_PROVIDED += periph_cpuid

View File

@ -0,0 +1,14 @@
# 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/
# explicitly tell the linker to link the syscalls and startup code.
# Without this the interrupt vectors will not be linked correctly!
export UNDEF += $(BINDIR)/cpu/startup.o
#include periph module
USEMODULE += periph
# CPU depends on the atmega common module, so include it
include $(ATMEGA_COMMON)Makefile.include

137
cpu/atmega256rfr2/cpu.c Normal file
View File

@ -0,0 +1,137 @@
/*
* Copyright (C) 2017 RWTH Aachen, Josua Arndt
*
* 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_atmega256rfr2
* @{
*
* @file
* @brief Implementation of the CPU initialization
*
* @author Steffen Robertz <steffen.robertz@rwth-aachen.de>
* @author Josua Arndt <jarndt@ias.rwth-aachen.de>
* @}
*/
#include <avr/io.h>
#include <avr/wdt.h>
#include <avr/pgmspace.h>
#include "cpu.h"
#include "board.h"
#include "periph/init.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
/*
* Since this MCU does not feature a software reset, the watchdog timer
* is being used. It will be set to the shortest time and then force a
* reset. Therefore the MCUSR register needs to be resetted as fast as
* possible. In this case in the bootloader already. In order to regain
* information about the reset cause, the MCUSR is copied to r2 beforehand.
* When a software reset was triggered, r3 will contain 0xAA. In order to
* prevent changes to the values from the .init section, r2 and r3 are saved
* in the .init0 section
*/
uint8_t mcusr_mirror __attribute__((section(".noinit")));
uint8_t soft_rst __attribute__((section(".noinit")));
void get_mcusr(void) __attribute__((naked)) __attribute__((section(".init0")));
void get_mcusr(void)
{
/* save the reset flags passed from the bootloader */
__asm__ __volatile__("mov %0, r2\n" : "=r" (mcusr_mirror) :);
__asm__ __volatile__("mov %0, r3\n" : "=r" (soft_rst) :);
}
void _reset_cause(void)
{
if (mcusr_mirror & (1 << PORF)) {
DEBUG("Power-on reset.\n");
}
if (mcusr_mirror & (1 << EXTRF)) {
DEBUG("External reset!\n");
}
if (mcusr_mirror & (1 << BORF)) {
DEBUG("Brownout reset!\n");
}
if (mcusr_mirror & (1 << WDRF)) {
if (soft_rst & 0xAA) {
DEBUG("Software reset!\n");
} else {
DEBUG("Watchdog reset!\n");
}
}
if (mcusr_mirror & (1 << JTRF)) {
DEBUG("JTAG reset!\n");
}
}
void cpu_init(void)
{
_reset_cause();
wdt_reset(); /* should not be nececessary as done in bootloader */
wdt_disable(); /* but when used without bootloader this is needed */
/* Set system clock Prescaler */
CLKPR = (1 << CLKPCE); /* enable a change to CLKPR */
/* set the Division factor to 1 results in divisor 2 for internal Oscillator
* So FCPU = 8MHz
*
* Attention!
* The CPU can not be used with the external xtal oscillator if the core
* should be put in sleep while the transceiver is in rx mode.
*
* It seems the as teh peripheral clock divider is set to 1 and this all
* clocks of the timer, etc run with 16MHz increasing power consumption.
* */
CLKPR = 0;
/* Initialize peripherals for which modules are included in the makefile.*/
/* spi_init */
/* rtc_init */
/* hwrng_init */
periph_init();
}
/* This is a vector which is aliased to __vector_default,
* the vector executed when an ISR fires with no accompanying
* ISR handler. This may be used along with the ISR() macro to
* create a catch-all for undefined but used ISRs for debugging
* purposes.
* SCIRQS Symbol Counter Interrupt Status Register
* BATMON Battery Monitor Control and Status Register
* IRQ_STATUS /1 Transceiver Interrupt Status Register
* EIFR External Interrupt Flag Register
* PCIFR Pin Change Interrupt Flag Register
*/
ISR(BADISR_vect){
_reset_cause();
printf_P(PSTR("FATAL ERROR: BADISR_vect called, unprocessed Interrupt.\n"
"STOP Execution.\n"));
printf("IRQ_STATUS %#02x\nIRQ_STATUS1 %#02x\n",
(unsigned int)IRQ_STATUS, (unsigned int)IRQ_STATUS1 );
printf("SCIRQS %#02x\nBATMON %#02x\n", (unsigned int)SCIRQS, (unsigned int)BATMON );
printf("EIFR %#02x\nPCIFR %#02x\n", (unsigned int)EIFR, (unsigned int)PCIFR );
/* White LED light is used to signal ERROR. */
LED_PORT |= (LED2_MASK | LED1_MASK | LED0_MASK);
while (1) {}
}
ISR(BAT_LOW_vect, ISR_BLOCK){
__enter_isr();
DEBUG("BAT_LOW \n");
__exit_isr();
}

View File

@ -0,0 +1,5 @@
/**
* @defgroup cpu_atmega256rfr2 Atmel ATmega256rfr2
* @ingroup cpu
* @brief Implementation of Atmel's ATmega256rfr2 MCU
*/

View File

@ -0,0 +1,51 @@
/*
* Copyright (C) 2017 RWTH Aachen, Josua Arndt
*
* 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_atmega256rfr2
* @{
*
* @file
* @brief Implementation specific CPU configuration options
*
* @author Josua Arndt <jarndt@ias.rwth-aachen.de>
* @author Steffen Robertz <steffen.robertz@rwth-aachen.de>
*/
#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 sucessfully even with pretty small stacks.k
* @{
*/
/* keep THREAD_STACKSIZE_IDLE > THREAD_EXTRA_STACKSIZE_PRINTF
* to avoid not printing of debug in interrupts
*/
#define THREAD_EXTRA_STACKSIZE_PRINTF (128)
#ifndef THREAD_STACKSIZE_DEFAULT
#define THREAD_STACKSIZE_DEFAULT (512)
#endif
#define THREAD_STACKSIZE_IDLE (129)
#ifdef __cplusplus
}
#endif
#endif /* CPU_CONF_H */
/** @} */

View File

@ -0,0 +1,71 @@
/*
* Copyright (C) Josua Arndt, Steffen Robertz 2017 RWTH Aachen
*
* 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_atmega256rfr2
* @{
*
* @file
* @brief CPU specific definitions for internal peripheral handling
*
* @author Josua Arndt <jarndt@ias.rwth-aachen.de>
* @author Steffen Robertz <steffen.robertz@rwth-aachen.de>
*/
#ifndef PERIPH_CPU_H
#define PERIPH_CPU_H
#include "periph_cpu_common.h"
#include "atmega_regs_common.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @name Length of the CPU_ID in octets
* @{
*/
#define CPUID_LEN (8U)
/** @} */
/**
* @name Available ports on the ATmega256rfr family
* @{
*/
enum {
PORT_B = 1, /**< port B */
PORT_D = 3, /**< port D */
PORT_E = 4, /**< port E */
PORT_F = 5, /**< port F */
PORT_G = 6, /**< port G */
};
/**
* @name Defines for the I2C interface
* @{
*/
#define I2C_PORT_REG PORTD
#define I2C_PIN_MASK (1 << PORTD1) | (1 << PORTD0)
/** @} */
/**
* @name GPIO pin not defined
* @{
*/
#ifndef GPIO_UNDEF
#define GPIO_UNDEF (0xFFFF)
#endif
/** @}*/
#ifdef __cplusplus
}
#endif
#endif /* PERIPH_CPU_H */
/** @} */

View File

@ -0,0 +1 @@
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,76 @@
/*
* Copyright (C) 2018 RWTH Aachen, Josua Arndt, Steffen Robertz
*
* 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_atmega256rfr2
* @{
*
* @file
* @brief Low-level CPUID driver implementation
*
* @author Steffen Robertz <steffen.robertz@rwth-aachen.de>
* @author Josua Arndt <jarndt@ias.rwth-aachen.de>
*
* @}
*/
#include <stdio.h>
#include <stdint.h>
#include <string.h>
#include "periph/cpuid.h"
#include "atmega_regs_common.h"
#include "avr/boot.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
/**
* @brief CPU_ID build from MCU register
*
* CPIUD is taken from MCU Control Register and Signature bytes.
* CPUID: 1e a8 02 1f 94 03 ff ff
* CPUID: 1e a8 02 1f 94 92 XX XX
* MEGA62/128/256_RFR2 [MANUAL] p.505
* MEGA62/128/256_RFR2 [MANUAL] p.138
* MEGA62/128/256_RFR2 [MANUAL] p.492
*
* usr_sign_0/1 are configurable values on flash page 1.
*/
void cpuid_get(void *id)
{
uint8_t signature_0 = boot_signature_byte_get(0x00);
uint8_t signature_1 = boot_signature_byte_get(0x02);
uint8_t signature_2 = boot_signature_byte_get(0x04);
uint8_t usr_sign_0 = boot_signature_byte_get(0x0100);
uint8_t usr_sign_1 = boot_signature_byte_get(0x0102);
uint8_t addr[CPUID_LEN] = {
signature_0, /* 0x1E Atmel manufacturer ID */
signature_1, /* 0xA8 Part Number high byte */
signature_2, /* 0x02 Part Number low byte */
MAN_ID_0, /* 0x1F Atmel JEDEC manufacturer ID */
PART_NUM, /* 0x94 PART_NUM Identification */
VERSION_NUM, /* 0x02 VERSION_NUM Identification */
/* last two bytes can be set to flash page 1. for differentiation of different boards */
usr_sign_0, /* user signature 0 */
usr_sign_1, /* user signature 1 */
};
#if defined(ENABLE_DEBUG)
DEBUG("CPUID: " );
for (uint8_t i=0; i<CPUID_LEN; i++)
{
DEBUG(" %02x ", addr[i] );
}
DEBUG("\n" );
#endif
memcpy( id , addr, CPUID_LEN);
}

View File

@ -0,0 +1,72 @@
/*
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
*
* 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_atmega256rfr2
* @{
*
* @file
* @brief Startup code and interrupt vector definition
*
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
* @author Josua Arndt <jarndt@ias.rwth-aachen.de>
* @author Steffen Robertz <steffen.robertz@rwth-aachen.de>
* @}
*/
#include <stdint.h>
#include <avr/interrupt.h>
#include <avr/io.h>
/* For Catchall-Loop */
#include "board.h"
/**
* @brief functions for initializing the board, std-lib and kernel
*/
extern void board_init(void);
extern void kernel_init(void);
extern void __libc_init_array(void);
/**
* @brief This pair of functions hook circumvent the call to main
*
* avr-libc normally uses the .init9 section for a call to main. This call
* seems to be not replaceable without hacking inside the library. We
* circumvent the call to main by using section .init7 to call the function
* reset_handler which therefore is the real entry point and section .init8
* which should never be reached but just in case jumps to exit.
* This way there should be no way to call main directly.
*/
void init7_ovr(void) __attribute__((section(".init7")));
void init8_ovr(void) __attribute__((section(".init8")));
__attribute__((used, naked)) void init7_ovr(void)
{
__asm__ ("call reset_handler");
}
__attribute__((used, naked)) void init8_ovr(void)
{
__asm__ ("jmp exit");
}
/**
* @brief This function is the entry point after a system reset
*
* After a system reset, the following steps are necessary and carried out:
* 1. initialize the board (sync clock, setup std-IO)
* 2. initialize and start RIOTs kernel
*/
__attribute__((used)) void reset_handler(void)
{
/* initialize the board and startup the kernel */
board_init();
/* startup the kernel */
kernel_init();
}

View File

@ -111,7 +111,7 @@ int adc_sample(adc_t line, adc_res_t res)
#if defined(CPU_ATMEGA328P) || defined(CPU_ATMEGA1281)
ADMUX &= 0xf0;
ADMUX |= line;
#elif defined(CPU_ATMEGA2560)
#elif defined(CPU_ATMEGA2560) || defined(CPU_ATMEGA256RFR2)
if (line < 8) {
ADCSRB &= ~(1 << MUX5);
ADMUX &= 0xf0;

View File

@ -23,7 +23,6 @@
* @}
*/
#include <stdio.h>
#include <avr/interrupt.h>
@ -289,9 +288,10 @@ ISR(INT6_vect, ISR_BLOCK)
}
#endif
#if defined(INT7_vect)
#if defined(INT7_vect) && !defined(BOARD_JIMINY_MEGA256RFR2)
/**< INT7 is context swap pin for the Jiminy board */
ISR(INT7_vect, ISR_BLOCK)
{
irq_handler(7); /**< predefined interrupt pin */
}
#endif
#endif /* INT7_vect && END BOARD_JIMINY_MEGA256RFR2 */

View File

@ -1,5 +1,6 @@
/*
* Copyright (C) 2016 Kaspar Schleiser <kaspar@schleiser.de>
* Copyright (C) 2018 Josua Arndt <jarndt@ias.rwth-aachen.de>
* 2016 Kaspar Schleiser <kaspar@schleiser.de>
* 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
*
* This file is subject to the terms and conditions of the GNU Lesser
@ -17,6 +18,7 @@
*
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
* @author Kaspar Schleiser <kaspar@schleiser.de>
* @author Josua Arndt <jarndt@ias.rwth-aachen.de>
*
* @}
*/
@ -28,6 +30,15 @@
void pm_reboot(void)
{
#if defined(CPU_ATMEGA256RFR2)
/* clear MCU Status Register Interrupt flags */
MCUSR = 0x00;
/* Softreset recognition feature, "r3" will be read out in .init0
* to be able to distinguish WDT reset and WDT software reset
*/
__asm__ __volatile__("mov r3, %0\n" :: "r" (0xAA));
#endif /* CPU_ATMEGA256RFR2 */
/*
* Since the AVR doesn't support a real software reset, we set the Watchdog
* Timer on a 250ms timeout. Consider this a kludge.

View File

@ -54,9 +54,20 @@ void spi_init_pins(spi_t bus)
#if defined (CPU_ATMEGA2560) || defined (CPU_ATMEGA1281)
DDRB |= ((1 << DDB2) | (1 << DDB1) | (1 << DDB0));
#endif
#ifdef CPU_ATMEGA328P
#if defined (CPU_ATMEGA328P)
DDRB |= ((1 << DDB2) | (1 << DDB3) | (1 << DDB5));
#endif
#if defined (CPU_ATMEGA256RFR2)
/* Master: PB3 MISO set to out
* PB2 MOSI set to input by hardware
* PB1 SCK set to out
* PB0 /CS kept as is, has to be configured by user. Flexibility to
* use different /CS pin.
* Only Master supported. Slave: Only MOSI has to be set as Input.
* ATmega256RFR2 data sheet p. 365
* */
DDRB |= ((1 << DDB2) | (1 << DDB1));
#endif
}
int spi_acquire(spi_t bus, spi_cs_t cs, spi_mode_t mode, spi_clk_t clk)

View File

@ -10,7 +10,7 @@ RIOTBASE ?= $(CURDIR)/../..
# TinyDTLS only has support for 32-bit architectures ATM
BOARD_BLACKLIST := arduino-duemilanove arduino-mega2560 arduino-uno chronos \
msb-430 msb-430h telosb waspmote-pro wsn430-v1_3b wsn430-v1_4 \
z1
z1 jiminy-mega256rfr2
BOARD_INSUFFICIENT_MEMORY := airfy-beacon b-l072z-lrwan1 bluepill calliope-mini \
cc2650-launchpad cc2650stk maple-mini \

View File

@ -14,7 +14,7 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon b-l072z-lrwan1 bluepill calliope-mini
BOARD_BLACKLIST := arduino-duemilanove arduino-mega2560 arduino-uno chronos \
msb-430 msb-430h telosb waspmote-pro wsn430-v1_3b \
wsn430-v1_4 z1 pic32-wifire pic32-clicker
wsn430-v1_4 z1 pic32-wifire pic32-clicker jiminy-mega256rfr2
# 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

@ -10,6 +10,7 @@ BOARD_BLACKLIST += telosb
BOARD_BLACKLIST += waspmote-pro
BOARD_BLACKLIST += wsn430-v1_3b wsn430-v1_4
BOARD_BLACKLIST += z1
BOARD_BLACKLIST += jiminy-mega256rfr2
USEMODULE += cbor
USEMODULE += cbor_ctime

View File

@ -1,7 +1,8 @@
include ../Makefile.tests_common
# the stm32f4discovery does not have the arduino pinout
BOARD_BLACKLIST := stm32f4discovery
BOARD_BLACKLIST := stm32f4discovery jiminy-mega256rfr2
# currently the test provides config params for arduinos only
FEATURES_REQUIRED += arduino

View File

@ -1,9 +1,9 @@
include ../Makefile.tests_common
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove \
jiminy-mega256rfr2
# arduino-mega2560: builds locally but breaks travis (possibly because of
# differences in the toolchain)
# 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

View File

@ -4,7 +4,7 @@ include ../Makefile.tests_common
# moment.
BOARD_BLACKLIST := arduino-uno arduino-duemilanove arduino-mega2560 chronos \
msb-430 msb-430h telosb waspmote-pro wsn430-v1_3b \
wsn430-v1_4 z1
wsn430-v1_4 z1 jiminy-mega256rfr2
BOARD_INSUFFICIENT_MEMORY := airfy-beacon nrf6310 nucleo32-f031 nucleo32-f042 \
nucleo32-l031 nucleo-f030 nucleo-f334 nucleo-l053 \
stm32f0discovery yunjia-nrf51822

View File

@ -4,7 +4,7 @@ include ../Makefile.tests_common
# moment.
BOARD_BLACKLIST := arduino-uno arduino-duemilanove arduino-mega2560 chronos \
msb-430 msb-430h telosb waspmote-pro wsn430-v1_3b \
wsn430-v1_4 z1
wsn430-v1_4 z1 jiminy-mega256rfr2
BOARD_INSUFFICIENT_MEMORY = nucleo32-f031 nucleo32-f042 nucleo32-l031 nucleo-f030 \
nucleo-f334 nucleo-l053 stm32f0discovery

View File

@ -4,7 +4,7 @@ include ../Makefile.tests_common
# moment.
BOARD_BLACKLIST := arduino-uno arduino-duemilanove arduino-mega2560 chronos \
msb-430 msb-430h telosb waspmote-pro wsn430-v1_3b \
wsn430-v1_4 z1
wsn430-v1_4 z1 jiminy-mega256rfr2
BOARD_INSUFFICIENT_MEMORY = nucleo32-f031 nucleo32-f042 nucleo32-l031 nucleo-f030 \
nucleo-f334 nucleo-l053 stm32f0discovery

View File

@ -4,7 +4,7 @@ include ../Makefile.tests_common
# moment.
BOARD_BLACKLIST := arduino-uno arduino-duemilanove arduino-mega2560 chronos \
msb-430 msb-430h telosb waspmote-pro wsn430-v1_3b \
wsn430-v1_4 z1
wsn430-v1_4 z1 jiminy-mega256rfr2
BOARD_INSUFFICIENT_MEMORY = nucleo32-f031 nucleo32-f042 nucleo32-l031 nucleo-f030 \
nucleo-f334 nucleo-l053 stm32f0discovery

View File

@ -2,7 +2,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
arduino-duemilanove jiminy-mega256rfr2
BOARD_INSUFFICIENT_MEMORY := nucleo32-f031 nucleo32-f042 nucleo32-l031 nucleo-f030 \
nucleo-f334 nucleo-l053 stm32f0discovery

View File

@ -1,5 +1,7 @@
include ../Makefile.tests_common
#malloc.h not found
BOARD_BLACKLIST := jiminy-mega256rfr2
BOARD_INSUFFICIENT_MEMORY := nucleo32-f031
USEMODULE += pipe

View File

@ -2,7 +2,8 @@ include ../Makefile.tests_common
# msp430 and avr have problems with int width and libcoaps usage of :x notation in structs
BOARD_BLACKLIST := arduino-mega2560 chronos msb-430 msb-430h telosb wsn430-v1_3b \
wsn430-v1_4 z1 waspmote-pro arduino-uno arduino-duemilanove
wsn430-v1_4 z1 waspmote-pro arduino-uno arduino-duemilanove \
jiminy-mega256rfr2
BOARD_INSUFFICIENT_MEMORY := chronos msb-430 msb-430h nucleo32-f031 nucleo32-f042 \
nucleo32-l031 nucleo-f030 nucleo-f070 nucleo-f334 nucleo-l053 \
stm32f0discovery telosb wsn430-v1_3b wsn430-v1_4 \

View File

@ -1,7 +1,9 @@
include ../Makefile.tests_common
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove \
jiminy-mega256rfr2
# arduino mega2560 uno duemilanove : unknown type name: clockid_t
# jiminy-mega256rfr2: unknown type name: clockid_t
USEMODULE += posix
USEMODULE += pthread

View File

@ -1,7 +1,9 @@
include ../Makefile.tests_common
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove
# arduino mega2560 uno duemilanove: unknown type name: clockid_t
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove \
jiminy-mega256rfr2
# arduino mega2560 uno duemilanove : unknown type name: clockid_t
# jiminy-mega256rfr2: unknown type name: clockid_t
# exclude boards with insufficient memory
BOARD_INSUFFICIENT_MEMORY := nucleo32-f031

View File

@ -1,7 +1,9 @@
include ../Makefile.tests_common
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove \
jiminy-mega256rfr2
# arduino mega2560 uno duemilanove : unknown type name: clockid_t
# jiminy-mega256rfr2: unknown type name: clockid_t
USEMODULE += pthread

View File

@ -1,7 +1,9 @@
include ../Makefile.tests_common
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove
# arduino mega2560 uno duemilanove: unknown type name: clockid_t
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove \
jiminy-mega256rfr2
# arduino mega2560 uno duemilanove : unknown type name: clockid_t
# jiminy-mega256rfr2: unknown type name: clockid_t
BOARD_INSUFFICIENT_MEMORY := nucleo32-f031

View File

@ -1,7 +1,9 @@
include ../Makefile.tests_common
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove
# arduino mega2560 uno duemilanove: unknown type name: clockid_t
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove \
jiminy-mega256rfr2
# arduino mega2560 uno duemilanove : unknown type name: clockid_t
# jiminy-mega256rfr2: unknown type name: clockid_t
BOARD_INSUFFICIENT_MEMORY := nucleo32-f031

View File

@ -1,7 +1,9 @@
include ../Makefile.tests_common
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove
# arduino mega2560 uno duemilanove: unknown type name: clockid_t
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove \
jiminy-mega256rfr2
# arduino mega2560 uno duemilanove : unknown type name: clockid_t
# jiminy-mega256rfr2: unknown type name: clockid_t
USEMODULE += pthread
USEMODULE += xtimer

View File

@ -1,7 +1,9 @@
include ../Makefile.tests_common
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove
# arduino mega2560 uno duemilanove: unknown type name: clockid_t
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove \
jiminy-mega256rfr2
# arduino mega2560 uno duemilanove : unknown type name: clockid_t
# jiminy-mega256rfr2: unknown type name: clockid_t
USEMODULE += posix
USEMODULE += pthread

View File

@ -3,7 +3,7 @@ include ../Makefile.tests_common
# avr8, msp430 and mips don't support ssp (yet)
BOARD_BLACKLIST := arduino-mega2560 waspmote-pro arduino-uno arduino-duemilanove \
chronos msb-430 msb-430h telosb wsn430-v1_3b wsn430-v1_4 z1 \
pic32-clicker pic32-wifire
pic32-clicker pic32-wifire jiminy-mega256rfr2
USEMODULE += ssp