diff --git a/boards/jiminy-mega256rfr2/Makefile b/boards/jiminy-mega256rfr2/Makefile new file mode 100644 index 0000000000..f8fcbb53a0 --- /dev/null +++ b/boards/jiminy-mega256rfr2/Makefile @@ -0,0 +1,3 @@ +MODULE = board + +include $(RIOTBASE)/Makefile.base diff --git a/boards/jiminy-mega256rfr2/Makefile.features b/boards/jiminy-mega256rfr2/Makefile.features new file mode 100644 index 0000000000..4e78995dd6 --- /dev/null +++ b/boards/jiminy-mega256rfr2/Makefile.features @@ -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 diff --git a/boards/jiminy-mega256rfr2/Makefile.include b/boards/jiminy-mega256rfr2/Makefile.include new file mode 100644 index 0000000000..a0fc16954e --- /dev/null +++ b/boards/jiminy-mega256rfr2/Makefile.include @@ -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 diff --git a/boards/jiminy-mega256rfr2/board.c b/boards/jiminy-mega256rfr2/board.c new file mode 100644 index 0000000000..193385591e --- /dev/null +++ b/boards/jiminy-mega256rfr2/board.c @@ -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 + * + * @} + */ + +#include "board.h" + +#include +#include + +#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; +} diff --git a/boards/jiminy-mega256rfr2/include/board.h b/boards/jiminy-mega256rfr2/include/board.h new file mode 100644 index 0000000000..632bc78d98 --- /dev/null +++ b/boards/jiminy-mega256rfr2/include/board.h @@ -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 + * @author Steffen Robertz + */ + +#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 */ +/** @} */ diff --git a/boards/jiminy-mega256rfr2/include/periph_conf.h b/boards/jiminy-mega256rfr2/include/periph_conf.h new file mode 100644 index 0000000000..94efb799db --- /dev/null +++ b/boards/jiminy-mega256rfr2/include/periph_conf.h @@ -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 + * @author Steffen Robertz + */ + +#ifndef PERIPH_CONF_H +#define PERIPH_CONF_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include +#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 */ diff --git a/cpu/atmega256rfr2/Makefile b/cpu/atmega256rfr2/Makefile new file mode 100644 index 0000000000..5148810cfa --- /dev/null +++ b/cpu/atmega256rfr2/Makefile @@ -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 diff --git a/cpu/atmega256rfr2/Makefile.features b/cpu/atmega256rfr2/Makefile.features new file mode 100644 index 0000000000..f5ad466ab1 --- /dev/null +++ b/cpu/atmega256rfr2/Makefile.features @@ -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 diff --git a/cpu/atmega256rfr2/Makefile.include b/cpu/atmega256rfr2/Makefile.include new file mode 100644 index 0000000000..4e3aa39e06 --- /dev/null +++ b/cpu/atmega256rfr2/Makefile.include @@ -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 diff --git a/cpu/atmega256rfr2/cpu.c b/cpu/atmega256rfr2/cpu.c new file mode 100644 index 0000000000..fa3b7d4e33 --- /dev/null +++ b/cpu/atmega256rfr2/cpu.c @@ -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 + * @author Josua Arndt + * @} + */ + +#include +#include +#include +#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(); +} diff --git a/cpu/atmega256rfr2/doc.txt b/cpu/atmega256rfr2/doc.txt new file mode 100644 index 0000000000..44fff73707 --- /dev/null +++ b/cpu/atmega256rfr2/doc.txt @@ -0,0 +1,5 @@ +/** + * @defgroup cpu_atmega256rfr2 Atmel ATmega256rfr2 + * @ingroup cpu + * @brief Implementation of Atmel's ATmega256rfr2 MCU + */ diff --git a/cpu/atmega256rfr2/include/cpu_conf.h b/cpu/atmega256rfr2/include/cpu_conf.h new file mode 100644 index 0000000000..0a4cee9368 --- /dev/null +++ b/cpu/atmega256rfr2/include/cpu_conf.h @@ -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 + * @author Steffen Robertz + */ + +#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 */ +/** @} */ diff --git a/cpu/atmega256rfr2/include/periph_cpu.h b/cpu/atmega256rfr2/include/periph_cpu.h new file mode 100644 index 0000000000..731149bb5a --- /dev/null +++ b/cpu/atmega256rfr2/include/periph_cpu.h @@ -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 + * @author Steffen Robertz + */ + +#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 */ +/** @} */ diff --git a/cpu/atmega256rfr2/periph/Makefile b/cpu/atmega256rfr2/periph/Makefile new file mode 100644 index 0000000000..48422e909a --- /dev/null +++ b/cpu/atmega256rfr2/periph/Makefile @@ -0,0 +1 @@ +include $(RIOTBASE)/Makefile.base diff --git a/cpu/atmega256rfr2/periph/cpuid.c b/cpu/atmega256rfr2/periph/cpuid.c new file mode 100644 index 0000000000..2fa936bea3 --- /dev/null +++ b/cpu/atmega256rfr2/periph/cpuid.c @@ -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 + * @author Josua Arndt + * + * @} + */ +#include +#include +#include + +#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 + * @author Josua Arndt + * @author Steffen Robertz + * @} + */ + +#include +#include +#include + +/* 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(); +} diff --git a/cpu/atmega_common/periph/adc.c b/cpu/atmega_common/periph/adc.c index fac2ad8918..81bc224c9f 100644 --- a/cpu/atmega_common/periph/adc.c +++ b/cpu/atmega_common/periph/adc.c @@ -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; diff --git a/cpu/atmega_common/periph/gpio.c b/cpu/atmega_common/periph/gpio.c index e74db5d68c..28d48bd7b7 100644 --- a/cpu/atmega_common/periph/gpio.c +++ b/cpu/atmega_common/periph/gpio.c @@ -23,7 +23,6 @@ * @} */ - #include #include @@ -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 */ diff --git a/cpu/atmega_common/periph/pm.c b/cpu/atmega_common/periph/pm.c index 1bed7f8d1b..609d2ce4bd 100644 --- a/cpu/atmega_common/periph/pm.c +++ b/cpu/atmega_common/periph/pm.c @@ -1,5 +1,6 @@ /* - * Copyright (C) 2016 Kaspar Schleiser + * Copyright (C) 2018 Josua Arndt + * 2016 Kaspar Schleiser * 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 * @author Kaspar Schleiser + * @author Josua Arndt * * @} */ @@ -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. diff --git a/cpu/atmega_common/periph/spi.c b/cpu/atmega_common/periph/spi.c index 6b89e73e7b..fb2fcd2e40 100644 --- a/cpu/atmega_common/periph/spi.c +++ b/cpu/atmega_common/periph/spi.c @@ -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) diff --git a/examples/dtls-echo/Makefile b/examples/dtls-echo/Makefile index 26d1c4291f..d1ed70d12a 100644 --- a/examples/dtls-echo/Makefile +++ b/examples/dtls-echo/Makefile @@ -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 \ diff --git a/examples/javascript/Makefile b/examples/javascript/Makefile index 042975bf97..fa25993b88 100644 --- a/examples/javascript/Makefile +++ b/examples/javascript/Makefile @@ -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 diff --git a/tests/cbor/Makefile b/tests/cbor/Makefile index a39b552142..c4f82bdb41 100644 --- a/tests/cbor/Makefile +++ b/tests/cbor/Makefile @@ -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 diff --git a/tests/driver_hd44780/Makefile b/tests/driver_hd44780/Makefile index 02ea04e922..0c28e37ef2 100644 --- a/tests/driver_hd44780/Makefile +++ b/tests/driver_hd44780/Makefile @@ -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 diff --git a/tests/libfixmath_unittests/Makefile b/tests/libfixmath_unittests/Makefile index e28ec3efed..d68880bea5 100644 --- a/tests/libfixmath_unittests/Makefile +++ b/tests/libfixmath_unittests/Makefile @@ -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 diff --git a/tests/lwip/Makefile b/tests/lwip/Makefile index b64158a1ef..aaac98aa03 100644 --- a/tests/lwip/Makefile +++ b/tests/lwip/Makefile @@ -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 diff --git a/tests/lwip_sock_ip/Makefile b/tests/lwip_sock_ip/Makefile index 351ad7cdd6..af42718505 100644 --- a/tests/lwip_sock_ip/Makefile +++ b/tests/lwip_sock_ip/Makefile @@ -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 diff --git a/tests/lwip_sock_tcp/Makefile b/tests/lwip_sock_tcp/Makefile index eb920b03b5..0896baba86 100644 --- a/tests/lwip_sock_tcp/Makefile +++ b/tests/lwip_sock_tcp/Makefile @@ -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 diff --git a/tests/lwip_sock_udp/Makefile b/tests/lwip_sock_udp/Makefile index e22e13014c..44c5f98eed 100644 --- a/tests/lwip_sock_udp/Makefile +++ b/tests/lwip_sock_udp/Makefile @@ -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 diff --git a/tests/nhdp/Makefile b/tests/nhdp/Makefile index d22af6bc41..f937942132 100644 --- a/tests/nhdp/Makefile +++ b/tests/nhdp/Makefile @@ -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 diff --git a/tests/pipe/Makefile b/tests/pipe/Makefile index 911723007b..09c994a8f1 100644 --- a/tests/pipe/Makefile +++ b/tests/pipe/Makefile @@ -1,5 +1,7 @@ include ../Makefile.tests_common +#malloc.h not found +BOARD_BLACKLIST := jiminy-mega256rfr2 BOARD_INSUFFICIENT_MEMORY := nucleo32-f031 USEMODULE += pipe diff --git a/tests/pkg_libcoap/Makefile b/tests/pkg_libcoap/Makefile index 49d9fc7185..c9c2f33057 100644 --- a/tests/pkg_libcoap/Makefile +++ b/tests/pkg_libcoap/Makefile @@ -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 \ diff --git a/tests/pthread/Makefile b/tests/pthread/Makefile index 025b79c4c1..c578999ab6 100644 --- a/tests/pthread/Makefile +++ b/tests/pthread/Makefile @@ -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 diff --git a/tests/pthread_barrier/Makefile b/tests/pthread_barrier/Makefile index e3fff2d8c1..b5a1b60bbc 100644 --- a/tests/pthread_barrier/Makefile +++ b/tests/pthread_barrier/Makefile @@ -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 diff --git a/tests/pthread_cleanup/Makefile b/tests/pthread_cleanup/Makefile index e8ee9114a2..5ccdedc5a3 100644 --- a/tests/pthread_cleanup/Makefile +++ b/tests/pthread_cleanup/Makefile @@ -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 diff --git a/tests/pthread_condition_variable/Makefile b/tests/pthread_condition_variable/Makefile index 3e47cc3df4..f953f20961 100644 --- a/tests/pthread_condition_variable/Makefile +++ b/tests/pthread_condition_variable/Makefile @@ -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 diff --git a/tests/pthread_cooperation/Makefile b/tests/pthread_cooperation/Makefile index c9076fbddb..ec335fd587 100644 --- a/tests/pthread_cooperation/Makefile +++ b/tests/pthread_cooperation/Makefile @@ -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 diff --git a/tests/pthread_rwlock/Makefile b/tests/pthread_rwlock/Makefile index 872f6ac984..3557468ad8 100644 --- a/tests/pthread_rwlock/Makefile +++ b/tests/pthread_rwlock/Makefile @@ -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 diff --git a/tests/pthread_tls/Makefile b/tests/pthread_tls/Makefile index d3176b05cf..c578999ab6 100644 --- a/tests/pthread_tls/Makefile +++ b/tests/pthread_tls/Makefile @@ -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 diff --git a/tests/ssp/Makefile b/tests/ssp/Makefile index 842461b75d..9e1715010c 100644 --- a/tests/ssp/Makefile +++ b/tests/ssp/Makefile @@ -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