Merge pull request #1420 from N8Fear/initial_import_arduino_mega2560
board: cpu: Initial import of the Arduino Mega2560
This commit is contained in:
commit
ea355d820b
@ -22,6 +22,7 @@ install:
|
||||
- sudo apt-get install pcregrep libpcre3
|
||||
- sudo apt-get install qemu-system-x86 python3
|
||||
- sudo apt-get install g++-multilib
|
||||
- sudo apt-get install gcc-avr binutils-avr avr-libc
|
||||
- git config --global user.email "travis@example.com"
|
||||
- git config --global user.name "Travis CI"
|
||||
|
||||
|
||||
3
boards/arduino-mega2560/Makefile
Normal file
3
boards/arduino-mega2560/Makefile
Normal file
@ -0,0 +1,3 @@
|
||||
MODULE = $(BOARD)_base
|
||||
|
||||
include $(RIOTBASE)/Makefile.base
|
||||
43
boards/arduino-mega2560/Makefile.include
Normal file
43
boards/arduino-mega2560/Makefile.include
Normal file
@ -0,0 +1,43 @@
|
||||
|
||||
# define the cpu used by the arduino mega2560 board
|
||||
export CPU = atmega2560
|
||||
|
||||
# define tools used for building the project
|
||||
export PREFIX = avr-
|
||||
export CC = $(PREFIX)gcc
|
||||
export CXX = $(PREFIX)c++
|
||||
export AR = $(PREFIX)ar
|
||||
export AS = $(PREFIX)as
|
||||
export LINK = $(PREFIX)gcc
|
||||
export SIZE = $(PREFIX)size
|
||||
export OBJCOPY = $(PREFIX)objcopy
|
||||
export TERMPROG = $(RIOTBASE)/dist/tools/pyterm/pyterm
|
||||
export TERMFLAGS = -b 38400 -p $(PORT)
|
||||
|
||||
#define the flash-tool and default port depending on the host operating system
|
||||
OS = $(shell uname)
|
||||
ifeq ($(OS),Linux)
|
||||
PORT ?= /dev/ttyACM0
|
||||
FLASHER = avrdude
|
||||
#else ifeq ($(OS),Darwin)
|
||||
# PORT ?=
|
||||
# FLASHER =
|
||||
else
|
||||
$(info CAUTION: No flash tool for your host system found!)
|
||||
# TODO: fix for building under windows/MacOS
|
||||
endif
|
||||
export FLASHER
|
||||
export PORT
|
||||
|
||||
# define build specific options
|
||||
export CPU_USAGE = -mmcu=atmega2560
|
||||
export CFLAGS += -ggdb -g3 -std=gnu99 -Os -Wall -Wstrict-prototypes $(CPU_USAGE)
|
||||
export ASFLAGS += -ggdb -g3 $(CPU_USAGE) $(FPU_USAGE)
|
||||
export LINKFLAGS += -g3 -ggdb -std=gnu99 $(CPU_USAGE) $(FPU_USAGE) -static -lgcc -e reset_handler
|
||||
# linkerscript specified in cpu/Makefile.include
|
||||
#export LINKFLAGS += -T$(LINKERSCRIPT)
|
||||
export OFLAGS += -j .text -j .data -O ihex
|
||||
export FFLAGS += -p m2560 -c stk500v2 -P $(PORT) -b 115200 -F -U flash:w:bin/$(BOARD)/$(PROJECT)$(APPLICATION).hex
|
||||
|
||||
# export board specific includes to the global includes-listing
|
||||
export INCLUDES += -I$(RIOTBOARD)/$(BOARD)/include
|
||||
148
boards/arduino-mega2560/board.c
Normal file
148
boards/arduino-mega2560/board.c
Normal file
@ -0,0 +1,148 @@
|
||||
/*
|
||||
* 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 board_arduino-mega2560
|
||||
* @{
|
||||
*
|
||||
* @file board.c
|
||||
* @brief Board specific implementations for the Arduino Mega 2560 board
|
||||
*
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include <avr/io.h>
|
||||
|
||||
#include "board.h"
|
||||
#include "cpu.h"
|
||||
#include "periph/uart.h"
|
||||
|
||||
#ifndef MODULE_UART0
|
||||
#include "ringbuffer.h"
|
||||
#include "mutex.h"
|
||||
#endif
|
||||
|
||||
#ifdef MODULE_UART0
|
||||
#include "board_uart0.h"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief use mutex for waiting on incoming UART chars
|
||||
*/
|
||||
#ifndef MODULE_UART0
|
||||
static mutex_t uart_rx_mutex;
|
||||
static char rx_buf_mem[STDIO_RX_BUFSIZE];
|
||||
static ringbuffer_t rx_buf;
|
||||
#endif
|
||||
|
||||
void led_init(void);
|
||||
void SystemInit(void);
|
||||
static int uart_putchar(unsigned char c, FILE *stream);
|
||||
static char 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);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Receive a new character from the UART and put it into the receive
|
||||
* buffer
|
||||
*
|
||||
* @param[in] data the newly received byte
|
||||
*/
|
||||
|
||||
void rx_cb(void *arg, char data)
|
||||
{
|
||||
LED_TOGGLE;
|
||||
#ifndef MODULE_UART0
|
||||
ringbuffer_add_one(&rx_buf, data);
|
||||
mutex_unlock(&uart_rx_mutex);
|
||||
#elif MODULE_UART0
|
||||
|
||||
if (uart0_handler_pid) {
|
||||
uart0_handle_incoming(data);
|
||||
uart0_notify_thread();
|
||||
}
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
void board_init(void)
|
||||
{
|
||||
/* initialize stdio via USART_0 */
|
||||
SystemInit();
|
||||
|
||||
/* initialize the CPU */
|
||||
cpu_init();
|
||||
|
||||
/* initialize the boards LEDs */
|
||||
led_init();
|
||||
|
||||
enableIRQ();
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Initialize the boards on-board LED (Amber LED "L")
|
||||
*
|
||||
* The LED initialization is hard-coded in this function. As the LED is soldered
|
||||
* onto the board it is fixed to its CPU pins.
|
||||
*
|
||||
* The LED is connected to the following pin:
|
||||
* - LED: PB27
|
||||
*/
|
||||
void led_init(void)
|
||||
{
|
||||
LED_ENABLE_PORT;
|
||||
LED_ON;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initialize the System, initialize IO via UART_0
|
||||
*/
|
||||
void SystemInit(void)
|
||||
{
|
||||
/* initialize UART_0 for use as stdout */
|
||||
#ifndef MODULE_UART0
|
||||
mutex_init(&uart_rx_mutex);
|
||||
ringbuffer_init(&rx_buf, rx_buf_mem, STDIO_RX_BUFSIZE);
|
||||
#endif
|
||||
uart_init(STDIO, STDIO_BAUDRATE, (uart_rx_cb_t) rx_cb, NULL, NULL);
|
||||
|
||||
stdout = &uart_stdout;
|
||||
stdin = &uart_stdin;
|
||||
|
||||
/* Flush stdout */
|
||||
puts("\f");
|
||||
}
|
||||
|
||||
static int uart_putchar(unsigned char c, FILE *stream)
|
||||
{
|
||||
uart_write_blocking(UART_0, c);
|
||||
return 0;
|
||||
}
|
||||
|
||||
char uart_getchar(FILE *stream)
|
||||
{
|
||||
#ifndef MODULE_UART0
|
||||
|
||||
if (rx_buf.avail == 0) {
|
||||
mutex_lock(&uart_rx_mutex);
|
||||
}
|
||||
|
||||
return ringbuffer_get_one(&rx_buf);
|
||||
#else
|
||||
LED_TOGGLE;
|
||||
char temp;
|
||||
temp = (char) uart0_readc();
|
||||
return temp;
|
||||
#endif
|
||||
}
|
||||
80
boards/arduino-mega2560/include/board.h
Normal file
80
boards/arduino-mega2560/include/board.h
Normal file
@ -0,0 +1,80 @@
|
||||
/*
|
||||
* 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.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @defgroup board_arduino-mega2560 Arduino Mega 2560
|
||||
* @ingroup boards
|
||||
* @brief Board specific files for the Arduino Mega 2560 board.
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Board specific definitions for the Arduino Mega 2560 board.
|
||||
*
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
*/
|
||||
|
||||
#ifndef __BOARD_H
|
||||
#define __BOARD_H
|
||||
|
||||
#include "cpu.h"
|
||||
|
||||
/**
|
||||
* Define the nominal CPU core clock in this board
|
||||
*/
|
||||
#define F_CPU (16000000L)
|
||||
|
||||
|
||||
/**
|
||||
* Assign the hardware timer
|
||||
*/
|
||||
#define HW_TIMER TIMER_0
|
||||
|
||||
/**
|
||||
* @name Define UART device and baudrate for stdio
|
||||
* @{
|
||||
*/
|
||||
#define STDIO UART_0
|
||||
#define STDIO_BAUDRATE (38400U)
|
||||
#define STDIO_RX_BUFSIZE (64U)
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name LED pin definitions
|
||||
* @{
|
||||
*/
|
||||
#define LED_PORT PORTB
|
||||
#define LED_PIN (1 << 7)
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name Macros for controlling the on-board LEDs.
|
||||
* @{
|
||||
*/
|
||||
#define LED_ENABLE_PORT DDRB |= (1 << DDB7)
|
||||
#define LED_ON LED_PORT |= LED_PIN
|
||||
#define LED_OFF LED_PORT &= ~LED_PIN
|
||||
#define LED_TOGGLE LED_PORT ^= LED_PIN;
|
||||
|
||||
/* for compatability to other boards */
|
||||
#define LED_GREEN_ON LED_ON
|
||||
#define LED_GREEN_OFF LED_OFF
|
||||
#define LED_GREEN_TOGGLE LED_TOGGLE
|
||||
#define LED_RED_ON /* not available */
|
||||
#define LED_RED_OFF /* not available */
|
||||
#define LED_RED_TOGGLE /* not available */
|
||||
/** @} */
|
||||
|
||||
|
||||
/**
|
||||
* @brief Initialize board specific hardware, including clock, LEDs and std-IO
|
||||
*/
|
||||
void board_init(void);
|
||||
|
||||
|
||||
#endif /** __BOARD_H */
|
||||
/** @} */
|
||||
282
boards/arduino-mega2560/include/periph_conf.h
Normal file
282
boards/arduino-mega2560/include/periph_conf.h
Normal file
@ -0,0 +1,282 @@
|
||||
/*
|
||||
* 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 board_arduino-mega2560
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Peripheral MCU configuration for the Arduino Mega 2560 board
|
||||
*
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
*/
|
||||
|
||||
#ifndef __PERIPH_CONF_H
|
||||
#define __PERIPH_CONF_H
|
||||
|
||||
|
||||
/**
|
||||
* @name Timer peripheral configuration
|
||||
* @brief The ATmega2560 has 6 timers. Timer0 and Timer2 are 8 Bit Timers,
|
||||
* Timer0 has special uses too and therefore we'll avoid using it.
|
||||
* Timer5 has special uses with certain Arduino Shields, too.
|
||||
* Therefore we'll also avoid using Timer5.
|
||||
* This results in the following mapping to use the left over 16 Bit
|
||||
* timers:
|
||||
*
|
||||
* Timer1 -> TIMER_0
|
||||
* Timer3 -> TIMER_1
|
||||
* Timer4 -> TIMER_2
|
||||
*
|
||||
* @{
|
||||
*/
|
||||
#define TIMER_NUMOF (3U)
|
||||
#define TIMER_0_EN 1
|
||||
#define TIMER_1_EN 0
|
||||
#define TIMER_2_EN 0
|
||||
|
||||
/* Timer 0 configuration */
|
||||
#define TIMER_0_CHANNELS 3
|
||||
#define TIMER_0_MAX_VALUE (0xffff)
|
||||
|
||||
/* Timer 0 register and flags */
|
||||
#define TIMER0_CONTROL_A TCCR1A
|
||||
#define TIMER0_CONTROL_B TCCR1B
|
||||
#define TIMER0_CONTROL_C TCCR1C
|
||||
#define TIMER0_COUNTER TCNT1
|
||||
#define TIMER0_IRQ_FLAG_REG TIFR1
|
||||
#define TIMER0_IRQ_MASK_REG TIMSK1
|
||||
#define TIMER0_COMP_A OCR1A
|
||||
#define TIMER0_COMP_B OCR1B
|
||||
#define TIMER0_COMP_C OCR1C
|
||||
#define TIMER0_COMP_A_FLAG OCF1A
|
||||
#define TIMER0_COMP_B_FLAG OCF1B
|
||||
#define TIMER0_COMP_C_FLAG OCF1C
|
||||
#define TIMER0_COMP_A_EN OCIE1A
|
||||
#define TIMER0_COMP_B_EN OCIE1B
|
||||
#define TIMER0_COMP_C_EN OCIE1C
|
||||
#define TIMER0_FREQ_16MHZ (0 << CS12) | (0 << CS11) | (1 << CS10)
|
||||
#define TIMER0_FREQ_DISABLE (0 << CS12) | (0 << CS11) | (0 << CS10)
|
||||
#define TIMER0_COMPA_ISR TIMER1_COMPA_vect
|
||||
#define TIMER0_COMPB_ISR TIMER1_COMPB_vect
|
||||
#define TIMER0_COMPC_ISR TIMER1_COMPC_vect
|
||||
|
||||
/* Timer 1 configuration */
|
||||
#define TIMER_1_CHANNELS 3
|
||||
#define TIMER_1_MAX_VALUE (0xffff)
|
||||
|
||||
/* Timer 1 register and flags */
|
||||
#define TIMER1_CONTROL_A TCCR3A
|
||||
#define TIMER1_CONTROL_B TCCR3B
|
||||
#define TIMER1_CONTROL_C TCCR3C
|
||||
#define TIMER1_COUNTER TCNT3
|
||||
#define TIMER1_IRQ_FLAG_REG TIFR3
|
||||
#define TIMER1_IRQ_MASK_REG TIMSK3
|
||||
#define TIMER1_COMP_A OCR3A
|
||||
#define TIMER1_COMP_B OCR3B
|
||||
#define TIMER1_COMP_C OCR3C
|
||||
#define TIMER1_COMP_A_FLAG OCF3A
|
||||
#define TIMER1_COMP_B_FLAG OCF3B
|
||||
#define TIMER1_COMP_C_FLAG OCF3C
|
||||
#define TIMER1_COMP_A_EN OCIE3A
|
||||
#define TIMER1_COMP_B_EN OCIE3B
|
||||
#define TIMER1_COMP_C_EN OCIE3C
|
||||
#define TIMER1_FREQ_16MHZ (0 << CS32) | (0 << CS31) | (1 << CS30)
|
||||
#define TIMER1_FREQ_DISABLE (0 << CS32) | (0 << CS31) | (0 << CS30)
|
||||
#define TIMER1_COMPA_ISR TIMER3_COMPA_vect
|
||||
#define TIMER1_COMPB_ISR TIMER3_COMPB_vect
|
||||
#define TIMER1_COMPC_ISR TIMER3_COMPC_vect
|
||||
|
||||
/* Timer 2 configuration */
|
||||
#define TIMER_2_CHANNELS 3
|
||||
#define TIMER_2_MAX_VALUE (0xffff)
|
||||
|
||||
/* Timer 2 register and flags */
|
||||
#define TIMER2_CONTROL_A TCCR4A
|
||||
#define TIMER2_CONTROL_B TCCR4B
|
||||
#define TIMER2_CONTROL_C TCCR4C
|
||||
#define TIMER2_COUNTER TCNT4
|
||||
#define TIMER2_IRQ_FLAG_REG TIFR4
|
||||
#define TIMER2_IRQ_MASK_REG TIMSK4
|
||||
#define TIMER2_COMP_A OCR4A
|
||||
#define TIMER2_COMP_B OCR4B
|
||||
#define TIMER2_COMP_C OCR4C
|
||||
#define TIMER2_COMP_A_FLAG OCF4A
|
||||
#define TIMER2_COMP_B_FLAG OCF4B
|
||||
#define TIMER2_COMP_C_FLAG OCF4C
|
||||
#define TIMER2_COMP_A_EN OCIE4A
|
||||
#define TIMER2_COMP_B_EN OCIE4B
|
||||
#define TIMER2_COMP_C_EN OCIE4C
|
||||
#define TIMER2_FREQ_16MHZ (0 << CS42) | (0 << CS41) | (1 << CS40)
|
||||
#define TIMER2_FREQ_DISABLE (0 << CS42) | (0 << CS41) | (0 << CS40)
|
||||
#define TIMER2_COMPA_ISR TIMER4_COMPA_vect
|
||||
#define TIMER2_COMPB_ISR TIMER4_COMPB_vect
|
||||
#define TIMER2_COMPC_ISR TIMER4_COMPC_vect
|
||||
|
||||
/**
|
||||
* @name UART configuration
|
||||
* @{
|
||||
*/
|
||||
#define UART_NUMOF (1U)
|
||||
#define UART_0_EN 1
|
||||
#define UART_1_EN 0
|
||||
#define UART_2_EN 0
|
||||
#define UART_3_EN 0
|
||||
|
||||
/* UART 0 registers */
|
||||
#define UART0_CTRL_STAT_A UCSR0A
|
||||
#define UART0_CTRL_STAT_B UCSR0B
|
||||
#define UART0_CTRL_STAT_C UCSR0C
|
||||
#define UART0_BAUD_RATE_L UBRR0L
|
||||
#define UART0_BAUD_RATE_H UBRR0H
|
||||
#define UART0_DATA_REGISTER UDR0
|
||||
|
||||
/* Flags */
|
||||
#define UART0_RX_COMPLETE RXC0
|
||||
#define UART0_DATA_EMPTY UDRE0
|
||||
#define UART0_RX_EN RXEN0
|
||||
#define UART0_TX_EN TXEN0
|
||||
#define UART0_RXC_IRQ_EN RXCIE0
|
||||
#define UART0_TXC_IRQ_EN TXCIE0
|
||||
#define UART0_8BIT_SIZE (1 << UCSZ00) | (1 << UCSZ01)
|
||||
|
||||
/* UART0 helper macros */
|
||||
#define UART0_RX_TX_EN UART0_CTRL_STAT_B |= (1 << UART0_RX_EN) | (1 << UART0_TX_EN)
|
||||
#define UART0_RX_IRQ_EN UART0_CTRL_STAT_B |= (1 << UART0_RXC_IRQ_EN)
|
||||
#define UART0_SET_8BIT_SIZE UART0_CTRL_STAT_C |= UART0_8BIT_SIZE
|
||||
#define UART0_RECEIVED_DATA (UART0_CTRL_STAT_A & (1 << UART0_RX_COMPLETE))
|
||||
#define UART0_DTREG_EMPTY (UART0_CTRL_STAT_A & (1 << UART0_DATA_EMPTY))
|
||||
|
||||
/* UART 1 registers */
|
||||
#define UART1_CTRL_STAT_A UCSR1A
|
||||
#define UART1_CTRL_STAT_B UCSR1B
|
||||
#define UART1_CTRL_STAT_C UCSR1C
|
||||
#define UART1_BAUD_RATE_L UBRR1L
|
||||
#define UART1_BAUD_RATE_H UBRR1H
|
||||
#define UART1_DATA_REGISTER UDR1
|
||||
|
||||
/* Flags */
|
||||
#define UART1_RX_COMPLETE RXC1
|
||||
#define UART1_DATA_EMPTY UDRE1
|
||||
#define UART1_RX_EN RXEN1
|
||||
#define UART1_TX_EN TXEN1
|
||||
#define UART1_RXC_IRQ_EN RXCIE1
|
||||
#define UART1_TXC_IRQ_EN TXCIE1
|
||||
#define UART1_8BIT_SIZE (1 << UCSZ10) | (1 << UCSZ11)
|
||||
|
||||
/* UART1 helper macros */
|
||||
#define UART1_RX_TX_EN UART1_CTRL_STAT_B |= (1 << UART1_RX_EN) | (1 << UART1_TX_EN)
|
||||
#define UART1_RX_IRQ_EN UART1_CTRL_STAT_B |= (1 << UART1_RXC_IRQ_EN)
|
||||
#define UART1_SET_8BIT_SIZE UART1_CTRL_STAT_C |= UART1_8BIT_SIZE
|
||||
#define UART1_RECEIVED_DATA (UART1_CTRL_STAT_A & (1 << UART1_RX_COMPLETE))
|
||||
#define UART1_DTREG_EMPTY (UART1_CTRL_STAT_A & (1 << UART1_DATA_EMPTY))
|
||||
|
||||
/* UART 2 registers */
|
||||
#define UART2_CTRL_STAT_A UCSR2A
|
||||
#define UART2_CTRL_STAT_B UCSR2B
|
||||
#define UART2_CTRL_STAT_C UCSR2C
|
||||
#define UART2_BAUD_RATE_L UBRR2L
|
||||
#define UART2_BAUD_RATE_H UBRR2H
|
||||
#define UART2_DATA_REGISTER UDR2
|
||||
|
||||
/* Flags */
|
||||
#define UART2_RX_COMPLETE RXC2
|
||||
#define UART2_DATA_EMPTY UDRE2
|
||||
#define UART2_RX_EN RXEN2
|
||||
#define UART2_TX_EN TXEN2
|
||||
#define UART2_RXC_IRQ_EN RXCIE2
|
||||
#define UART2_TXC_IRQ_EN TXCIE2
|
||||
#define UART2_8BIT_SIZE (1 << UCSZ20) | (1 << UCSZ21)
|
||||
|
||||
/* UART2 helper macros */
|
||||
#define UART2_RX_TX_EN UART2_CTRL_STAT_B |= (1 << UART2_RX_EN) | (1 << UART2_TX_EN)
|
||||
#define UART2_RX_IRQ_EN UART2_CTRL_STAT_B |= (1 << UART2_RXC_IRQ_EN)
|
||||
#define UART2_SET_8BIT_SIZE UART2_CTRL_STAT_C |= UART2_8BIT_SIZE
|
||||
#define UART2_RECEIVED_DATA (UART2_CTRL_STAT_A & (1 << UART2_RX_COMPLETE))
|
||||
#define UART2_DTREG_EMPTY (UART2_CTRL_STAT_A & (1 << UART2_DATA_EMPTY))
|
||||
|
||||
/* UART 2 registers */
|
||||
#define UART3_CTRL_STAT_A UCSR3A
|
||||
#define UART3_CTRL_STAT_B UCSR3B
|
||||
#define UART3_CTRL_STAT_C UCSR3C
|
||||
#define UART3_BAUD_RATE_L UBRR3L
|
||||
#define UART3_BAUD_RATE_H UBRR3H
|
||||
#define UART3_DATA_REGISTER UDR3
|
||||
|
||||
/* Flags */
|
||||
#define UART3_RX_COMPLETE RXC3
|
||||
#define UART3_DATA_EMPTY UDRE3
|
||||
#define UART3_RX_EN RXEN3
|
||||
#define UART3_TX_EN TXEN3
|
||||
#define UART3_RXC_IRQ_EN RXCIE3
|
||||
#define UART3_TXC_IRQ_EN TXCIE3
|
||||
#define UART3_8BIT_SIZE (1 << UCSZ30) | (1 << UCSZ31)
|
||||
|
||||
/* UART3 helper macros */
|
||||
#define UART3_RX_TX_EN UART3_CTRL_STAT_B |= (1 << UART3_RX_EN) | (1 << UART3_TX_EN)
|
||||
#define UART3_RX_IRQ_EN UART3_CTRL_STAT_B |= (1 << UART3_RXC_IRQ_EN)
|
||||
#define UART3_SET_8BIT_SIZE UART3_CTRL_STAT_C |= UART3_8BIT_SIZE
|
||||
#define UART3_RECEIVED_DATA (UART3_CTRL_STAT_A & (1 << UART3_RX_COMPLETE))
|
||||
#define UART3_DTREG_EMPTY (UART3_CTRL_STAT_A & (1 << UART3_DATA_EMPTY))
|
||||
|
||||
|
||||
|
||||
/* TODO: add defines for device agnostic implementation */
|
||||
/** @} */
|
||||
|
||||
|
||||
/**
|
||||
* @brief ADC configuration
|
||||
*/
|
||||
#define ADC_NUMOF (0U)
|
||||
#define ADC_0_EN 0
|
||||
#define ADC_1_EN 0
|
||||
|
||||
/**
|
||||
* @brief PWM configuration
|
||||
*/
|
||||
#define PWM_NUMOF (0U)
|
||||
#define PWM_0_EN 0
|
||||
#define PWM_1_EN 0
|
||||
|
||||
/**
|
||||
* @brief SPI configuration
|
||||
*/
|
||||
#define SPI_NUMOF (0U) /* TODO */
|
||||
#define SPI_0_EN 0
|
||||
#define SPI_1_EN 0
|
||||
|
||||
/**
|
||||
* @brief I2C configuration
|
||||
*/
|
||||
#define I2C_NUMOF (0U) /* TODO */
|
||||
#define I2C_0_EN 0
|
||||
#define I2C_0_EN 0
|
||||
|
||||
/**
|
||||
* @brief GPIO configuration
|
||||
*/
|
||||
#define GPIO_NUMOF (15U)
|
||||
#define GPIO_0_EN 0
|
||||
#define GPIO_1_EN 0
|
||||
#define GPIO_2_EN 0
|
||||
#define GPIO_3_EN 0
|
||||
#define GPIO_4_EN 0
|
||||
#define GPIO_5_EN 0
|
||||
#define GPIO_6_EN 0
|
||||
#define GPIO_7_EN 0
|
||||
#define GPIO_8_EN 0
|
||||
#define GPIO_9_EN 0
|
||||
#define GPIO_10_EN 0
|
||||
#define GPIO_11_EN 0
|
||||
#define GPIO_12_EN 0
|
||||
#define GPIO_13_EN 0
|
||||
#define GPIO_14_EN 0
|
||||
#define GPIO_15_EN 0
|
||||
|
||||
#endif /* __PERIPH_CONF_H */
|
||||
5
cpu/atmega2560/Makefile
Normal file
5
cpu/atmega2560/Makefile
Normal file
@ -0,0 +1,5 @@
|
||||
# define the module that is build
|
||||
MODULE = cpu
|
||||
# add a list of subdirectories, that should also be build
|
||||
DIRS = periph $(ATMEGA_COMMON)
|
||||
include $(RIOTBASE)/Makefile.base
|
||||
28
cpu/atmega2560/Makefile.include
Normal file
28
cpu/atmega2560/Makefile.include
Normal file
@ -0,0 +1,28 @@
|
||||
|
||||
# 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
|
||||
export USEMODULE += atmega_common
|
||||
|
||||
# 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)/atmega2560_linkerscript.ld
|
||||
|
||||
# include CPU specific includes
|
||||
export INCLUDES += -I$(RIOTCPU)/$(CPU)/include
|
||||
|
||||
# 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
|
||||
|
||||
# export the peripheral drivers to be linked into the final binary
|
||||
export USEMODULE += periph
|
||||
|
||||
# the uart implementation uses ringbuffer and therefore needs lib
|
||||
export USEMODULE += lib
|
||||
|
||||
# CPU depends on the atmega common module, so include it
|
||||
include $(ATMEGA_COMMON)Makefile.include
|
||||
29
cpu/atmega2560/cpu.c
Normal file
29
cpu/atmega2560/cpu.c
Normal file
@ -0,0 +1,29 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_atmega2560
|
||||
* @{
|
||||
*
|
||||
* @file cpu.c
|
||||
* @brief Implementation of the CPU initialization
|
||||
*
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "cpu.h"
|
||||
|
||||
/**
|
||||
* @brief Initialize the CPU, set IRQ priorities
|
||||
*/
|
||||
void cpu_init(void)
|
||||
{
|
||||
/* Right now we need to do nothing here */
|
||||
;
|
||||
}
|
||||
10
cpu/atmega2560/doc.txt
Normal file
10
cpu/atmega2560/doc.txt
Normal file
@ -0,0 +1,10 @@
|
||||
/**
|
||||
* @defgroup cpu_atmega2560 Atmel ATmega2560
|
||||
* @ingroup cpu
|
||||
* @brief Implementation of Atmel's ATmega2560 MCU
|
||||
*/
|
||||
|
||||
/**
|
||||
* @defgroup cpu_atmega2560_definitions Atmel ATmega2560 Definitions
|
||||
* @ingroup cpu_atmega2560
|
||||
*/
|
||||
73
cpu/atmega2560/hwtimer_arch.c
Normal file
73
cpu/atmega2560/hwtimer_arch.c
Normal file
@ -0,0 +1,73 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_atmega2560
|
||||
* @{
|
||||
*
|
||||
* @file hwtimer_arch.c
|
||||
* @brief Implementation of the kernels hwtimer interface
|
||||
*
|
||||
* The hardware timer implementation uses the ATmega2560 build-in system timer as back-end.
|
||||
*
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "arch/hwtimer_arch.h"
|
||||
#include "board.h"
|
||||
#include "periph/timer.h"
|
||||
#include "thread.h"
|
||||
|
||||
|
||||
void irq_handler(int channel);
|
||||
void (*timeout_handler)(int);
|
||||
|
||||
|
||||
void hwtimer_arch_init(void (*handler)(int), uint32_t fcpu)
|
||||
{
|
||||
timeout_handler = handler;
|
||||
timer_init(HW_TIMER, 1, &irq_handler);
|
||||
}
|
||||
|
||||
void hwtimer_arch_enable_interrupt(void)
|
||||
{
|
||||
timer_irq_enable(HW_TIMER);
|
||||
}
|
||||
|
||||
void hwtimer_arch_disable_interrupt(void)
|
||||
{
|
||||
timer_irq_disable(HW_TIMER);
|
||||
}
|
||||
|
||||
void hwtimer_arch_set(unsigned long offset, short timer)
|
||||
{
|
||||
timer_set(HW_TIMER, timer, offset);
|
||||
}
|
||||
|
||||
void hwtimer_arch_set_absolute(unsigned long value, short timer)
|
||||
{
|
||||
timer_set_absolute(HW_TIMER, timer, value);
|
||||
}
|
||||
|
||||
void hwtimer_arch_unset(short timer)
|
||||
{
|
||||
timer_clear(HW_TIMER, timer);
|
||||
}
|
||||
|
||||
unsigned long hwtimer_arch_now(void)
|
||||
{
|
||||
return timer_read(HW_TIMER);
|
||||
}
|
||||
|
||||
void irq_handler(int channel)
|
||||
{
|
||||
timeout_handler((short)(channel));
|
||||
}
|
||||
52
cpu/atmega2560/include/cpu-conf.h
Normal file
52
cpu/atmega2560/include/cpu-conf.h
Normal file
@ -0,0 +1,52 @@
|
||||
/*
|
||||
* 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.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Implementation specific CPU configuration options
|
||||
*
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
*/
|
||||
|
||||
#ifndef __CPU_CONF_H
|
||||
#define __CPU_CONF_H
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @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
|
||||
* @{
|
||||
*/
|
||||
#define KERNEL_CONF_STACKSIZE_PRINTF (128)
|
||||
|
||||
#ifndef KERNEL_CONF_STACKSIZE_DEFAULT
|
||||
#define KERNEL_CONF_STACKSIZE_DEFAULT (256)
|
||||
#endif
|
||||
|
||||
#define KERNEL_CONF_STACKSIZE_IDLE (128)
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name UART0 buffer size definition for compatibility reasons
|
||||
*
|
||||
* TODO: remove once the remodeling of the uart0 driver is done
|
||||
* @{
|
||||
*/
|
||||
#ifndef UART0_BUFSIZE
|
||||
#define UART0_BUFSIZE (128)
|
||||
#endif
|
||||
/** @} */
|
||||
|
||||
#endif /* __CPU_CONF_H */
|
||||
/** @} */
|
||||
32
cpu/atmega2560/include/hwtimer_cpu.h
Normal file
32
cpu/atmega2560/include/hwtimer_cpu.h
Normal file
@ -0,0 +1,32 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_atmega2560
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief CPU specific hwtimer configuration options
|
||||
*
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
*/
|
||||
|
||||
#ifndef __HWTIMER_CPU_H
|
||||
#define __HWTIMER_CPU_H
|
||||
|
||||
/**
|
||||
* @name Hardware timer configuration
|
||||
* @{
|
||||
*/
|
||||
#define HWTIMER_MAXTIMERS 3 /**< the CPU implementation supports 3 HW timers */
|
||||
#define HWTIMER_SPEED 1000000 /**< the HW timer runs with 1MHz */
|
||||
#define HWTIMER_MAXTICKS (0xFFFF) /**< 16-bit timer */
|
||||
/** @} */
|
||||
|
||||
#endif /* __HWTIMER_CPU_H */
|
||||
/** @} */
|
||||
35
cpu/atmega2560/io_arch.c
Normal file
35
cpu/atmega2560/io_arch.c
Normal file
@ -0,0 +1,35 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_atmega2560
|
||||
* @{
|
||||
*
|
||||
* @file io_arch.c
|
||||
* @brief Implementation of the kernel's architecture dependent IO interface
|
||||
*
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
#include "arch/io_arch.h"
|
||||
|
||||
int io_arch_puts(char *data, int size)
|
||||
{
|
||||
int i = 0;
|
||||
|
||||
for (; i < size; i++) {
|
||||
putchar(data[i]);
|
||||
}
|
||||
|
||||
return i;
|
||||
}
|
||||
53
cpu/atmega2560/lpm_arch.c
Normal file
53
cpu/atmega2560/lpm_arch.c
Normal file
@ -0,0 +1,53 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_atmega2560
|
||||
* @{
|
||||
*
|
||||
* @file lpm_arch.c
|
||||
* @brief Implementation of the kernels power management interface
|
||||
*
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "arch/lpm_arch.h"
|
||||
|
||||
void lpm_arch_init(void)
|
||||
{
|
||||
/* TODO */
|
||||
}
|
||||
|
||||
enum lpm_mode lpm_arch_set(enum lpm_mode target)
|
||||
{
|
||||
/* TODO */
|
||||
return 0;
|
||||
}
|
||||
|
||||
enum lpm_mode lpm_arch_get(void)
|
||||
{
|
||||
/* TODO */
|
||||
return 0;
|
||||
}
|
||||
|
||||
void lpm_arch_awake(void)
|
||||
{
|
||||
/* TODO */
|
||||
}
|
||||
|
||||
void lpm_arch_begin_awake(void)
|
||||
{
|
||||
/* TODO */
|
||||
}
|
||||
|
||||
void lpm_arch_end_awake(void)
|
||||
{
|
||||
/* TODO */
|
||||
}
|
||||
2
cpu/atmega2560/periph/Makefile
Normal file
2
cpu/atmega2560/periph/Makefile
Normal file
@ -0,0 +1,2 @@
|
||||
MODULE = periph
|
||||
include $(RIOTBASE)/Makefile.base
|
||||
71
cpu/atmega2560/periph/gpio.c
Normal file
71
cpu/atmega2560/periph/gpio.c
Normal file
@ -0,0 +1,71 @@
|
||||
/*
|
||||
* 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 gpio.c
|
||||
* @brief Low-level GPIO driver implementation
|
||||
*
|
||||
* @author Hauke Petersen <mail@haukepetersen.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
/*
|
||||
* TODO: Implement GPIO interface
|
||||
*/
|
||||
|
||||
#include "cpu.h"
|
||||
#include "periph/gpio.h"
|
||||
#include "periph_conf.h"
|
||||
|
||||
typedef struct {
|
||||
void (*cb)(void);
|
||||
} gpio_state_t;
|
||||
|
||||
/*static gpio_state_t config[GPIO_NUMOF]; */
|
||||
|
||||
|
||||
|
||||
int gpio_init_out(gpio_t dev, gpio_pp_t pushpull)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
int gpio_init_in(gpio_t dev, gpio_pp_t pushpull)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
int gpio_init_int(gpio_t dev, gpio_pp_t pushpull, gpio_flank_t flank, gpio_cb_t cb, void *arg)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
int gpio_read(gpio_t dev)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
void gpio_set(gpio_t dev)
|
||||
{
|
||||
}
|
||||
|
||||
void gpio_clear(gpio_t dev)
|
||||
{
|
||||
}
|
||||
|
||||
void gpio_toggle(gpio_t dev)
|
||||
{
|
||||
}
|
||||
|
||||
void gpio_write(gpio_t dev, int value)
|
||||
{
|
||||
}
|
||||
672
cpu/atmega2560/periph/timer.c
Normal file
672
cpu/atmega2560/periph/timer.c
Normal file
@ -0,0 +1,672 @@
|
||||
/*
|
||||
* 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 timer.c
|
||||
* @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 <stdlib.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#include "board.h"
|
||||
#include "cpu.h"
|
||||
|
||||
#include "periph/timer.h"
|
||||
#include "periph_conf.h"
|
||||
|
||||
static inline int __set_timer(tim_t dev,
|
||||
int channel,
|
||||
unsigned int timeout,
|
||||
unsigned int interval
|
||||
);
|
||||
|
||||
#define IRQ_DISABLED 0x00
|
||||
|
||||
typedef struct {
|
||||
void (*cb)(int);
|
||||
volatile uint8_t ctr_a;
|
||||
volatile uint8_t ctr_b;
|
||||
volatile uint8_t ctr_c;
|
||||
uint8_t limit;
|
||||
uint16_t timeout_a;
|
||||
uint16_t timeout_b;
|
||||
uint16_t timeout_c;
|
||||
} timer_conf_t;
|
||||
|
||||
/**
|
||||
* @brief Timer state memory
|
||||
*/
|
||||
timer_conf_t config[TIMER_NUMOF];
|
||||
|
||||
/**
|
||||
* @brief Setup the given timer
|
||||
*
|
||||
*/
|
||||
int timer_init(tim_t dev, unsigned int ticks_per_us, void (*callback)(int))
|
||||
{
|
||||
/* reject impossible ticks_per_us values */
|
||||
if ((ticks_per_us > 16) && (ticks_per_us == 0)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
config[dev].limit = 16 / ticks_per_us;
|
||||
config[dev].ctr_a = 0x00;
|
||||
config[dev].ctr_b = 0x00;
|
||||
config[dev].ctr_c = 0x00;
|
||||
|
||||
/* select the timer and enable the timer specific peripheral clocks */
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
|
||||
case TIMER_0:
|
||||
TIMER0_COUNTER = 0;
|
||||
TIMER0_CONTROL_B |= TIMER0_FREQ_16MHZ;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
|
||||
case TIMER_1:
|
||||
TIMER1_COUNTER = 0;
|
||||
TIMER1_CONTROL_B |= TIMER1_FREQ_16MHZ;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_2_EN
|
||||
|
||||
case TIMER_2:
|
||||
TIMER2_COUNTER = 0;
|
||||
TIMER2_CONTROL_B |= TIMER2_FREQ_16MHZ;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case TIMER_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* save callback */
|
||||
config[dev].cb = callback;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int timer_set(tim_t dev, int channel, unsigned int timeout)
|
||||
{
|
||||
return __set_timer(dev, channel, timer_read(dev) + timeout, timeout);
|
||||
}
|
||||
|
||||
int timer_set_absolute(tim_t dev, int channel, unsigned int timeout)
|
||||
{
|
||||
return __set_timer(dev, channel, timeout, timeout);
|
||||
}
|
||||
|
||||
int timer_clear(tim_t dev, int channel)
|
||||
{
|
||||
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
|
||||
case TIMER_0:
|
||||
switch (channel) {
|
||||
case 0:
|
||||
TIMER0_IRQ_FLAG_REG &= ~(1 << TIMER0_COMP_A_FLAG);
|
||||
config[dev].timeout_a = IRQ_DISABLED;
|
||||
break;
|
||||
|
||||
case 1:
|
||||
TIMER0_IRQ_FLAG_REG &= ~(1 << TIMER0_COMP_B_FLAG);
|
||||
config[dev].timeout_b = IRQ_DISABLED;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
TIMER0_IRQ_FLAG_REG &= ~(1 << TIMER0_COMP_C_FLAG);
|
||||
config[dev].timeout_c = IRQ_DISABLED;
|
||||
break;
|
||||
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
|
||||
case TIMER_1:
|
||||
switch (channel) {
|
||||
case 0:
|
||||
TIMER1_IRQ_FLAG_REG &= ~(1 << TIMER1_COMP_A_FLAG);
|
||||
config[dev].timeout_a = IRQ_DISABLED;
|
||||
break;
|
||||
|
||||
case 1:
|
||||
TIMER1_IRQ_FLAG_REG &= ~(1 << TIMER1_COMP_B_FLAG);
|
||||
config[dev].timeout_b = IRQ_DISABLED;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
TIMER1_IRQ_FLAG_REG &= ~(1 << TIMER1_COMP_C_FLAG);
|
||||
config[dev].timeout_c = IRQ_DISABLED;
|
||||
break;
|
||||
|
||||
default:
|
||||
return -1;
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_2_EN
|
||||
|
||||
case TIMER_2:
|
||||
switch (channel) {
|
||||
case 0:
|
||||
TIMER2_IRQ_FLAG_REG &= ~(1 << TIMER2_COMP_A_FLAG);
|
||||
config[dev].timeout_a = IRQ_DISABLED;
|
||||
break;
|
||||
|
||||
case 1:
|
||||
TIMER2_IRQ_FLAG_REG &= ~(1 << TIMER2_COMP_B_FLAG);
|
||||
config[dev].timeout_b = IRQ_DISABLED;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
TIMER2_IRQ_FLAG_REG &= ~(1 << TIMER2_COMP_C_FLAG);
|
||||
config[dev].timeout_c = IRQ_DISABLED;
|
||||
break;
|
||||
|
||||
default:
|
||||
return -1;
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
#endif
|
||||
|
||||
case TIMER_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
timer_irq_disable(dev);
|
||||
return 1;
|
||||
}
|
||||
|
||||
unsigned int timer_read(tim_t dev)
|
||||
{
|
||||
uint16_t value;
|
||||
/*
|
||||
* Disabling interrupts globally because read from 16 Bit register can
|
||||
* otherwise be messed up
|
||||
*/
|
||||
disableIRQ();
|
||||
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
|
||||
case TIMER_0:
|
||||
value = TIMER0_COUNTER;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
|
||||
case TIMER_1:
|
||||
value = TIMER1_COUNTER;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_2_EN
|
||||
|
||||
case TIMER_2:
|
||||
value = TIMER2_COUNTER;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case TIMER_UNDEFINED:
|
||||
default:
|
||||
value = 0;
|
||||
enableIRQ();
|
||||
}
|
||||
|
||||
enableIRQ();
|
||||
return value;
|
||||
}
|
||||
|
||||
void timer_stop(tim_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
|
||||
case TIMER_0:
|
||||
TIMER0_CONTROL_B = TIMER0_FREQ_DISABLE;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
|
||||
case TIMER_1:
|
||||
TIMER1_CONTROL_B = TIMER1_FREQ_DISABLE;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_2_EN
|
||||
|
||||
case TIMER_2:
|
||||
TIMER2_CONTROL_B = TIMER2_FREQ_DISABLE;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case TIMER_UNDEFINED:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void timer_start(tim_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
|
||||
case TIMER_0:
|
||||
TIMER0_CONTROL_B |= TIMER0_FREQ_16MHZ;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
|
||||
case TIMER_1:
|
||||
TIMER1_CONTROL_B |= TIMER1_FREQ_16MHZ;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_2_EN
|
||||
|
||||
case TIMER_2:
|
||||
TIMER1_CONTROL_B |= TIMER1_FREQ_16MHZ;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case TIMER_UNDEFINED:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void timer_irq_enable(tim_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
|
||||
case TIMER_0:
|
||||
if (config[dev].timeout_a != IRQ_DISABLED) {
|
||||
TIMER0_IRQ_MASK_REG |= (1 << TIMER0_COMP_A_EN);
|
||||
}
|
||||
|
||||
if (config[dev].timeout_b != IRQ_DISABLED) {
|
||||
TIMER0_IRQ_MASK_REG |= (1 << TIMER0_COMP_B_EN);
|
||||
}
|
||||
|
||||
if (config[dev].timeout_c != IRQ_DISABLED) {
|
||||
TIMER0_IRQ_MASK_REG |= (1 << TIMER0_COMP_C_EN);
|
||||
}
|
||||
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
|
||||
case TIMER_1:
|
||||
if (config[dev].timeout_a != IRQ_DISABLED) {
|
||||
TIMER1_IRQ_MASK_REG |= (1 << TIMER1_COMP_A_EN);
|
||||
}
|
||||
|
||||
if (config[dev].timeout_b != IRQ_DISABLED) {
|
||||
TIMER1_IRQ_MASK_REG |= (1 << TIMER1_COMP_B_EN);
|
||||
}
|
||||
|
||||
if (config[dev].timeout_c != IRQ_DISABLED) {
|
||||
TIMER1_IRQ_MASK_REG |= (1 << TIMER1_COMP_C_EN);
|
||||
}
|
||||
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_2_EN
|
||||
|
||||
case TIMER_2:
|
||||
if (config[dev].timeout_a != IRQ_DISABLED) {
|
||||
TIMER2_IRQ_MASK_REG |= (1 << TIMER2_COMP_A_EN);
|
||||
}
|
||||
|
||||
if (config[dev].timeout_b != IRQ_DISABLED) {
|
||||
TIMER2_IRQ_MASK_REG |= (1 << TIMER2_COMP_B_EN);
|
||||
}
|
||||
|
||||
if (config[dev].timeout_c != IRQ_DISABLED) {
|
||||
TIMER2_IRQ_MASK_REG |= (1 << TIMER2_COMP_C_EN);
|
||||
}
|
||||
|
||||
break;
|
||||
#endif
|
||||
|
||||
case TIMER_UNDEFINED:
|
||||
break;
|
||||
}
|
||||
|
||||
enableIRQ();
|
||||
}
|
||||
|
||||
void timer_irq_disable(tim_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
|
||||
case TIMER_0:
|
||||
if (config[dev].timeout_a == IRQ_DISABLED) {
|
||||
TIMER0_IRQ_MASK_REG &= ~(1 << TIMER0_COMP_A_EN);
|
||||
}
|
||||
|
||||
if (config[dev].timeout_b == IRQ_DISABLED) {
|
||||
TIMER0_IRQ_MASK_REG &= ~(1 << TIMER0_COMP_B_EN);
|
||||
}
|
||||
|
||||
if (config[dev].timeout_c == IRQ_DISABLED) {
|
||||
TIMER0_IRQ_MASK_REG &= ~(1 << TIMER0_COMP_C_EN);
|
||||
}
|
||||
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
|
||||
case TIMER_1:
|
||||
if (config[dev].timeout_a == IRQ_DISABLED) {
|
||||
TIMER1_IRQ_MASK_REG &= ~(1 << TIMER1_COMP_A_EN);
|
||||
}
|
||||
|
||||
if (config[dev].timeout_b == IRQ_DISABLED) {
|
||||
TIMER1_IRQ_MASK_REG &= ~(1 << TIMER1_COMP_B_EN);
|
||||
}
|
||||
|
||||
if (config[dev].timeout_c == IRQ_DISABLED) {
|
||||
TIMER1_IRQ_MASK_REG &= ~(1 << TIMER1_COMP_C_EN);
|
||||
}
|
||||
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_2_EN
|
||||
|
||||
case TIMER_2:
|
||||
if (config[dev].timeout_a == IRQ_DISABLED) {
|
||||
TIMER2_IRQ_MASK_REG &= ~(1 << TIMER2_COMP_A_EN);
|
||||
}
|
||||
|
||||
if (config[dev].timeout_b == IRQ_DISABLED) {
|
||||
TIMER2_IRQ_MASK_REG &= ~(1 << TIMER2_COMP_B_EN);
|
||||
}
|
||||
|
||||
if (config[dev].timeout_c == IRQ_DISABLED) {
|
||||
TIMER2_IRQ_MASK_REG &= ~(1 << TIMER2_COMP_C_EN);
|
||||
}
|
||||
|
||||
break;
|
||||
#endif
|
||||
|
||||
case TIMER_UNDEFINED:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void timer_reset(tim_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
|
||||
case TIMER_0:
|
||||
TIMER0_COUNTER = 0;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
|
||||
case TIMER_1:
|
||||
TIMER1_COUNTER = 0;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_2_EN
|
||||
|
||||
case TIMER_2:
|
||||
TIMER2_COUNTER = 0;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case TIMER_UNDEFINED:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
inline int __set_timer(tim_t dev, int channel, unsigned int timeout, unsigned int interval)
|
||||
{
|
||||
/*
|
||||
* Disabling interrupts globally because write to 16 Bit register can
|
||||
* otherwise be messed up
|
||||
*/
|
||||
disableIRQ();
|
||||
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
|
||||
case TIMER_0:
|
||||
switch (channel) {
|
||||
case 0:
|
||||
TIMER0_COMP_A = (uint16_t) timeout * config[dev].limit;
|
||||
config[dev].timeout_a = interval;
|
||||
break;
|
||||
|
||||
case 1:
|
||||
TIMER0_COMP_B = (uint16_t) timeout * config[dev].limit;
|
||||
config[dev].timeout_b = interval;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
TIMER0_COMP_C = (uint16_t) timeout * config[dev].limit;
|
||||
config[dev].timeout_c = interval;
|
||||
break;
|
||||
|
||||
default:
|
||||
enableIRQ();
|
||||
return -1;
|
||||
}
|
||||
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
|
||||
case TIMER_1:
|
||||
switch (channel) {
|
||||
case 0:
|
||||
TIMER1_COMP_A = (uint16_t) timeout * config[dev].limit;
|
||||
config[dev].timeout_a = interval;
|
||||
break;
|
||||
|
||||
case 1:
|
||||
TIMER1_COMP_B = (uint16_t) timeout * config[dev].limit;
|
||||
config[dev].timeout_b = interval;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
TIMER1_COMP_C = (uint16_t) timeout * config[dev].limit;
|
||||
config[dev].timeout_c = interval;
|
||||
break;
|
||||
|
||||
default:
|
||||
enableIRQ();
|
||||
return -1;
|
||||
}
|
||||
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_2_EN
|
||||
|
||||
case TIMER_2:
|
||||
switch (channel) {
|
||||
case 0:
|
||||
TIMER2_COMP_A = (uint16_t) timeout * config[dev].limit;
|
||||
config[dev].timeout_a = interval;
|
||||
break;
|
||||
|
||||
case 1:
|
||||
TIMER2_COMP_B = (uint16_t) timeout * config[dev].limit;
|
||||
config[dev].timeout_b = interval;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
TIMER2_COMP_C = (uint16_t) timeout * config[dev].limit;
|
||||
config[dev].timeout_c = interval;
|
||||
break;
|
||||
|
||||
default:
|
||||
enableIRQ();
|
||||
return -1;
|
||||
}
|
||||
|
||||
break;
|
||||
#endif
|
||||
|
||||
case TIMER_UNDEFINED:
|
||||
default:
|
||||
enableIRQ();
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* enable interrupts for given timer */
|
||||
timer_irq_enable(dev);
|
||||
enableIRQ();
|
||||
|
||||
return 1;
|
||||
}
|
||||
#if TIMER_0_EN
|
||||
ISR(TIMER0_COMPA_ISR, ISR_BLOCK)
|
||||
{
|
||||
config[TIMER_0].ctr_a++;
|
||||
|
||||
if (config[TIMER_0].ctr_a >= config[TIMER_0].limit) {
|
||||
config[TIMER_0].limit = 0;
|
||||
config[TIMER_0].cb(0);
|
||||
TIMER0_COMP_A = TIMER0_COMP_A + config[TIMER_0].timeout_a * config[TIMER_0].limit;
|
||||
}
|
||||
}
|
||||
ISR(TIMER0_COMPB_ISR, ISR_BLOCK)
|
||||
{
|
||||
config[TIMER_0].ctr_b++;
|
||||
|
||||
if (config[TIMER_0].ctr_b >= config[TIMER_0].limit) {
|
||||
config[TIMER_0].limit = 0;
|
||||
config[TIMER_0].cb(1);
|
||||
TIMER0_COMP_B = TIMER0_COMP_B + config[TIMER_0].timeout_b * config[TIMER_0].limit;
|
||||
}
|
||||
}
|
||||
ISR(TIMER0_COMPC_ISR, ISR_BLOCK)
|
||||
{
|
||||
config[TIMER_0].ctr_c++;
|
||||
|
||||
if (config[TIMER_0].ctr_c >= config[TIMER_0].limit) {
|
||||
config[TIMER_0].limit = 0;
|
||||
config[TIMER_0].cb(2);
|
||||
TIMER0_COMP_C = TIMER0_COMP_C + config[TIMER_0].timeout_c * config[TIMER_0].limit;
|
||||
}
|
||||
}
|
||||
#endif /* TIMER_0_EN */
|
||||
|
||||
#if TIMER_1_EN
|
||||
ISR(TIMER1_COMPA_ISR, ISR_BLOCK)
|
||||
{
|
||||
config[TIMER_1].ctr_a++;
|
||||
|
||||
if (config[TIMER_1].ctr_a >= config[TIMER_1].limit) {
|
||||
config[TIMER_1].limit = 0;
|
||||
config[TIMER_1].cb(0);
|
||||
TIMER1_COMP_A = TIMER1_COMP_A + config[TIMER_1].timeout_a * config[TIMER_1].limit;
|
||||
}
|
||||
|
||||
if (sched_context_switch_request) {
|
||||
thread_yield();
|
||||
}
|
||||
}
|
||||
ISR(TIMER1_COMPB_ISR, ISR_BLOCK)
|
||||
{
|
||||
config[TIMER_1].ctr_b++;
|
||||
|
||||
if (config[TIMER_1].ctr_b >= config[TIMER_1].limit) {
|
||||
config[TIMER_1].limit = 0;
|
||||
config[TIMER_1].cb(1);
|
||||
TIMER1_COMP_B = TIMER1_COMP_B + config[TIMER_1].timeout_b * config[TIMER_1].limit;
|
||||
}
|
||||
|
||||
if (sched_context_switch_request) {
|
||||
thread_yield();
|
||||
}
|
||||
}
|
||||
ISR(TIMER1_COMPC_ISR, ISR_BLOCK)
|
||||
{
|
||||
config[TIMER_1].ctr_c++;
|
||||
|
||||
if (config[TIMER_1].ctr_c >= config[TIMER_1].limit) {
|
||||
config[TIMER_1].limit = 0;
|
||||
config[TIMER_1].cb(2);
|
||||
TIMER1_COMP_C = TIMER1_COMP_C + config[TIMER_1].timeout_c * config[TIMER_1].limit;
|
||||
}
|
||||
|
||||
if (sched_context_switch_request) {
|
||||
thread_yield();
|
||||
}
|
||||
}
|
||||
#endif /* TIMER_1_EN */
|
||||
|
||||
#if TIMER_2_EN
|
||||
ISR(TIMER2_COMPA_ISR, ISR_BLOCK)
|
||||
{
|
||||
config[TIMER_2].ctr_a++;
|
||||
|
||||
if (config[TIMER_2].ctr_a >= config[TIMER_2].limit) {
|
||||
config[TIMER_2].limit = 0;
|
||||
config[TIMER_2].cb(0);
|
||||
TIMER2_COMP_A = TIMER2_COMP_A + config[TIMER_2].timeout_a * config[TIMER_2].limit;
|
||||
}
|
||||
|
||||
if (sched_context_switch_request) {
|
||||
thread_yield();
|
||||
}
|
||||
}
|
||||
ISR(TIMER2_COMPB_ISR, ISR_BLOCK)
|
||||
{
|
||||
config[TIMER_2].ctr_b++;
|
||||
|
||||
if (config[TIMER_2].ctr_b >= config[TIMER_2].limit) {
|
||||
config[TIMER_2].limit = 0;
|
||||
config[TIMER_2].cb(1);
|
||||
TIMER2_COMP_B = TIMER2_COMP_B + config[TIMER_2].timeout_b * config[TIMER_2].limit;
|
||||
}
|
||||
|
||||
if (sched_context_switch_request) {
|
||||
thread_yield();
|
||||
}
|
||||
}
|
||||
ISR(TIMER2_COMPC_ISR, ISR_BLOCK)
|
||||
{
|
||||
config[TIMER_2].ctr_c++;
|
||||
|
||||
if (config[TIMER_2].ctr_c >= config[TIMER_2].limit) {
|
||||
config[TIMER_2].limit = 0;
|
||||
config[TIMER_2].cb(2);
|
||||
TIMER2_COMP_C = TIMER2_COMP_C + config[TIMER_2].timeout_c * config[TIMER_2].limit;
|
||||
}
|
||||
|
||||
if (sched_context_switch_request) {
|
||||
thread_yield();
|
||||
}
|
||||
}
|
||||
#endif /* TIMER_2_EN */
|
||||
317
cpu/atmega2560/periph/uart.c
Normal file
317
cpu/atmega2560/periph/uart.c
Normal file
@ -0,0 +1,317 @@
|
||||
/*
|
||||
* 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 uart.c
|
||||
* @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 "board.h"
|
||||
#include "cpu.h"
|
||||
#include "thread.h"
|
||||
#include "sched.h"
|
||||
|
||||
#include "periph/uart.h"
|
||||
#include "periph_conf.h"
|
||||
|
||||
|
||||
/**
|
||||
* @brief Each UART device has to store two callbacks.
|
||||
*/
|
||||
typedef struct {
|
||||
uart_rx_cb_t rx_cb;
|
||||
uart_tx_cb_t tx_cb;
|
||||
void *arg;
|
||||
} uart_conf_t;
|
||||
|
||||
/**
|
||||
* @brief Allocate memory to store the callback functions.
|
||||
*/
|
||||
static uart_conf_t config[UART_NUMOF];
|
||||
|
||||
int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, uart_tx_cb_t tx_cb, void *arg)
|
||||
{
|
||||
/* initialize basic functionality */
|
||||
int res = uart_init_blocking(uart, baudrate);
|
||||
|
||||
if (res != 0) {
|
||||
return res;
|
||||
}
|
||||
|
||||
/* register callbacks */
|
||||
config[uart].rx_cb = rx_cb;
|
||||
config[uart].tx_cb = tx_cb;
|
||||
config[uart].arg = arg;
|
||||
|
||||
/* configure interrupts and enable RX interrupt */
|
||||
switch (uart) {
|
||||
#if UART_0_EN
|
||||
|
||||
case UART_0:
|
||||
UART0_RX_IRQ_EN;
|
||||
break;
|
||||
#endif /* UART_0_EN */
|
||||
#if UART_1_EN
|
||||
|
||||
case UART_1:
|
||||
UART1_RX_IRQ_EN;
|
||||
break;
|
||||
#endif /* UART_1_EN */
|
||||
#if UART_2_EN
|
||||
|
||||
case UART_2:
|
||||
UART2_RX_IRQ_EN;
|
||||
break;
|
||||
#endif /* UART_2_EN */
|
||||
#if UART_3_EN
|
||||
|
||||
case UART_3:
|
||||
UART3_RX_IRQ_EN;
|
||||
break;
|
||||
#endif /* UART_3_EN */
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int uart_init_blocking(uart_t uart, uint32_t baudrate)
|
||||
{
|
||||
uint16_t clock_divider = F_CPU / (16 * baudrate);
|
||||
|
||||
switch (uart) {
|
||||
#if UART_0_EN
|
||||
|
||||
case UART_0:
|
||||
/* enable RX and TX */
|
||||
UART0_RX_TX_EN;
|
||||
/* use 8 Bit characters */
|
||||
UART0_SET_8BIT_SIZE;
|
||||
|
||||
/* set clock divider */
|
||||
UART0_BAUD_RATE_L = clock_divider;
|
||||
UART0_BAUD_RATE_H = (clock_divider >> 8);
|
||||
break;
|
||||
#endif /* UART_0 */
|
||||
#if UART_1_EN
|
||||
|
||||
case UART_1:
|
||||
/* enable RX and TX */
|
||||
UART1_RX_TX_EN;
|
||||
/* use 8 Bit characters */
|
||||
UART1_SET_8BIT_SIZE;
|
||||
|
||||
/* set clock divider */
|
||||
UART1_BAUD_RATE_L = clock_divider;
|
||||
UART1_BAUD_RATE_H = (clock_divider >> 8);
|
||||
break;
|
||||
#endif /* UART_1 */
|
||||
#if UART_2_EN
|
||||
|
||||
case UART_2:
|
||||
/* enable RX and TX */
|
||||
UART2_RX_TX_EN;
|
||||
/* use 8 Bit characters */
|
||||
UART2_SET_8BIT_SIZE;
|
||||
|
||||
/* set clock divider */
|
||||
UART2_BAUD_RATE_L = clock_divider;
|
||||
UART2_BAUD_RATE_H = (clock_divider >> 8);
|
||||
break;
|
||||
#endif /* UART_2 */
|
||||
#if UART_3_EN
|
||||
|
||||
case UART_3:
|
||||
/* enable RX and TX */
|
||||
UART3_RX_TX_EN;
|
||||
/* use 8 Bit characters */
|
||||
UART3_SET_8BIT_SIZE;
|
||||
|
||||
/* set clock divider */
|
||||
UART3_BAUD_RATE_L = clock_divider;
|
||||
UART3_BAUD_RATE_H = (clock_divider >> 8);
|
||||
break;
|
||||
#endif /* UART_3 */
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void uart_tx_begin(uart_t uart)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void uart_tx_end(uart_t uart)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
int uart_write(uart_t uart, char data)
|
||||
{
|
||||
switch (uart) {
|
||||
#if UART_0_EN
|
||||
|
||||
case UART_0:
|
||||
UART0_DATA_REGISTER = data;
|
||||
break;
|
||||
#endif /* UART_0_EN */
|
||||
#if UART_1_EN
|
||||
|
||||
case UART_1:
|
||||
UART1_DATA_REGISTER = data;
|
||||
break;
|
||||
#endif /* UART_1_EN */
|
||||
#if UART_2_EN
|
||||
|
||||
case UART_2:
|
||||
UART2_DATA_REGISTER = data;
|
||||
break;
|
||||
#endif /* UART_2_EN */
|
||||
#if UART_3_EN
|
||||
|
||||
case UART_3:
|
||||
UART3_DATA_REGISTER = data;
|
||||
break;
|
||||
#endif /* UART_3_EN */
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
int uart_read_blocking(uart_t uart, char *data)
|
||||
{
|
||||
switch (uart) {
|
||||
#if UART_0_EN
|
||||
|
||||
case UART_0:
|
||||
while (!UART0_RECEIVED_DATA);
|
||||
|
||||
*data = (char) UART0_DATA_REGISTER;
|
||||
break;
|
||||
#endif /* UART_0_EN */
|
||||
#if UART_1_EN
|
||||
|
||||
case UART_1:
|
||||
while (!UART1_RECEIVED_DATA);
|
||||
|
||||
*data = (char) UART1_DATA_REGISTER;
|
||||
break;
|
||||
#endif /* UART_1_EN */
|
||||
#if UART_2_EN
|
||||
|
||||
case UART_2:
|
||||
while (!UART2_RECEIVED_DATA);
|
||||
|
||||
*data = (char) UART2_DATA_REGISTER;
|
||||
break;
|
||||
#endif /* UART_2_EN */
|
||||
#if UART_3_EN
|
||||
|
||||
case UART_3:
|
||||
while (!UART3_RECEIVED_DATA);
|
||||
|
||||
*data = (char) UART3_DATA_REGISTER;
|
||||
break;
|
||||
#endif /* UART_3_EN */
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
int uart_write_blocking(uart_t uart, char data)
|
||||
{
|
||||
switch (uart) {
|
||||
#if UART_0_EN
|
||||
|
||||
case UART_0:
|
||||
while (!UART0_DTREG_EMPTY);
|
||||
|
||||
UART0_DATA_REGISTER = data;
|
||||
break;
|
||||
#endif /* UART_0_EN */
|
||||
#if UART_1_EN
|
||||
|
||||
case UART_1:
|
||||
while (!UART1_DTREG_EMPTY);
|
||||
|
||||
UART1_DATA_REGISTER = data;
|
||||
break;
|
||||
#endif /* UART_1_EN */
|
||||
#if UART_2_EN
|
||||
|
||||
case UART_2:
|
||||
while (!UART2_DTREG_EMPTY);
|
||||
|
||||
UART2_DATA_REGISTER = data;
|
||||
break;
|
||||
#endif /* UART_2_EN */
|
||||
#if UART_3_EN
|
||||
|
||||
case UART_3:
|
||||
while (!UART3_DTREG_EMPTY);
|
||||
|
||||
UART3_DATA_REGISTER = data;
|
||||
break;
|
||||
#endif /* UART_3_EN */
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
#if UART_0_EN
|
||||
ISR(USART0_RX_vect, ISR_BLOCK)
|
||||
{
|
||||
config[UART_0].rx_cb(config[UART_0].arg, UART0_DATA_REGISTER);
|
||||
|
||||
if (sched_context_switch_request) {
|
||||
thread_yield();
|
||||
}
|
||||
}
|
||||
#endif /* UART_0_EN */
|
||||
|
||||
#if UART_1_EN
|
||||
ISR(USART1_RX_vect, ISR_BLOCK)
|
||||
{
|
||||
config[UART_1].rx_cb(config[UART_1].arg, UART0_DATA_REGISTER);
|
||||
|
||||
if (sched_context_switch_request) {
|
||||
thread_yield();
|
||||
}
|
||||
}
|
||||
#endif /* UART_1_EN */
|
||||
|
||||
#if UART_1_EN
|
||||
ISR(USART2_RX_vect, ISR_BLOCK)
|
||||
{
|
||||
config[UART_2].rx_cb(config[UART_2].arg, UART0_DATA_REGISTER);
|
||||
|
||||
if (sched_context_switch_request) {
|
||||
thread_yield();
|
||||
}
|
||||
}
|
||||
#endif /* UART_2_EN */
|
||||
|
||||
#if UART_2_EN
|
||||
ISR(USART2_RX_vect, ISR_BLOCK)
|
||||
{
|
||||
config[UART_3].rx_cb(config[UART_3].arg, UART0_DATA_REGISTER);
|
||||
|
||||
if (sched_context_switch_request) {
|
||||
thread_yield();
|
||||
}
|
||||
}
|
||||
#endif /* UART_3_EN */
|
||||
40
cpu/atmega2560/reboot_arch.c
Normal file
40
cpu/atmega2560/reboot_arch.c
Normal file
@ -0,0 +1,40 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_atmega2560
|
||||
* @{
|
||||
*
|
||||
* @file reboot_arch.c
|
||||
* @brief Implementation of the kernels reboot interface
|
||||
*
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include <avr/wdt.h>
|
||||
|
||||
#include "arch/reboot_arch.h"
|
||||
#include "cpu.h"
|
||||
|
||||
|
||||
int reboot_arch(int mode)
|
||||
{
|
||||
printf("Going into reboot, mode %i\n", mode);
|
||||
|
||||
/*
|
||||
* Since the AVR doesn't support a real software reset, we set the Watchdog
|
||||
* Timer on a 250ms timeout. Consider this a kludge.
|
||||
*/
|
||||
wdt_enable(WDTO_250MS);
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
74
cpu/atmega2560/startup.c
Normal file
74
cpu/atmega2560/startup.c
Normal file
@ -0,0 +1,74 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_atmega2560
|
||||
* @{
|
||||
*
|
||||
* @file startup.c
|
||||
* @brief Startup code and interrupt vector definition
|
||||
*
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include <avr/io.h>
|
||||
|
||||
/* For Catchall-Loop */
|
||||
#include "board.h"
|
||||
#include <util/delay.h>
|
||||
#include <stdio.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__((naked)) __attribute__((section(".init7")));
|
||||
void init8_ovr(void) __attribute__((naked)) __attribute__((section(".init8")));
|
||||
|
||||
|
||||
void init7_ovr(void)
|
||||
{
|
||||
asm("call reset_handler");
|
||||
}
|
||||
|
||||
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
|
||||
*/
|
||||
void reset_handler(void)
|
||||
{
|
||||
/* initialize the board and startup the kernel */
|
||||
board_init();
|
||||
/* startup the kernel */
|
||||
kernel_init();
|
||||
}
|
||||
5
cpu/atmega_common/Makefile
Normal file
5
cpu/atmega_common/Makefile
Normal file
@ -0,0 +1,5 @@
|
||||
|
||||
# define the module that is build
|
||||
MODULE = atmega_common
|
||||
|
||||
include $(RIOTBASE)/Makefile.base
|
||||
3
cpu/atmega_common/Makefile.include
Normal file
3
cpu/atmega_common/Makefile.include
Normal file
@ -0,0 +1,3 @@
|
||||
|
||||
# include module specific includes
|
||||
export INCLUDES += -I$(RIOTCPU)/atmega_common/include -isystem$(RIOTCPU)/atmega_common/avr-libc-extra
|
||||
33
cpu/atmega_common/atomic_arch.c
Normal file
33
cpu/atmega_common/atomic_arch.c
Normal file
@ -0,0 +1,33 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_atmega_common
|
||||
* @{
|
||||
*
|
||||
* @file atomic_arch.c
|
||||
* @brief Implementation of the kernels atomic interface
|
||||
*
|
||||
* @author Stefan Pfeiffer <stefan.pfeiffer@fu-berlin.de>
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "arch/atomic_arch.h"
|
||||
#include "irq.h"
|
||||
|
||||
unsigned int atomic_arch_set_return(unsigned int *to_set, unsigned int value)
|
||||
{
|
||||
disableIRQ();
|
||||
unsigned int old = *to_set;
|
||||
*to_set = value;
|
||||
enableIRQ();
|
||||
return old;
|
||||
}
|
||||
147
cpu/atmega_common/avr-libc-extra/errno.h
Normal file
147
cpu/atmega_common/avr-libc-extra/errno.h
Normal file
@ -0,0 +1,147 @@
|
||||
/* Copyright (c) 2002,2007 Marek Michalkiewicz
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
|
||||
* Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
|
||||
* Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in
|
||||
the documentation and/or other materials provided with the
|
||||
distribution.
|
||||
|
||||
* Neither the name of the copyright holders nor the names of
|
||||
contributors may be used to endorse or promote products derived
|
||||
from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
|
||||
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||||
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||||
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
POSSIBILITY OF SUCH DAMAGE. */
|
||||
|
||||
/* $Id$ */
|
||||
|
||||
#ifndef __ERRNO_H_
|
||||
#define __ERRNO_H_ 1
|
||||
|
||||
/** \file */
|
||||
/** \defgroup avr_errno <errno.h>: System Errors
|
||||
|
||||
\code #include <errno.h>\endcode
|
||||
|
||||
Some functions in the library set the global variable \c errno when an
|
||||
error occurs. The file, \c <errno.h>, provides symbolic names for various
|
||||
error codes.
|
||||
|
||||
\warning The \c errno global variable is not safe to use in a threaded or
|
||||
multi-task system. A race condition can occur if a task is interrupted
|
||||
between the call which sets \c error and when the task examines \c
|
||||
errno. If another task changes \c errno during this time, the result will
|
||||
be incorrect for the interrupted task. */
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
extern int errno;
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
/** \ingroup avr_errno
|
||||
\def EDOM
|
||||
|
||||
Domain error. */
|
||||
#define EDOM 33
|
||||
|
||||
/** \ingroup avr_errno
|
||||
\def ERANGE
|
||||
|
||||
Range error. */
|
||||
#define ERANGE 34
|
||||
|
||||
/* ((((('E'-64)*26+('N'-64))*26+('O'-64))*26+('S'-64))*26+('Y'-64))*26+'S'-64 */
|
||||
#define ENOSYS ((int)(66081697 & 0x7fff))
|
||||
|
||||
/* (((('E'-64)*26+('I'-64))*26+('N'-64))*26+('T'-64))*26+('R'-64) */
|
||||
#define EINTR ((int)(2453066 & 0x7fff))
|
||||
|
||||
#define E2BIG ENOERR
|
||||
#define EACCES ENOERR
|
||||
#define EADDRINUSE ENOERR
|
||||
#define EADDRNOTAVAIL ENOERR
|
||||
#define EAFNOSUPPORT ENOERR
|
||||
#define EAGAIN ENOERR
|
||||
#define EALREADY ENOERR
|
||||
#define EBADF ENOERR
|
||||
//#define EBUSY ENOERR
|
||||
#define ECHILD ENOERR
|
||||
#define ECONNABORTED ENOERR
|
||||
#define ECONNREFUSED ENOERR
|
||||
#define ECONNRESET ENOERR
|
||||
#define EDEADLK ENOERR
|
||||
#define EDESTADDRREQ ENOERR
|
||||
#define EEXIST ENOERR
|
||||
#define EFAULT ENOERR
|
||||
#define EFBIG ENOERR
|
||||
#define EHOSTUNREACH ENOERR
|
||||
#define EILSEQ ENOERR
|
||||
#define EINPROGRESS ENOERR
|
||||
//#define EINVAL ENOERR
|
||||
#define EIO ENOERR
|
||||
#define EISCONN ENOERR
|
||||
#define EISDIR ENOERR
|
||||
#define ELOOP ENOERR
|
||||
#define EMFILE ENOERR
|
||||
#define EMLINK ENOERR
|
||||
#define EMSGSIZE ENOERR
|
||||
#define ENAMETOOLONG ENOERR
|
||||
#define ENETDOWN ENOERR
|
||||
#define ENETRESET ENOERR
|
||||
#define ENETUNREACH ENOERR
|
||||
#define ENFILE ENOERR
|
||||
#define ENOBUFS ENOERR
|
||||
#define ENODEV ENOERR
|
||||
#define ENOENT ENOERR
|
||||
#define ENOEXEC ENOERR
|
||||
#define ENOLCK ENOERR
|
||||
#define ENOMEM ENOERR
|
||||
#define ENOMSG ENOERR
|
||||
#define ENOPROTOOPT ENOERR
|
||||
#define ENOSPC ENOERR
|
||||
#define ENOTCONN ENOERR
|
||||
#define ENOTDIR ENOERR
|
||||
#define ENOTEMPTY ENOERR
|
||||
#define ENOTSOCK ENOERR
|
||||
#define ENOTTY ENOERR
|
||||
#define ENXIO ENOERR
|
||||
#define EOPNOTSUPP ENOERR
|
||||
#define EPERM ENOERR
|
||||
#define EPIPE ENOERR
|
||||
#define EPROTONOSUPPORT ENOERR
|
||||
#define EPROTOTYPE ENOERR
|
||||
#define EROFS ENOERR
|
||||
#define ESPIPE ENOERR
|
||||
#define ESRCH ENOERR
|
||||
#define ETIMEDOUT ENOERR
|
||||
#define EWOULDBLOCK ENOERR
|
||||
#define EXDEV ENOERR
|
||||
|
||||
/* ((((('E'-64)*26+('N'-64))*26+('O'-64))*26+('E'-64))*26+('R'-64))*26+'R'-64 */
|
||||
#define ENOERR ((int)(66072050 & 0xffff))
|
||||
|
||||
#define EBUSY 16 /* Device or resource busy */
|
||||
#define EINVAL 22 /* Invalid argument */
|
||||
#define EOVERFLOW 75 /* Value too large for defined data type */
|
||||
|
||||
#endif
|
||||
528
cpu/atmega_common/avr-libc-extra/time.h
Normal file
528
cpu/atmega_common/avr-libc-extra/time.h
Normal file
@ -0,0 +1,528 @@
|
||||
/*
|
||||
* (C)2012 Michael Duane Rice All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are
|
||||
* met:
|
||||
*
|
||||
* Redistributions of source code must retain the above copyright notice, this
|
||||
* list of conditions and the following disclaimer. Redistributions in binary
|
||||
* form must reproduce the above copyright notice, this list of conditions
|
||||
* and the following disclaimer in the documentation and/or other materials
|
||||
* provided with the distribution. Neither the name of the copyright holders
|
||||
* nor the names of contributors may be used to endorse or promote products
|
||||
* derived from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
|
||||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
/* $Id$ */
|
||||
|
||||
/** \file */
|
||||
|
||||
/** \defgroup avr_time <time.h>: Time
|
||||
\code #include <time.h> \endcode
|
||||
<h3>Introduction to the Time functions</h3>
|
||||
This file declares the time functions implemented in \c avr-libc.
|
||||
|
||||
The implementation aspires to conform with ISO/IEC 9899 (C90). However, due to limitations of the
|
||||
target processor and the nature of its development environment, a practical implementation must
|
||||
of necessity deviate from the standard.
|
||||
|
||||
|
||||
|
||||
Section 7.23.2.1 clock()
|
||||
The type clock_t, the macro CLOCKS_PER_SEC, and the function clock() are not implemented. We
|
||||
consider these items belong to operating system code, or to application code when no operating
|
||||
system is present.
|
||||
|
||||
Section 7.23.2.3 mktime()
|
||||
The standard specifies that mktime() should return (time_t) -1, if the time cannot be represented.
|
||||
This implementation always returns a 'best effort' representation.
|
||||
|
||||
Section 7.23.2.4 time()
|
||||
The standard specifies that time() should return (time_t) -1, if the time is not available.
|
||||
Since the application must initialize the time system, this functionality is not implemented.
|
||||
|
||||
Section 7.23.2.2, difftime()
|
||||
Due to the lack of a 64 bit double, the function difftime() returns a long integer. In most cases
|
||||
this change will be invisible to the user, handled automatically by the compiler.
|
||||
|
||||
Section 7.23.1.4 struct tm
|
||||
Per the standard, struct tm->tm_isdst is greater than zero when Daylight Saving time is in effect.
|
||||
This implementation further specifies that, when positive, the value of tm_isdst represents
|
||||
the amount time is advanced during Daylight Saving time.
|
||||
|
||||
Section 7.23.3.5 strftime()
|
||||
Only the 'C' locale is supported, therefore the modifiers 'E' and 'O' are ignored.
|
||||
The 'Z' conversion is also ignored, due to the lack of time zone name.
|
||||
|
||||
In addition to the above departures from the standard, there are some behaviors which are different
|
||||
from what is often expected, though allowed under the standard.
|
||||
|
||||
There is no 'platform standard' method to obtain the current time, time zone, or
|
||||
daylight savings 'rules' in the AVR environment. Therefore the application must initialize
|
||||
the time system with this information. The functions set_zone(), set_dst(), and
|
||||
set_system_time() are provided for initialization. Once initialized, system time is maintained by
|
||||
calling the function system_tick() at one second intervals.
|
||||
|
||||
Though not specified in the standard, it is often expected that time_t is a signed integer
|
||||
representing an offset in seconds from Midnight Jan 1 1970... i.e. 'Unix time'. This implementation
|
||||
uses an unsigned 32 bit integer offset from Midnight Jan 1 2000. The use of this 'epoch' helps to
|
||||
simplify the conversion functions, while the 32 bit value allows time to be properly represented
|
||||
until Tue Feb 7 06:28:15 2136 UTC. The macros UNIX_OFFSET and NTP_OFFSET are defined to assist in
|
||||
converting to and from Unix and NTP time stamps.
|
||||
|
||||
Unlike desktop counterparts, it is impractical to implement or maintain the 'zoneinfo' database.
|
||||
Therefore no attempt is made to account for time zone, daylight saving, or leap seconds in past dates.
|
||||
All calculations are made according to the currently configured time zone and daylight saving 'rule'.
|
||||
|
||||
In addition to C standard functions, re-entrant versions of ctime(), asctime(), gmtime() and
|
||||
localtime() are provided which, in addition to being re-entrant, have the property of claiming
|
||||
less permanent storage in RAM. An additional time conversion, isotime() and its re-entrant version,
|
||||
uses far less storage than either ctime() or asctime().
|
||||
|
||||
Along with the usual smattering of utility functions, such as is_leap_year(), this library includes
|
||||
a set of functions related the sun and moon, as well as sidereal time functions.
|
||||
*/
|
||||
|
||||
#ifndef TIME_H
|
||||
#define TIME_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
/** \ingroup avr_time */
|
||||
/* @{ */
|
||||
|
||||
/**
|
||||
time_t represents seconds elapsed from Midnight, Jan 1 2000 UTC (the Y2K 'epoch').
|
||||
Its range allows this implementation to represent time up to Tue Feb 7 06:28:15 2136 UTC.
|
||||
*/
|
||||
typedef uint32_t time_t;
|
||||
|
||||
/**
|
||||
The time function returns the systems current time stamp.
|
||||
If timer is not a null pointer, the return value is also assigned to the object it points to.
|
||||
*/
|
||||
time_t time(time_t *timer);
|
||||
|
||||
/**
|
||||
The difftime function returns the difference between two binary time stamps,
|
||||
time1 - time0.
|
||||
*/
|
||||
int32_t difftime(time_t time1, time_t time0);
|
||||
|
||||
|
||||
/**
|
||||
The tm structure contains a representation of time 'broken down' into components of the
|
||||
Gregorian calendar.
|
||||
|
||||
The normal ranges of the elements are..
|
||||
|
||||
\code
|
||||
tm_sec seconds after the minute - [ 0 to 59 ]
|
||||
tm_min minutes after the hour - [ 0 to 59 ]
|
||||
tm_hour hours since midnight - [ 0 to 23 ]
|
||||
tm_mday day of the month - [ 1 to 31 ]
|
||||
tm_wday days since Sunday - [ 0 to 6 ]
|
||||
tm_mon months since January - [ 0 to 11 ]
|
||||
tm_year years since 1900
|
||||
tm_yday days since January 1 - [ 0 to 365 ]
|
||||
tm_isdst Daylight Saving Time flag *
|
||||
|
||||
\endcode
|
||||
|
||||
*The value of tm_isdst is zero if Daylight Saving Time is not in effect, and is negative if
|
||||
the information is not available.
|
||||
|
||||
When Daylight Saving Time is in effect, the value represents the number of
|
||||
seconds the clock is advanced.
|
||||
|
||||
See the set_dst() function for more information about Daylight Saving.
|
||||
|
||||
*/
|
||||
struct tm {
|
||||
int tm_sec;
|
||||
int tm_min;
|
||||
int tm_hour;
|
||||
int tm_mday;
|
||||
int tm_wday;
|
||||
int tm_mon;
|
||||
int tm_year;
|
||||
int tm_yday;
|
||||
int tm_isdst;
|
||||
};
|
||||
|
||||
|
||||
/* We have to provide clock_t / CLOCKS_PER_SEC so that libstdc++-v3 can
|
||||
be built. We define CLOCKS_PER_SEC via a symbol _CLOCKS_PER_SEC_
|
||||
so that the user can provide the value on the link line, which should
|
||||
result in little or no run-time overhead compared with a constant. */
|
||||
typedef unsigned long clock_t;
|
||||
extern char *_CLOCKS_PER_SEC_;
|
||||
#define CLOCKS_PER_SEC ((clock_t) _CLOCKS_PER_SEC_)
|
||||
extern clock_t clock(void);
|
||||
|
||||
/**
|
||||
This function 'compiles' the elements of a broken-down time structure, returning a binary time stamp.
|
||||
The elements of timeptr are interpreted as representing Local Time.
|
||||
|
||||
The original values of the tm_wday and tm_yday elements of the structure are ignored,
|
||||
and the original values of the other elements are not restricted to the ranges stated for struct tm.
|
||||
|
||||
On successful completion, the values of all elements of timeptr are set to the appropriate range.
|
||||
*/
|
||||
time_t mktime(struct tm * timeptr);
|
||||
|
||||
/**
|
||||
This function 'compiles' the elements of a broken-down time structure, returning a binary time stamp.
|
||||
The elements of timeptr are interpreted as representing UTC.
|
||||
|
||||
The original values of the tm_wday and tm_yday elements of the structure are ignored,
|
||||
and the original values of the other elements are not restricted to the ranges stated for struct tm.
|
||||
|
||||
Unlike mktime(), this function DOES NOT modify the elements of timeptr.
|
||||
*/
|
||||
time_t mk_gmtime(const struct tm * timeptr);
|
||||
|
||||
/**
|
||||
The gmtime function converts the time stamp pointed to by timer into broken-down time,
|
||||
expressed as UTC.
|
||||
*/
|
||||
struct tm *gmtime(const time_t * timer);
|
||||
|
||||
/**
|
||||
Re entrant version of gmtime().
|
||||
*/
|
||||
void gmtime_r(const time_t * timer, struct tm * timeptr);
|
||||
|
||||
/**
|
||||
The localtime function converts the time stamp pointed to by timer into broken-down time,
|
||||
expressed as Local time.
|
||||
*/
|
||||
struct tm *localtime(const time_t * timer);
|
||||
|
||||
/**
|
||||
Re entrant version of localtime().
|
||||
*/
|
||||
void localtime_r(const time_t * timer, struct tm * timeptr);
|
||||
|
||||
/**
|
||||
The asctime function converts the broken-down time of timeptr, into an ascii string in the form
|
||||
|
||||
Sun Mar 23 01:03:52 2013
|
||||
*/
|
||||
char *asctime(const struct tm * timeptr);
|
||||
|
||||
/**
|
||||
Re entrant version of asctime().
|
||||
*/
|
||||
void asctime_r(const struct tm * timeptr, char *buf);
|
||||
|
||||
/**
|
||||
The ctime function is equivalent to asctime(localtime(timer))
|
||||
*/
|
||||
char *ctime(const time_t * timer);
|
||||
|
||||
/**
|
||||
Re entrant version of ctime().
|
||||
*/
|
||||
void ctime_r(const time_t * timer, char *buf);
|
||||
|
||||
/**
|
||||
The isotime function constructs an ascii string in the form
|
||||
\code2013-03-23 01:03:52\endcode
|
||||
*/
|
||||
char *isotime(const struct tm * tmptr);
|
||||
|
||||
/**
|
||||
Re entrant version of isotime()
|
||||
*/
|
||||
void isotime_r(const struct tm *, char *);
|
||||
|
||||
/**
|
||||
A complete description of strftime() is beyond the pale of this document.
|
||||
Refer to ISO/IEC document 9899 for details.
|
||||
|
||||
All conversions are made using the 'C Locale', ignoring the E or O modifiers. Due to the lack of
|
||||
a time zone 'name', the 'Z' conversion is also ignored.
|
||||
*/
|
||||
size_t strftime(char *s, size_t maxsize, const char *format, const struct tm * timeptr);
|
||||
|
||||
/**
|
||||
Specify the Daylight Saving function.
|
||||
|
||||
The Daylight Saving function should examine its parameters to determine whether
|
||||
Daylight Saving is in effect, and return a value appropriate for tm_isdst.
|
||||
|
||||
Working examples for the USA and the EU are available..
|
||||
|
||||
\code #include <util/eu_dst.h>\endcode
|
||||
for the European Union, and
|
||||
\code #include <util/usa_dst.h>\endcode
|
||||
for the United States
|
||||
|
||||
If a Daylight Saving function is not specified, the system will ignore Daylight Saving.
|
||||
*/
|
||||
void set_dst(int (*) (const time_t *, int32_t *));
|
||||
|
||||
/**
|
||||
Set the 'time zone'. The parameter is given in seconds East of the Prime Meridian.
|
||||
Example for New York City:
|
||||
\code set_zone(-5 * ONE_HOUR);\endcode
|
||||
|
||||
If the time zone is not set, the time system will operate in UTC only.
|
||||
*/
|
||||
void set_zone(int32_t);
|
||||
|
||||
/**
|
||||
Initialize the system time. Examples are...
|
||||
|
||||
From a Clock / Calendar type RTC:
|
||||
\code
|
||||
struct tm rtc_time;
|
||||
|
||||
read_rtc(&rtc_time);
|
||||
rtc_time.tm_isdst = 0;
|
||||
set_system_time( mktime(&rtc_time) );
|
||||
\endcode
|
||||
|
||||
From a Network Time Protocol time stamp:
|
||||
\code
|
||||
set_system_time(ntp_timestamp - NTP_OFFSET);
|
||||
\endcode
|
||||
|
||||
From a UNIX time stamp:
|
||||
\code
|
||||
set_system_time(unix_timestamp - UNIX_OFFSET);
|
||||
\endcode
|
||||
|
||||
*/
|
||||
void set_system_time(time_t timestamp);
|
||||
|
||||
/**
|
||||
Maintain the system time by calling this function at a rate of 1 Hertz.
|
||||
|
||||
It is anticipated that this function will typically be called from within an
|
||||
Interrupt Service Routine, (though that is not required). It therefore includes code which
|
||||
makes it simple to use from within a 'Naked' ISR, avoiding the cost of saving and restoring
|
||||
all the cpu registers.
|
||||
|
||||
Such an ISR may resemble the following example...
|
||||
\code
|
||||
ISR(RTC_OVF_vect, ISR_NAKED)
|
||||
{
|
||||
system_tick();
|
||||
reti();
|
||||
}
|
||||
\endcode
|
||||
*/
|
||||
void system_tick(void);
|
||||
|
||||
/**
|
||||
Enumerated labels for the days of the week.
|
||||
*/
|
||||
enum _WEEK_DAYS_ {
|
||||
SUNDAY,
|
||||
MONDAY,
|
||||
TUESDAY,
|
||||
WEDNESDAY,
|
||||
THURSDAY,
|
||||
FRIDAY,
|
||||
SATURDAY
|
||||
};
|
||||
|
||||
/**
|
||||
Enumerated labels for the months.
|
||||
*/
|
||||
enum _MONTHS_ {
|
||||
JANUARY,
|
||||
FEBRUARY,
|
||||
MARCH,
|
||||
APRIL,
|
||||
MAY,
|
||||
JUNE,
|
||||
JULY,
|
||||
AUGUST,
|
||||
SEPTEMBER,
|
||||
OCTOBER,
|
||||
NOVEMBER,
|
||||
DECEMBER
|
||||
};
|
||||
|
||||
/**
|
||||
Return 1 if year is a leap year, zero if it is not.
|
||||
*/
|
||||
uint8_t is_leap_year(int16_t year);
|
||||
|
||||
/**
|
||||
Return the length of month, given the year and month, where month is in the range 1 to 12.
|
||||
*/
|
||||
uint8_t month_length(int16_t year, uint8_t month);
|
||||
|
||||
/**
|
||||
Return the calendar week of year, where week 1 is considered to begin on the
|
||||
day of week specified by 'start'. The returned value may range from zero to 52.
|
||||
*/
|
||||
uint8_t week_of_year(const struct tm * timeptr, uint8_t start);
|
||||
|
||||
/**
|
||||
Return the calendar week of month, where the first week is considered to begin on the
|
||||
day of week specified by 'start'. The returned value may range from zero to 5.
|
||||
*/
|
||||
uint8_t week_of_month(const struct tm * timeptr, uint8_t start);
|
||||
|
||||
/**
|
||||
Structure which represents a date as a year, week number of that year, and day of week.
|
||||
See http://en.wikipedia.org/wiki/ISO_week_date for more information.
|
||||
*/
|
||||
struct week_date{
|
||||
int year;
|
||||
int week;
|
||||
int day;
|
||||
};
|
||||
|
||||
/**
|
||||
Return a week_date structure with the ISO_8601 week based date corresponding to the given
|
||||
year and day of year. See http://en.wikipedia.org/wiki/ISO_week_date for more
|
||||
information.
|
||||
*/
|
||||
struct week_date * iso_week_date( int year, int yday);
|
||||
|
||||
/**
|
||||
Re-entrant version of iso-week_date.
|
||||
*/
|
||||
void iso_week_date_r( int year, int yday, struct week_date *);
|
||||
|
||||
/**
|
||||
Convert a Y2K time stamp into a FAT file system time stamp.
|
||||
*/
|
||||
uint32_t fatfs_time(const struct tm * timeptr);
|
||||
|
||||
/** One hour, expressed in seconds */
|
||||
#define ONE_HOUR 3600
|
||||
|
||||
/** Angular degree, expressed in arc seconds */
|
||||
#define ONE_DEGREE 3600
|
||||
|
||||
/** One day, expressed in seconds */
|
||||
#define ONE_DAY 86400
|
||||
|
||||
/** Difference between the Y2K and the UNIX epochs, in seconds. To convert a Y2K
|
||||
timestamp to UNIX...
|
||||
\code
|
||||
long unix;
|
||||
time_t y2k;
|
||||
|
||||
y2k = time(NULL);
|
||||
unix = y2k + UNIX_OFFSET;
|
||||
\endcode
|
||||
*/
|
||||
#define UNIX_OFFSET 946684800
|
||||
|
||||
/** Difference between the Y2K and the NTP epochs, in seconds. To convert a Y2K
|
||||
timestamp to NTP...
|
||||
\code
|
||||
unsigned long ntp;
|
||||
time_t y2k;
|
||||
|
||||
y2k = time(NULL);
|
||||
ntp = y2k + NTP_OFFSET;
|
||||
\endcode
|
||||
*/
|
||||
#define NTP_OFFSET 3155673600
|
||||
|
||||
/*
|
||||
* ===================================================================
|
||||
* Ephemera
|
||||
*/
|
||||
|
||||
/**
|
||||
Set the geographic coordinates of the 'observer', for use with several of the
|
||||
following functions. Parameters are passed as seconds of North Latitude, and seconds
|
||||
of East Longitude.
|
||||
|
||||
For New York City...
|
||||
\code set_position( 40.7142 * ONE_DEGREE, -74.0064 * ONE_DEGREE); \endcode
|
||||
*/
|
||||
void set_position(int32_t latitude, int32_t longitude);
|
||||
|
||||
/**
|
||||
Computes the difference between apparent solar time and mean solar time.
|
||||
The returned value is in seconds.
|
||||
*/
|
||||
int16_t equation_of_time(const time_t * timer);
|
||||
|
||||
/**
|
||||
Computes the amount of time the sun is above the horizon, at the location of the observer.
|
||||
|
||||
NOTE: At observer locations inside a polar circle, this value can be zero during the winter,
|
||||
and can exceed ONE_DAY during the summer.
|
||||
|
||||
The returned value is in seconds.
|
||||
*/
|
||||
int32_t daylight_seconds(const time_t * timer);
|
||||
|
||||
/**
|
||||
Computes the time of solar noon, at the location of the observer.
|
||||
*/
|
||||
time_t solar_noon(const time_t * timer);
|
||||
|
||||
/**
|
||||
Return the time of sunrise, at the location of the observer. See the note about daylight_seconds().
|
||||
*/
|
||||
time_t sun_rise(const time_t * timer);
|
||||
|
||||
/**
|
||||
Return the time of sunset, at the location of the observer. See the note about daylight_seconds().
|
||||
*/
|
||||
time_t sun_set(const time_t * timer);
|
||||
|
||||
/** Returns the declination of the sun in radians. */
|
||||
double solar_declination(const time_t * timer);
|
||||
|
||||
/**
|
||||
Returns an approximation to the phase of the moon.
|
||||
The sign of the returned value indicates a waning or waxing phase.
|
||||
The magnitude of the returned value indicates the percentage illumination.
|
||||
*/
|
||||
int8_t moon_phase(const time_t * timer);
|
||||
|
||||
/**
|
||||
Returns Greenwich Mean Sidereal Time, as seconds into the sidereal day.
|
||||
The returned value will range from 0 through 86399 seconds.
|
||||
*/
|
||||
unsigned long gm_sidereal(const time_t * timer);
|
||||
|
||||
/**
|
||||
Returns Local Mean Sidereal Time, as seconds into the sidereal day.
|
||||
The returned value will range from 0 through 86399 seconds.
|
||||
*/
|
||||
unsigned long lm_sidereal(const time_t * timer);
|
||||
|
||||
struct timespec {
|
||||
time_t tv_sec;
|
||||
long tv_nsec;
|
||||
};
|
||||
|
||||
/* @} */
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* TIME_H */
|
||||
5
cpu/atmega_common/doc.txt
Normal file
5
cpu/atmega_common/doc.txt
Normal file
@ -0,0 +1,5 @@
|
||||
/**
|
||||
* @defgroup cpu_atmega_common Atmel ATmega CPU: common files
|
||||
* @brief AVR Atmega specific code
|
||||
* @ingroup cpu
|
||||
*/
|
||||
46
cpu/atmega_common/include/cpu.h
Normal file
46
cpu/atmega_common/include/cpu.h
Normal file
@ -0,0 +1,46 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu
|
||||
* @brief Common implementations and headers for ATmega family based micro-controllers
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Basic definitions for the ATmega common module
|
||||
*
|
||||
* When ever you want to do something hardware related, that is accessing MCUs registers directly,
|
||||
* just include this file. It will then make sure that the MCU specific headers are included.
|
||||
*
|
||||
* @author Stefan Pfeiffer <stefan.pfeiffer@fu-berlin.de>
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
*/
|
||||
|
||||
#ifndef __ATMEGA_COMMON_H
|
||||
#define __ATMEGA_COMMON_H
|
||||
|
||||
#include "cpu-conf.h"
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
/**
|
||||
* For downwards compatibility with old RIOT code.
|
||||
* TODO: remove once core was adjusted
|
||||
*/
|
||||
#include "irq.h"
|
||||
#define eINT enableIRQ
|
||||
#define dINT disableIRQ
|
||||
|
||||
/**
|
||||
* @brief Initialization of the CPU
|
||||
*/
|
||||
void cpu_init(void);
|
||||
|
||||
|
||||
#endif /* __ATMEGA_COMMON_H */
|
||||
/** @} */
|
||||
15
cpu/atmega_common/include/sys/time.h
Normal file
15
cpu/atmega_common/include/sys/time.h
Normal file
@ -0,0 +1,15 @@
|
||||
/*
|
||||
* 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.
|
||||
*/
|
||||
|
||||
|
||||
#include <sys/types.h>
|
||||
|
||||
struct timeval {
|
||||
time_t tv_sec;
|
||||
suseconds_t tv_usec;
|
||||
};
|
||||
13
cpu/atmega_common/include/sys/types.h
Normal file
13
cpu/atmega_common/include/sys/types.h
Normal file
@ -0,0 +1,13 @@
|
||||
/*
|
||||
* 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.
|
||||
*/
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <stddef.h>
|
||||
|
||||
typedef int16_t suseconds_t;
|
||||
typedef size_t ssize_t;
|
||||
92
cpu/atmega_common/irq_arch.c
Normal file
92
cpu/atmega_common/irq_arch.c
Normal file
@ -0,0 +1,92 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_atmega_common
|
||||
* @{
|
||||
*
|
||||
* @file irq_arch.c
|
||||
* @brief Implementation of the kernels irq interface
|
||||
*
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include "arch/irq_arch.h"
|
||||
#include "cpu.h"
|
||||
|
||||
/**
|
||||
* @brief Macro returns state of the global interrupt register
|
||||
*/
|
||||
static uint8_t __get_interrupt_state(void);
|
||||
static void __set_interrupt_state(uint8_t state);
|
||||
|
||||
__attribute__((always_inline)) static inline uint8_t __get_interrupt_state(void)
|
||||
{
|
||||
uint8_t sreg;
|
||||
asm volatile("in r0, __SREG__; \n\t"
|
||||
"mov %0, r0 \n\t"
|
||||
: "=g"(sreg)
|
||||
:
|
||||
: "r0");
|
||||
return sreg & (1 << 7);
|
||||
}
|
||||
|
||||
__attribute__((always_inline)) inline void __set_interrupt_state(uint8_t state)
|
||||
{
|
||||
asm volatile("mov r15,%0; \n\t"
|
||||
"in r16, __SREG__; \n\t"
|
||||
"cbr r16,7; \n\t"
|
||||
"or r15,r16; \n\t"
|
||||
"out __SREG__, r15 \n\t"
|
||||
:
|
||||
: "g"(state)
|
||||
: "r15", "r16");
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Disable all maskable interrupts
|
||||
*/
|
||||
unsigned int irq_arch_disable(void)
|
||||
{
|
||||
uint8_t mask = __get_interrupt_state();
|
||||
cli();
|
||||
return (unsigned int) mask;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enable all maskable interrupts
|
||||
*/
|
||||
unsigned int irq_arch_enable(void)
|
||||
{
|
||||
sei();
|
||||
return __get_interrupt_state();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Restore the state of the IRQ flags
|
||||
*/
|
||||
void irq_arch_restore(unsigned int state)
|
||||
{
|
||||
__set_interrupt_state(state);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief See if the current context is inside an ISR
|
||||
*/
|
||||
int irq_arch_in(void)
|
||||
{
|
||||
/*
|
||||
* TODO: find a way to implement this function (e.g. a static variable dis- or
|
||||
* set and unset in each ISR)
|
||||
*/
|
||||
return 0;
|
||||
}
|
||||
344
cpu/atmega_common/thread_arch.c
Normal file
344
cpu/atmega_common/thread_arch.c
Normal file
@ -0,0 +1,344 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_atmega_common
|
||||
* @{
|
||||
*
|
||||
* @file thread_arch.c
|
||||
* @brief Implementation of the kernel's architecture dependent thread interface
|
||||
*
|
||||
* @author Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
#include "arch/thread_arch.h"
|
||||
#include "thread.h"
|
||||
#include "sched.h"
|
||||
#include "irq.h"
|
||||
#include "cpu.h"
|
||||
#include "kernel_internal.h"
|
||||
|
||||
/*
|
||||
* local function declarations (prefixed with __)
|
||||
*/
|
||||
|
||||
static void __context_save(void);
|
||||
static void __context_restore(void);
|
||||
static void __enter_thread_mode(void);
|
||||
|
||||
/**
|
||||
* @brief Since AVR doesn't support direct manipulation of the program counter we
|
||||
* model a stack like it would be left by __context_save().
|
||||
* The resulting layout in memory is the following:
|
||||
* ---------------tcb_t (not created by thread_arch_stack_init) ----------
|
||||
* local variables (a temporary value and the stackpointer)
|
||||
* -----------------------------------------------------------------------
|
||||
* a marker (AFFE) - for debugging purposes (helps finding the stack
|
||||
* -----------------------------------------------------------------------
|
||||
* a 16 Bit pointer to sched_task_exit
|
||||
* (Optional 17 bit (bit is set to zero) for ATmega2560
|
||||
* -----------------------------------------------------------------------
|
||||
* a 16 Bit pointer to task_func
|
||||
* this is placed exactly at the place where the program counter would be
|
||||
* stored normally and thus can be returned to when __context_restore()
|
||||
* has been run
|
||||
* (Optional 17 bit (bit is set to zero) for ATmega2560
|
||||
* -----------------------------------------------------------------------
|
||||
* saved registers from context:
|
||||
* r0
|
||||
* status register
|
||||
* (Optional EIND and RAMPZ registers for ATmega2560)
|
||||
* r1 - r23
|
||||
* pointer to arg in r24 and r25
|
||||
* r26 - r31
|
||||
* -----------------------------------------------------------------------
|
||||
*
|
||||
* After the invocation of __context_restore() the pointer to task_func is
|
||||
* on top of the stack and can be returned to. This way we can actually place
|
||||
* it inside of the programm counter of the MCU.
|
||||
* if task_func returns sched_task_exit gets popped into the PC
|
||||
*/
|
||||
char *thread_arch_stack_init(void *(*task_func)(void *), void *arg, void *stack_start,
|
||||
int stack_size)
|
||||
{
|
||||
uint16_t tmp_adress;
|
||||
uint8_t *stk;
|
||||
|
||||
/* AVR uses 16 Bit or two 8 Bit registers for storing pointers*/
|
||||
stk = (uint8_t *)((uint16_t)stack_start + stack_size);
|
||||
|
||||
/* put marker on stack */
|
||||
stk--;
|
||||
*stk = (uint8_t) 0xAF;
|
||||
stk--;
|
||||
*stk = (uint8_t) 0xFE;
|
||||
|
||||
/* save sched_task_exit */
|
||||
stk--;
|
||||
tmp_adress = (uint16_t) sched_task_exit;
|
||||
*stk = (uint8_t)(tmp_adress & (uint16_t) 0x00ff);
|
||||
stk--;
|
||||
tmp_adress >>= 8;
|
||||
*stk = (uint8_t)(tmp_adress & (uint16_t) 0x00ff);
|
||||
|
||||
#if defined(__AVR_ATmega2560__)
|
||||
/* The ATMega2560 uses a 17 bit PC, we set whole the top byte forcibly to 0 */
|
||||
stk--;
|
||||
*stk = (uint8_t) 0x00;
|
||||
#endif
|
||||
|
||||
/* save address to task_func in place of the program counter */
|
||||
stk--;
|
||||
tmp_adress = (uint16_t) task_func;
|
||||
*stk = (uint8_t)(tmp_adress & (uint16_t) 0x00ff);
|
||||
stk--;
|
||||
tmp_adress >>= 8;
|
||||
*stk = (uint8_t)(tmp_adress & (uint16_t) 0x00ff);
|
||||
|
||||
#if defined(__AVR_ATmega2560__)
|
||||
/* The ATMega2560 uses a 17 byte PC, we set the top byte forcibly to 0 */
|
||||
stk--;
|
||||
*stk = (uint8_t) 0x00;
|
||||
#endif
|
||||
|
||||
|
||||
/* r0 */
|
||||
stk--;
|
||||
*stk = (uint8_t) 0x00;
|
||||
|
||||
/* status register (with interrupts enabled) */
|
||||
stk--;
|
||||
*stk = (uint8_t) 0x80;
|
||||
|
||||
#if defined(__AVR_ATmega2560__)
|
||||
/* EIND */
|
||||
stk--;
|
||||
*stk = (uint8_t) 0x00;
|
||||
|
||||
/* RAMPZ */
|
||||
stk--;
|
||||
*stk = (uint8_t) 0x00;
|
||||
#endif
|
||||
|
||||
/* r1 - has always to be 0 */
|
||||
stk--;
|
||||
*stk = (uint8_t) 0x00;
|
||||
/*
|
||||
* Space for registers r2 -r23
|
||||
*
|
||||
* use loop for better readability, the compiler unrolls anyways
|
||||
*/
|
||||
|
||||
int i;
|
||||
|
||||
for (i = 2; i <= 23 ; i++) {
|
||||
stk--;
|
||||
*stk = (uint8_t) 0;
|
||||
}
|
||||
|
||||
/*
|
||||
* In accordance with the AVR calling conventions *arg has to be inside
|
||||
* r24 and r25
|
||||
* */
|
||||
stk--;
|
||||
tmp_adress = (uint16_t) arg;
|
||||
*stk = (uint8_t)(tmp_adress & (uint16_t) 0x00ff);
|
||||
stk--;
|
||||
tmp_adress >>= 8;
|
||||
*stk = (uint8_t)(tmp_adress & (uint16_t) 0x00ff);
|
||||
|
||||
/*
|
||||
* Space for registers r26-r31
|
||||
*/
|
||||
for (i = 26; i <= 31; i++) {
|
||||
stk--;
|
||||
*stk = (uint8_t) i;
|
||||
}
|
||||
|
||||
stk--;
|
||||
return (char *) stk;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief thread_arch_stack_print prints the stack to stdout.
|
||||
* It depends on getting the correct values for stack_start, stack_size and sp
|
||||
* from sched_active_thread.
|
||||
* Maybe it would be good to change that to way that is less dependant on
|
||||
* getting correct values elsewhere (since it is a debugging tool and in the
|
||||
* presence of bugs the data may be corrupted).
|
||||
*/
|
||||
void thread_arch_stack_print(void)
|
||||
{
|
||||
uint8_t found_marker = 1;
|
||||
uint8_t *sp = (uint8_t *)sched_active_thread->sp;
|
||||
uint16_t size = 0;
|
||||
|
||||
printf("Printing current stack of thread %" PRIkernel_pid "\n", thread_getpid());
|
||||
printf("\taddress:\tdata:\n");
|
||||
|
||||
do {
|
||||
printf("\t0x%04x:\t\t0x%04x\n", (unsigned int)sp, (unsigned int)*sp);
|
||||
sp++;
|
||||
size++;
|
||||
|
||||
if ((*sp == 0xFE) && (*(sp + 1) == 0xAF)) {
|
||||
found_marker = 0;
|
||||
}
|
||||
}
|
||||
while (found_marker == 1);
|
||||
|
||||
printf("stack size: %u bytes\n", size);
|
||||
}
|
||||
|
||||
void thread_arch_start_threading(void) __attribute__((naked));
|
||||
void thread_arch_start_threading(void)
|
||||
{
|
||||
sched_run();
|
||||
__enter_thread_mode();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Set the MCU into Thread-Mode and load the initial task from the stack and run it
|
||||
*/
|
||||
|
||||
void NORETURN __enter_thread_mode(void) __attribute__((naked));
|
||||
void NORETURN __enter_thread_mode(void)
|
||||
{
|
||||
enableIRQ();
|
||||
__context_restore();
|
||||
asm volatile("ret");
|
||||
|
||||
UNREACHABLE();
|
||||
}
|
||||
|
||||
void thread_arch_yield(void) __attribute__((naked));
|
||||
void thread_arch_yield(void)
|
||||
{
|
||||
__context_save();
|
||||
|
||||
/* disableIRQ(); */ /* gets already disabled during __context_save() */
|
||||
sched_run();
|
||||
enableIRQ();
|
||||
|
||||
__context_restore();
|
||||
asm volatile("ret");
|
||||
}
|
||||
|
||||
|
||||
__attribute__((always_inline)) static inline void __context_save(void)
|
||||
{
|
||||
asm volatile(
|
||||
"push r0 \n\t"
|
||||
"in r0, __SREG__ \n\t"
|
||||
"cli \n\t"
|
||||
"push r0 \n\t"
|
||||
#if defined(__AVR_ATmega2560__)
|
||||
/* EIND and RAMPZ */
|
||||
"in r0, 0x3b \n\t"
|
||||
"push r0 \n\t"
|
||||
"in r0, 0x3c \n\t"
|
||||
"push r0 \n\t"
|
||||
#endif
|
||||
"push r1 \n\t"
|
||||
"clr r1 \n\t"
|
||||
"push r2 \n\t"
|
||||
"push r3 \n\t"
|
||||
"push r4 \n\t"
|
||||
"push r5 \n\t"
|
||||
"push r6 \n\t"
|
||||
"push r7 \n\t"
|
||||
"push r8 \n\t"
|
||||
"push r9 \n\t"
|
||||
"push r10 \n\t"
|
||||
"push r11 \n\t"
|
||||
"push r12 \n\t"
|
||||
"push r13 \n\t"
|
||||
"push r14 \n\t"
|
||||
"push r15 \n\t"
|
||||
"push r16 \n\t"
|
||||
"push r17 \n\t"
|
||||
"push r18 \n\t"
|
||||
"push r19 \n\t"
|
||||
"push r20 \n\t"
|
||||
"push r21 \n\t"
|
||||
"push r22 \n\t"
|
||||
"push r23 \n\t"
|
||||
"push r24 \n\t"
|
||||
"push r25 \n\t"
|
||||
"push r26 \n\t"
|
||||
"push r27 \n\t"
|
||||
"push r28 \n\t"
|
||||
"push r29 \n\t"
|
||||
"push r30 \n\t"
|
||||
"push r31 \n\t"
|
||||
"lds r26, sched_active_thread \n\t"
|
||||
"lds r27, sched_active_thread + 1 \n\t"
|
||||
"in r0, __SP_L__ \n\t"
|
||||
"st x+, r0 \n\t"
|
||||
"in r0, __SP_H__ \n\t"
|
||||
"st x+, r0 \n\t"
|
||||
);
|
||||
|
||||
}
|
||||
|
||||
__attribute__((always_inline)) static inline void __context_restore(void)
|
||||
{
|
||||
asm volatile(
|
||||
"lds r26, sched_active_thread \n\t"
|
||||
"lds r27, sched_active_thread + 1 \n\t"
|
||||
"ld r28, x+ \n\t"
|
||||
"out __SP_L__, r28 \n\t"
|
||||
"ld r29, x+ \n\t"
|
||||
"out __SP_H__, r29 \n\t"
|
||||
"pop r31 \n\t"
|
||||
"pop r30 \n\t"
|
||||
"pop r29 \n\t"
|
||||
"pop r28 \n\t"
|
||||
"pop r27 \n\t"
|
||||
"pop r26 \n\t"
|
||||
"pop r25 \n\t"
|
||||
"pop r24 \n\t"
|
||||
"pop r23 \n\t"
|
||||
"pop r22 \n\t"
|
||||
"pop r21 \n\t"
|
||||
"pop r20 \n\t"
|
||||
"pop r19 \n\t"
|
||||
"pop r18 \n\t"
|
||||
"pop r17 \n\t"
|
||||
"pop r16 \n\t"
|
||||
"pop r15 \n\t"
|
||||
"pop r14 \n\t"
|
||||
"pop r13 \n\t"
|
||||
"pop r12 \n\t"
|
||||
"pop r11 \n\t"
|
||||
"pop r10 \n\t"
|
||||
"pop r9 \n\t"
|
||||
"pop r8 \n\t"
|
||||
"pop r7 \n\t"
|
||||
"pop r6 \n\t"
|
||||
"pop r5 \n\t"
|
||||
"pop r4 \n\t"
|
||||
"pop r3 \n\t"
|
||||
"pop r2 \n\t"
|
||||
"pop r1 \n\t"
|
||||
#if defined(__AVR_ATmega2560__)
|
||||
/* EIND and RAMPZ */
|
||||
"pop r0 \n\t"
|
||||
"out 0x3c, r0 \n\t"
|
||||
"pop r0 \n\t"
|
||||
"out 0x3b, r0 \n\t"
|
||||
#endif
|
||||
"pop r0 \n\t"
|
||||
"out __SREG__, r0 \n\t"
|
||||
"pop r0 \n\t"
|
||||
);
|
||||
}
|
||||
1
dist/tools/licenses/patterns/mod-BSD-avr-libc
vendored
Normal file
1
dist/tools/licenses/patterns/mod-BSD-avr-libc
vendored
Normal file
@ -0,0 +1 @@
|
||||
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer\. * Redistributions in binary form must reproduce the above copyright notice\, this list of conditions and the following disclaimer in the documentation and.or other materials provided with the distribution\. * Neither the name of the copyright holders nor the names of contributors may be used to endorse or promote products derived from this software without specific prior written permission\.
|
||||
@ -29,7 +29,7 @@ QUIET ?= 1
|
||||
|
||||
BOARD_INSUFFICIENT_RAM := chronos msb-430h telosb wsn430-v1_3b wsn430-v1_4 z1 redbee-econotag
|
||||
BOARD_BLACKLIST := arduino-due mbed_lpc1768 msb-430 pttu udoo qemu-i386 \
|
||||
stm32f0discovery stm32f3discovery stm32f4discovery pca10000 pca10005
|
||||
stm32f0discovery stm32f3discovery stm32f4discovery pca10000 pca10005 arduino-mega2560
|
||||
# mbed_lpc1768: see https://github.com/RIOT-OS/RIOT/issues/675
|
||||
# msb-430: see https://github.com/RIOT-OS/RIOT/issues/658
|
||||
# pttu: see https://github.com/RIOT-OS/RIOT/issues/659
|
||||
@ -39,6 +39,7 @@ BOARD_BLACKLIST := arduino-due mbed_lpc1768 msb-430 pttu udoo qemu-i386 \
|
||||
# stm32f4discovery: no transceiver, yet
|
||||
# pca10000: no transceiver, yet
|
||||
# pca10005: no transceiver, yet
|
||||
# arduino-mega2560: no transceiver, yet
|
||||
|
||||
# Modules to include:
|
||||
|
||||
|
||||
@ -30,7 +30,7 @@ QUIET ?= 1
|
||||
BOARD_INSUFFICIENT_RAM := chronos msb-430h telosb wsn430-v1_3b wsn430-v1_4 z1 redbee-econotag
|
||||
BOARD_BLACKLIST := arduino-due mbed_lpc1768 msb-430 pttu udoo qemu-i386 \
|
||||
stm32f0discovery stm32f3discovery stm32f4discovery \
|
||||
pca10000 pca10005
|
||||
pca10000 pca10005 arduino-mega2560
|
||||
# mbed_lpc1768: see https://github.com/RIOT-OS/RIOT/issues/675
|
||||
# msb-430: see https://github.com/RIOT-OS/RIOT/issues/658
|
||||
# pttu: see https://github.com/RIOT-OS/RIOT/issues/659
|
||||
@ -39,6 +39,8 @@ BOARD_BLACKLIST := arduino-due mbed_lpc1768 msb-430 pttu udoo qemu-i386 \
|
||||
# stm32f3discovery: no transceiver, yet
|
||||
# stm32f4discovery: no transceiver, yet
|
||||
# pca10000/5: no transceiver, yet
|
||||
# arduino-mega2560: no transceiver, yet
|
||||
|
||||
# Modules to include:
|
||||
|
||||
USEMODULE += posix
|
||||
|
||||
@ -30,7 +30,7 @@ QUIET ?= 1
|
||||
# Blacklist boards
|
||||
BOARD_BLACKLIST := arduino-due avsextrem chronos mbed_lpc1768 msb-430h msba2 redbee-econotag \
|
||||
telosb wsn430-v1_3b wsn430-v1_4 msb-430 pttu udoo qemu-i386 z1 stm32f0discovery \
|
||||
stm32f3discovery stm32f4discovery pca10000 pca10005 iot-lab_M3
|
||||
stm32f3discovery stm32f4discovery pca10000 pca10005 iot-lab_M3 arduino-mega2560
|
||||
|
||||
# This example only works with native for now.
|
||||
# msb430-based boards: msp430-g++ is not provided in mspgcc.
|
||||
@ -42,6 +42,7 @@ BOARD_BLACKLIST := arduino-due avsextrem chronos mbed_lpc1768 msb-430h msba2 red
|
||||
# pca10000: g++ does not support some used flags (e.g. -mthumb...)
|
||||
# pca10005: g++ does not support some used flags (e.g. -mthumb...)
|
||||
# iot-lab_M3: g++ does not support some used flags (e.g. -mthumb...)
|
||||
# arduino-mega2560: cstdio header missing from avr-libc
|
||||
# others: untested.
|
||||
|
||||
# If you want to add some extra flags when compile c++ files, add these flags
|
||||
|
||||
@ -36,7 +36,7 @@ endif
|
||||
|
||||
BOARD_INSUFFICIENT_RAM := chronos msb-430h redbee-econotag telosb wsn430-v1_3b wsn430-v1_4 z1
|
||||
BOARD_BLACKLIST := arduino-due mbed_lpc1768 msb-430 pttu udoo qemu-i386 stm32f0discovery \
|
||||
stm32f3discovery stm32f4discovery pca10000 pca10005
|
||||
stm32f3discovery stm32f4discovery pca10000 pca10005 arduino-mega2560
|
||||
# mbed_lpc1768: see https://github.com/RIOT-OS/RIOT/issues/675
|
||||
# msb-430: see https://github.com/RIOT-OS/RIOT/issues/658
|
||||
# pttu: see https://github.com/RIOT-OS/RIOT/issues/659
|
||||
@ -46,6 +46,7 @@ BOARD_BLACKLIST := arduino-due mbed_lpc1768 msb-430 pttu udoo qemu-i386 stm32f0d
|
||||
# stm32f4discovery: no transceiver, yet
|
||||
# pca10000: no transceiver, yet
|
||||
# pca10005: no transceiver, yet
|
||||
# arduino-mega2560: time.h missing from avr-libc
|
||||
|
||||
# Modules to include:
|
||||
|
||||
|
||||
@ -18,6 +18,10 @@
|
||||
#include <string.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#if defined(MCU_ATMEGA2560)
|
||||
#include <sys/types.h>
|
||||
#endif
|
||||
|
||||
#include "kernel.h"
|
||||
|
||||
#include "inet_pton.h"
|
||||
|
||||
@ -25,7 +25,11 @@
|
||||
* @}
|
||||
*/
|
||||
|
||||
#if defined(MCU_ATMEGA2560)
|
||||
#include <stdlib.h>
|
||||
#else
|
||||
#include <malloc.h>
|
||||
#endif
|
||||
|
||||
#include "pipe.h"
|
||||
|
||||
|
||||
@ -5,6 +5,10 @@ BOARD_INSUFFICIENT_RAM := chronos mbed_lpc1768 msb-430 msb-430h redbee-econotag
|
||||
telosb wsn430-v1_3b wsn430-v1_4 z1 stm32f0discovery \
|
||||
stm32f3discovery pca10000 pca10005
|
||||
|
||||
BOARD_BLACKLIST := arduino-mega2560
|
||||
# arduino-mega2560: Errors in assembly, e.g:
|
||||
# Error: value of 105617 too large for field of 2 bytes at 20018
|
||||
|
||||
USEMODULE += hashes
|
||||
USEMODULE += bloom
|
||||
|
||||
|
||||
@ -3,7 +3,9 @@ include ../Makefile.tests_common
|
||||
|
||||
BOARD_BLACKLIST := arduino-due chronos mbed_lpc1768 msb-430 msb-430h qemu-i386 stm32f0discovery \
|
||||
stm32f3discovery stm32f4discovery telosb wsn430-v1_3b wsn430-v1_4 udoo z1 \
|
||||
pca10000 pca10005
|
||||
pca10000 pca10005 arduino-mega2560
|
||||
#arduino-mega2560: missing header sys/types.h
|
||||
|
||||
BOARD_INSUFFICIENT_RAM := redbee-econotag
|
||||
#MSP boards: no assert.h
|
||||
#rest: no radio
|
||||
|
||||
@ -1,6 +1,10 @@
|
||||
APPLICATION = libfixmath_unittests
|
||||
include ../Makefile.tests_common
|
||||
|
||||
BOARD_BLACKLIST := arduino-mega2560
|
||||
# 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_INSUFFICIENT_RAM := chronos msb-430 msb-430h telosb wsn430-v1_3b wsn430-v1_4 z1
|
||||
|
||||
|
||||
@ -1,8 +1,7 @@
|
||||
APPLICATION = net_if
|
||||
|
||||
BOARD_BLACKLIST = mbed_lpc1768 arduino-due udoo qemu-i386 stm32f0discovery stm32f3discovery \
|
||||
stm32f4discovery pca10000 pca10005
|
||||
|
||||
stm32f4discovery pca10000 pca10005 arduino-mega2560
|
||||
# qemu-i386: no transceiver, yet
|
||||
# stm32f0discovery: no transceiver, yet
|
||||
# stm32f3discovery: no transceiver, yet
|
||||
|
||||
@ -3,7 +3,7 @@ include ../Makefile.tests_common
|
||||
|
||||
BOARD_INSUFFICIENT_RAM := chronos msb-430h redbee-econotag telosb wsn430-v1_3b wsn430-v1_4 z1
|
||||
BOARD_BLACKLIST := arduino-due mbed_lpc1768 msb-430 udoo qemu-i386 stm32f0discovery \
|
||||
stm32f3discovery stm32f4discovery pca10000 pca10005
|
||||
stm32f3discovery stm32f4discovery pca10000 pca10005 arduino-mega2560
|
||||
# mbed_lpc1768: see https://github.com/RIOT-OS/RIOT/issues/675
|
||||
# msb-430: see https://github.com/RIOT-OS/RIOT/issues/658
|
||||
# qemu-i386: no transceiver, yet
|
||||
@ -12,6 +12,7 @@ BOARD_BLACKLIST := arduino-due mbed_lpc1768 msb-430 udoo qemu-i386 stm32f0discov
|
||||
# stm32f4discovery: no transceiver, yet
|
||||
# pca10000: no transceiver, yet
|
||||
# pca10005: no transceiver, yet
|
||||
# arduino-mega2560: unknown type name ‘radio_packet_length_t’
|
||||
|
||||
USEMODULE += posix
|
||||
USEMODULE += pnet
|
||||
|
||||
@ -1,6 +1,10 @@
|
||||
APPLICATION = posix_sleep
|
||||
include ../Makefile.tests_common
|
||||
|
||||
BOARD_BLACKLIST := arduino-mega2560
|
||||
# arduino-mega2560: warning: iteration 2u invokes undefined behavior
|
||||
# [-Waggressive-loop-optimizations]
|
||||
|
||||
USEMODULE += posix
|
||||
|
||||
DISABLE_MODULE += auto_init
|
||||
|
||||
@ -1,6 +1,9 @@
|
||||
APPLICATION = pthread
|
||||
include ../Makefile.tests_common
|
||||
|
||||
BOARD_BLACKLIST := arduino-mega2560
|
||||
# arduino-mega2560: unknown type name: clockid_t
|
||||
|
||||
USEMODULE += posix
|
||||
USEMODULE += pthread
|
||||
|
||||
|
||||
@ -2,6 +2,9 @@
|
||||
APPLICATION = pthread_barrier
|
||||
include ../Makefile.tests_common
|
||||
|
||||
BOARD_BLACKLIST := arduino-mega2560
|
||||
# arduino-mega2560: unknown type name: clockid_t
|
||||
|
||||
# exclude boards with insufficient RAM
|
||||
BOARD_INSUFFICIENT_RAM := stm32f0discovery
|
||||
|
||||
|
||||
@ -1,6 +1,9 @@
|
||||
APPLICATION = pthread_cleanup
|
||||
include ../Makefile.tests_common
|
||||
|
||||
BOARD_BLACKLIST := arduino-mega2560
|
||||
# arduino-mega2560: unknown type name: clockid_t
|
||||
|
||||
USEMODULE += pthread
|
||||
|
||||
include $(RIOTBASE)/Makefile.include
|
||||
|
||||
@ -1,6 +1,9 @@
|
||||
APPLICATION = condition_variable
|
||||
include ../Makefile.tests_common
|
||||
|
||||
BOARD_BLACKLIST := arduino-mega2560
|
||||
# arduino-mega2560: unknown type name: clockid_t
|
||||
|
||||
BOARD_INSUFFICIENT_RAM := stm32f0discovery
|
||||
|
||||
USEMODULE += posix
|
||||
|
||||
@ -1,6 +1,9 @@
|
||||
APPLICATION = pthread_cooperation
|
||||
include ../Makefile.tests_common
|
||||
|
||||
BOARD_BLACKLIST := arduino-mega2560
|
||||
# arduino-mega2560: unknown type name: clockid_t
|
||||
|
||||
USEMODULE += posix
|
||||
USEMODULE += pthread
|
||||
|
||||
|
||||
@ -1,6 +1,9 @@
|
||||
APPLICATION = pthread_rwlock
|
||||
include ../Makefile.tests_common
|
||||
|
||||
BOARD_BLACKLIST := arduino-mega2560
|
||||
# arduino-mega2560: unknown type name: clockid_t
|
||||
|
||||
USEMODULE += pthread
|
||||
USEMODULE += vtimer
|
||||
USEMODULE += random
|
||||
|
||||
@ -1,6 +1,10 @@
|
||||
APPLICATION = vtimer_msg_diff
|
||||
include ../Makefile.tests_common
|
||||
|
||||
BOARD_BLACKLIST := arduino-mega2560
|
||||
# arduino-mega2560: missing define for PRId64, avr-libc's printf function
|
||||
# possibly not compatible at all
|
||||
|
||||
BOARD_INSUFFICIENT_RAM := mbed_lpc1768 stm32f0discovery pca10000 pca10005
|
||||
|
||||
USEMODULE += vtimer
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user