From 17c78e70e2914d63a21c246129afeeaf34faf341 Mon Sep 17 00:00:00 2001 From: kYc0o <fco.ja.ac@gmail.com> Date: Mon, 6 Jun 2016 17:54:42 +0200 Subject: [PATCH] cpu/atmega_common: add common atmega CPU code to atmega_common --- cpu/atmega2560/Makefile.include | 3 - cpu/atmega_common/Makefile.include | 6 + .../include/atmega_regs_common.h | 116 ++++++++ cpu/atmega_common/include/periph_cpu_common.h | 88 ++++++ cpu/atmega_common/periph/Makefile | 3 + cpu/atmega_common/periph/gpio.c | 270 ++++++++++++++++++ cpu/atmega_common/periph/spi.c | 151 ++++++++++ cpu/atmega_common/periph/timer.c | 266 +++++++++++++++++ cpu/atmega_common/periph/uart.c | 133 +++++++++ 9 files changed, 1033 insertions(+), 3 deletions(-) create mode 100644 cpu/atmega_common/include/atmega_regs_common.h create mode 100644 cpu/atmega_common/include/periph_cpu_common.h create mode 100644 cpu/atmega_common/periph/Makefile create mode 100644 cpu/atmega_common/periph/gpio.c create mode 100644 cpu/atmega_common/periph/spi.c create mode 100644 cpu/atmega_common/periph/timer.c create mode 100644 cpu/atmega_common/periph/uart.c diff --git a/cpu/atmega2560/Makefile.include b/cpu/atmega2560/Makefile.include index a3ddf00809..2efb70e9b8 100644 --- a/cpu/atmega2560/Makefile.include +++ b/cpu/atmega2560/Makefile.include @@ -13,9 +13,6 @@ export USEMODULE += uart_stdio # define path to atmega common module, which is needed for this CPU export ATMEGA_COMMON = $(RIOTCPU)/atmega_common/ -# define the linker script to use for this CPU -#export LINKERSCRIPT = $(RIOTCPU)/$(CPU)/ldscripts/atmega2560.ld - # 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 diff --git a/cpu/atmega_common/Makefile.include b/cpu/atmega_common/Makefile.include index efd66a0dbf..6e59bcd911 100644 --- a/cpu/atmega_common/Makefile.include +++ b/cpu/atmega_common/Makefile.include @@ -1,5 +1,11 @@ # Target architecture for the build. Use avr if you are unsure. export TARGET_ARCH ?= avr +# export the peripheral drivers to be linked into the final binary +export USEMODULE += periph + +# the atmel port uses uart_stdio +export USEMODULE += uart_stdio + # include module specific includes export INCLUDES += -I$(RIOTCPU)/atmega_common/include -isystem$(RIOTCPU)/atmega_common/avr-libc-extra diff --git a/cpu/atmega_common/include/atmega_regs_common.h b/cpu/atmega_common/include/atmega_regs_common.h new file mode 100644 index 0000000000..a9721224d3 --- /dev/null +++ b/cpu/atmega_common/include/atmega_regs_common.h @@ -0,0 +1,116 @@ +/* + * Copyright (C) 2016 Freie Universität Berlin + * 2016 INRIA + * + * 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_atmega_common + * @{ + * + * @file + * @brief CMSIS style register definitions for the atmega family + * + * @author Hauke Petersen <hauke.petersen@fu-berlin.de> + * @author Francisco Acosta <francisco.acosta@inria.fr> + */ + +#ifndef ATMEGA_REGS_COMMON_H +#define ATMEGA_REGS_COMMON_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) +#if defined(__AVR_ATmega2560__) +#define MEGA_TIMER3_BASE (uint16_t *)(&TCCR3A) +#define MEGA_TIMER4_BASE (uint16_t *)(&TCCR4A) +#define MEGA_TIMER5_BASE (uint16_t *)(&TCCR5A) +#endif +/** @} */ + +/** + * @brief Base register address definitions + * @{ + */ +#define MEGA_UART0_BASE ((uint16_t *)(&UCSR0A)) +#if defined(__AVR_ATmega2560__) +#define MEGA_UART1_BASE ((uint16_t *)(&UCSR1A)) +#define MEGA_UART2_BASE ((uint16_t *)(&UCSR2A)) +#define MEGA_UART3_BASE ((uint16_t *)(&UCSR3A)) +#endif +/** @} */ + +/** + * @brief Peripheral instances + * @{ + */ +#define MEGA_TIMER1 ((mega_timer_t *)MEGA_TIMER1_BASE) +#if defined(__AVR_ATmega2560__) +#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) +#endif +/** @} */ + +/** + * @brief Peripheral instances + * @{ + */ +#define MEGA_UART0 ((mega_uart_t *)MEGA_UART0_BASE) +#if defined(__AVR_ATmega2560__) +#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) +#endif +/** @} */ + +#ifdef __cplusplus +} +#endif + +#endif /* ATMEGA2560_REGS_H */ +/** @} */ diff --git a/cpu/atmega_common/include/periph_cpu_common.h b/cpu/atmega_common/include/periph_cpu_common.h new file mode 100644 index 0000000000..7f005ddca7 --- /dev/null +++ b/cpu/atmega_common/include/periph_cpu_common.h @@ -0,0 +1,88 @@ +/* + * Copyright (C) 2015 HAW Hamburg + * 2016 Freie Universität Berlin + * 2016 INRIA + * + * 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_atmega_common + * @{ + * + * @file + * @brief CPU specific definitions for internal peripheral handling + * + * @author René Herthel <rene-herthel@outlook.de> + * @author Hauke Petersen <hauke.petersen@fu-berlin.de> + * @author Francisco Acosta <francisco.acosta@inria.fr> + */ + +#ifndef PERIPH_CPU_COMMON_H_ +#define 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 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 + +#endif /* PERIPH_CPU_COMMON_H_ */ +/** @} */ diff --git a/cpu/atmega_common/periph/Makefile b/cpu/atmega_common/periph/Makefile new file mode 100644 index 0000000000..6d1887b640 --- /dev/null +++ b/cpu/atmega_common/periph/Makefile @@ -0,0 +1,3 @@ +MODULE = periph + +include $(RIOTBASE)/Makefile.base diff --git a/cpu/atmega_common/periph/gpio.c b/cpu/atmega_common/periph/gpio.c new file mode 100644 index 0000000000..c4d3752c93 --- /dev/null +++ b/cpu/atmega_common/periph/gpio.c @@ -0,0 +1,270 @@ +/* + * Copyright (C) 2015 HAW Hamburg + * 2016 INRIA + + * + * 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 ATmega family + * + * @author René Herthel <rene-herthel@outlook.de> + * @author Francisco Acosta <francisco.acosta@inria.fr> + * + * @} + */ + + +#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) + +/* + * @brief Define GPIO interruptions for an specific atmega CPU, by default + * 2 (for small atmega CPUs) + */ +#if defined(__AVR_ATmega2560__) +#define GPIO_EXT_INT_NUMOF (8U) +#else +#define GPIO_EXT_INT_NUMOF (2U) +#endif + +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 */ +} + +#if defined(__AVR_ATmega2560__) +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 */ +} +#endif diff --git a/cpu/atmega_common/periph/spi.c b/cpu/atmega_common/periph/spi.c new file mode 100644 index 0000000000..7a48aba5a7 --- /dev/null +++ b/cpu/atmega_common/periph/spi.c @@ -0,0 +1,151 @@ +/* + * 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" + +#define ENABLE_DEBUG (0) +#include "debug.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) +{ + DEBUG("spi.c: conf = %d, speed = %d\n", conf, 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 by reading SPSR */ + (void)SPSR; + + /* clear data register */ + (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/atmega_common/periph/timer.c b/cpu/atmega_common/periph/timer.c new file mode 100644 index 0000000000..ac0df5995f --- /dev/null +++ b/cpu/atmega_common/periph/timer.c @@ -0,0 +1,266 @@ +/* + * 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" + +#define ENABLE_DEBUG (0) +#include "debug.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 + * @{ + */ +#ifdef 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) +{ + DEBUG("timer.c: freq = %ld\n", freq); + 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) { + DEBUG("timer.c: prescaling failed!\n"); + 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); + DEBUG("timer.c: prescaler set at %d\n", 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; +} + +#ifdef TIMER_NUMOF +static inline void _isr(tim_t tim, int chan) +{ + __enter_isr(); + + *ctx[tim].mask &= ~(1 << (chan + OCIE1A)); + ctx[tim].cb(ctx[tim].arg, chan); + + if (sched_context_switch_request) { + thread_yield(); + } + + __exit_isr(); +} +#endif + +#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/atmega_common/periph/uart.c b/cpu/atmega_common/periph/uart.c new file mode 100644 index 0000000000..4736f57054 --- /dev/null +++ b/cpu/atmega_common/periph/uart.c @@ -0,0 +1,133 @@ +/* + * 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 */ -- GitLab