diff --git a/cpu/atmega2560/Makefile b/cpu/atmega2560/Makefile index 5148810cfa673b6e7b397f91f539d7f7c1627c69..e17e41db7225d898b224d42b91d3f00fa6f6bc0f 100644 --- a/cpu/atmega2560/Makefile +++ b/cpu/atmega2560/Makefile @@ -1,5 +1,5 @@ # define the module that is build MODULE = cpu # add a list of subdirectories, that should also be build -DIRS = periph $(ATMEGA_COMMON) +DIRS = $(ATMEGA_COMMON) include $(RIOTBASE)/Makefile.base diff --git a/cpu/atmega2560/Makefile.include b/cpu/atmega2560/Makefile.include index 2efb70e9b8b152de0b4c5671c8c2f5e13df520e6..dfbc4bc326ca6e6f72f4eb5f553da819391a013f 100644 --- a/cpu/atmega2560/Makefile.include +++ b/cpu/atmega2560/Makefile.include @@ -4,12 +4,6 @@ export CFLAGS += -DCOREIF_NG=1 # tell the build system that the CPU depends on the atmega common files USEMODULE += atmega_common -# export the peripheral drivers to be linked into the final binary -export USEMODULE += periph - -# the atmel port uses uart_stdio -export USEMODULE += uart_stdio - # define path to atmega common module, which is needed for this CPU export ATMEGA_COMMON = $(RIOTCPU)/atmega_common/ diff --git a/cpu/atmega2560/include/atmega2560_regs.h b/cpu/atmega2560/include/atmega2560_regs.h deleted file mode 100644 index 9a47ee5759125e7d4a15ac089fe97f013daf0690..0000000000000000000000000000000000000000 --- a/cpu/atmega2560/include/atmega2560_regs.h +++ /dev/null @@ -1,96 +0,0 @@ -/* - * Copyright (C) 2016 Freie Universität Berlin - * - * 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_atmega2560 - * @{ - * - * @file - * @brief CMSIS style register definitions for the atmega2560 - * - * @author Hauke Petersen <hauke.petersen@fu-berlin.de> - */ - -#ifndef ATMEGA2560_REGS_H -#define ATMEGA2560_REGS_H - -#include <avr/io.h> - -#ifdef __cplusplus -extern "C" { -#endif - -/** - * @brief Register types - * @{ - */ -#define REG8 volatile uint8_t -#define REG16 volatile uint16_t -/** @} */ - -/** - * @brief Timer register map - */ -typedef struct { - REG8 CRA; /**< control A */ - REG8 CRB; /**< control B */ - REG8 CRC; /**< control C */ - REG8 reserved; /**< reserved */ - REG16 CNT; /**< counter */ - REG16 ICR; /**< input capture */ - REG16 OCR[3]; /**< output compare */ -} mega_timer_t; - -/** - * @brief UART register map - */ -typedef struct { - REG8 CSRA; /**< control and status register A */ - REG8 CSRB; /**< control and status register B */ - REG8 CSRC; /**< control and status register C */ - REG8 reserved; /**< reserved */ - REG16 BRR; /**< baud rate register */ - REG8 DR; /**< data register */ -} mega_uart_t; - -/** - * @brief Base register address definitions - * @{ - */ -#define MEGA_TIMER1_BASE (uint16_t *)(&TCCR1A) -#define MEGA_TIMER3_BASE (uint16_t *)(&TCCR3A) -#define MEGA_TIMER4_BASE (uint16_t *)(&TCCR4A) -#define MEGA_TIMER5_BASE (uint16_t *)(&TCCR5A) - -#define MEGA_UART0_BASE ((uint16_t *)(&UCSR0A)) -#define MEGA_UART1_BASE ((uint16_t *)(&UCSR1A)) -#define MEGA_UART2_BASE ((uint16_t *)(&UCSR2A)) -#define MEGA_UART3_BASE ((uint16_t *)(&UCSR3A)) -/** @} */ - -/** - * @brief Peripheral instances - * @{ - */ -#define MEGA_TIMER1 ((mega_timer_t *)MEGA_TIMER1_BASE) -#define MEGA_TIMER3 ((mega_timer_t *)MEGA_TIMER3_BASE) -#define MEGA_TIMER4 ((mega_timer_t *)MEGA_TIMER4_BASE) -#define MEGA_TIMER5 ((mega_timer_t *)MEGA_TIMER5_BASE) - -#define MEGA_UART0 ((mega_uart_t *)MEGA_UART0_BASE) -#define MEGA_UART1 ((mega_uart_t *)MEGA_UART1_BASE) -#define MEGA_UART2 ((mega_uart_t *)MEGA_UART2_BASE) -#define MEGA_UART3 ((mega_uart_t *)MEGA_UART3_BASE) -/** @} */ - -#ifdef __cplusplus -} -#endif - -#endif /* ATMEGA2560_REGS_H */ -/** @} */ diff --git a/cpu/atmega2560/include/cpu_conf.h b/cpu/atmega2560/include/cpu_conf.h index 2219a0af402826471fa70de34f8e044600e0fab1..7216b2800649d56238449266d156b8d0f1befd40 100644 --- a/cpu/atmega2560/include/cpu_conf.h +++ b/cpu/atmega2560/include/cpu_conf.h @@ -20,7 +20,7 @@ #ifndef CPU_CONF_H #define CPU_CONF_H -#include "atmega2560_regs.h" +#include "atmega_regs_common.h" #ifdef __cplusplus extern "C" { diff --git a/cpu/atmega2560/include/periph_cpu.h b/cpu/atmega2560/include/periph_cpu.h index 9d94934bb86224cf2738a62b86f35a45b69e43b4..9f08ffdaeefebb9d81444529f62e612b6c3b20ea 100644 --- a/cpu/atmega2560/include/periph_cpu.h +++ b/cpu/atmega2560/include/periph_cpu.h @@ -21,15 +21,12 @@ #ifndef PERIPH_CPU_H_ #define PERIPH_CPU_H_ +#include "periph_cpu_common.h" + #ifdef __cplusplus extern "C" { #endif -/** - * @brief Define a CPU specific GPIO pin generator macro - */ -#define GPIO_PIN(x, y) ((x << 4) | y) - /** * @brief Available ports on the ATmega2560 family */ @@ -47,54 +44,6 @@ enum { PORT_L = 10 /**< port L */ }; -/** - * @brief SPI mode select macro - * - * The polarity is determined by bit 3 in the configuration register, the phase - * by bit 2. - */ -#define SPI_MODE_SEL(pol, pha) ((pol << 3) | (pha << 2)) - -/** - * @brief Override the SPI mode values - * - * As the mode is set in bit 3 and 2 of the configuration register, we put the - * correct configuration there - * @{ - */ -#define HAVE_SPI_CONF_T -typedef enum { - SPI_CONF_FIRST_RISING = SPI_MODE_SEL(0, 0), /**< mode 0 */ - SPI_CONF_SECOND_RISING = SPI_MODE_SEL(0, 1), /**< mode 1 */ - SPI_CONF_FIRST_FALLING = SPI_MODE_SEL(1, 0), /**< mode 2 */ - SPI_CONF_SECOND_FALLING = SPI_MODE_SEL(1, 1) /**< mode 3 */ -} spi_conf_t; -/** @} */ - -/** - * @brief SPI speed selection macro - * - * We encode the speed in bits 2, 1, and 0, where bit0 and bit1 hold the SPCR - * prescaler bits, while bit2 holds the SPI2X bit. - */ -#define SPI_SPEED_SEL(s2x, pr1, pr0) ((s2x << 2) | (pr1 << 1) | pr0) - -/** - * @brief Override SPI speed values - * - * We assume a master clock speed of 16MHz here. - * @{ - */ -#define HAVE_SPI_SPEED_T -typedef enum { - SPI_SPEED_100KHZ = SPI_SPEED_SEL(0, 1, 1), /**< 16/128 -> 125KHz */ - SPI_SPEED_400KHZ = SPI_SPEED_SEL(1, 1, 0), /**< 16/32 -> 500KHz */ - SPI_SPEED_1MHZ = SPI_SPEED_SEL(0, 0, 1), /**< 16/16 -> 1MHz */ - SPI_SPEED_5MHZ = SPI_SPEED_SEL(0, 0, 0), /**< 16/4 -> 4MHz */ - SPI_SPEED_10MHZ = SPI_SPEED_SEL(1, 0, 0) /**< 16/2 -> 8MHz */ -} spi_speed_t; -/** @} */ - #ifdef __cplusplus } #endif diff --git a/cpu/atmega2560/periph/Makefile b/cpu/atmega2560/periph/Makefile deleted file mode 100644 index 6d1887b640099d130c5a6400e3f878f0c65aa6f1..0000000000000000000000000000000000000000 --- a/cpu/atmega2560/periph/Makefile +++ /dev/null @@ -1,3 +0,0 @@ -MODULE = periph - -include $(RIOTBASE)/Makefile.base diff --git a/cpu/atmega2560/periph/gpio.c b/cpu/atmega2560/periph/gpio.c deleted file mode 100644 index 7ce2ec76616b4c8b3393853c14712191ced76030..0000000000000000000000000000000000000000 --- a/cpu/atmega2560/periph/gpio.c +++ /dev/null @@ -1,257 +0,0 @@ -/* - * Copyright (C) 2015 HAW Hamburg - - * - * This file is subject to the terms and conditions of the GNU Lesser - * General Public License v2.1. See the file LICENSE in the top level - * directory for more details. - */ - -/** - * @ingroup driver_periph - * @{ - * - * @file - * @brief Low-level GPIO driver implementation for ATmega2560 - * - * @author René Herthel <rene-herthel@outlook.de> - * - * @} - */ - - -#include <stdio.h> - -#include <avr/interrupt.h> - -#include "cpu.h" -#include "periph/gpio.h" -#include "periph_conf.h" - -#define GPIO_BASE_PORT_A (0x20) -#define GPIO_OFFSET_PORT_H (0xCB) -#define GPIO_OFFSET_PIN_PORT (0x02) -#define GPIO_OFFSET_PIN_PIN (0x03) -#define GPIO_EXT_INT_NUMOF (8U) - -static gpio_isr_ctx_t config[GPIO_EXT_INT_NUMOF]; - -/** - * @brief Extract the pin number of the given pin - */ -static inline uint8_t _pin_num(gpio_t pin) -{ - return (pin & 0x0f); -} - -/** - * @brief Extract the port number of the given pin - */ -static inline uint8_t _port_num(gpio_t pin) -{ - return (pin >> 4) & 0x0f; -} - -/** - * @brief Generate the PORTx address of the give pin. - */ -static inline uint16_t _port_addr(gpio_t pin) -{ - uint8_t port_num = _port_num(pin); - uint16_t port_addr = port_num * GPIO_OFFSET_PIN_PIN; - - port_addr += GPIO_BASE_PORT_A; - port_addr += GPIO_OFFSET_PIN_PORT; - - if (port_num > PORT_G) { - port_addr += GPIO_OFFSET_PORT_H; - } - - return port_addr; -} - -/** - * @brief Generate the DDRx address of the given pin - */ -static inline uint16_t _ddr_addr(gpio_t pin) -{ - return (_port_addr(pin) - 0x01); -} - -/** - * @brief Generate the PINx address of the given pin. - */ -static inline uint16_t _pin_addr(gpio_t pin) -{ - return (_port_addr(pin) - 0x02); -} - -int gpio_init(gpio_t pin, gpio_mode_t mode) -{ - switch (mode) { - case GPIO_OUT: - _SFR_MEM8(_ddr_addr(pin)) |= (1 << _pin_num(pin)); - break; - case GPIO_IN: - _SFR_MEM8(_ddr_addr(pin)) &= ~(1 << _pin_num(pin)); - _SFR_MEM8(_port_addr(pin)) &= ~(1 << _pin_num(pin)); - break; - case GPIO_IN_PU: - _SFR_MEM8(_port_addr(pin)) |= (1 << _pin_num(pin)); - break; - default: - return -1; - } - - return 0; -} - -int gpio_init_int(gpio_t pin, gpio_mode_t mode, gpio_flank_t flank, - gpio_cb_t cb, void *arg) -{ - uint8_t pin_num = _pin_num(pin); - - if ((_port_num(pin) == PORT_D && pin_num > 3) - || (_port_num(pin) == PORT_E && pin_num < 4) - || ((mode != GPIO_IN) && (mode != GPIO_IN_PU))) { - return -1; - } - - gpio_init(pin, mode); - - /* clear global interrupt flag */ - cli(); - - EIMSK |= (1 << pin_num); - - /* configure the flank */ - switch (flank) { - case GPIO_RISING: - if (pin_num < 4) { - EICRA |= (3 << pin_num * 2); - } - else { - EICRB |= (3 << (pin_num * 2) % 4); - } - break; - case GPIO_FALLING: - if (pin_num < 4) { - EICRA |= (2 << pin_num * 2); - } - else { - EICRB |= (2 << (pin_num * 2) % 4); - } - break; - case GPIO_BOTH: - if (pin_num < 4) { - EICRA |= (1 << pin_num * 2); - } - else { - EICRB |= (1 << (pin_num * 2) % 4); - } - break; - default: - return -1; - }; - - /* set callback */ - config[pin_num].cb = cb; - config[pin_num].arg = arg; - - /* set global interrupt flag */ - sei(); - - return 0; -} - -void gpio_irq_enable(gpio_t pin) -{ - EIMSK |= (1 << _pin_num(pin)); -} - -void gpio_irq_disable(gpio_t pin) -{ - EIMSK &= ~(1 << _pin_num(pin)); -} - -int gpio_read(gpio_t pin) -{ - return (_SFR_MEM8(_pin_addr(pin)) & (1 << _pin_num(pin))); -} - -void gpio_set(gpio_t pin) -{ - _SFR_MEM8(_port_addr(pin)) |= (1 << _pin_num(pin)); -} - -void gpio_clear(gpio_t pin) -{ - _SFR_MEM8(_port_addr(pin)) &= ~(1 << _pin_num(pin)); -} - -void gpio_toggle(gpio_t pin) -{ - if (gpio_read(pin)) { - gpio_clear(pin); - } - else { - gpio_set(pin); - } -} - -void gpio_write(gpio_t pin, int value) -{ - if (value) { - gpio_set(pin); - } - else { - gpio_clear(pin); - } -} - -static inline void irq_handler(uint8_t pin_num) -{ - __enter_isr(); - config[pin_num].cb(config[pin_num].arg); - __exit_isr(); -} - -ISR(INT0_vect, ISR_BLOCK) -{ - irq_handler(0); /**< predefined interrupt pin */ -} - -ISR(INT1_vect, ISR_BLOCK) -{ - irq_handler(1); /**< predefined interrupt pin */ -} - -ISR(INT2_vect, ISR_BLOCK) -{ - irq_handler(2); /**< predefined interrupt pin */ -} - -ISR(INT3_vect, ISR_BLOCK) -{ - irq_handler(3); /**< predefined interrupt pin */ -} - -ISR(INT4_vect, ISR_BLOCK) -{ - irq_handler(4); /**< predefined interrupt pin */ -} - -ISR(INT5_vect, ISR_BLOCK) -{ - irq_handler(5); /**< predefined interrupt pin */ -} - -ISR(INT6_vect, ISR_BLOCK) -{ - irq_handler(6); /**< predefined interrupt pin */ -} - -ISR(INT7_vect, ISR_BLOCK) -{ - irq_handler(7); /**< predefined interrupt pin */ -} diff --git a/cpu/atmega2560/periph/spi.c b/cpu/atmega2560/periph/spi.c deleted file mode 100644 index 17f1e85b7dadd2be1a62a4a9968e9d1f5d83e6be..0000000000000000000000000000000000000000 --- a/cpu/atmega2560/periph/spi.c +++ /dev/null @@ -1,145 +0,0 @@ -/* - * Copyright (C) 2015 Daniel Amkaer Sorensen - * 2016 Freie Universität Berlin - * - * 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_atmega2560 - * @{ - * - * @file - * @brief Low-level SPI driver implementation - * - * @author Daniel Amkaer Sorensen <daniel.amkaer@gmail.com> - * @author Hauke Petersen <hauke.petersen@fu-berlin.de> - * - * @} - */ - -#include "cpu.h" -#include "mutex.h" -#include "periph/spi.h" - -/* guard this file in case no SPI device is defined */ -#if SPI_NUMOF - -/** - * @brief Extract BR0, BR1 and SPI2X bits from speed value - * @{ - */ -#define SPEED_MASK (0x3) -#define S2X_SHIFT (2) -/** @} */ - -static mutex_t lock = MUTEX_INIT; - -int spi_init_master(spi_t dev, spi_conf_t conf, spi_speed_t speed) -{ - /* make sure device is valid (there is only one...) */ - if (dev != 0) { - return -1; - } - - /* the pin configuration for this CPU is fixed: - * - PB3: MISO (configure as input - done automatically) - * - PB2: MOSI (configure as output) - * - PB1: SCK (configure as output) - * - PB0: SS (configure as output, but unused) - * - * 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 - * select externally for now) - */ - DDRB |= ((1 << DDB2) | (1 << DDB1) | (1 << DDB0)); - - /* make sure the SPI is not powered off */ - PRR0 &= ~(1 << PRSPI); - - /* configure as master, with given mode and clock */ - SPSR = (speed >> S2X_SHIFT); - SPCR = ((1 << SPE) | (1 << MSTR) | conf | (speed & SPEED_MASK)); - - /* clear interrupt flag */ - (void)SPSR; - (void)SPDR; - - return 0; -} - -int spi_acquire(spi_t dev) -{ - mutex_lock(&lock); - return 0; -} - -int spi_release(spi_t dev) -{ - mutex_unlock(&lock); - return 0; -} - -int spi_init_slave(spi_t dev, spi_conf_t conf, char (*cb)(char data)) -{ - (void) dev; - (void) conf; - (void) cb; - - /* not implemented */ - return -1; -} - -void spi_transmission_begin(spi_t dev, char reset_val) -{ - (void)dev; - (void)reset_val; - - /* not implemented */ -} - -int spi_transfer_byte(spi_t dev, char out, char *in) -{ - return spi_transfer_bytes(dev, &out, in, 1); -} - -int spi_transfer_bytes(spi_t dev, char *out, char *in, unsigned int length) -{ - for (unsigned int i = 0; i < length; i++) { - char tmp = (out) ? out[i] : 0; - SPDR = tmp; - while (!(SPSR & (1 << SPIF))) {} - tmp = SPDR; - if (in) { - in[i] = tmp; - } - } - - return (int)length; -} - -int spi_transfer_reg(spi_t dev, uint8_t reg, char out, char *in) -{ - spi_transfer_bytes(dev, (char *)®, NULL, 1); - return spi_transfer_bytes(dev, &out, in, 1); -} - -int spi_transfer_regs(spi_t dev, uint8_t reg, char *out, char *in, unsigned int length) -{ - spi_transfer_bytes(dev, (char *)®, NULL, 1); - return spi_transfer_bytes(dev, out, in, length); -} - -void spi_poweron(spi_t dev) -{ - SPCR |= (1 << SPE); -} - -void spi_poweroff(spi_t dev) -{ - SPCR &= ~(1 << SPE); -} - -#endif /* SPI_NUMOF */ diff --git a/cpu/atmega2560/periph/timer.c b/cpu/atmega2560/periph/timer.c deleted file mode 100644 index e923f6666aeedd4841fe3d9e352fc759755f63f6..0000000000000000000000000000000000000000 --- a/cpu/atmega2560/periph/timer.c +++ /dev/null @@ -1,258 +0,0 @@ -/* - * 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 driver_periph - * @{ - * - * @file - * @brief Low-level timer driver implementation for the ATmega2560 CPU - * - * @author Hauke Petersen <hauke.petersen@fu-berlin.de> - * @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de> - * - * @} - */ - -#include <avr/interrupt.h> - -#include "board.h" -#include "cpu.h" -#include "thread.h" - -#include "periph/timer.h" -#include "periph_conf.h" - -/** - * @brief All timers have three channels - */ -#define CHANNELS (3) - -/** - * @brief We have 5 possible prescaler values - */ -#define PRESCALE_NUMOF (5U) - -/** - * @brief Possible prescaler values, encoded as 2 ^ val - */ -static const uint8_t prescalers[] = { 0, 3, 6, 8, 10 }; - -/** - * @brief Timer state context - */ -typedef struct { - mega_timer_t *dev; /**< timer device */ - volatile uint8_t *mask; /**< address of interrupt mask register */ - volatile uint8_t *flag; /**< address of interrupt flag register */ - timer_cb_t cb; /**< interrupt callback */ - void *arg; /**< interrupt callback argument */ - uint8_t mode; /**< remember the configured mode */ - uint8_t isrs; /**< remember the interrupt state */ -} ctx_t; - -/** - * @brief Allocate memory for saving the device states - * @{ - */ -#if TIMER_NUMOF -static ctx_t ctx[] = { -#ifdef TIMER_0 - { TIMER_0, TIMER_0_MASK, TIMER_0_FLAG, NULL, NULL, 0, 0 }, -#endif -#ifdef TIMER_1 - { TIMER_1, TIMER_1_MASK, TIMER_1_FLAG, NULL, NULL, 0, 0 }, -#endif -#ifdef TIMER_2 - { TIMER_2, TIMER_2_MASK, TIMER_2_FLAG, NULL, NULL, 0, 0 }, -#endif -#ifdef TIMER_3 - { TIMER_3, TIMER_3_MASK, TIMER_3_FLAG, NULL, NULL, 0, 0 }, -#endif -}; -#else -/* fallback if no timer is configured */ -static ctx_t *ctx[] = {{ NULL }}; -#endif -/** @} */ - -/** - * @brief Setup the given timer - */ -int timer_init(tim_t tim, unsigned long freq, timer_cb_t cb, void *arg) -{ - uint8_t pre = 0; - - /* make sure given device is valid */ - if (tim >= TIMER_NUMOF) { - return -1; - } - - /* figure out if freq is applicable */ - for (; pre < PRESCALE_NUMOF; pre++) { - if ((CLOCK_CORECLOCK >> prescalers[pre]) == freq) { - break; - } - } - if (pre == PRESCALE_NUMOF) { - return -1; - } - - /* stop and reset timer */ - ctx[tim].dev->CRA = 0; - ctx[tim].dev->CRB = 0; - ctx[tim].dev->CRC = 0; - ctx[tim].dev->CNT = 0; - - /* save interrupt context and timer mode */ - ctx[tim].cb = cb; - ctx[tim].arg = arg; - ctx[tim].mode = (pre + 1); - - /* enable timer with calculated prescaler */ - ctx[tim].dev->CRB = (pre + 1); - - return 0; -} - -int timer_set(tim_t tim, int channel, unsigned int timeout) -{ - return timer_set_absolute(tim, channel, timer_read(tim) + timeout); -} - -int timer_set_absolute(tim_t tim, int channel, unsigned int value) -{ - if (channel >= CHANNELS) { - return -1; - } - - ctx[tim].dev->OCR[channel] = (uint16_t)value; - *ctx[tim].flag &= ~(1 << (channel + OCF1A)); - *ctx[tim].mask |= (1 << (channel + OCIE1A)); - - return 0; -} - -int timer_clear(tim_t tim, int channel) -{ - if (channel >= CHANNELS) { - return -1; - } - - *ctx[tim].mask &= ~(1 << (channel + OCIE1A)); - - return 0; -} - -unsigned int timer_read(tim_t tim) -{ - return (unsigned int)ctx[tim].dev->CNT; -} - -void timer_stop(tim_t tim) -{ - ctx[tim].dev->CRB = 0; -} - -void timer_start(tim_t tim) -{ - ctx[tim].dev->CRB = ctx[tim].mode; -} - -void timer_irq_enable(tim_t tim) -{ - *ctx[tim].mask = ctx[tim].isrs; -} - -void timer_irq_disable(tim_t tim) -{ - ctx[tim].isrs = *(ctx[tim].mask); - *ctx[tim].mask = 0; -} - -static inline void _isr(int num, int chan) -{ - __enter_isr(); - - *ctx[num].mask &= ~(1 << (chan + OCIE1A)); - ctx[num].cb(ctx[num].arg, chan); - - if (sched_context_switch_request) { - thread_yield(); - } - - __exit_isr(); -} - -#ifdef TIMER_0 -ISR(TIMER_0_ISRA, ISR_BLOCK) -{ - _isr(0, 0); -} - -ISR(TIMER_0_ISRB, ISR_BLOCK) -{ - _isr(0, 1); -} - -ISR(TIMER_0_ISRC, ISR_BLOCK) -{ - _isr(0, 2); -} -#endif /* TIMER_0 */ - -#ifdef TIMER_1 -ISR(TIMER_1_ISRA, ISR_BLOCK) -{ - _isr(1, 0); -} - -ISR(TIMER_1_ISRB, ISR_BLOCK) -{ - _isr(1, 1); -} - -ISR(TIMER_1_ISRC, ISR_BLOCK) -{ - _isr(1, 2); -} -#endif /* TIMER_1 */ - -#ifdef TIMER_2 -ISR(TIMER_2_ISRA, ISR_BLOCK) -{ - _isr(2, 0); -} - -ISR(TIMER_2_ISRB, ISR_BLOCK) -{ - _isr(2, 1); -} - -ISR(TIMER_2_ISRC, ISR_BLOCK) -{ - _isr(2, 2); -} -#endif /* TIMER_2 */ - -#ifdef TIMER_3 -ISR(TIMER_3_ISRA, ISR_BLOCK) -{ - _isr(2, 0); -} - -ISR(TIMER_3_ISRB, ISR_BLOCK) -{ - _isr(2, 1); -} - -ISR(TIMER_3_ISRC, ISR_BLOCK) -{ - _isr(2, 2); -} -#endif /* TIMER_3 */ diff --git a/cpu/atmega2560/periph/uart.c b/cpu/atmega2560/periph/uart.c deleted file mode 100644 index 4736f570549701b5d15ba2a3f68449e8c06d5191..0000000000000000000000000000000000000000 --- a/cpu/atmega2560/periph/uart.c +++ /dev/null @@ -1,133 +0,0 @@ -/* - * 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 driver_periph - * @{ - * - * @file - * @brief Low-level UART driver implementation - * - * @author Hauke Petersen <hauke.petersen@fu-berlin.de> - * @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de> - * - * @} - */ - -#include "cpu.h" -#include "sched.h" -#include "thread.h" - -#include "periph/uart.h" - -/** - * @brief Configured device map - * @{ - */ -#if UART_NUMOF -static mega_uart_t *dev[] = { -#ifdef UART_0 - UART_0, -#endif -#ifdef UART_1 - UART_1, -#endif -#ifdef UART_2 - UART_2, -#endif -#ifdef UART_3 - UART_3 -#endif -}; -#else -/* fallback if no UART is defined */ -static const mega_uart_t *dev[] = { NULL }; -#endif - -/** - * @brief Allocate memory to store the callback functions. - */ -static uart_isr_ctx_t isr_ctx[UART_NUMOF]; - -int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg) -{ - /* make sure the given device is valid */ - if (uart >= UART_NUMOF) { - return -1; - } - - /* register interrupt context */ - isr_ctx[uart].rx_cb = rx_cb; - isr_ctx[uart].arg = arg; - - /* disable and reset UART */ - dev[uart]->CSRB = 0; - dev[uart]->CSRA = 0; - - /* configure UART to 8N1 mode */ - dev[uart]->CSRC = (1 << UCSZ00) | (1 << UCSZ01); - /* set clock divider */ - dev[uart]->BRR = CLOCK_CORECLOCK / (16 * baudrate); - /* enable RX and TX and the RX interrupt */ - dev[uart]->CSRB = ((1 << RXCIE0) | (1 << RXEN0) | (1 << TXEN0)); - - return 0; -} - -void uart_write(uart_t uart, const uint8_t *data, size_t len) -{ - for (size_t i = 0; i < len; i++) { - while (!(dev[uart]->CSRA & (1 << UDRE0))); - dev[uart]->DR = data[i]; - } -} - -static inline void isr_handler(int num) -{ - isr_ctx[num].rx_cb(isr_ctx[num].arg, dev[num]->DR); - - if (sched_context_switch_request) { - thread_yield(); - } -} - -#ifdef UART_0_ISR -ISR(UART_0_ISR, ISR_BLOCK) -{ - __enter_isr(); - isr_handler(0); - __exit_isr(); -} -#endif /* UART_0_ISR */ - -#ifdef UART_1_ISR -ISR(UART_1_ISR, ISR_BLOCK) -{ - __enter_isr(); - isr_handler(1); - __exit_isr(); -} -#endif /* UART_1_ISR */ - -#ifdef UART_2_ISR -ISR(UART_2_ISR, ISR_BLOCK) -{ - __enter_isr(); - isr_handler(2); - __exit_isr(); -} -#endif /* UART_2_ISR */ - -#ifdef UART_3_ISR -ISR(UART_3_ISR, ISR_BLOCK) -{ - __enter_isr(); - isr_handler(3); - __exit_isr(); -} -#endif /* UART_3_ISR */ diff --git a/cpu/atmega_common/Makefile b/cpu/atmega_common/Makefile index affd083e6f421d0c12c9d2bcc1b92e59b057f832..387e91627c4526c4990e6aef48bc8e5bc75b41eb 100644 --- a/cpu/atmega_common/Makefile +++ b/cpu/atmega_common/Makefile @@ -1,5 +1,5 @@ - # define the module that is build MODULE = atmega_common - +# add a list of subdirectories, that should also be build +DIRS = periph include $(RIOTBASE)/Makefile.base