From ae48fccdf7e1b1747b6763d6181e7cc2d8e1992c Mon Sep 17 00:00:00 2001 From: Hauke Petersen Date: Tue, 23 Sep 2014 18:49:17 -0400 Subject: [PATCH] Copy some files from cpu/sam3x8e to cpu/cc2538. --- cpu/cc2538/cc2538_linkerscript.ld | 144 ++++++++++++++++ cpu/cc2538/hwtimer_arch.c | 73 ++++++++ cpu/cc2538/io_arch.c | 32 ++++ cpu/cc2538/reboot_arch.c | 34 ++++ cpu/cc2538/startup.c | 233 +++++++++++++++++++++++++ cpu/cc2538/syscalls.c | 277 ++++++++++++++++++++++++++++++ 6 files changed, 793 insertions(+) create mode 100644 cpu/cc2538/cc2538_linkerscript.ld create mode 100644 cpu/cc2538/hwtimer_arch.c create mode 100644 cpu/cc2538/io_arch.c create mode 100644 cpu/cc2538/reboot_arch.c create mode 100644 cpu/cc2538/startup.c create mode 100644 cpu/cc2538/syscalls.c diff --git a/cpu/cc2538/cc2538_linkerscript.ld b/cpu/cc2538/cc2538_linkerscript.ld new file mode 100644 index 0000000000..078b6efb83 --- /dev/null +++ b/cpu/cc2538/cc2538_linkerscript.ld @@ -0,0 +1,144 @@ +/* ---------------------------------------------------------------------------- + * SAM Software Package License + * ---------------------------------------------------------------------------- + * Copyright (c) 2012, Atmel Corporation + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following condition is met: + * + * - Redistributions of source code must retain the above copyright notice, + * this list of conditions and the disclaimer below. + * + * Atmel's name may not be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * DISCLAIMED. IN NO EVENT SHALL ATMEL 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. + * ---------------------------------------------------------------------------- + */ + +OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm") +OUTPUT_ARCH(arm) +SEARCH_DIR(.) + +/* Memory Spaces Definitions */ +MEMORY +{ + rom (rx) : ORIGIN = 0x00080000, LENGTH = 0x00080000 /* Flash, 512K */ + sram0 (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00010000 /* sram0, 64K */ + sram1 (rwx) : ORIGIN = 0x20080000, LENGTH = 0x00008000 /* sram1, 32K */ + ram (rwx) : ORIGIN = 0x20070000, LENGTH = 0x00018000 /* sram, 96K */ +} + +/* The stack size used by the application. NOTE: you need to adjust */ +STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : 0x2000 ; + +/* Section Definitions */ +SECTIONS +{ + .text : + { + . = ALIGN(4); + _sfixed = .; + KEEP(*(.vectors .vectors.*)) + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + *(.ARM.extab* .gnu.linkonce.armextab.*) + + /* Support C constructors, and C destructors in both user code + and the C library. This also provides support for C++ code. */ + . = ALIGN(4); + KEEP(*(.init)) + . = ALIGN(4); + __preinit_array_start = .; + KEEP (*(.preinit_array)) + __preinit_array_end = .; + + . = ALIGN(4); + __init_array_start = .; + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array)) + __init_array_end = .; + + . = ALIGN(0x4); + KEEP (*crtbegin.o(.ctors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors)) + KEEP (*(SORT(.ctors.*))) + KEEP (*crtend.o(.ctors)) + + . = ALIGN(4); + KEEP(*(.fini)) + + . = ALIGN(4); + __fini_array_start = .; + KEEP (*(.fini_array)) + KEEP (*(SORT(.fini_array.*))) + __fini_array_end = .; + + KEEP (*crtbegin.o(.dtors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors)) + KEEP (*(SORT(.dtors.*))) + KEEP (*crtend.o(.dtors)) + + . = ALIGN(4); + _efixed = .; /* End of text section */ + } > rom + + /* .ARM.exidx is sorted, so has to go in its own output section. */ + PROVIDE_HIDDEN (__exidx_start = .); + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > rom + PROVIDE_HIDDEN (__exidx_end = .); + + . = ALIGN(4); + _etext = .; + + .relocate : AT (_etext) + { + . = ALIGN(4); + _srelocate = .; + *(.ramfunc .ramfunc.*); + *(.data .data.*); + . = ALIGN(4); + _erelocate = .; + } > ram + + /* .bss section which is used for uninitialized data */ + .bss (NOLOAD) : + { + . = ALIGN(4); + _sbss = . ; + _szero = .; + *(.bss .bss.*) + *(COMMON) + . = ALIGN(4); + _ebss = . ; + _ezero = .; + } > ram + + /* stack section */ + .stack (NOLOAD): + { + . = ALIGN(8); + _sstack = .; + . = . + STACK_SIZE; + . = ALIGN(8); + _estack = .; + } > ram + + . = ALIGN(4); + _end = . ; +} \ No newline at end of file diff --git a/cpu/cc2538/hwtimer_arch.c b/cpu/cc2538/hwtimer_arch.c new file mode 100644 index 0000000000..b8dbe81b32 --- /dev/null +++ b/cpu/cc2538/hwtimer_arch.c @@ -0,0 +1,73 @@ +/* + * 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_sam3x8e + * @{ + * + * @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 Hauke Petersen + * + * @} + */ + +#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)); + thread_yield(); +} diff --git a/cpu/cc2538/io_arch.c b/cpu/cc2538/io_arch.c new file mode 100644 index 0000000000..ed63cb8da0 --- /dev/null +++ b/cpu/cc2538/io_arch.c @@ -0,0 +1,32 @@ +/* + * 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_sam3x8e + * @{ + * + * @file io_arch.c + * @brief Implementation of the kernel's architecture dependent IO interface + * + * @author Hauke Petersen + * + * @} + */ + +#include + +#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; +} diff --git a/cpu/cc2538/reboot_arch.c b/cpu/cc2538/reboot_arch.c new file mode 100644 index 0000000000..6d61335b51 --- /dev/null +++ b/cpu/cc2538/reboot_arch.c @@ -0,0 +1,34 @@ +/* + * 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_sam3x8e + * @{ + * + * @file reboot_arch.c + * @brief Implementation of the kernels reboot interface + * + * @author Hauke Petersen + * + * @} + */ + +#include + +#include "arch/reboot_arch.h" +#include "cpu.h" + + +int reboot_arch(int mode) +{ + printf("Going into reboot, mode %i\n", mode); + + NVIC_SystemReset(); + + return 0; +} diff --git a/cpu/cc2538/startup.c b/cpu/cc2538/startup.c new file mode 100644 index 0000000000..c5f14caf27 --- /dev/null +++ b/cpu/cc2538/startup.c @@ -0,0 +1,233 @@ +/* + * 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_sam3x8e + * @{ + * + * @file startup.c + * @brief Startup code and interrupt vector definition + * + * @author Hauke Petersen + * + * @} + */ + +#include + + +/** + * memory markers as defined in the linker script + */ +extern uint32_t _sfixed; +extern uint32_t _efixed; +extern uint32_t _etext; +extern uint32_t _srelocate; +extern uint32_t _erelocate; +extern uint32_t _szero; +extern uint32_t _ezero; +extern uint32_t _sstack; +extern uint32_t _estack; + + +/** + * @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 function is the entry point after a system reset + * + * After a system reset, the following steps are necessary and carried out: + * 1. load data section from flash to ram + * 2. overwrite uninitialized data section (BSS) with zeros + * 3. initialize the newlib + * 4. initialize the board (sync clock, setup std-IO) + * 5. initialize and start RIOTs kernel + */ +void reset_handler(void) +{ + uint32_t *dst; + uint32_t *src = &_etext; + + /* load data section from flash to ram */ + for (dst = &_srelocate; dst < &_erelocate; ) { + *(dst++) = *(src++); + } + + /* default bss section to zero */ + for (dst = &_szero; dst < &_ezero; ) { + *(dst++) = 0; + } + + /* initialize the board and startup the kernel */ + board_init(); + /* initialize std-c library (this should be done after board_init) */ + __libc_init_array(); + /* startup the kernel */ + kernel_init(); +} + +/** + * @brief Default handler is called in case no interrupt handler was defined + */ +void dummy_handler(void) +{ + while (1) {asm ("nop");} +} + + +void isr_nmi(void) +{ + while (1) {asm ("nop");} +} + +void isr_mem_manage(void) +{ + while (1) {asm ("nop");} +} + +void isr_debug_mon(void) +{ + while (1) {asm ("nop");} +} + +void isr_hard_fault(void) +{ + while (1) {asm ("nop");} +} + +void isr_bus_fault(void) +{ + while (1) {asm ("nop");} +} + +void isr_usage_fault(void) +{ + while (1) {asm ("nop");} +} + +/* Cortex-M specific interrupt vectors */ +void isr_svc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_pendsv(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_systick(void) __attribute__ ((weak, alias("dummy_handler"))); + +/* SAM3X8E specific interrupt vector */ +void isr_supc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_rstc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_rtc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_rtt(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_wdt(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_pmc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_efc0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_efc1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_uart(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_smc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_pioa(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_piob(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_pioc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_piod(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_usart0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_usart1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_usart2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_usart3(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_hsmci(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_twi0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_twi1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_spi0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_ssc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tc0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tc1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tc2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tc3(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tc4(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tc5(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tc6(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tc7(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tc8(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_pwm(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_adc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dacc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dmac(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_uotghs(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_trng(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_emac(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_can0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_can1(void) __attribute__ ((weak, alias("dummy_handler"))); + + +/* interrupt vector table */ +__attribute__ ((section(".vectors"))) +const void *interrupt_vector[] = { + /* Stack pointer */ + (void*) (&_estack), /* pointer to the top of the empty stack */ + /* Cortex-M handlers */ + (void*) reset_handler, /* entry point of the program */ + (void*) isr_nmi, /* non maskable interrupt handler */ + (void*) isr_hard_fault, /* if you end up here its not good */ + (void*) isr_mem_manage, /* memory controller interrupt */ + (void*) isr_bus_fault, /* also not good to end up here */ + (void*) isr_usage_fault, /* autsch */ + (void*) (0UL), /* Reserved */ + (void*) (0UL), /* Reserved */ + (void*) (0UL), /* Reserved */ + (void*) (0UL), /* Reserved */ + (void*) isr_svc, /* system call interrupt */ + (void*) isr_debug_mon, /* debug interrupt */ + (void*) (0UL), /* Reserved */ + (void*) isr_pendsv, /* pendSV interrupt, used for task switching in RIOT */ + (void*) isr_systick, /* SysTick interrupt, not used in RIOT */ + /* STM specific peripheral handlers */ + (void*) isr_supc, /* 0 supply controller */ + (void*) isr_rstc, /* 1 reset controller */ + (void*) isr_rtc, /* 2 real time clock */ + (void*) isr_rtt, /* 3 real timer timer */ + (void*) isr_wdt, /* 4 watchdog timer */ + (void*) isr_pmc, /* 5 power management controller */ + (void*) isr_efc0, /* 6 enhanced flash controller 0 */ + (void*) isr_efc1, /* 7 enhanced flash controller 1 */ + (void*) isr_uart, /* 8 universal asynchronous receiver transceiver */ + (void*) isr_smc, /* 9 static memory controller */ + (void*) (0UL), + (void*) isr_pioa, /* 11 GPIO port A */ + (void*) isr_piob, /* 12 GPIO port B */ + (void*) isr_pioc, /* 13 GPIO port C */ + (void*) isr_piod, /* 14 GPIO port D */ + (void*) (0UL), + (void*) (0UL), + (void*) isr_usart0, /* 17 USART0 */ + (void*) isr_usart1, /* 18 USART1 */ + (void*) isr_usart2, /* 19 USART2 */ + (void*) isr_usart3, /* 20 USART3 */ + (void*) isr_hsmci, /* 21 multimedia card interface */ + (void*) isr_twi0, /* 22 two-wire interface 0 */ + (void*) isr_twi1, /* 23 two-wire interface 1 */ + (void*) isr_spi0, /* 24 serial peripheral interface */ + (void*) (0UL), + (void*) isr_ssc, /* 26 synchronous serial controller */ + (void*) isr_tc0, /* 27 timer counter 0 */ + (void*) isr_tc1, /* 28 timer counter 1 */ + (void*) isr_tc2, /* 29 timer counter 2 */ + (void*) isr_tc3, /* 30 timer counter 3 */ + (void*) isr_tc4, /* 31 timer counter 4 */ + (void*) isr_tc5, /* 32 timer counter 5 */ + (void*) isr_tc6, /* 33 timer counter 6 */ + (void*) isr_tc7, /* 34 timer counter 7 */ + (void*) isr_tc8, /* 35 timer counter 8 */ + (void*) isr_pwm, /* 36 pulse width modulation controller */ + (void*) isr_adc, /* 37 ADC controller */ + (void*) isr_dacc, /* 38 DAC controller */ + (void*) isr_dmac, /* 39 DMA controller */ + (void*) isr_uotghs, /* 40 USB OTG high speed */ + (void*) isr_trng, /* 41 true random number generator */ + (void*) isr_emac, /* 42 Ethernet MAC*/ + (void*) isr_can0, /* 43 CAN controller 0*/ + (void*) isr_can1, /* 44 CAN controller 1*/ +}; diff --git a/cpu/cc2538/syscalls.c b/cpu/cc2538/syscalls.c new file mode 100644 index 0000000000..06edd0400c --- /dev/null +++ b/cpu/cc2538/syscalls.c @@ -0,0 +1,277 @@ +/* + * 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_sam3x8e + * @{ + * + * @file syscalls.c + * @brief NewLib system calls implementations for SAM3X8E + * + * @author Michael Baar + * @author Stefan Pfeiffer + * @author Hauke Petersen + * + * @} + */ + +#include +#include +#include +#include +#include +#include +#include + +#include "board.h" +#include "thread.h" +#include "kernel.h" +#include "irq.h" +#include "periph/uart.h" + +/** + * manage the heap + */ +extern uint32_t _end; /* address of last used memory cell */ +caddr_t heap_top = (caddr_t)&_end + 4; + + +/** + * @brief Initialize NewLib, called by __libc_init_array() from the startup script + */ +void _init(void) +{ + uart_init_blocking(STDIO, STDIO_BAUDRATE); +} + +/** + * @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 + * - check if the returned address is valid (no check if the memory very exists) + * - have any means to free memory again + * + * TODO: check if the requested memory is really available + * + * @return [description] + */ +caddr_t _sbrk_r(struct _reent *r, ptrdiff_t incr) +{ + unsigned int state = disableIRQ(); + caddr_t res = heap_top; + 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 + */ +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) +{ + char c; + char *buff = (char*)buffer; + uart_read_blocking(UART_0, &c); + buff[0] = c; + return 1; +} + +/** + * @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++) { + uart_write_blocking(UART_0, c[i]); + } + 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; +}