Merge pull request #1514 from cgundogan/remove_tabs_cpu

converting tabs to spaces in cpu (#1439)
dev/timer
Oleg Hahm 9 years ago
commit 8890470783

@ -11,70 +11,70 @@
#define __ARM_COMMON_H
/**
* @ingroup arm_common
* @ingroup arm_common
* @{
*/
#define I_Bit 0x80
#define F_Bit 0x40
#define I_Bit 0x80
#define F_Bit 0x40
#define SYS32Mode 0x1F
#define IRQ32Mode 0x12
#define FIQ32Mode 0x11
#define SYS32Mode 0x1F
#define IRQ32Mode 0x12
#define FIQ32Mode 0x11
#define INTMode (FIQ32Mode | IRQ32Mode)
/**
* @name IRQ Priority Mapping
* @name IRQ Priority Mapping
*/
//@{
#define HIGHEST_PRIORITY 0x01
#define IRQP_RTIMER 1 // FIQ_PRIORITY // TODO: investigate problems with rtimer and FIQ
#define IRQP_TIMER1 1
#define IRQP_WATCHDOG 1
#define IRQP_CLOCK 3
#define IRQP_GPIO 4
#define IRQP_RTC 8
#define LOWEST_PRIORITY 0x0F
#define HIGHEST_PRIORITY 0x01
#define IRQP_RTIMER 1 // FIQ_PRIORITY // TODO: investigate problems with rtimer and FIQ
#define IRQP_TIMER1 1
#define IRQP_WATCHDOG 1
#define IRQP_CLOCK 3
#define IRQP_GPIO 4
#define IRQP_RTC 8
#define LOWEST_PRIORITY 0x0F
// @}
#define WDT_INT 0
#define SWI_INT 1
#define ARM_CORE0_INT 2
#define ARM_CORE1_INT 3
#define TIMER0_INT 4
#define TIMER1_INT 5
#define UART0_INT 6
#define UART1_INT 7
#define PWM0_1_INT 8
#define I2C0_INT 9
#define SPI0_INT 10 /* SPI and SSP0 share VIC slot */
#define SSP0_INT 10
#define SSP1_INT 11
#define PLL_INT 12
#define RTC_INT 13
#define EINT0_INT 14
#define EINT1_INT 15
#define EINT2_INT 16
#define EINT3_INT 17
#define ADC0_INT 18
#define I2C1_INT 19
#define BOD_INT 20
#define EMAC_INT 21
#define USB_INT 22
#define CAN_INT 23
#define MCI_INT 24
#define GPDMA_INT 25
#define TIMER2_INT 26
#define TIMER3_INT 27
#define UART2_INT 28
#define UART3_INT 29
#define I2C2_INT 30
#define I2S_INT 31
#define WDT_INT 0
#define SWI_INT 1
#define ARM_CORE0_INT 2
#define ARM_CORE1_INT 3
#define TIMER0_INT 4
#define TIMER1_INT 5
#define UART0_INT 6
#define UART1_INT 7
#define PWM0_1_INT 8
#define I2C0_INT 9
#define SPI0_INT 10 /* SPI and SSP0 share VIC slot */
#define SSP0_INT 10
#define SSP1_INT 11
#define PLL_INT 12
#define RTC_INT 13
#define EINT0_INT 14
#define EINT1_INT 15
#define EINT2_INT 16
#define EINT3_INT 17
#define ADC0_INT 18
#define I2C1_INT 19
#define BOD_INT 20
#define EMAC_INT 21
#define USB_INT 22
#define CAN_INT 23
#define MCI_INT 24
#define GPDMA_INT 25
#define TIMER2_INT 26
#define TIMER3_INT 27
#define UART2_INT 28
#define UART3_INT 29
#define I2C2_INT 30
#define I2S_INT 31
#define VECT_ADDR_INDEX 0x100
#define VECT_ADDR_INDEX 0x100
#define VECT_CNTL_INDEX 0x200
#include <stdbool.h>

@ -4,13 +4,13 @@
#include <stdint.h>
/* IAP-Commands */
#define PREPARE_SECTOR_FOR_WRITE_OPERATION (50)
#define COPY_RAM_TO_FLASH (51)
#define ERASE_SECTOR (52)
#define BLANK_CHECK_SECTOR (53)
#define READ_PART_ID (54)
#define READ_BOOT_CODE_VERSION (55)
#define COMPARE (56)
#define PREPARE_SECTOR_FOR_WRITE_OPERATION (50)
#define COPY_RAM_TO_FLASH (51)
#define ERASE_SECTOR (52)
#define BLANK_CHECK_SECTOR (53)
#define READ_PART_ID (54)
#define READ_BOOT_CODE_VERSION (55)
#define COMPARE (56)
/* IAP status codes */
#define CMD_SUCCESS (0)
@ -32,16 +32,16 @@
#define IAP_LOCATION (0x7FFFFFF1)
/* PLL */
#define PLLCON_PLLE (0x01) ///< PLL Enable
#define PLLCON_PLLD (0x00) ///< PLL Disable
#define PLLCON_PLLC (0x03) ///< PLL Connect
#define PLLSTAT_PLOCK (0x0400) //</ PLL Lock Status
#define PLLCON_PLLE (0x01) ///< PLL Enable
#define PLLCON_PLLD (0x00) ///< PLL Disable
#define PLLCON_PLLC (0x03) ///< PLL Connect
#define PLLSTAT_PLOCK (0x0400) //</ PLL Lock Status
/*
* @brief: Converts 'addr' to sector number
* @note: Sector table (Users Manual P. 610)
*
* @param addr Flash address
* @param addr Flash address
*
* @return Sector number. 0xFF on error
*/

@ -12,10 +12,10 @@ See the file LICENSE in the top level directory for more details.
*******************************************************************************/
/**
* @ingroup cc430
* @ingroup cc430
* @file cc430-gpioint.c
* @brief CC430 GPIO Interrupt Multiplexer implementation
* @author Oliver Hahm <oliver.hahm@inria.fr>
* @brief CC430 GPIO Interrupt Multiplexer implementation
* @author Oliver Hahm <oliver.hahm@inria.fr>
*/
#include <stdlib.h>

@ -14,8 +14,8 @@ See the file LICENSE in the top level directory for more details.
/**
* @ingroup rtc
* @file cc430-rtc.c
* @brief CC430 real time clock implementation
* @author Oliver Hahm <oliver.hahm@inria.fr>
* @brief CC430 real time clock implementation
* @author Oliver Hahm <oliver.hahm@inria.fr>
*/
#include <string.h>
@ -62,10 +62,10 @@ void rtc_set_localtime(struct tm *localt)
/*---------------------------------------------------------------------------
void rtc_set(time_t time) {
struct tm* localt;
localt = localtime(&time); // convert seconds to broken-down time
rtc_set_localtime(localt);
epoch = time - localt->tm_sec - localt->tm_min * 60;
struct tm* localt;
localt = localtime(&time); // convert seconds to broken-down time
rtc_set_localtime(localt);
epoch = time - localt->tm_sec - localt->tm_min * 60;
}
*/
@ -75,7 +75,7 @@ time_t rtc_time(void) {
struct tm t;
rtc_get_localtime(&t);
sec = mktime(&t);
return sec;
return sec;
}
*/
/*---------------------------------------------------------------------------*/

@ -1,35 +1,35 @@
/* *************************************************************************************************
*
* Copyright (C) 2009 Texas Instruments Incorporated - http://www.ti.com/
*
*
* 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 Texas Instruments Incorporated nor the names of
* its 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.
* Copyright (C) 2009 Texas Instruments Incorporated - http://www.ti.com/
*
*
* 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 Texas Instruments Incorporated nor the names of
* its 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.
*
* ************************************************************************************************/

@ -28,22 +28,22 @@ See the file LICENSE in the top level directory for more details.
*/
/**
* @brief Mask for RTC alarms
* @see ::rtc_set_alarm
* @brief Mask for RTC alarms
* @see ::rtc_set_alarm
*/
typedef enum {
RTC_ALARM_DISABLED = 0x00, ///< Alarm disables
RTC_ALARM_MIN = 0x01, ///< Alarm mask for Minutes
RTC_ALARM_HOUR = 0x02, ///< Alarm mask for Hours
RTC_ALARM_DOW = 0x04, ///< Alarm mask for Day of Week
RTC_ALARM_DISABLED = 0x00, ///< Alarm disables
RTC_ALARM_MIN = 0x01, ///< Alarm mask for Minutes
RTC_ALARM_HOUR = 0x02, ///< Alarm mask for Hours
RTC_ALARM_DOW = 0x04, ///< Alarm mask for Day of Week
RTC_ALARM_DOM = 0x08 ///< Alarm mask for Day of Month
} rtc_alarm_mask_t;
/**
* @brief Sets the alarm
* @brief Sets the alarm
* @internal
* @param[in] localt Alarm time
* @param[in] mask Sets the registers to poll for the alarm
* @param[in] localt Alarm time
* @param[in] mask Sets the registers to poll for the alarm
*
* To disable the alarm set mask to RTC_ALARM_DISABLED.
*

@ -23,13 +23,13 @@
NORETURN void sched_task_return(void);
unsigned int atomic_set_return(unsigned int* p, unsigned int uiVal) {
//unsigned int cspr = disableIRQ(); //crashes
dINT();
unsigned int uiOldVal = *p;
*p = uiVal;
//restoreIRQ(cspr); //crashes
eINT();
return uiOldVal;
//unsigned int cspr = disableIRQ(); //crashes
dINT();
unsigned int uiOldVal = *p;
*p = uiVal;
//restoreIRQ(cspr); //crashes
eINT();
return uiOldVal;
}
NORETURN void cpu_switch_context_exit(void){
@ -39,56 +39,56 @@ NORETURN void cpu_switch_context_exit(void){
void thread_yield(void) {
asm("svc 0x01\n");
asm("svc 0x01\n");
}
__attribute__((naked))
void SVC_Handler(void)
{
save_context();
asm("bl sched_run");
/* call scheduler update sched_active_thread variable with pdc of next thread
* the thread that has higest priority and is in PENDING state */
restore_context();
save_context();
asm("bl sched_run");
/* call scheduler update sched_active_thread variable with pdc of next thread
* the thread that has higest priority and is in PENDING state */
restore_context();
}
/* kernel functions */
void ctx_switch(void)
{
/* Save return address on stack */
/* stmfd sp!, {lr} */
/* Save return address on stack */
/* stmfd sp!, {lr} */
/* disable interrupts */
/* mov lr, #NOINT|SVCMODE */
/* msr CPSR_c, lr */
/* cpsid i */
/* disable interrupts */
/* mov lr, #NOINT|SVCMODE */
/* msr CPSR_c, lr */
/* cpsid i */
/* save other register */
asm("nop");
/* save other register */
asm("nop");
asm("mov r12, sp");
asm("stmfd r12!, {r4-r11}");
asm("mov r12, sp");
asm("stmfd r12!, {r4-r11}");
/* save user mode stack pointer in *sched_active_thread */
asm("ldr r1, =sched_active_thread"); /* r1 = &sched_active_thread */
asm("ldr r1, [r1]"); /* r1 = *r1 = sched_active_thread */
asm("str r12, [r1]"); /* store stack pointer in tasks pdc*/
/* save user mode stack pointer in *sched_active_thread */
asm("ldr r1, =sched_active_thread"); /* r1 = &sched_active_thread */
asm("ldr r1, [r1]"); /* r1 = *r1 = sched_active_thread */
asm("str r12, [r1]"); /* store stack pointer in tasks pdc*/
sched_task_return();
sched_task_return();
}
/* call scheduler so sched_active_thread points to the next task */
NORETURN void sched_task_return(void)
{
/* load pdc->stackpointer in r0 */
asm("ldr r0, =sched_active_thread"); /* r0 = &sched_active_thread */
asm("ldr r0, [r0]"); /* r0 = *r0 = sched_active_thread */
asm("ldr sp, [r0]"); /* sp = r0 restore stack pointer*/
asm("pop {r4}"); /* skip exception return */
asm(" pop {r4-r11}");
asm(" pop {r0-r3,r12,lr}"); /* simulate register restor from stack */
// asm("pop {r4}"); /*foo*/
asm("pop {pc}");
/* load pdc->stackpointer in r0 */
asm("ldr r0, =sched_active_thread"); /* r0 = &sched_active_thread */
asm("ldr r0, [r0]"); /* r0 = *r0 = sched_active_thread */
asm("ldr sp, [r0]"); /* sp = r0 restore stack pointer*/
asm("pop {r4}"); /* skip exception return */
asm(" pop {r4-r11}");
asm(" pop {r0-r3,r12,lr}"); /* simulate register restor from stack */
// asm("pop {r4}"); /*foo*/
asm("pop {pc}");
UNREACHABLE();
}
@ -113,62 +113,62 @@ NORETURN void sched_task_return(void)
*/
char * thread_stack_init(void *(*task_func)(void *), void *arg, void *stack_start, int stack_size)
{
unsigned int * stk;
stk = (unsigned int *) (stack_start + stack_size);
/* marker */
stk--;
*stk = 0x77777777;
//FIXME FPSCR
stk--;
*stk = (unsigned int) 0;
//S0 - S15
for (int i = 15; i >= 0; i--) {
stk--;
*stk = i;
}
//FIXME xPSR
stk--;
*stk = (unsigned int) 0x01000200;
//program counter
stk--;
*stk = (unsigned int) task_func;
/* link register */
stk--;
*stk = (unsigned int) 0x0;
/* r12 */
stk--;
*stk = (unsigned int) 0;
/* r1 - r3 */
for (int i = 3; i >= 1; i--) {
stk--;
*stk = i;
}
/* r0 -> thread function parameter */
stk--;
*stk = (unsigned int) arg;
/* r11 - r4 */
for (int i = 11; i >= 4; i--) {
stk--;
*stk = i;
}
/* foo */
/*stk--;
*stk = (unsigned int) 0xDEADBEEF;*/
/* lr means exception return code */
stk--;
*stk = (unsigned int) 0xfffffff9; // return to taskmode main stack pointer
return (char*) stk;
unsigned int * stk;
stk = (unsigned int *) (stack_start + stack_size);
/* marker */
stk--;
*stk = 0x77777777;
//FIXME FPSCR
stk--;
*stk = (unsigned int) 0;
//S0 - S15
for (int i = 15; i >= 0; i--) {
stk--;
*stk = i;
}
//FIXME xPSR
stk--;
*stk = (unsigned int) 0x01000200;
//program counter
stk--;
*stk = (unsigned int) task_func;
/* link register */
stk--;
*stk = (unsigned int) 0x0;
/* r12 */
stk--;
*stk = (unsigned int) 0;
/* r1 - r3 */
for (int i = 3; i >= 1; i--) {
stk--;
*stk = i;
}
/* r0 -> thread function parameter */
stk--;
*stk = (unsigned int) arg;
/* r11 - r4 */
for (int i = 11; i >= 4; i--) {
stk--;
*stk = i;
}
/* foo */
/*stk--;
*stk = (unsigned int) 0xDEADBEEF;*/
/* lr means exception return code */
stk--;
*stk = (unsigned int) 0xfffffff9; // return to taskmode main stack pointer
return (char*) stk;
}

@ -128,8 +128,8 @@ typedef struct
__IO uint32_t CCLKCFG;
__IO uint32_t USBCLKCFG;
__IO uint32_t CLKSRCSEL;
__IO uint32_t CANSLEEPCLR;
__IO uint32_t CANWAKEFLAGS;
__IO uint32_t CANSLEEPCLR;
__IO uint32_t CANWAKEFLAGS;
uint32_t RESERVED4[10];
__IO uint32_t EXTINT; /* External Interrupts */
uint32_t RESERVED5;

@ -5,12 +5,12 @@
* @name Kernel configuration
* @{
*/
#define KERNEL_CONF_STACKSIZE_PRINTF (4096)
#define KERNEL_CONF_STACKSIZE_PRINTF (4096)
#ifndef KERNEL_CONF_STACKSIZE_DEFAULT
#define KERNEL_CONF_STACKSIZE_DEFAULT 1500
#define KERNEL_CONF_STACKSIZE_DEFAULT 1500
#endif
#define KERNEL_CONF_STACKSIZE_IDLE 1000
#define KERNEL_CONF_STACKSIZE_IDLE 1000
#define UART0_BUFSIZE (128)
/** @} */

@ -1,8 +1,8 @@
#ifndef HWTIMER_CPU_H_
#define HWTIMER_CPU_H_
#define HWTIMER_MAXTIMERS 3
#define HWTIMER_SPEED 1000000
#define HWTIMER_MAXTICKS (0xFFFFFFFF)
#define HWTIMER_MAXTIMERS 3
#define HWTIMER_SPEED 1000000
#define HWTIMER_MAXTICKS (0xFFFFFFFF)
#endif /* HWTIMER_CPU_H_ */

@ -24,13 +24,13 @@ static enum lpm_mode lpm;
// TODO
enum lpm_mode lpm_set(enum lpm_mode target) {
enum lpm_mode last_lpm = lpm;
enum lpm_mode last_lpm = lpm;
lpm = target;
lpm = target;
return last_lpm;
return last_lpm;
}
void lpm_awake(void) {
lpm = LPM_ON;
lpm = LPM_ON;
}

@ -32,17 +32,17 @@
* @name Heaps (defined in linker script)
* @{
*/
#define NUM_HEAPS 1
#define NUM_HEAPS 1
#define DEBUG_SYSCALLS 0
#define DEBUG_SYSCALLS 0
#if DEBUG_SYSCALLS
#define PRINTF(...) printf(__VA_ARGS__)
#define PRINTF(...) printf(__VA_ARGS__)
#else
#define PRINTF(...)
#endif
extern uintptr_t __heap_start; ///< start of heap memory space
extern uintptr_t __heap_max; ///< maximum for end of heap memory space
extern uintptr_t __heap_start; ///< start of heap memory space
extern uintptr_t __heap_max; ///< maximum for end of heap memory space
/// current position in heap
static caddr_t heap[NUM_HEAPS] = {(caddr_t)&__heap_start};
@ -57,20 +57,20 @@ volatile static uint8_t iUsedHeap = 0;
/*-----------------------------------------------------------------------------------*/
void heap_stats(void) {
for(int i = 0; i < NUM_HEAPS; i++)
printf("# heap %i: %p -- %p -> %p (%li of %li free)\n", i, heap_start[i], heap[i], heap_max[i],
(uint32_t)heap_max[i] - (uint32_t)heap[i], (uint32_t)heap_max[i] - (uint32_t)heap_start[i]);
for(int i = 0; i < NUM_HEAPS; i++)
printf("# heap %i: %p -- %p -> %p (%li of %li free)\n", i, heap_start[i], heap[i], heap_max[i],
(uint32_t)heap_max[i] - (uint32_t)heap[i], (uint32_t)heap_max[i] - (uint32_t)heap_start[i]);
}
/*-----------------------------------------------------------------------------------*/
void __assert_func(const char *file, int line, const char *func, const char *failedexpr)
{
printf("#! assertion %s failed\n\t%s() in %s:%d\n", failedexpr, func, file, line );
_exit(3);
printf("#! assertion %s failed\n\t%s() in %s:%d\n", failedexpr, func, file, line );
_exit(3);
}
/*-----------------------------------------------------------------------------------*/
void __assert(const char *file, int line, const char *failedexpr)
{
__assert_func(file, line, "?", failedexpr);
__assert_func(file, line, "?", failedexpr);
}
/*-----------------------------------------------------------------------------------*/
caddr_t _sbrk_r(struct _reent *r, size_t incr)
@ -85,150 +85,150 @@ caddr_t _sbrk_r(struct _reent *r, size_t incr)
uint32_t cpsr = disableIRQ();
/* check all heaps for a chunk of the requested size */
for( ; iUsedHeap < NUM_HEAPS; iUsedHeap++ ) {
caddr_t new_heap = heap[iUsedHeap] + incr;
for( ; iUsedHeap < NUM_HEAPS; iUsedHeap++ ) {
caddr_t new_heap = heap[iUsedHeap] + incr;
if( new_heap <= heap_max[iUsedHeap] ) {
caddr_t prev_heap = heap[iUsedHeap];
heap[iUsedHeap] = new_heap;
if( new_heap <= heap_max[iUsedHeap] ) {
caddr_t prev_heap = heap[iUsedHeap];
heap[iUsedHeap] = new_heap;
r->_errno = 0;
restoreIRQ(cpsr);
return prev_heap;
}
}
restoreIRQ(cpsr);
r->_errno = 0;
restoreIRQ(cpsr);
return prev_heap;
}
}
restoreIRQ(cpsr);
r->_errno = ENOMEM;
return NULL;
r->_errno = ENOMEM;
return NULL;
}
/*---------------------------------------------------------------------------*/
int _isatty_r(struct _reent *r, int fd)
{
r->_errno = 0;
if( fd == STDOUT_FILENO || fd == STDERR_FILENO )
return 1;
else
return 0;
r->_errno = 0;
if( fd == STDOUT_FILENO || fd == STDERR_FILENO )
return 1;
else
return 0;
}
/*---------------------------------------------------------------------------*/
_off_t _lseek_r(struct _reent *r, int fd, _off_t pos, int whence)
{
_off_t result = -1;
PRINTF("lseek [%i] pos %li whence %i\n", fd, pos, whence);
_off_t result = -1;
PRINTF("lseek [%i] pos %li whence %i\n", fd, pos, whence);
r->_errno = ENODEV;
r->_errno = ENODEV;
PRINTF("lseek returned %li (0 is success)\n", result);
return result;
PRINTF("lseek returned %li (0 is success)\n", result);
return result;
}
/*---------------------------------------------------------------------------*/
int _open_r(struct _reent *r, const char *name, int mode)
{
int ret = -1;
PRINTF("open '%s' mode %#x\n", name, mode);
int ret = -1;
PRINTF("open '%s' mode %#x\n", name, mode);
r->_errno = ENODEV; // no such device
r->_errno = ENODEV; // no such device
PRINTF("open [%i] errno %i\n", ret, r->_errno);
return ret;
PRINTF("open [%i] errno %i\n", ret, r->_errno);
return ret;
}
/*---------------------------------------------------------------------------*/
int _stat_r(struct _reent *r, char *name, struct stat *st)
{
int ret = -1;
PRINTF("_stat_r '%s' \n", name);
r->_errno = ENODEV; // no such device
PRINTF("_stat_r [%i] errno %i\n", ret, r->_errno);
return ret;
int ret = -1;
PRINTF("_stat_r '%s' \n", name);
r->_errno = ENODEV; // no such device
PRINTF("_stat_r [%i] errno %i\n", ret, r->_errno);
return ret;
}
/*---------------------------------------------------------------------------*/
int _fstat_r(struct _reent *r, int fd, struct stat * st)
{
int ret = -1;
r->_errno = 0;
memset(st, 0, sizeof(*st));
if (fd == STDOUT_FILENO || fd == STDERR_FILENO) {
st->st_mode = S_IFCHR;
ret = 0;
}
int ret = -1;
r->_errno = 0;
memset(st, 0, sizeof(*st));
if (fd == STDOUT_FILENO || fd == STDERR_FILENO) {
st->st_mode = S_IFCHR;
ret = 0;
}
else {
r->_errno = ENODEV;
}
return ret;
}
return ret;
}
/*---------------------------------------------------------------------------*/
int _write_r(struct _reent *r, int fd, const void *data, unsigned int count)
{
int result = EOF;
r->_errno = EBADF;
switch(fd) {
case STDOUT_FILENO:
case STDERR_FILENO:
{
//FIXME impl fw_puts
//char* chars = (char*) data;
for(int i = 0;i < count;i++) {
//USART_SendData(USART2, chars[i]);
/* Loop until the end of transmission */
//while (USART_GetFlagStatus(USART2, USART_FLAG_TC) == RESET){}
}
return count;
//result = fw_puts((char*)data, count);
}
break;
default:
break;
}
int result = EOF;
r->_errno = EBADF;
switch(fd) {
case STDOUT_FILENO:
case STDERR_FILENO:
{
//FIXME impl fw_puts
//char* chars = (char*) data;
for(int i = 0;i < count;i++) {
//USART_SendData(USART2, chars[i]);
/* Loop until the end of transmission */
//while (USART_GetFlagStatus(USART2, USART_FLAG_TC) == RESET){}
}
return count;
//result = fw_puts((char*)data, count);
}
break;
default:
break;
}
return result;
return result;
}
/*---------------------------------------------------------------------------*/
int _read_r(struct _reent *r, int fd, void *buffer, unsigned int count)
{
int result = -1;
r->_errno = EBADF;
return result;
int result = -1;
r->_errno = EBADF;
return result;
}
/*---------------------------------------------------------------------------*/
int _close_r(struct _reent *r, int fd)
{
int ret = -1;
r->_errno = EBADF;
return ret;
int ret = -1;
r->_errno = EBADF;
return ret;
}
/*---------------------------------------------------------------------------*/
int _unlink_r(struct _reent *r, char* path)
{
int ret = -1;
r->_errno = ENODEV;
return ret;
int ret = -1;
r->_errno = ENODEV;
return ret;
}
/*---------------------------------------------------------------------------*/
void _exit(int n)
{
printf("#! exit %i: resetting\n", n);
printf("#! exit %i: resetting\n", n);
//FIXME write out all peripherie buffers stdout flush
NVIC_SystemReset();
while(1);
//FIXME write out all peripherie buffers stdout flush
NVIC_SystemReset();
while(1);
}
/*---------------------------------------------------------------------------*/
int _getpid(void)
{
return sched_active_thread->pid;
return sched_active_thread->pid;
}
/*---------------------------------------------------------------------------*/
int _kill_r(struct _reent *r, int pid, int sig)
{
/* not implemented */
r->_errno = ESRCH; // no such process
return -1;
/* not implemented */
r->_errno = ESRCH; // no such process
return -1;
}
/*---------------------------------------------------------------------------*/
#ifdef MODULE_VTIMER

@ -11,7 +11,7 @@ See the file LICENSE in the top level directory for more details.
*******************************************************************************/
/**
* @ingroup lpc2387
* @ingroup lpc2387
* @{
*/
@ -54,18 +54,18 @@ void cpu_clock_scale(uint32_t source, uint32_t target, uint32_t *prescale)
lpc2387_pclk_scale(source, target, &pclksel, prescale);
PCLKSEL0 = (PCLKSEL0 & ~(BIT2 | BIT3)) | (pclksel << 2); // timer 0
PCLKSEL0 = (PCLKSEL0 & ~(BIT4 | BIT5)) | (pclksel << 4); // timer 1
PCLKSEL1 = (PCLKSEL1 & ~(BIT12 | BIT13)) | (pclksel << 12); // timer 2
PCLKSEL0 = (PCLKSEL0 & ~(BIT2 | BIT3)) | (pclksel << 2); // timer 0
PCLKSEL0 = (PCLKSEL0 & ~(BIT4 | BIT5)) | (pclksel << 4); // timer 1
PCLKSEL1 = (PCLKSEL1 & ~(BIT12 | BIT13)) | (pclksel << 12); // timer 2
}
/******************************************************************************
** Function name: install_irq
** Function name: install_irq
**
** Descriptions: Install interrupt handler
** parameters: Interrupt number, interrupt handler address,
** interrupt priority
** Returned value: true or false, return false if IntNum is out of range
** Descriptions: Install interrupt handler
** parameters: Interrupt number, interrupt handler address,
** interrupt priority
** Returned value: true or false, return false if IntNum is out of range
**
******************************************************************************/
#define VIC_BASE_ADDR 0xFFFFF000
@ -75,7 +75,7 @@ bool install_irq(int IntNumber, void (*HandlerAddr)(void), int Priority)
int *vect_addr;
int *vect_cntl;
VICIntEnClr = 1 << IntNumber; /* Disable Interrupt */
VICIntEnClr = 1 << IntNumber; /* Disable Interrupt */
if (IntNumber >= VIC_SIZE) {
return (false);
@ -84,9 +84,9 @@ bool install_irq(int IntNumber, void (*HandlerAddr)(void), int Priority)
/* find first un-assigned VIC address for the handler */
vect_addr = (int *)(VIC_BASE_ADDR + VECT_ADDR_INDEX + IntNumber * 4);
vect_cntl = (int *)(VIC_BASE_ADDR + VECT_CNTL_INDEX + IntNumber * 4);
*vect_addr = (int)HandlerAddr; /* set interrupt vector */
*vect_addr = (int)HandlerAddr; /* set interrupt vector */
*vect_cntl = Priority;
VICIntEnable = 1 << IntNumber; /* Enable Interrupt */
VICIntEnable = 1 << IntNumber; /* Enable Interrupt */
return(true);
}
}

@ -14,38 +14,38 @@ See the file LICENSE in the top level directory for more details.
#define CPUCONF_H_
/**
* @ingroup conf
* @ingroup lpc2387
* @ingroup conf
* @ingroup lpc2387
*
* @{
*/
/**
* @file
* @brief LPC2387 CPUconfiguration
* @brief LPC2387 CPUconfiguration
*
* @author baar
* @author baar
* @version $Revision$
*
* @note $Id$
* @note $Id$
*/
#define FEUERWARE_CONF_CPU_NAME "NXP LPC2387"
#define FEUERWARE_CONF_CPU_NAME "NXP LPC2387"
/**
* @name CPU capabilities
* @{
*/
#define FEUERWARE_CPU_LPC2387 1
#define FEUERWARE_CONF_CORE_SUPPORTS_TIME 1
#define FEUERWARE_CPU_LPC2387 1
#define FEUERWARE_CONF_CORE_SUPPORTS_TIME 1
/** @} */
/**
* @name Stdlib configuration
* @{
*/
#define __FOPEN_MAX__ 4
#define __FILENAME_MAX__ 12
#define __FOPEN_MAX__ 4
#define __FILENAME_MAX__ 12
/** @} */
/**
@ -56,20 +56,20 @@ See the file LICENSE in the top level directory for more details.
#define KERNEL_CONF_STACKSIZE_PRINTF (2048)
#ifndef KERNEL_CONF_STACKSIZE_DEFAULT
#define KERNEL_CONF_STACKSIZE_DEFAULT (512)
#define KERNEL_CONF_STACKSIZE_DEFAULT (512)
#endif
#define KERNEL_CONF_STACKSIZE_IDLE (160)
#define KERNEL_CONF_STACKSIZE_IDLE (160)
/** @} */
/**
* @name Compiler specifics
* @{
*/
#define CC_CONF_INLINE inline
#define CC_CONF_USED __attribute__((used))
#define CC_CONF_NONNULL(...) __attribute__((nonnull(__VA_ARGS__)))
#define CC_CONF_WARN_UNUSED_RESULT __attribute__((warn_unused_result))
#define CC_CONF_INLINE inline
#define CC_CONF_USED __attribute__((used))
#define CC_CONF_NONNULL(...) __attribute__((nonnull(__VA_ARGS__)))
#define CC_CONF_WARN_UNUSED_RESULT __attribute__((warn_unused_result))
/** @} */
#define TRANSCEIVER_BUFFER_SIZE (10)

@ -14,44 +14,44 @@ See the file LICENSE in the top level directory for more details.
#define LPC2387ADC_H_
/**
* @defgroup lpc2387_adc LPC2387 ADC
* @ingroup lpc2387
* @defgroup lpc2387_adc LPC2387 ADC
* @ingroup lpc2387
*
* @{
*/
/**
* @file
* @brief LPC2387 ADC
* @brief LPC2387 ADC
*
* @author Thomas Hillebrandt <hillebra@inf.fu-berlin.de>
* @author Thomas Hillebrandt <hillebra@inf.fu-berlin.de>
* @version $Revision: 3249 $
*
* @note $Id: lpc2387-adc.h 3249 2011-03-11 09:44:46Z schmittb $
* @note $Id: lpc2387-adc.h 3249 2011-03-11 09:44:46Z schmittb $
*/
#include <stdint.h>
#define ADC_NUM (6)
#define ADC_OFFSET (0x10)
#define ADC_INDEX (4)
#define ADC_NUM (6)
#define ADC_OFFSET (0x10)
#define ADC_INDEX (4)
#define ADC_DONE (0x80000000)
#define ADC_OVERRUN (0x40000000)
#define ADC_DONE (0x80000000)
#define ADC_OVERRUN (0x40000000)
/**
* @brief Initialize ADC.
* @brief Initialize ADC.
*/
void adc_init(void);
void adc_init_1(void);
void adc_init_2(void);
/**
* @brief Read ADC value of selected channel.
* @brief Read ADC value of selected channel.
*
* Valid channel numbers are from 0 to 2.
*
* @return ADC value of selected channel.
* @return ADC value of selected channel.
*/
uint16_t adc_read(uint8_t channel);

@ -14,10 +14,10 @@ See the file LICENSE in the top level directory for more details.
#define LPC2387_RTC_H
/**
* @defgroup lpc2387_rtc LPC2387 Real-Time-Clock
* @ingroup lpc2387
* @defgroup lpc2387_rtc LPC2387 Real-Time-Clock
* @ingroup lpc2387
*
* \section lpc2387_rtc_newlib Standard library support
* \section lpc2387_rtc_newlib Standard library support
* Currently reading and setting time and date through standard C functions is implemented.
* Standard C timers are not available.
*
@ -26,12 +26,12 @@ See the file LICENSE in the top level directory for more details.
/**
* @file
* @brief LPC2387 Real-Time-Clock
* @brief LPC2387 Real-Time-Clock
*
* @author Freie Universität Berlin, Computer Systems & Telematics
* @version $Revision: 1998 $
*
* @note $Id: lpc2387-rtc.h 1998 2010-03-16 13:05:41Z baar $
* @note $Id: lpc2387-rtc.h 1998 2010-03-16 13:05:41Z baar $
*/
#include <time.h>
@ -48,48 +48,48 @@ See the file LICENSE in the top level directory for more details.
/** @} */
/**
* @brief Mask for RTC alarms
* @see ::rtc_set_alarm, ::rtc_get_alarm
* @brief Mask for RTC alarms
* @see ::rtc_set_alarm, ::rtc_get_alarm
*/
enum rtc_alarm_mask {
RTC_AMR_DISABLED = 0, ///< Alarm disables
RTC_AMR_SEC = AMRSEC, ///< Alarm mask for Seconds
RTC_AMR_MIN = AMRMIN, ///< Alarm mask for Minutes
RTC_AMR_HOUR = AMRHOUR, ///< Alarm mask for Hours
RTC_AMR_DOM = AMRDOM, ///< Alarm mask for Day of Month
RTC_AMR_DOW = AMRDOW, ///< Alarm mask for Day of Week
RTC_AMR_DOY = AMRDOY, ///< Alarm mask for Day of Year
RTC_AMR_MON = AMRMON, ///< Alarm mask for Month
RTC_AMR_YEAR = AMRYEAR, ///< Alarm mask for Year
RTC_AMR_DISABLED = 0, ///< Alarm disables
RTC_AMR_SEC = AMRSEC, ///< Alarm mask for Seconds
RTC_AMR_MIN = AMRMIN, ///< Alarm mask for Minutes
RTC_AMR_HOUR = AMRHOUR, ///< Alarm mask for Hours
RTC_AMR_DOM = AMRDOM, ///< Alarm mask for Day of Month
RTC_AMR_DOW = AMRDOW, ///< Alarm mask for Day of Week
RTC_AMR_DOY = AMRDOY, ///< Alarm mask for Day of Year
RTC_AMR_MON = AMRMON, ///< Alarm mask for Month
RTC_AMR_YEAR = AMRYEAR, ///< Alarm mask for Year
};
void rtc_reset(void);
/**
* @brief Returns the time of compilation in seconds
* @brief Returns the time of compilation in seconds
* @internal
*/
time_t rtc_get_compile_time(void) __attribute__((noinline));
/**
* @brief Returns the current clock time
* @param[out] time optional return value
* @return clock time in seconds
* @brief Returns the current clock time
* @param[out] time optional return value
* @return clock time in seconds
*/
time_t rtc_time(struct timeval *time);
/**
* @brief Sets the current clock time
* @param[in] time new time in seconds
* @note Any set alarm is shifted
* @brief Sets the current clock time
* @param[in] time new time in seconds
* @note Any set alarm is shifted
*/
void rtc_set(time_t time);
/**
* @brief Sets the alarm
* @brief Sets the alarm
* @internal
* @param[in] localt Alarm time
* @param[in] mask Sets the registers to poll for the alarm
* @param[in] localt Alarm time
* @param[in] mask Sets the registers to poll for the alarm
*
* To disable the alarm set mask to RTC_AMR_DISABLED.
*
@ -98,10 +98,10 @@ void rtc_set(time_t time);
void rtc_set_alarm(struct tm *localt, enum rtc_alarm_mask mask);
/**
* @brief Gets the current alarm setting
* @brief Gets the current alarm setting
* @internal
* @param[out] localt Pointer to structure to receive alarm time
* @return Alarm mask
* @param[out] localt Pointer to structure to receive alarm time
* @return Alarm mask
*
* @see rtc_set_alarm
* @see ::rtc_alarm_mask

@ -12,11 +12,11 @@
#include "lpc23xx.h"
#include "bitarithm.h"
#define F_CCO 288000000
#define CL_CPU_DIV 4 ///< CPU clock divider
#define F_CPU (F_CCO / CL_CPU_DIV) ///< CPU target speed in Hz
#define F_RC_OSCILLATOR 4000000 ///< Frequency of internal RC oscillator
#define F_RTC_OSCILLATOR 32767 ///< Frequency of RTC oscillator
#define F_CCO 288000000
#define CL_CPU_DIV 4 ///< CPU clock divider
#define F_CPU (F_CCO / CL_CPU_DIV) ///< CPU target speed in Hz
#define F_RC_OSCILLATOR 4000000 ///< Frequency of internal RC oscillator
#define F_RTC_OSCILLATOR 32767 ///< Frequency of RTC oscillator
#define VIC_SIZE 32
@ -26,7 +26,7 @@
#define _XTAL (72000)
/**
* @name Timer Symbols
* @name Timer Symbols
* @{
*/
#define MR0I BIT0
@ -47,139 +47,139 @@
* @name RTC constants
* @{
*/
#define IMSEC 0x00000001
#define IMMIN 0x00000002
#define IMHOUR 0x00000004
#define IMDOM 0x00000008
#define IMDOW 0x00000010
#define IMDOY 0x00000020
#define IMMON 0x00000040
#define IMYEAR 0x00000080
#define AMRSEC 0x00000001 /* Alarm mask for Seconds */
#define AMRMIN 0x00000002 /* Alarm mask for Minutes */
#define AMRHOUR 0x00000004 /* Alarm mask for Hours */
#define AMRDOM 0x00000008 /* Alarm mask for Day of Month */
#define AMRDOW 0x00000010 /* Alarm mask for Day of Week */
#define AMRDOY 0x00000020 /* Alarm mask for Day of Year */
#define AMRMON 0x00000040 /* Alarm mask for Month */
#define AMRYEAR 0x00000080 /* Alarm mask for Year */
#define ILR_RTCCIF BIT0
#define ILR_RTCALF BIT1
#define ILR_RTSSF BIT2
#define CCR_CLKEN 0x01
#define CCR_CTCRST 0x02
#define CCR_CLKSRC 0x10
#define IMSEC 0x00000001
#define IMMIN 0x00000002
#define IMHOUR 0x00000004
#define IMDOM 0x00000008
#define IMDOW 0x00000010
#define IMDOY 0x00000020
#define IMMON 0x00000040
#define IMYEAR 0x00000080
#define AMRSEC 0x00000001 /* Alarm mask for Seconds */
#define AMRMIN 0x00000002 /* Alarm mask for Minutes */
#define AMRHOUR 0x00000004 /* Alarm mask for Hours */
#define AMRDOM 0x00000008 /* Alarm mask for Day of Month */
#define AMRDOW 0x00000010 /* Alarm mask for Day of Week */
#define AMRDOY 0x00000020 /* Alarm mask for Day of Year */
#define AMRMON 0x00000040 /* Alarm mask for Month */
#define AMRYEAR 0x00000080 /* Alarm mask for Year */
#define ILR_RTCCIF BIT0
#define ILR_RTCALF BIT1
#define ILR_RTSSF BIT2
#define CCR_CLKEN 0x01
#define CCR_CTCRST 0x02
#define CCR_CLKSRC 0x10
/** @} */
/**
* @name WD constants
* @{
*/
#define WDEN BIT0
#define WDRESET BIT1
#define WDTOF BIT2
#define WDINT BIT3
#define WDEN BIT0
#define WDRESET BIT1
#define WDTOF BIT2
#define WDINT BIT3
/** @} */
/**
* @name PCONP Constants
* @name PCONP Constants
* @{
*/
#define PCTIM0 BIT1
#define PCTIM1 BIT2
#define PCUART0 BIT3
#define PCUART1 BIT4
#define PCPWM1 BIT6
#define PCI2C0 BIT7
#define PCSPI BIT8
#define PCRTC BIT9
#define PCSSP1 BIT10
#define PCEMC BIT11
#define PCAD BIT12
#define PCAN1 BIT13
#define PCAN2 BIT14
#define PCI2C1 BIT19
#define PCSSP0 BIT21
#define PCTIM2 BIT22
#define PCTIM3 BIT23
#define PCUART2 BIT24
#define PCUART3 BIT25
#define PCI2C2 BIT26
#define PCI2S BIT27
#define PCSDC BIT28
#define PCGPDMA BIT29
#define PCENET BIT30
#define PCUSB BIT31
#define PCTIM0 BIT1
#define PCTIM1 BIT2
#define PCUART0 BIT3
#define PCUART1 BIT4
#define PCPWM1 BIT6
#define PCI2C0 BIT7
#define PCSPI BIT8
#define PCRTC BIT9
#define PCSSP1 BIT10
#define PCEMC BIT11
#define PCAD BIT12
#define PCAN1 BIT13
#define PCAN2 BIT14
#define PCI2C1 BIT19
#define PCSSP0 BIT21
#define PCTIM2 BIT22
#define PCTIM3 BIT23
#define PCUART2 BIT24
#define PCUART3 BIT25
#define PCI2C2 BIT26
#define PCI2S BIT27
#define PCSDC BIT28
#define PCGPDMA BIT29
#define PCENET BIT30
#define PCUSB BIT31
/** @} */
/**
* @name PCON Constants
* @name PCON Constants
* @{
*/
#define PM0 BIT0
#define PM1 BIT1
#define BODPDM BIT2
#define BOGD BIT3
#define BORD BIT4
#define PM2 BIT7
#define PM_IDLE (PM0)
#define PM_SLEEP (PM2|PM0)
#define PM_POWERDOWN (PM1)
#define PM0 BIT0