diff --git a/boards/common/atmega/include/periph_conf_atmega_common.h b/boards/common/atmega/include/periph_conf_atmega_common.h index 257f1fba9d..24cc3f3d5e 100644 --- a/boards/common/atmega/include/periph_conf_atmega_common.h +++ b/boards/common/atmega/include/periph_conf_atmega_common.h @@ -93,6 +93,14 @@ 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 @@ -129,7 +137,7 @@ extern "C" { #define TIMER_0_FLAG &TIFR1 #define TIMER_0_ISRA TIMER1_COMPA_vect #define TIMER_0_ISRB TIMER1_COMPB_vect -#elif defined(CPU_ATMEGA1284P) +#elif defined(CPU_ATMEGA1284P) || defined(CPU_ATMEGA32U4) #define TIMER_NUMOF (2U) #define TIMER_CHANNELS (2) @@ -138,12 +146,18 @@ extern "C" { #define TIMER_0_FLAG &TIFR1 #define TIMER_0_ISRA TIMER1_COMPA_vect #define TIMER_0_ISRB TIMER1_COMPB_vect + #ifdef CPU_ATMEGA32U4 + #define TIMER_0_ISRC TIMER1_COMPC_vect + #endif #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 + #ifdef CPU_ATMEGA32U4 + #define TIMER_1_ISRC TIMER3_COMPC_vect + #endif #elif defined(CPU_ATMEGA2560) || defined(CPU_ATMEGA1281) #define TIMER_NUMOF (2U) #define TIMER_CHANNELS (3) @@ -192,6 +206,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 +224,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 +284,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 +316,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])) diff --git a/cpu/atmega32u4/Makefile b/cpu/atmega32u4/Makefile new file mode 100644 index 0000000000..81f110b68d --- /dev/null +++ b/cpu/atmega32u4/Makefile @@ -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 diff --git a/cpu/atmega32u4/Makefile.features b/cpu/atmega32u4/Makefile.features new file mode 100644 index 0000000000..008260685b --- /dev/null +++ b/cpu/atmega32u4/Makefile.features @@ -0,0 +1 @@ +-include $(RIOTCPU)/atmega_common/Makefile.features diff --git a/cpu/atmega32u4/Makefile.include b/cpu/atmega32u4/Makefile.include new file mode 100644 index 0000000000..baaebcb351 --- /dev/null +++ b/cpu/atmega32u4/Makefile.include @@ -0,0 +1,18 @@ +# 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 + +# 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 + +# CPU depends on the atmega common module, so include it +include $(ATMEGA_COMMON)Makefile.include diff --git a/cpu/atmega32u4/cpu.c b/cpu/atmega32u4/cpu.c new file mode 100644 index 0000000000..0eca9cb905 --- /dev/null +++ b/cpu/atmega32u4/cpu.c @@ -0,0 +1,30 @@ +/* + * Copyright (C) 2017 Thomas Perrot + * + * 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 + * @} + */ + +#include "cpu.h" +#include "periph/init.h" + +/** + * @brief Initialize the CPU, set IRQ priorities + */ +void cpu_init(void) +{ + /* trigger static peripheral initialization */ + periph_init(); +} diff --git a/cpu/atmega32u4/doc.txt b/cpu/atmega32u4/doc.txt new file mode 100644 index 0000000000..37b6eef431 --- /dev/null +++ b/cpu/atmega32u4/doc.txt @@ -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 + */ diff --git a/cpu/atmega32u4/include/cpu_conf.h b/cpu/atmega32u4/include/cpu_conf.h new file mode 100644 index 0000000000..31812c92b1 --- /dev/null +++ b/cpu/atmega32u4/include/cpu_conf.h @@ -0,0 +1,50 @@ +/* + * Copyright (C) 2017 Thomas Perrot + * + * 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 + * + */ + +#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 */ +/** @} */ diff --git a/cpu/atmega32u4/include/periph_cpu.h b/cpu/atmega32u4/include/periph_cpu.h new file mode 100644 index 0000000000..7bb719dfc0 --- /dev/null +++ b/cpu/atmega32u4/include/periph_cpu.h @@ -0,0 +1,71 @@ +/* + * Copyright (C) 2017 Thomas Perrot + * + * 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 + * + */ + +#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 */ +/** @} */ diff --git a/cpu/atmega32u4/startup.c b/cpu/atmega32u4/startup.c new file mode 100644 index 0000000000..d5a7989486 --- /dev/null +++ b/cpu/atmega32u4/startup.c @@ -0,0 +1,73 @@ +/* + * Copyright (C) 2017 Thomas Perrot + * + * 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 Startup code and interrupt vector definition + * + * @author Thomas Perrot + * + * @} + */ + +#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/include/atmega_regs_common.h b/cpu/atmega_common/include/atmega_regs_common.h index b2e8c07fe4..85cd67abc7 100644 --- a/cpu/atmega_common/include/atmega_regs_common.h +++ b/cpu/atmega_common/include/atmega_regs_common.h @@ -1,6 +1,7 @@ /* * Copyright (C) 2016 Freie Universität Berlin * 2016 INRIA + * 2017 Thomas Perrot * * 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 * @author Francisco Acosta + * @author Thomas Perrot + * */ #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; diff --git a/cpu/atmega_common/periph/adc.c b/cpu/atmega_common/periph/adc.c index db6fd79502..a51f2e929d 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) _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) diff --git a/cpu/atmega_common/periph/spi.c b/cpu/atmega_common/periph/spi.c index de4ac97cfc..c0124c2147 100644 --- a/cpu/atmega_common/periph/spi.c +++ b/cpu/atmega_common/periph/spi.c @@ -2,6 +2,7 @@ * Copyright (C) 2015 Daniel Amkaer Sorensen * 2016 Freie Universität Berlin * 2017 Hamburg University of Applied Sciences + * 2017 Thomas Perrot * * 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 * @author Hauke Petersen * @author Dimitri Nahm + * @author Thomas Perrot * * @} */ @@ -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) diff --git a/cpu/atmega_common/periph/uart.c b/cpu/atmega_common/periph/uart.c index 2a195f78c4..1d62bc1640 100644 --- a/cpu/atmega_common/periph/uart.c +++ b/cpu/atmega_common/periph/uart.c @@ -1,5 +1,6 @@ /* * Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen + * 2017 Thomas Perrot * * 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 * @author Hinnerk van Bruinehsen + * @author Thomas Perrot * * * 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]; } } diff --git a/cpu/atmega_common/thread_arch.c b/cpu/atmega_common/thread_arch.c index 763b716c52..db9607d11f 100644 --- a/cpu/atmega_common/thread_arch.c +++ b/cpu/atmega_common/thread_arch.c @@ -1,5 +1,6 @@ /* * Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen + * 2017 Thomas Perrot * 2018 RWTH Aachen, Josua Arndt * * 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 + * @author Thomas Perrot * @author Josua Arndt * * @} @@ -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 diff --git a/sys/pipe/pipe_dynamic.c b/sys/pipe/pipe_dynamic.c index b6ecd2982d..410b41a3cc 100644 --- a/sys/pipe/pipe_dynamic.c +++ b/sys/pipe/pipe_dynamic.c @@ -25,7 +25,7 @@ * @} */ -#if defined(MCU_ATMEGA2560) || defined(MCU_ATMEGA1281) || defined(MCU_ATMEGA328P) +#if defined(MCU_ATMEGA2560) || defined(MCU_ATMEGA1281) || defined(MCU_ATMEGA328P) || defined(MCU_ATMEGA32U4) #include #else #include