mirror of
https://github.com/RIOT-OS/RIOT.git
synced 2024-12-29 04:50:03 +01:00
Merge pull request #3076 from haukepetersen/opt_saml21_makefiles
board/cpu saml21: cleaned Makefiles and unused files
This commit is contained in:
commit
e2aa1051bc
@ -1,54 +1,17 @@
|
||||
# define the cpu used by the saml21 board
|
||||
export CPU = saml21
|
||||
export CPU_MODEL = saml21j18a
|
||||
export CFLAGS += -D__SAML21J18A__
|
||||
|
||||
# set the default port
|
||||
export PORT ?= /dev/ttyACM0
|
||||
|
||||
# define tools used for building the project
|
||||
export PREFIX = arm-none-eabi-
|
||||
export CC = $(PREFIX)gcc
|
||||
export CXX = $(PREFIX)g++
|
||||
export AR = $(PREFIX)ar
|
||||
export AS = $(PREFIX)as
|
||||
export LINK = $(PREFIX)gcc
|
||||
export SIZE = $(PREFIX)size
|
||||
export OBJCOPY = $(PREFIX)objcopy
|
||||
export DBG = $(PREFIX)gdb
|
||||
export TERMPROG = $(RIOTBASE)/dist/tools/pyterm/pyterm
|
||||
export FLASHER = $(RIOTBASE)/dist/tools/openocd/openocd.sh
|
||||
export DEBUGGER = $(RIOTBASE)/dist/tools/openocd/openocd.sh
|
||||
export DEBUGSERVER = $(RIOTBASE)/dist/tools/openocd/openocd.sh
|
||||
export RESET = $(RIOTBASE)/dist/tools/openocd/openocd.sh
|
||||
|
||||
# define build specific options
|
||||
export CPU_USAGE = -mcpu=cortex-m0plus
|
||||
FPU_USAGE =
|
||||
export CFLAGS += -ggdb -g3 -std=gnu99 -Os -Wall -Wstrict-prototypes $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian -mthumb -mno-thumb-interwork -nostartfiles
|
||||
export CFLAGS += -ffunction-sections -fdata-sections -fno-builtin
|
||||
export ASFLAGS += -ggdb -g3 $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian
|
||||
export LINKFLAGS += -g3 -ggdb -std=gnu99 $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian -static -lgcc -mthumb -mno-thumb-interwork -nostartfiles
|
||||
# linkerscript specified in cpu/Makefile.include
|
||||
export LINKFLAGS += -T$(LINKERSCRIPT)
|
||||
export OFLAGS = -O ihex
|
||||
export TERMFLAGS += -p "$(PORT)" -b 115200
|
||||
export FFLAGS = flash
|
||||
ifneq (,$(SERIAL))
|
||||
export FFLAGS += "-c cmsis_dap_serial $(SERIAL)"
|
||||
endif
|
||||
export DEBUGGER_FLAGS = debug
|
||||
export DEBUGSERVER_FLAGS = debug-server
|
||||
export RESET_FLAGS = reset
|
||||
|
||||
# unwanted (CXXUWFLAGS) and extra (CXXEXFLAGS) flags for c++
|
||||
export CXXUWFLAGS +=
|
||||
export CXXEXFLAGS +=
|
||||
|
||||
# use the nano-specs of the NewLib when available
|
||||
ifeq ($(shell $(LINK) -specs=nano.specs -E - 2>/dev/null >/dev/null </dev/null ; echo $$?),0)
|
||||
export LINKFLAGS += -specs=nano.specs -lc -lnosys
|
||||
endif
|
||||
|
||||
# export board specific includes to the global includes-listing
|
||||
export INCLUDES += -I$(RIOTBOARD)/$(BOARD)/include/
|
||||
# include dependencies
|
||||
include $(RIOTBOARD)/$(BOARD)/Makefile.dep
|
||||
|
||||
# setup serial terminal
|
||||
PORT_LINUX ?= /dev/ttyACM0
|
||||
include $(RIOTBOARD)/Makefile.include.serial
|
||||
|
||||
# this board uses openocd
|
||||
include $(RIOTBOARD)/Makefile.include.openocd
|
||||
|
||||
# include cortex defaults
|
||||
include $(RIOTBOARD)/Makefile.include.cortex_common
|
||||
|
@ -44,7 +44,7 @@ extern "C" {
|
||||
*/
|
||||
#define STDIO UART_0
|
||||
#define STDIO_BAUDRATE (115200U)
|
||||
#define STDIO_BUFSIZE (64U)
|
||||
#define STDIO_RX_BUFSIZE (64U)
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
|
@ -1,28 +1,9 @@
|
||||
# this CPU implementation is using the new core/CPU interface
|
||||
export CFLAGS += -DCOREIF_NG=1
|
||||
export CORTEX = cortex-m0
|
||||
|
||||
# this CPU implementation doesn't use CMSIS initialisation
|
||||
export CFLAGS += -DDONT_USE_CMSIS_INIT
|
||||
|
||||
# tell the build system that the CPU depends on the Cortex-M common files
|
||||
export USEMODULE += cortex-m0_common
|
||||
# use the hwtimer compatibility module
|
||||
USEMODULE += hwtimer_compat
|
||||
|
||||
# define path to cortex-m common module, which is needed for this CPU
|
||||
export CORTEX_COMMON = $(RIOTCPU)/cortex-m0_common/
|
||||
|
||||
# define the linker script to use for this CPU
|
||||
export LINKERSCRIPT ?= $(RIOTCPU)/$(CPU)/saml21_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/syscalls.o
|
||||
export UNDEF += $(BINDIR)cpu/startup.o
|
||||
|
||||
# export the peripheral drivers to be linked into the final binary
|
||||
export USEMODULE += periph
|
||||
|
||||
# CPU depends on the cortex-m common module, so include it
|
||||
include $(CORTEX_COMMON)Makefile.include
|
||||
include $(RIOTCPU)/Makefile.include.cortex_common
|
||||
|
@ -1,71 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_samd21
|
||||
* @{
|
||||
*
|
||||
* @file hwtimer_arch.c
|
||||
* @brief Implementation of the kernels hwtimer interface
|
||||
*
|
||||
* The hardware timer implementation uses the Cortex build-in system timer as back-end.
|
||||
*
|
||||
* @author Thomas Eichinger <thomas.eichinger@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));
|
||||
}
|
@ -1,350 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_saml21
|
||||
* @{
|
||||
*
|
||||
* @file syscalls.c
|
||||
* @brief NewLib system calls implementations for saml21
|
||||
*
|
||||
* @author Michael Baar <michael.baar@fu-berlin.de>
|
||||
* @author Stefan Pfeiffer <pfeiffer@inf.fu-berlin.de>
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <sys/stat.h>
|
||||
#include <sys/unistd.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "board.h"
|
||||
#include "thread.h"
|
||||
#include "kernel.h"
|
||||
#include "mutex.h"
|
||||
#include "ringbuffer.h"
|
||||
#include "irq.h"
|
||||
#include "periph/uart.h"
|
||||
|
||||
#ifdef MODULE_UART0
|
||||
#include "board_uart0.h"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* manage the heap
|
||||
*/
|
||||
extern char _sheap; /* start of the heap */
|
||||
extern char _eheap; /* end of the heap */
|
||||
caddr_t heap_top = (caddr_t)&_sheap + 4;
|
||||
|
||||
#ifndef MODULE_UART0
|
||||
/**
|
||||
* @brief use mutex for waiting on incoming UART chars
|
||||
*/
|
||||
static mutex_t uart_rx_mutex;
|
||||
static char rx_buf_mem[STDIO_BUFSIZE];
|
||||
static ringbuffer_t rx_buf;
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Receive a new character from the UART and put it into the receive buffer
|
||||
*/
|
||||
void rx_cb(void *arg, char data)
|
||||
{
|
||||
#ifndef MODULE_UART0
|
||||
(void)arg;
|
||||
|
||||
ringbuffer_add_one(&rx_buf, data);
|
||||
mutex_unlock(&uart_rx_mutex);
|
||||
#else
|
||||
if (uart0_handler_pid) {
|
||||
uart0_handle_incoming(data);
|
||||
|
||||
uart0_notify_thread();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initialize NewLib, called by __libc_init_array() from the startup script
|
||||
*/
|
||||
void _init(void)
|
||||
{
|
||||
#ifndef MODULE_UART0
|
||||
mutex_init(&uart_rx_mutex);
|
||||
ringbuffer_init(&rx_buf, rx_buf_mem, STDIO_BUFSIZE);
|
||||
#endif
|
||||
|
||||
#if UART_NUMOF
|
||||
uart_init(STDIO, STDIO_BAUDRATE, rx_cb, 0, 0);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Free resources on NewLib de-initialization, not used for RIOT
|
||||
*/
|
||||
void _fini(void)
|
||||
{
|
||||
/* nothing to do here */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Exit a program without cleaning up files
|
||||
*
|
||||
* If your system doesn't provide this, it is best to avoid linking with subroutines that
|
||||
* require it (exit, system).
|
||||
*
|
||||
* @param n the exit code, 0 for all OK, >0 for not OK
|
||||
*/
|
||||
void _exit(int n)
|
||||
{
|
||||
printf("#! exit %i: resetting\n", n);
|
||||
NVIC_SystemReset();
|
||||
while(1);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Allocate memory from the heap.
|
||||
*
|
||||
* The current heap implementation is very rudimentary, it is only able to allocate
|
||||
* memory. But it does not
|
||||
* - have any means to free memory again
|
||||
*
|
||||
* @return Upon successful completion, sbrk() returns the prior break value.
|
||||
* Otherwise, it returns (void *)-1 and sets errno to indicate the error.
|
||||
*/
|
||||
caddr_t _sbrk_r(struct _reent *r, ptrdiff_t incr)
|
||||
{
|
||||
unsigned int state = disableIRQ();
|
||||
caddr_t res = heap_top;
|
||||
|
||||
if (((incr > 0) && ((heap_top + incr > &_eheap) || (heap_top + incr < res))) ||
|
||||
((incr < 0) && ((heap_top + incr < &_sheap) || (heap_top + incr > res)))) {
|
||||
r->_errno = ENOMEM;
|
||||
res = (void *) -1;
|
||||
}
|
||||
else {
|
||||
heap_top += incr;
|
||||
}
|
||||
|
||||
restoreIRQ(state);
|
||||
return res;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get the process-ID of the current thread
|
||||
*
|
||||
* @return the process ID of the current thread
|
||||
*/
|
||||
pid_t _getpid(void)
|
||||
{
|
||||
return (pid_t) sched_active_pid;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a signal to a given thread
|
||||
*
|
||||
* @param r TODO
|
||||
* @param pid TODO
|
||||
* @param sig TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
__attribute__ ((weak))
|
||||
int _kill_r(struct _reent *r, pid_t pid, int sig)
|
||||
{
|
||||
r->_errno = ESRCH; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Open a file
|
||||
*
|
||||
* @param r TODO
|
||||
* @param name TODO
|
||||
* @param mode TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _open_r(struct _reent *r, const char *name, int mode)
|
||||
{
|
||||
r->_errno = ENODEV; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Read from a file
|
||||
*
|
||||
* All input is read from UART_0. The function will block until a byte is actually read.
|
||||
*
|
||||
* Note: the read function does not buffer - data will be lost if the function is not
|
||||
* called fast enough.
|
||||
*
|
||||
* TODO: implement more sophisticated read call.
|
||||
*
|
||||
* @param r TODO
|
||||
* @param fd TODO
|
||||
* @param buffer TODO
|
||||
* @param int TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _read_r(struct _reent *r, int fd, void *buffer, unsigned int count)
|
||||
{
|
||||
#ifndef MODULE_UART0
|
||||
while (rx_buf.avail == 0) {
|
||||
mutex_lock(&uart_rx_mutex);
|
||||
}
|
||||
return ringbuffer_get(&rx_buf, (char*)buffer, rx_buf.avail);
|
||||
#else
|
||||
r->_errno = ENODEV;
|
||||
return -1;
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Write characters to a file
|
||||
*
|
||||
* All output is currently directed to UART_0, independent of the given file descriptor.
|
||||
* The write call will further block until the byte is actually written to the UART.
|
||||
*
|
||||
* TODO: implement more sophisticated write call.
|
||||
*
|
||||
* @param r TODO
|
||||
* @param fd TODO
|
||||
* @param data TODO
|
||||
* @param int TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _write_r(struct _reent *r, int fd, const void *data, unsigned int count)
|
||||
{
|
||||
char *c = (char*)data;
|
||||
for (int i = 0; i < count; i++) {
|
||||
#if UART_NUMOF
|
||||
uart_write_blocking(UART_0, c[i]);
|
||||
#else
|
||||
#warning UART_NUMOF == 0, no uarts configured
|
||||
#endif
|
||||
}
|
||||
return count;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Close a file
|
||||
*
|
||||
* @param r TODO
|
||||
* @param fd TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _close_r(struct _reent *r, int fd)
|
||||
{
|
||||
r->_errno = ENODEV; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Set position in a file
|
||||
*
|
||||
* @param r TODO
|
||||
* @param fd TODO
|
||||
* @param pos TODO
|
||||
* @param dir TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
_off_t _lseek_r(struct _reent *r, int fd, _off_t pos, int dir)
|
||||
{
|
||||
r->_errno = ENODEV; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Status of an open file
|
||||
*
|
||||
* @param r TODO
|
||||
* @param fd TODO
|
||||
* @param stat TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _fstat_r(struct _reent *r, int fd, struct stat * st)
|
||||
{
|
||||
r->_errno = ENODEV; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Status of a file (by name)
|
||||
*
|
||||
* @param r TODO
|
||||
* @param name TODO
|
||||
* @param stat TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _stat_r(struct _reent *r, char *name, struct stat *st)
|
||||
{
|
||||
r->_errno = ENODEV; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Query whether output stream is a terminal
|
||||
*
|
||||
* @param r TODO
|
||||
* @param fd TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _isatty_r(struct _reent *r, int fd)
|
||||
{
|
||||
r->_errno = 0;
|
||||
if(fd == STDOUT_FILENO || fd == STDERR_FILENO) {
|
||||
return 1;
|
||||
}
|
||||
else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Remove a file's directory entry
|
||||
*
|
||||
* @param r TODO
|
||||
* @param path TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _unlink_r(struct _reent *r, char* path)
|
||||
{
|
||||
r->_errno = ENODEV; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a signal to a thread
|
||||
*
|
||||
* @param[in] pid the pid to send to
|
||||
* @param[in] sig the signal to send
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
__attribute__ ((weak))
|
||||
int _kill(int pid, int sig)
|
||||
{
|
||||
errno = ESRCH; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
Loading…
Reference in New Issue
Block a user