From 398994567902f730b8a22fe4268c8a9df2a5c7aa Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cenk=20G=C3=BCndo=C4=9Fan?= Date: Thu, 31 Jul 2014 20:46:28 +0200 Subject: [PATCH] converting tabs to spaces in cpu (#1439) This PR converts tabs to white spaces. The statement I used for the conversion: ```find . -name "*.[ch]" -exec zsh -c 'expand -t 4 "$0" > /tmp/e && mv /tmp/e "$0"' {} \;``` Afterwards, I had a quick overview of the converted files to prevent odd indentation. --- cpu/arm_common/include/VIC.h | 98 +++--- cpu/arm_common/include/iap.h | 24 +- cpu/cc430/cc430-gpioint.c | 6 +- cpu/cc430/cc430-rtc.c | 14 +- cpu/cc430/include/cc430-adc.h | 60 ++-- cpu/cc430/include/cc430-rtc.h | 18 +- cpu/lpc1768/atom.c | 190 +++++----- cpu/lpc1768/include/LPC17xx.h | 4 +- cpu/lpc1768/include/cpu-conf.h | 6 +- cpu/lpc1768/include/hwtimer_cpu.h | 6 +- cpu/lpc1768/lpc1768-lpm.c | 8 +- cpu/lpc1768/syscalls.c | 192 +++++------ cpu/lpc2387/cpu.c | 24 +- cpu/lpc2387/include/cpu-conf.h | 32 +- cpu/lpc2387/include/lpc2387-adc.h | 26 +- cpu/lpc2387/include/lpc2387-rtc.h | 58 ++-- cpu/lpc2387/include/lpc2387.h | 214 ++++++------ cpu/lpc2387/include/lpc23xx.h | 224 ++++++------ cpu/lpc2387/lpc2387-adc.c | 70 ++-- cpu/lpc2387/lpc2387-lpm.c | 16 +- cpu/lpc2387/mci/lpc2387-mci.c | 344 +++++++++--------- cpu/lpc2387/rtc/lpc2387-rtc.c | 52 +-- cpu/lpc_common/iap.c | 188 +++++----- cpu/mc1322x/asm/asm.c | 10 +- cpu/mc1322x/asm/include/asm.h | 78 ++--- cpu/mc1322x/include/cpu-conf.h | 24 +- cpu/mc1322x/include/cpu.h | 6 +- cpu/mc1322x/include/mc1322x.h | 498 +++++++++++++-------------- cpu/msp430-common/include/cpu-conf.h | 2 +- cpu/sam3x8e/include/system_sam3xa.h | 2 +- cpu/stm32f0/include/stm32f051x8.h | 4 +- cpu/stm32f4/include/stm32f407xx.h | 2 +- 32 files changed, 1250 insertions(+), 1250 deletions(-) diff --git a/cpu/arm_common/include/VIC.h b/cpu/arm_common/include/VIC.h index 2b61585cdf5e..cca16b63f8db 100644 --- a/cpu/arm_common/include/VIC.h +++ b/cpu/arm_common/include/VIC.h @@ -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 diff --git a/cpu/arm_common/include/iap.h b/cpu/arm_common/include/iap.h index c4c14f848d4a..28cb5da3f289 100644 --- a/cpu/arm_common/include/iap.h +++ b/cpu/arm_common/include/iap.h @@ -4,13 +4,13 @@ #include /* 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) // + * @brief CC430 GPIO Interrupt Multiplexer implementation + * @author Oliver Hahm */ #include diff --git a/cpu/cc430/cc430-rtc.c b/cpu/cc430/cc430-rtc.c index 189aef0fcda3..5714303ad715 100644 --- a/cpu/cc430/cc430-rtc.c +++ b/cpu/cc430/cc430-rtc.c @@ -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 + * @brief CC430 real time clock implementation + * @author Oliver Hahm */ #include @@ -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; } */ /*---------------------------------------------------------------------------*/ diff --git a/cpu/cc430/include/cc430-adc.h b/cpu/cc430/include/cc430-adc.h index c5f49feb18aa..1e0e33f52ddb 100644 --- a/cpu/cc430/include/cc430-adc.h +++ b/cpu/cc430/include/cc430-adc.h @@ -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. * * ************************************************************************************************/ diff --git a/cpu/cc430/include/cc430-rtc.h b/cpu/cc430/include/cc430-rtc.h index 4d9b7b57761f..2988546ec3ba 100644 --- a/cpu/cc430/include/cc430-rtc.h +++ b/cpu/cc430/include/cc430-rtc.h @@ -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. * diff --git a/cpu/lpc1768/atom.c b/cpu/lpc1768/atom.c index e23b5f423087..b451c16ac00e 100644 --- a/cpu/lpc1768/atom.c +++ b/cpu/lpc1768/atom.c @@ -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; } diff --git a/cpu/lpc1768/include/LPC17xx.h b/cpu/lpc1768/include/LPC17xx.h index b8de826da13d..7e0c37cbdcbb 100644 --- a/cpu/lpc1768/include/LPC17xx.h +++ b/cpu/lpc1768/include/LPC17xx.h @@ -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; diff --git a/cpu/lpc1768/include/cpu-conf.h b/cpu/lpc1768/include/cpu-conf.h index e6d046aa1eb3..115727ed74dd 100644 --- a/cpu/lpc1768/include/cpu-conf.h +++ b/cpu/lpc1768/include/cpu-conf.h @@ -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) /** @} */ diff --git a/cpu/lpc1768/include/hwtimer_cpu.h b/cpu/lpc1768/include/hwtimer_cpu.h index fed2d2200956..d91982eb49be 100644 --- a/cpu/lpc1768/include/hwtimer_cpu.h +++ b/cpu/lpc1768/include/hwtimer_cpu.h @@ -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_ */ diff --git a/cpu/lpc1768/lpc1768-lpm.c b/cpu/lpc1768/lpc1768-lpm.c index c4541a8e0ebe..f3a4df3329fb 100644 --- a/cpu/lpc1768/lpc1768-lpm.c +++ b/cpu/lpc1768/lpc1768-lpm.c @@ -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; } diff --git a/cpu/lpc1768/syscalls.c b/cpu/lpc1768/syscalls.c index 261019c94389..226bee8acbb9 100644 --- a/cpu/lpc1768/syscalls.c +++ b/cpu/lpc1768/syscalls.c @@ -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 diff --git a/cpu/lpc2387/cpu.c b/cpu/lpc2387/cpu.c index c82358646877..a7732af2840f 100644 --- a/cpu/lpc2387/cpu.c +++ b/cpu/lpc2387/cpu.c @@ -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); } } diff --git a/cpu/lpc2387/include/cpu-conf.h b/cpu/lpc2387/include/cpu-conf.h index ad88f842f031..aaecbbca4159 100644 --- a/cpu/lpc2387/include/cpu-conf.h +++ b/cpu/lpc2387/include/cpu-conf.h @@ -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) diff --git a/cpu/lpc2387/include/lpc2387-adc.h b/cpu/lpc2387/include/lpc2387-adc.h index 2b52c701be8b..686ae8441840 100644 --- a/cpu/lpc2387/include/lpc2387-adc.h +++ b/cpu/lpc2387/include/lpc2387-adc.h @@ -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 + * @author Thomas Hillebrandt * @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 -#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); diff --git a/cpu/lpc2387/include/lpc2387-rtc.h b/cpu/lpc2387/include/lpc2387-rtc.h index 384fbf11afa9..6f64e88c9d34 100644 --- a/cpu/lpc2387/include/lpc2387-rtc.h +++ b/cpu/lpc2387/include/lpc2387-rtc.h @@ -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 @@ -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 diff --git a/cpu/lpc2387/include/lpc2387.h b/cpu/lpc2387/include/lpc2387.h index 66a03d983c4e..5c362a92a974 100644 --- a/cpu/lpc2387/include/lpc2387.h +++ b/cpu/lpc2387/include/lpc2387.h @@ -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 +#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) /** @} */ /** - * @name INTWAKE Constants + * @name INTWAKE Constants * @{ */ -#define EXTWAKE0 BIT0 -#define EXTWAKE1 BIT1 -#define EXTWAKE2 BIT2 -#define EXTWAKE3 BIT3 -#define ETHWAKE BIT4 -#define USBWAKE BIT5 -#define CANWAKE BIT6 -#define GPIO0WAKE BIT7 -#define GPIO2WAKE BIT8 -#define BODWAKE BIT14 -#define RTCWAKE BIT15 +#define EXTWAKE0 BIT0 +#define EXTWAKE1 BIT1 +#define EXTWAKE2 BIT2 +#define EXTWAKE3 BIT3 +#define ETHWAKE BIT4 +#define USBWAKE BIT5 +#define CANWAKE BIT6 +#define GPIO0WAKE BIT7 +#define GPIO2WAKE BIT8 +#define BODWAKE BIT14 +#define RTCWAKE BIT15 /** @} */ /** * @name UART Constants * @{ */ -#define ULSR_RDR BIT0 -#define ULSR_OE BIT1 -#define ULSR_PE BIT2 -#define ULSR_FE BIT3 -#define ULSR_BI BIT4 -#define ULSR_THRE BIT5 -#define ULSR_TEMT BIT6 -#define ULSR_RXFE BIT7 - -#define UIIR_INT_STATUS (BIT0) ///< Interrupt Status -#define UIIR_THRE_INT (BIT1) ///< Transmit Holding Register Empty -#define UIIR_RDA_INT (BIT2) ///< Receive Data Available -#define UIIR_RLS_INT (BIT1 | BIT2) ///< Receive Line Status -#define UIIR_CTI_INT (BIT2 | BIT3) ///< Character Timeout Indicator +#define ULSR_RDR BIT0 +#define ULSR_OE BIT1 +#define ULSR_PE BIT2 +#define ULSR_FE BIT3 +#define ULSR_BI BIT4 +#define ULSR_THRE BIT5 +#define ULSR_TEMT BIT6 +#define ULSR_RXFE BIT7 + +#define UIIR_INT_STATUS (BIT0) ///< Interrupt Status +#define UIIR_THRE_INT (BIT1) ///< Transmit Holding Register Empty +#define UIIR_RDA_INT (BIT2) ///< Receive Data Available +#define UIIR_RLS_INT (BIT1 | BIT2) ///< Receive Line Status +#define UIIR_CTI_INT (BIT2 | BIT3) ///< Character Timeout Indicator #define UIIR_ID_MASK (BIT1 | BIT2 | BIT3) -#define UIIR_ABEO_INT BIT8 -#define UIIR_ABTO_INT BIT9 +#define UIIR_ABEO_INT BIT8 +#define UIIR_ABTO_INT BIT9 /** @} */ /** - * @name SSP Status Register Constants + * @name SSP Status Register Constants * @{ */ -#define SSPSR_TFE BIT0 ///< Transmit FIFO Empty. This bit is 1 is the Transmit FIFO is empty, 0 if not. -#define SSPSR_TNF BIT1 ///< Transmit FIFO Not Full. This bit is 0 if the Tx FIFO is full, 1 if not. -#define SSPSR_RNE BIT2 ///< Receive FIFO Not Empty. This bit is 0 if the Receive FIFO is empty, 1 if not. -#define SSPSR_RFF BIT3 ///< Receive FIFO Full. This bit is 1 if the Receive FIFO is full, 0 if not. -#define SSPSR_BSY BIT4 ///< Busy. This bit is 0 if the SSPn controller is idle, or 1 if it is currently sending/receiving a frame and/or the Tx FIFO is not empty. +#define SSPSR_TFE BIT0 ///< Transmit FIFO Empty. This bit is 1 is the Transmit FIFO is empty, 0 if not. +#define SSPSR_TNF BIT1 ///< Transmit FIFO Not Full. This bit is 0 if the Tx FIFO is full, 1 if not. +#define SSPSR_RNE BIT2 ///< Receive FIFO Not Empty. This bit is 0 if the Receive FIFO is empty, 1 if not. +#define SSPSR_RFF BIT3 ///< Receive FIFO Full. This bit is 1 if the Receive FIFO is full, 0 if not. +#define SSPSR_BSY BIT4 ///< Busy. This bit is 0 if the SSPn controller is idle, or 1 if it is currently sending/receiving a frame and/or the Tx FIFO is not empty. /** @} */ /** @@ -188,7 +188,7 @@ */ #define TXIR 0x00 #define TXTCR 0x04 -#define TXTC 0x08 ///< Timer counter +#define TXTC 0x08 ///< Timer counter #define TXPR 0x0C #define TXPC 0x10 #define TXMCR 0x14 diff --git a/cpu/lpc2387/include/lpc23xx.h b/cpu/lpc2387/include/lpc23xx.h index 0358c26d269c..b1d1c019e5d3 100644 --- a/cpu/lpc2387/include/lpc23xx.h +++ b/cpu/lpc2387/include/lpc23xx.h @@ -16,7 +16,7 @@ #define __LPC23xx_H /* Vectored Interrupt Controller (VIC) */ -#define VIC_BASE_ADDR 0xFFFFF000 +#define VIC_BASE_ADDR 0xFFFFF000 #define VICIRQStatus (*(volatile unsigned long *)(VIC_BASE_ADDR + 0x000)) #define VICFIQStatus (*(volatile unsigned long *)(VIC_BASE_ADDR + 0x004)) #define VICRawIntr (*(volatile unsigned long *)(VIC_BASE_ADDR + 0x008)) @@ -100,7 +100,7 @@ these registers are known as "VICVectPriority(x)". */ /* Pin Connect Block */ -#define PINSEL_BASE_ADDR 0xE002C000 +#define PINSEL_BASE_ADDR 0xE002C000 #define PINSEL0 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x00)) #define PINSEL1 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x04)) #define PINSEL2 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x08)) @@ -125,7 +125,7 @@ these registers are known as "VICVectPriority(x)". */ #define PINMODE9 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x64)) /* General Purpose Input/Output (GPIO) */ -#define GPIO_BASE_ADDR 0xE0028000 +#define GPIO_BASE_ADDR 0xE0028000 #define IOPIN0 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x00)) #define IOSET0 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x04)) #define IODIR0 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x08)) @@ -150,11 +150,11 @@ these registers are known as "VICVectPriority(x)". */ #define IO_INT_STAT (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x80)) -#define PARTCFG_BASE_ADDR 0x3FFF8000 +#define PARTCFG_BASE_ADDR 0x3FFF8000 #define PARTCFG (*(volatile unsigned long *)(PARTCFG_BASE_ADDR + 0x00)) /* Fast I/O setup */ -#define FIO_BASE_ADDR 0x3FFFC000 +#define FIO_BASE_ADDR 0x3FFFC000 #define FIO0DIR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x00)) #define FIO0MASK (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x10)) #define FIO0PIN (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x14)) @@ -370,7 +370,7 @@ these registers are known as "VICVectPriority(x)". */ /* System Control Block(SCB) modules include Memory Accelerator Module, Phase Locked Loop, VPB divider, Power Control, External Interrupt, Reset, and Code Security/Debugging */ -#define SCB_BASE_ADDR 0xE01FC000 +#define SCB_BASE_ADDR 0xE01FC000 /* Memory Accelerator Module (MAM) */ #define MAMCR (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x000)) @@ -416,18 +416,18 @@ Reset, and Code Security/Debugging */ /* MPMC(EMC) registers, note: all the external memory controller(EMC) registers are for LPC24xx only. */ -#define STATIC_MEM0_BASE 0x80000000 -#define STATIC_MEM1_BASE 0x81000000 -#define STATIC_MEM2_BASE 0x82000000 -#define STATIC_MEM3_BASE 0x83000000 +#define STATIC_MEM0_BASE 0x80000000 +#define STATIC_MEM1_BASE 0x81000000 +#define STATIC_MEM2_BASE 0x82000000 +#define STATIC_MEM3_BASE 0x83000000 -#define DYNAMIC_MEM0_BASE 0xA0000000 -#define DYNAMIC_MEM1_BASE 0xB0000000 -#define DYNAMIC_MEM2_BASE 0xC0000000 -#define DYNAMIC_MEM3_BASE 0xD0000000 +#define DYNAMIC_MEM0_BASE 0xA0000000 +#define DYNAMIC_MEM1_BASE 0xB0000000 +#define DYNAMIC_MEM2_BASE 0xC0000000 +#define DYNAMIC_MEM3_BASE 0xD0000000 /* External Memory Controller (EMC) */ -#define EMC_BASE_ADDR 0xFFE08000 +#define EMC_BASE_ADDR 0xFFE08000 #define EMC_CTRL (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x000)) #define EMC_STAT (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x004)) #define EMC_CONFIG (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x008)) @@ -493,7 +493,7 @@ are for LPC24xx only. */ #define EMC_STA_EXT_WAIT (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x880)) /* Timer 0 */ -#define TMR0_BASE_ADDR 0xE0004000 +#define TMR0_BASE_ADDR 0xE0004000 #define T0IR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x00)) #define T0TCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x04)) #define T0TC (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x08)) @@ -513,7 +513,7 @@ are for LPC24xx only. */ #define T0CTCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x70)) /* Timer 1 */ -#define TMR1_BASE_ADDR 0xE0008000 +#define TMR1_BASE_ADDR 0xE0008000 #define T1IR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x00)) #define T1TCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x04)) #define T1TC (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x08)) @@ -533,7 +533,7 @@ are for LPC24xx only. */ #define T1CTCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x70)) /* Timer 2 */ -#define TMR2_BASE_ADDR 0xE0070000 +#define TMR2_BASE_ADDR 0xE0070000 #define T2IR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x00)) #define T2TCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x04)) #define T2TC (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x08)) @@ -553,7 +553,7 @@ are for LPC24xx only. */ #define T2CTCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x70)) /* Timer 3 */ -#define TMR3_BASE_ADDR 0xE0074000 +#define TMR3_BASE_ADDR 0xE0074000 #define T3IR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x00)) #define T3TCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x04)) #define T3TC (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x08)) @@ -574,7 +574,7 @@ are for LPC24xx only. */ /* Pulse Width Modulator (PWM) */ -#define PWM0_BASE_ADDR 0xE0014000 +#define PWM0_BASE_ADDR 0xE0014000 #define PWM0IR (*(volatile unsigned long *)(PWM0_BASE_ADDR + 0x00)) #define PWM0TCR (*(volatile unsigned long *)(PWM0_BASE_ADDR + 0x04)) #define PWM0TC (*(volatile unsigned long *)(PWM0_BASE_ADDR + 0x08)) @@ -598,7 +598,7 @@ are for LPC24xx only. */ #define PWM0LER (*(volatile unsigned long *)(PWM0_BASE_ADDR + 0x50)) #define PWM0CTCR (*(volatile unsigned long *)(PWM0_BASE_ADDR + 0x70)) -#define PWM1_BASE_ADDR 0xE0018000 +#define PWM1_BASE_ADDR 0xE0018000 #define PWM1IR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x00)) #define PWM1TCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x04)) #define PWM1TC (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x08)) @@ -624,7 +624,7 @@ are for LPC24xx only. */ /* Universal Asynchronous Receiver Transmitter 0 (UART0) */ -#define UART0_BASE_ADDR 0xE000C000 +#define UART0_BASE_ADDR 0xE000C000 #define U0RBR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x00)) #define U0THR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x00)) #define U0DLL (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x00)) @@ -641,7 +641,7 @@ are for LPC24xx only. */ #define U0TER (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x30)) /* Universal Asynchronous Receiver Transmitter 1 (UART1) */ -#define UART1_BASE_ADDR 0xE0010000 +#define UART1_BASE_ADDR 0xE0010000 #define U1RBR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x00)) #define U1THR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x00)) #define U1DLL (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x00)) @@ -659,7 +659,7 @@ are for LPC24xx only. */ #define U1TER (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x30)) /* Universal Asynchronous Receiver Transmitter 2 (UART2) */ -#define UART2_BASE_ADDR 0xE0078000 +#define UART2_BASE_ADDR 0xE0078000 #define U2RBR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x00)) #define U2THR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x00)) #define U2DLL (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x00)) @@ -676,7 +676,7 @@ are for LPC24xx only. */ #define U2TER (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x30)) /* Universal Asynchronous Receiver Transmitter 3 (UART3) */ -#define UART3_BASE_ADDR 0xE007C000 +#define UART3_BASE_ADDR 0xE007C000 #define U3RBR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x00)) #define U3THR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x00)) #define U3DLL (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x00)) @@ -693,7 +693,7 @@ are for LPC24xx only. */ #define U3TER (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x30)) /* I2C Interface 0 */ -#define I2C0_BASE_ADDR 0xE001C000 +#define I2C0_BASE_ADDR 0xE001C000 #define I20CONSET (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x00)) #define I20STAT (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x04)) #define I20DAT (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x08)) @@ -703,7 +703,7 @@ are for LPC24xx only. */ #define I20CONCLR (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x18)) /* I2C Interface 1 */ -#define I2C1_BASE_ADDR 0xE005C000 +#define I2C1_BASE_ADDR 0xE005C000 #define I21CONSET (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x00)) #define I21STAT (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x04)) #define I21DAT (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x08)) @@ -713,7 +713,7 @@ are for LPC24xx only. */ #define I21CONCLR (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x18)) /* I2C Interface 2 */ -#define I2C2_BASE_ADDR 0xE0080000 +#define I2C2_BASE_ADDR 0xE0080000 #define I22CONSET (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x00)) #define I22STAT (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x04)) #define I22DAT (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x08)) @@ -723,7 +723,7 @@ are for LPC24xx only. */ #define I22CONCLR (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x18)) /* SPI0 (Serial Peripheral Interface 0) */ -#define SPI0_BASE_ADDR 0xE0020000 +#define SPI0_BASE_ADDR 0xE0020000 #define S0SPCR (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x00)) #define S0SPSR (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x04)) #define S0SPDR (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x08)) @@ -731,7 +731,7 @@ are for LPC24xx only. */ #define S0SPINT (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x1C)) /* SSP0 Controller */ -#define SSP0_BASE_ADDR 0xE0068000 +#define SSP0_BASE_ADDR 0xE0068000 #define SSP0CR0 (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x00)) #define SSP0CR1 (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x04)) #define SSP0DR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x08)) @@ -744,7 +744,7 @@ are for LPC24xx only. */ #define SSP0DMACR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x24)) /* SSP1 Controller */ -#define SSP1_BASE_ADDR 0xE0030000 +#define SSP1_BASE_ADDR 0xE0030000 #define SSP1CR0 (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x00)) #define SSP1CR1 (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x04)) #define SSP1DR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x08)) @@ -758,7 +758,7 @@ are for LPC24xx only. */ /* Real Time Clock */ -#define RTC_BASE_ADDR 0xE0024000 +#define RTC_BASE_ADDR 0xE0024000 #define RTC_ILR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x00)) #define RTC_CTC (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x04)) #define RTC_CCR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x08)) @@ -789,7 +789,7 @@ are for LPC24xx only. */ /* A/D Converter 0 (AD0) */ -#define AD0_BASE_ADDR 0xE0034000 +#define AD0_BASE_ADDR 0xE0034000 #define AD0CR (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x00)) #define AD0GDR (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x04)) #define AD0INTEN (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x0C)) @@ -805,12 +805,12 @@ are for LPC24xx only. */ /* D/A Converter */ -#define DAC_BASE_ADDR 0xE006C000 +#define DAC_BASE_ADDR 0xE006C000 #define DACR (*(volatile unsigned long *)(DAC_BASE_ADDR + 0x00)) /* Watchdog */ -#define WDG_BASE_ADDR 0xE0000000 +#define WDG_BASE_ADDR 0xE0000000 #define WDMOD (*(volatile unsigned long *)(WDG_BASE_ADDR + 0x00)) #define WDTC (*(volatile unsigned long *)(WDG_BASE_ADDR + 0x04)) #define WDFEED (*(volatile unsigned long *)(WDG_BASE_ADDR + 0x08)) @@ -818,78 +818,78 @@ are for LPC24xx only. */ #define WDCLKSEL (*(volatile unsigned long *)(WDG_BASE_ADDR + 0x10)) /* CAN CONTROLLERS AND ACCEPTANCE FILTER */ -#define CAN_ACCEPT_BASE_ADDR 0xE003C000 -#define CAN_AFMR (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x00)) -#define CAN_SFF_SA (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x04)) -#define CAN_SFF_GRP_SA (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x08)) -#define CAN_EFF_SA (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x0C)) -#define CAN_EFF_GRP_SA (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x10)) -#define CAN_EOT (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x14)) +#define CAN_ACCEPT_BASE_ADDR 0xE003C000 +#define CAN_AFMR (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x00)) +#define CAN_SFF_SA (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x04)) +#define CAN_SFF_GRP_SA (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x08)) +#define CAN_EFF_SA (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x0C)) +#define CAN_EFF_GRP_SA (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x10)) +#define CAN_EOT (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x14)) #define CAN_LUT_ERR_ADR (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x18)) -#define CAN_LUT_ERR (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x1C)) - -#define CAN_CENTRAL_BASE_ADDR 0xE0040000 -#define CAN_TX_SR (*(volatile unsigned long *)(CAN_CENTRAL_BASE_ADDR + 0x00)) -#define CAN_RX_SR (*(volatile unsigned long *)(CAN_CENTRAL_BASE_ADDR + 0x04)) -#define CAN_MSR (*(volatile unsigned long *)(CAN_CENTRAL_BASE_ADDR + 0x08)) - -#define CAN1_BASE_ADDR 0xE0044000 -#define CAN1MOD (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x00)) -#define CAN1CMR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x04)) -#define CAN1GSR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x08)) -#define CAN1ICR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x0C)) -#define CAN1IER (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x10)) -#define CAN1BTR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x14)) -#define CAN1EWL (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x18)) -#define CAN1SR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x1C)) -#define CAN1RFS (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x20)) -#define CAN1RID (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x24)) -#define CAN1RDA (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x28)) -#define CAN1RDB (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x2C)) - -#define CAN1TFI1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x30)) -#define CAN1TID1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x34)) -#define CAN1TDA1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x38)) -#define CAN1TDB1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x3C)) -#define CAN1TFI2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x40)) -#define CAN1TID2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x44)) -#define CAN1TDA2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x48)) -#define CAN1TDB2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x4C)) -#define CAN1TFI3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x50)) -#define CAN1TID3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x54)) -#define CAN1TDA3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x58)) -#define CAN1TDB3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x5C)) - -#define CAN2_BASE_ADDR 0xE0048000 -#define CAN2MOD (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x00)) -#define CAN2CMR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x04)) -#define CAN2GSR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x08)) -#define CAN2ICR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x0C)) -#define CAN2IER (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x10)) -#define CAN2BTR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x14)) -#define CAN2EWL (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x18)) -#define CAN2SR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x1C)) -#define CAN2RFS (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x20)) -#define CAN2RID (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x24)) -#define CAN2RDA (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x28)) -#define CAN2RDB (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x2C)) - -#define CAN2TFI1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x30)) -#define CAN2TID1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x34)) -#define CAN2TDA1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x38)) -#define CAN2TDB1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x3C)) -#define CAN2TFI2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x40)) -#define CAN2TID2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x44)) -#define CAN2TDA2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x48)) -#define CAN2TDB2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x4C)) -#define CAN2TFI3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x50)) -#define CAN2TID3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x54)) -#define CAN2TDA3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x58)) -#define CAN2TDB3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x5C)) +#define CAN_LUT_ERR (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x1C)) + +#define CAN_CENTRAL_BASE_ADDR 0xE0040000 +#define CAN_TX_SR (*(volatile unsigned long *)(CAN_CENTRAL_BASE_ADDR + 0x00)) +#define CAN_RX_SR (*(volatile unsigned long *)(CAN_CENTRAL_BASE_ADDR + 0x04)) +#define CAN_MSR (*(volatile unsigned long *)(CAN_CENTRAL_BASE_ADDR + 0x08)) + +#define CAN1_BASE_ADDR 0xE0044000 +#define CAN1MOD (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x00)) +#define CAN1CMR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x04)) +#define CAN1GSR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x08)) +#define CAN1ICR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x0C)) +#define CAN1IER (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x10)) +#define CAN1BTR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x14)) +#define CAN1EWL (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x18)) +#define CAN1SR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x1C)) +#define CAN1RFS (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x20)) +#define CAN1RID (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x24)) +#define CAN1RDA (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x28)) +#define CAN1RDB (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x2C)) + +#define CAN1TFI1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x30)) +#define CAN1TID1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x34)) +#define CAN1TDA1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x38)) +#define CAN1TDB1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x3C)) +#define CAN1TFI2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x40)) +#define CAN1TID2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x44)) +#define CAN1TDA2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x48)) +#define CAN1TDB2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x4C)) +#define CAN1TFI3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x50)) +#define CAN1TID3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x54)) +#define CAN1TDA3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x58)) +#define CAN1TDB3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x5C)) + +#define CAN2_BASE_ADDR 0xE0048000 +#define CAN2MOD (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x00)) +#define CAN2CMR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x04)) +#define CAN2GSR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x08)) +#define CAN2ICR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x0C)) +#define CAN2IER (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x10)) +#define CAN2BTR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x14)) +#define CAN2EWL (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x18)) +#define CAN2SR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x1C)) +#define CAN2RFS (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x20)) +#define CAN2RID (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x24)) +#define CAN2RDA (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x28)) +#define CAN2RDB (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x2C)) + +#define CAN2TFI1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x30)) +#define CAN2TID1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x34)) +#define CAN2TDA1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x38)) +#define CAN2TDB1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x3C)) +#define CAN2TFI2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x40)) +#define CAN2TID2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x44)) +#define CAN2TDA2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x48)) +#define CAN2TDB2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x4C)) +#define CAN2TFI3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x50)) +#define CAN2TID3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x54)) +#define CAN2TDA3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x58)) +#define CAN2TDB3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x5C)) /* MultiMedia Card Interface(MCI) Controller */ -#define MCI_BASE_ADDR 0xE008C000 +#define MCI_BASE_ADDR 0xE008C000 #define MCI_POWER (*(volatile unsigned long *)(MCI_BASE_ADDR + 0x00)) #define MCI_CLOCK (*(volatile unsigned long *)(MCI_BASE_ADDR + 0x04)) #define MCI_ARGUMENT (*(volatile unsigned long *)(MCI_BASE_ADDR + 0x08)) @@ -912,7 +912,7 @@ are for LPC24xx only. */ /* I2S Interface Controller (I2S) */ -#define I2S_BASE_ADDR 0xE0088000 +#define I2S_BASE_ADDR 0xE0088000 #define I2S_DAO (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x00)) #define I2S_DAI (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x04)) #define I2S_TX_FIFO (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x08)) @@ -926,7 +926,7 @@ are for LPC24xx only. */ /* General-purpose DMA Controller */ -#define DMA_BASE_ADDR 0xFFE04000 +#define DMA_BASE_ADDR 0xFFE04000 #define GPDMA_INT_STAT (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x000)) #define GPDMA_INT_TCSTAT (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x004)) #define GPDMA_INT_TCCLR (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x008)) @@ -958,8 +958,8 @@ are for LPC24xx only. */ /* USB Controller */ -#define USB_INT_BASE_ADDR 0xE01FC1C0 -#define USB_BASE_ADDR 0xFFE0C200 /* USB Base Address */ +#define USB_INT_BASE_ADDR 0xE01FC1C0 +#define USB_BASE_ADDR 0xFFE0C200 /* USB Base Address */ #define USB_INT_STAT (*(volatile unsigned long *)(USB_INT_BASE_ADDR + 0x00)) @@ -1015,7 +1015,7 @@ are for LPC24xx only. */ /* USB Host and OTG registers are for LPC24xx only */ /* USB Host Controller */ -#define USBHC_BASE_ADDR 0xFFE0C000 +#define USBHC_BASE_ADDR 0xFFE0C000 #define HC_REVISION (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x00)) #define HC_CONTROL (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x04)) #define HC_CMD_STAT (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x08)) @@ -1041,7 +1041,7 @@ are for LPC24xx only. */ #define HC_RH_PORT_STAT2 (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x58)) /* USB OTG Controller */ -#define USBOTG_BASE_ADDR 0xFFE0C100 +#define USBOTG_BASE_ADDR 0xFFE0C100 #define OTG_INT_STAT (*(volatile unsigned long *)(USBOTG_BASE_ADDR + 0x00)) #define OTG_INT_EN (*(volatile unsigned long *)(USBOTG_BASE_ADDR + 0x04)) #define OTG_INT_SET (*(volatile unsigned long *)(USBOTG_BASE_ADDR + 0x08)) @@ -1050,7 +1050,7 @@ are for LPC24xx only. */ #define OTG_STAT_CTRL (*(volatile unsigned long *)(USBOTG_BASE_ADDR + 0x10)) #define OTG_TIMER (*(volatile unsigned long *)(USBOTG_BASE_ADDR + 0x14)) -#define USBOTG_I2C_BASE_ADDR 0xFFE0C300 +#define USBOTG_I2C_BASE_ADDR 0xFFE0C300 #define OTG_I2C_RX (*(volatile unsigned long *)(USBOTG_I2C_BASE_ADDR + 0x00)) #define OTG_I2C_TX (*(volatile unsigned long *)(USBOTG_I2C_BASE_ADDR + 0x00)) #define OTG_I2C_STS (*(volatile unsigned long *)(USBOTG_I2C_BASE_ADDR + 0x04)) @@ -1060,7 +1060,7 @@ are for LPC24xx only. */ /* On LPC23xx, the names are USBClkCtrl and USBClkSt; on LPC24xx, the names are OTG_CLK_CTRL and OTG_CLK_STAT respectively. */ -#define USBOTG_CLK_BASE_ADDR 0xFFE0CFF0 +#define USBOTG_CLK_BASE_ADDR 0xFFE0CFF0 #define OTG_CLK_CTRL (*(volatile unsigned long *)(USBOTG_CLK_BASE_ADDR + 0x04)) #define OTG_CLK_STAT (*(volatile unsigned long *)(USBOTG_CLK_BASE_ADDR + 0x08)) @@ -1071,7 +1071,7 @@ with the spec. update in USB Device Section. */ #define USBClkSt (*(volatile unsigned long *)(USBOTG_CLK_BASE_ADDR + 0x08)) /* Ethernet MAC (32 bit data bus) -- all registers are RW unless indicated in parentheses */ -#define MAC_BASE_ADDR 0xFFE00000 /* AHB Peripheral # 0 */ +#define MAC_BASE_ADDR 0xFFE00000 /* AHB Peripheral # 0 */ #define MAC_MAC1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x000)) /* MAC config reg 1 */ #define MAC_MAC2 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x004)) /* MAC config reg 2 */ #define MAC_IPGT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x008)) /* b2b InterPacketGap reg */ diff --git a/cpu/lpc2387/lpc2387-adc.c b/cpu/lpc2387/lpc2387-adc.c index 5fc37953a51b..60589ea7ad62 100644 --- a/cpu/lpc2387/lpc2387-adc.c +++ b/cpu/lpc2387/lpc2387-adc.c @@ -12,13 +12,13 @@ See the file LICENSE in the top level directory for more details. /** * @file - * @ingroup lpc2387_adc - * @brief LPC2387 ADC + * @ingroup lpc2387_adc + * @brief LPC2387 ADC * - * @author Thomas Hillebrandt + * @author Thomas Hillebrandt * @version $Revision: 3250 $ * - * @note $Id: lpc2387-adc.c 3250 2011-03-11 09:45:44Z schmittb $ + * @note $Id: lpc2387-adc.c 3250 2011-03-11 09:45:44Z schmittb $ */ // cpu @@ -40,17 +40,17 @@ adc_init(void) PCONP |= BIT12; // peripheral Clock Selection for ADC - PCLKSEL0 |= 0x03000000; // pclock = cclock/8 + PCLKSEL0 |= 0x03000000; // pclock = cclock/8 // set A/D control register AD0CR - AD0CR = (0x01 << 0) | /* SEL=1, select channel 0~7 on ADC0 */ - (0xff << 8) | /* CLKDIV = 1, ADC_CLK = PCLK/10 = 0.45 MHz */ - (0 << 16) | /* BURST = 0, no BURST, software controlled */ - (0 << 17) | /* CLKS = 0, 11 clocks/10 bits */ - (1 << 21) | /* PDN = 1, normal operation */ - (0 << 22) | /* TEST1:0 = 00 */ - (0 << 24) | /* START = 0 A/D conversion stops */ - (0 << 27); /* EDGE = 0 (CAP/MAT signal falling,trigger A/D conversion) */ + AD0CR = (0x01 << 0) | /* SEL=1, select channel 0~7 on ADC0 */ + (0xff << 8) | /* CLKDIV = 1, ADC_CLK = PCLK/10 = 0.45 MHz */ + (0 << 16) | /* BURST = 0, no BURST, software controlled */ + (0 << 17) | /* CLKS = 0, 11 clocks/10 bits */ + (1 << 21) | /* PDN = 1, normal operation */ + (0 << 22) | /* TEST1:0 = 00 */ + (0 << 24) | /* START = 0 A/D conversion stops */ + (0 << 27); /* EDGE = 0 (CAP/MAT signal falling,trigger A/D conversion) */ } /*---------------------------------------------------------------------------*/ void @@ -63,17 +63,17 @@ adc_init_1(void) PINSEL1 |= BIT16; // peripheral Clock Selection for ADC - PCLKSEL0 |= 0x03000000; // pclock = cclock/8 + PCLKSEL0 |= 0x03000000; // pclock = cclock/8 // set A/D control register AD0CR - AD0CR = (0x01 << 0) | /* SEL=1, select channel 0~7 on ADC0 */ - (0x00 << 8) | /* CLKDIV = 1, ADC_CLK = PCLK/1 = 4.5 MHz */ - (0 << 16) | /* BURST = 0, no BURST, software controlled */ - (0 << 17) | /* CLKS = 0, 11 clocks/10 bits */ - (1 << 21) | /* PDN = 1, normal operation */ - (0 << 22) | /* TEST1:0 = 00 */ - (0 << 24) | /* START = 0 A/D conversion stops */ - (0 << 27); /* EDGE = 0 (CAP/MAT signal falling,trigger A/D conversion) */ + AD0CR = (0x01 << 0) | /* SEL=1, select channel 0~7 on ADC0 */ + (0x00 << 8) | /* CLKDIV = 1, ADC_CLK = PCLK/1 = 4.5 MHz */ + (0 << 16) | /* BURST = 0, no BURST, software controlled */ + (0 << 17) | /* CLKS = 0, 11 clocks/10 bits */ + (1 << 21) | /* PDN = 1, normal operation */ + (0 << 22) | /* TEST1:0 = 00 */ + (0 << 24) | /* START = 0 A/D conversion stops */ + (0 << 27); /* EDGE = 0 (CAP/MAT signal falling,trigger A/D conversion) */ } /*---------------------------------------------------------------------------*/ void adc_init_2(void) @@ -85,17 +85,17 @@ void adc_init_2(void) PINSEL1 |= BIT14; // peripheral Clock Selection for ADC - PCLKSEL0 |= 0x03000000; // pclock = cclock/8 + PCLKSEL0 |= 0x03000000; // pclock = cclock/8 // set A/D control register AD0CR - AD0CR = (0x01 << 0) | /* SEL=1, select channel 0 on ADC0 */ - (0x00 << 8) | /* CLKDIV = 1, ADC_CLK = PCLK/1 = 4.5 MHz */ - (0 << 16) | /* BURST = 0, no BURST */ - (0 << 17) | /* CLKS = 0, 11 clocks/10 bits */ - (1 << 21) | /* PDN = 1, normal operation */ - (0 << 22) | /* TEST1:0 = 00 */ - (0 << 24) | /* START = 0 A/D conversion stops */ - (0 << 27); /* EDGE = 0 (CAP/MAT signal falling,trigger A/D conversion) */ + AD0CR = (0x01 << 0) | /* SEL=1, select channel 0 on ADC0 */ + (0x00 << 8) | /* CLKDIV = 1, ADC_CLK = PCLK/1 = 4.5 MHz */ + (0 << 16) | /* BURST = 0, no BURST */ + (0 << 17) | /* CLKS = 0, 11 clocks/10 bits */ + (1 << 21) | /* PDN = 1, normal operation */ + (0 << 22) | /* TEST1:0 = 00 */ + (0 << 24) | /* START = 0 A/D conversion stops */ + (0 << 27); /* EDGE = 0 (CAP/MAT signal falling,trigger A/D conversion) */ } /*---------------------------------------------------------------------------*/ uint16_t adc_read(uint8_t channel) @@ -107,7 +107,7 @@ uint16_t adc_read(uint8_t channel) /* channel number is 0 through 7 */ if (channel >= ADC_NUM) { - channel = 0; /* reset channel number to 0 */ + channel = 0; /* reset channel number to 0 */ } /* switch channel, start A/D convert */ @@ -131,14 +131,14 @@ uint16_t adc_read(uint8_t channel) } } - AD0CR &= 0xF8FFFFFF; /* stop ADC now */ + AD0CR &= 0xF8FFFFFF; /* stop ADC now */ - if (regVal & ADC_OVERRUN) { /* save data when it's not overrun, otherwise, return zero */ + if (regVal & ADC_OVERRUN) { /* save data when it's not overrun, otherwise, return zero */ return 0; } adc_data = (regVal >> 6) & 0x3FF; DEBUG("%s, %d: %lu\n", __FILE__, __LINE__, t1); DEBUG("%s, %d: %lu\n", __FILE__, __LINE__, t2); - return (uint16_t) adc_data; /* return A/D conversion value */ + return (uint16_t) adc_data; /* return A/D conversion value */ } diff --git a/cpu/lpc2387/lpc2387-lpm.c b/cpu/lpc2387/lpc2387-lpm.c index e9a05c595cd4..145552295b82 100644 --- a/cpu/lpc2387/lpc2387-lpm.c +++ b/cpu/lpc2387/lpc2387-lpm.c @@ -18,13 +18,13 @@ See the file LICENSE in the top level directory for more details. /** * @file - * @brief LPC2387 Low-Power management - * @ingroup lpc2387 + * @brief LPC2387 Low-Power management + * @ingroup lpc2387 * - * @author Heiko Will + * @author Heiko Will * @version $Revision$ * - * @note $Id$ + * @note $Id$ */ #include @@ -52,14 +52,14 @@ void lpm_init(void) void lpm_begin_awake(void) { - if (lpm >= LPM_SLEEP) { // wake up from deep sleep + if (lpm >= LPM_SLEEP) { // wake up from deep sleep init_clks1(); } } void lpm_end_awake(void) { - if (lpm >= LPM_SLEEP) { // wake up from deep sleep + if (lpm >= LPM_SLEEP) { // wake up from deep sleep init_clks2(); } @@ -72,7 +72,7 @@ void lpm_awake(void) unsigned long usec = RTC_CTC; #endif - if (lpm >= LPM_SLEEP) { // wake up from deep sleep + if (lpm >= LPM_SLEEP) { // wake up from deep sleep /* benchmark */ init_clks1(); init_clks2(); @@ -109,7 +109,7 @@ enum lpm_mode lpm_set(enum lpm_mode target) DEBUG("# LPM power down %u -> %u", lpm, target); - PCON |= target_flags; // set target power mode + PCON |= target_flags; // set target power mode return last_lpm; } /*---------------------------------------------------------------------------*/ diff --git a/cpu/lpc2387/mci/lpc2387-mci.c b/cpu/lpc2387/mci/lpc2387-mci.c index 952876e80c1f..cd96b21ddb6b 100644 --- a/cpu/lpc2387/mci/lpc2387-mci.c +++ b/cpu/lpc2387/mci/lpc2387-mci.c @@ -24,11 +24,11 @@ extern unsigned long hwtimer_now(void); /* --- MCI configurations --- */ -#define N_BUF 4 /* Block transfer FIFO depth (>= 2) */ -#define USE_4BIT 1 /* Use wide bus mode if SDC is detected */ -#define PCLK 36000000UL /* PCLK supplied to MCI module */ -#define MCLK_ID 400000UL /* MCICLK for ID state (100k-400k) */ -#define MCLK_RW 18000000UL /* MCICLK for data transfer (PCLK divided by even number) */ +#define N_BUF 4 /* Block transfer FIFO depth (>= 2) */ +#define USE_4BIT 1 /* Use wide bus mode if SDC is detected */ +#define PCLK 36000000UL /* PCLK supplied to MCI module */ +#define MCLK_ID 400000UL /* MCICLK for ID state (100k-400k) */ +#define MCLK_RW 18000000UL /* MCICLK for data transfer (PCLK divided by even number) */ /* This MCI driver assumes that MCLK_RW is CCLK/4 or slower. If block buffer underrun/overrun / occured due to any interrupt by higher priority process or slow external memory, increasing @@ -36,42 +36,42 @@ extern unsigned long hwtimer_now(void); /* ----- Port definitions ----- */ -#define SOCKINS !(FIO0PIN2 & 0x20) /* Card detect switch */ -#define SOCKWP (FIO0PIN2 & 0x04) /* Write protect switch */ +#define SOCKINS !(FIO0PIN2 & 0x20) /* Card detect switch */ +#define SOCKWP (FIO0PIN2 & 0x04) /* Write protect switch */ /* ----- MMC/SDC command ----- */ -#define CMD0 (0) /* GO_IDLE_STATE */ -#define CMD1 (1) /* SEND_OP_COND (MMC) */ -#define CMD2 (2) /* ALL_SEND_CID */ -#define CMD3 (3) /* SEND_RELATIVE_ADDR */ -#define ACMD6 (6|0x80) /* SET_BUS_WIDTH (SDC) */ -#define CMD7 (7) /* SELECT_CARD */ -#define CMD8 (8) /* SEND_IF_COND */ -#define CMD9 (9) /* SEND_CSD */ -#define CMD10 (10) /* SEND_CID */ -#define CMD12 (12) /* STOP_TRANSMISSION */ -#define CMD13 (13) /* SEND_STATUS */ -#define ACMD13 (13|0x80) /* SD_STATUS (SDC) */ -#define CMD16 (16) /* SET_BLOCKLEN */ -#define CMD17 (17) /* READ_SINGLE_BLOCK */ -#define CMD18 (18) /* READ_MULTIPLE_BLOCK */ -#define CMD23 (23) /* SET_BLK_COUNT (MMC) */ -#define ACMD23 (23|0x80) /* SET_WR_BLK_ERASE_COUNT (SDC) */ -#define CMD24 (24) /* WRITE_BLOCK */ -#define CMD25 (25) /* WRITE_MULTIPLE_BLOCK */ -#define CMD32 (32) /* ERASE_ER_BLK_START */ -#define CMD33 (33) /* ERASE_ER_BLK_END */ -#define CMD38 (38) /* ERASE */ -#define ACMD41 (41|0x80) /* SEND_OP_COND (SDC) */ -#define CMD55 (55) /* APP_CMD */ +#define CMD0 (0) /* GO_IDLE_STATE */ +#define CMD1 (1) /* SEND_OP_COND (MMC) */ +#define CMD2 (2) /* ALL_SEND_CID */ +#define CMD3 (3) /* SEND_RELATIVE_ADDR */ +#define ACMD6 (6|0x80) /* SET_BUS_WIDTH (SDC) */ +#define CMD7 (7) /* SELECT_CARD */ +#define CMD8 (8) /* SEND_IF_COND */ +#define CMD9 (9) /* SEND_CSD */ +#define CMD10 (10) /* SEND_CID */ +#define CMD12 (12) /* STOP_TRANSMISSION */ +#define CMD13 (13) /* SEND_STATUS */ +#define ACMD13 (13|0x80) /* SD_STATUS (SDC) */ +#define CMD16 (16) /* SET_BLOCKLEN */ +#define CMD17 (17) /* READ_SINGLE_BLOCK */ +#define CMD18 (18) /* READ_MULTIPLE_BLOCK */ +#define CMD23 (23) /* SET_BLK_COUNT (MMC) */ +#define ACMD23 (23|0x80) /* SET_WR_BLK_ERASE_COUNT (SDC) */ +#define CMD24 (24) /* WRITE_BLOCK */ +#define CMD25 (25) /* WRITE_MULTIPLE_BLOCK */ +#define CMD32 (32) /* ERASE_ER_BLK_START */ +#define CMD33 (33) /* ERASE_ER_BLK_END */ +#define CMD38 (38) /* ERASE */ +#define ACMD41 (41|0x80) /* SEND_OP_COND (SDC) */ +#define CMD55 (55) /* APP_CMD */ /* Card type flags (CardType) */ -#define CT_MMC 0x01 /* MMC ver 3 */ -#define CT_SD1 0x02 /* SD ver 1 */ -#define CT_SD2 0x04 /* SD ver 2 */ -#define CT_SDC (CT_SD1|CT_SD2) /* SD */ -#define CT_BLOCK 0x08 /* Block addressing */ +#define CT_MMC 0x01 /* MMC ver 3 */ +#define CT_SD1 0x02 /* SD ver 1 */ +#define CT_SD2 0x04 /* SD ver 2 */ +#define CT_SDC (CT_SD1|CT_SD2) /* SD */ +#define CT_BLOCK 0x08 /* Block addressing */ /*-------------------------------------------------------------------------- @@ -80,15 +80,15 @@ extern unsigned long hwtimer_now(void); ---------------------------------------------------------------------------*/ -static volatile DSTATUS Stat = STA_NOINIT; /* Disk status */ +static volatile DSTATUS Stat = STA_NOINIT; /* Disk status */ -static unsigned short CardRCA; /* Assigned RCA */ -static unsigned char CardType, /* Card type flag */ - CardInfo[16 + 16 + 4]; /* CSD(16), CID(16), OCR(4) */ +static unsigned short CardRCA; /* Assigned RCA */ +static unsigned char CardType, /* Card type flag */ + CardInfo[16 + 16 + 4]; /* CSD(16), CID(16), OCR(4) */ -static volatile unsigned char XferStat, /* b3:MCI error, b2:Overrun, b1:Write, b0:Read */ - XferWc, /* Write block counter */ - XferWp, XferRp; /* R/W index of block FIFO */ +static volatile unsigned char XferStat, /* b3:MCI error, b2:Overrun, b1:Write, b0:Read */ + XferWc, /* Write block counter */ + XferWp, XferRp; /* R/W index of block FIFO */ static unsigned long DmaBuff[N_BUF][128] __attribute__((section(".usbdata"))); /* Block transfer FIFO */ static unsigned long LinkList [N_BUF][4] __attribute__((section(".usbdata"))); /* DMA link list */ @@ -105,26 +105,26 @@ void Isr_MCI(void) unsigned long ms; unsigned char n, xs; - ms = MCI_STATUS & 0x073A; /* Clear MCI interrupt status */ + ms = MCI_STATUS & 0x073A; /* Clear MCI interrupt status */ MCI_CLEAR = ms; xs = XferStat; - if (ms & 0x400) { /* A block transfer completed (DataBlockEnd) */ - if (xs & 1) { /* In card read operation */ - if (ms & 0x100) { /* When last block is received (DataEnd), */ + if (ms & 0x400) { /* A block transfer completed (DataBlockEnd) */ + if (xs & 1) { /* In card read operation */ + if (ms & 0x100) { /* When last block is received (DataEnd), */ GPDMA_SOFT_BREQ = 0x10; /* Pop off remaining data in the MCIFIFO */ } - n = (XferWp + 1) % N_BUF; /* Next write buffer */ + n = (XferWp + 1) % N_BUF; /* Next write buffer */ XferWp = n; if (n == XferRp) { xs |= 4; /* Check block overrun */ } } - else { /* In card write operation */ - n = (XferRp + 1) % N_BUF; /* Next read buffer */ + else { /* In card write operation */ + n = (XferRp + 1) % N_BUF; /* Next read buffer */ XferRp = n; if (n == XferWp) { @@ -132,7 +132,7 @@ void Isr_MCI(void) } } } - else { /* An MCI error occured (not DataBlockEnd) */ + else { /* An MCI error occured (not DataBlockEnd) */ xs |= 8; } @@ -144,7 +144,7 @@ void Isr_MCI(void) void Isr_GPDMA(void) { if (GPDMA_INT_TCSTAT & BIT0) { - GPDMA_INT_TCCLR = 0x01; /* Clear GPDMA interrupt flag */ + GPDMA_INT_TCCLR = 0x01; /* Clear GPDMA interrupt flag */ if (XferStat & 2) { /* In write operation */ @@ -167,7 +167,7 @@ void Isr_GPDMA(void) /** * @param blks Number of blocks to receive (1..127) - * @param bs Block size (64 or 512) + * @param bs Block size (64 or 512) * */ static void ready_reception(unsigned int blks, unsigned int bs) { @@ -175,9 +175,9 @@ static void ready_reception(unsigned int blks, unsigned int bs) unsigned long dma_ctrl; /* ------ Setting up GPDMA Ch-0 ------ */ - GPDMA_CH0_CFG &= 0xFFF80420; /* Disable ch-0 */ - GPDMA_INT_TCCLR = 0x01; /* Clear interrupt flag */ - dma_ctrl = 0x88492000 | (bs / 4); /* 1_000_1_0_00_010_010_010_010_************ */ + GPDMA_CH0_CFG &= 0xFFF80420; /* Disable ch-0 */ + GPDMA_INT_TCCLR = 0x01; /* Clear interrupt flag */ + dma_ctrl = 0x88492000 | (bs / 4); /* 1_000_1_0_00_010_010_010_010_************ */ /* Create link list */ for (n = 0; n < N_BUF; n++) { @@ -194,22 +194,22 @@ static void ready_reception(unsigned int blks, unsigned int bs) GPDMA_CH0_CTRL = LinkList[0][3]; /* Enable ch-0 */ - GPDMA_CH0_CFG |= 0x19009; /* *************_0_0_1_1_0_010_*_0000_*_0100_1 */ + GPDMA_CH0_CFG |= 0x19009; /* *************_0_0_1_1_0_010_*_0000_*_0100_1 */ /* --------- Setting up MCI ---------- */ XferRp = 0; - XferWp = 0; /* Block FIFO R/W index */ - XferStat = 1; /* Transfer status: MCI --> Memory */ + XferWp = 0; /* Block FIFO R/W index */ + XferStat = 1; /* Transfer status: MCI --> Memory */ - MCI_DATA_LEN = bs * blks; /* Set total data length */ - MCI_DATA_TMR = (unsigned long)(MCLK_RW * 0.2); /* Data timer: 0.2sec */ - MCI_CLEAR = 0x72A; /* Clear status flags */ - MCI_MASK0 = 0x72A; /* DataBlockEnd StartBitErr DataEnd RxOverrun DataTimeOut DataCrcFail */ + MCI_DATA_LEN = bs * blks; /* Set total data length */ + MCI_DATA_TMR = (unsigned long)(MCLK_RW * 0.2); /* Data timer: 0.2sec */ + MCI_CLEAR = 0x72A; /* Clear status flags */ + MCI_MASK0 = 0x72A; /* DataBlockEnd StartBitErr DataEnd RxOverrun DataTimeOut DataCrcFail */ for (n = 0; bs > 1; bs >>= 1, n += 0x10); - MCI_DATA_CTRL = n | 0xB; /* Start to receive data blocks */ + MCI_DATA_CTRL = n | 0xB; /* Start to receive data blocks */ } @@ -229,9 +229,9 @@ static void start_transmission(unsigned char blks) /* ------ Setting up GPDMA Ch-0 ------ */ - GPDMA_CH0_CFG &= 0xFFF80420; /* Disable ch-0 */ - GPDMA_INT_TCCLR = 0x01; /* Clear interrupt flag */ - dma_ctrl = 0x84492080; /* 1_000_0_1_00_010_010_010_010_000010000000 */ + GPDMA_CH0_CFG &= 0xFFF80420; /* Disable ch-0 */ + GPDMA_INT_TCCLR = 0x01; /* Clear interrupt flag */ + dma_ctrl = 0x84492080; /* 1_000_0_1_00_010_010_010_010_000010000000 */ /* Create link list */ for (n = 0; n < N_BUF; n++) { @@ -248,21 +248,21 @@ static void start_transmission(unsigned char blks) GPDMA_CH0_CTRL = LinkList[0][3]; /* Enable ch-0 */ - GPDMA_CH0_CFG |= 0x18901; /* *************_0_0_1_1_0_001_*_0100_*_0000_1 */ + GPDMA_CH0_CFG |= 0x18901; /* *************_0_0_1_1_0_001_*_0100_*_0000_1 */ /* --------- Setting up MCI ---------- */ - XferRp = 0; /* Block FIFO read index */ + XferRp = 0; /* Block FIFO read index */ XferWc = blks; - XferStat = 2; /* Transfer status: Memroy --> MCI */ + XferStat = 2; /* Transfer status: Memroy --> MCI */ - MCI_DATA_LEN = 512 * (blks + 1); /* Set total data length */ - MCI_DATA_TMR = (unsigned long)(MCLK_RW * 0.5); /* Data timer: 0.5sec */ - MCI_CLEAR = 0x51A; /* Clear status flags */ - MCI_MASK0 = 0x51A; /* DataBlockEnd DataEnd TxUnderrun DataTimeOut DataCrcFail */ - MCI_DATA_CTRL = (9 << 4) | 0x9; /* Start to transmit data blocks */ + MCI_DATA_LEN = 512 * (blks + 1); /* Set total data length */ + MCI_DATA_TMR = (unsigned long)(MCLK_RW * 0.5); /* Data timer: 0.5sec */ + MCI_CLEAR = 0x51A; /* Clear status flags */ + MCI_MASK0 = 0x51A; /* DataBlockEnd DataEnd TxUnderrun DataTimeOut DataCrcFail */ + MCI_DATA_CTRL = (9 << 4) | 0x9; /* Start to transmit data blocks */ } -#endif /* _READONLY */ +#endif /* _READONLY */ @@ -273,10 +273,10 @@ static void start_transmission(unsigned char blks) static void stop_transfer(void) { - MCI_MASK0 = 0; /* Disable MCI interrupt */ - MCI_DATA_CTRL = 0; /* Stop MCI data transfer */ + MCI_MASK0 = 0; /* Disable MCI interrupt */ + MCI_DATA_CTRL = 0; /* Stop MCI data transfer */ - GPDMA_CH0_CFG &= 0xFFF80420; /* Disable DMA ch-0 */ + GPDMA_CH0_CFG &= 0xFFF80420; /* Disable DMA ch-0 */ } @@ -298,7 +298,7 @@ static void power_on(void) PCONP |= (3 << 28); /* Enable GPDMA controller with little-endian */ - GPDMA_CH0_CFG &= 0xFFF80000; /* Disable DMA ch-0 */ + GPDMA_CH0_CFG &= 0xFFF80000; /* Disable DMA ch-0 */ GPDMA_CONFIG = 0x01; /* Select PCLK for MCI, CCLK/2 = 36MHz */ @@ -306,14 +306,14 @@ static void power_on(void) //0.19 0.20 0.21 0.22 PINMODE1 &= ~((BIT6 | BIT7) | (BIT8 | BIT9) | (BIT10 | BIT11) | (BIT12 | BIT13)); - PINMODE1 |= (BIT7) | (BIT9) | (BIT11) | (BIT13); // no resistors + PINMODE1 |= (BIT7) | (BIT9) | (BIT11) | (BIT13); // no resistors //2.11 2.12 2.13 PINMODE4 &= ~((BIT22 | BIT23) | (BIT24 | BIT25) | (BIT26 | BIT27)); - PINMODE4 |= (BIT23) | (BIT25) | (BIT27); // no resistors + PINMODE4 |= (BIT23) | (BIT25) | (BIT27); // no resistors /* Attach MCI unit to I/O pad */ - PINSEL1 = (PINSEL1 & 0xFFFFC03F) | 0x00002A80; /* MCICLK, MCICMD, MCIDATA0, MCIPWR */ + PINSEL1 = (PINSEL1 & 0xFFFFC03F) | 0x00002A80; /* MCICLK, MCICMD, MCIDATA0, MCIPWR */ #if USE_4BIT - PINSEL4 = (PINSEL4 & 0xF03FFFFF) | 0x0A800000; /* MCIDATA1-3 */ + PINSEL4 = (PINSEL4 & 0xF03FFFFF) | 0x0A800000; /* MCIDATA1-3 */ #endif MCI_MASK0 = 0; MCI_COMMAND = 0; @@ -331,12 +331,12 @@ static void power_on(void) /* Power-on (VCC is always tied to the socket on this board) */ - MCI_POWER = 0x01; /* Power on */ + MCI_POWER = 0x01; /* Power on */ - //for (Timer[0] = 10; Timer[0]; ) ; /* 10ms */ + //for (Timer[0] = 10; Timer[0]; ) ; /* 10ms */ hwtimer_wait(1000); - MCI_POWER = 0x03; /* Enable signals */ + MCI_POWER = 0x03; /* Enable signals */ } @@ -346,7 +346,7 @@ static void power_off(void) MCI_COMMAND = 0; MCI_DATA_CTRL = 0; - MCI_POWER = 0; /* Power-off */ + MCI_POWER = 0; /* Power-off */ MCI_CLOCK = 0; // pin 0.21 low inactive @@ -356,12 +356,12 @@ static void power_off(void) //0.19 0.20 0.21 0.22 with pull-down PINMODE1 |= (BIT6 | BIT7) | (BIT8 | BIT9) | (BIT10 | BIT11) | (BIT12 | BIT13); PINSEL1 &= ~((BIT6 | BIT7) | (BIT8 | BIT9) | (BIT10 | BIT11) | (BIT12 | BIT13)); - // Pins should be now configured as standard input (see board_init.c if you accidentally reconfigured them) + // Pins should be now configured as standard input (see board_init.c if you accidentally reconfigured them) //2.11 2.12 2.13 with pull-down PINMODE4 |= (BIT22 | BIT23) | (BIT24 | BIT25) | (BIT26 | BIT27); PINSEL4 &= ~((BIT22 | BIT23) | (BIT24 | BIT25) | (BIT26 | BIT27)); - // Pins should be now configured as standard input (see board_init.c if you accidentally reconfigured them) + // Pins should be now configured as standard input (see board_init.c if you accidentally reconfigured them) Stat |= STA_NOINIT; } @@ -382,18 +382,18 @@ static int send_cmd(unsigned int idx, unsigned long arg, unsigned int rt, unsign { unsigned int s, mc; - if (idx & 0x80) { /* Send a CMD55 prior to the specified command if it is ACMD class */ - if (!send_cmd(CMD55, (unsigned long)CardRCA << 16, 1, buff) /* When CMD55 is faild, */ + if (idx & 0x80) { /* Send a CMD55 prior to the specified command if it is ACMD class */ + if (!send_cmd(CMD55, (unsigned long)CardRCA << 16, 1, buff) /* When CMD55 is faild, */ || !(buff[0] & 0x00000020)) { return 0; /* exit with error */ } } - idx &= 0x3F; /* Mask out ACMD flag */ + idx &= 0x3F; /* Mask out ACMD flag */ - do { /* Wait while CmdActive bit is set */ - MCI_COMMAND = 0; /* Cancel to transmit command */ - MCI_CLEAR = 0x0C5; /* Clear status flags */ + do { /* Wait while CmdActive bit is set */ + MCI_COMMAND = 0; /* Cancel to transmit command */ + MCI_CLEAR = 0x0C5; /* Clear status flags */ for (s = 0; s < 10; s++) { MCI_STATUS; /* Skip lock out time of command reg. */ @@ -401,8 +401,8 @@ static int send_cmd(unsigned int idx, unsigned long arg, unsigned int rt, unsign } while (MCI_STATUS & 0x00800); - MCI_ARGUMENT = arg; /* Set the argument into argument register */ - mc = 0x400 | idx; /* Enable bit + index */ + MCI_ARGUMENT = arg; /* Set the argument into argument register */ + mc = 0x400 | idx; /* Enable bit + index */ if (rt == 1) { mc |= 0x040; /* Set Response bit to reveice short resp */ @@ -412,19 +412,19 @@ static int send_cmd(unsigned int idx, unsigned long arg, unsigned int rt, unsign mc |= 0x0C0; /* Set Response and LongResp bit to receive long resp */ } - MCI_COMMAND = mc; /* Initiate command transaction */ + MCI_COMMAND = mc; /* Initiate command transaction */ //Timer[1] = 100; uint32_t timerstart = hwtimer_now(); - while (1) { /* Wait for end of the cmd/resp transaction */ + while (1) { /* Wait for end of the cmd/resp transaction */ //if (!Timer[1]) return 0; if (hwtimer_now() - timerstart > 10000) { return 0; } - s = MCI_STATUS; /* Get the transaction status */ + s = MCI_STATUS; /* Get the transaction status */ if (rt == 0) { if (s & 0x080) { @@ -451,7 +451,7 @@ static int send_cmd(unsigned int idx, unsigned long arg, unsigned int rt, unsign } } - buff[0] = MCI_RESP0; /* Read the response words */ + buff[0] = MCI_RESP0; /* Read the response words */ if (rt == 2) { buff[1] = MCI_RESP1; @@ -459,7 +459,7 @@ static int send_cmd(unsigned int idx, unsigned long arg, unsigned int rt, unsign buff[3] = MCI_RESP3; } - return 1; /* Return with success */ + return 1; /* Return with success */ } @@ -537,12 +537,12 @@ DSTATUS MCI_initialize(void) hwtimer_wait(HWTIMER_TICKS(1000)); - power_on(); /* Force socket power on */ - MCI_CLOCK = 0x100 | (PCLK / MCLK_ID / 2 - 1); /* Set MCICLK = MCLK_ID */ + power_on(); /* Force socket power on */ + MCI_CLOCK = 0x100 | (PCLK / MCLK_ID / 2 - 1); /* Set MCICLK = MCLK_ID */ //for (Timer[0] = 2; Timer[0]; ); hwtimer_wait(250); - send_cmd(CMD0, 0, 0, NULL); /* Enter idle state */ + send_cmd(CMD0, 0, 0, NULL); /* Enter idle state */ CardRCA = 0; /*---- Card is 'idle' state ----*/ @@ -555,7 +555,7 @@ DSTATUS MCI_initialize(void) /* The card can work at vdd range of 2.7-3.6V */ DEBUG("SDC Ver. 2\n"); - do { /* Wait while card is busy state (use ACMD41 with HCS bit) */ + do { /* Wait while card is busy state (use ACMD41 with HCS bit) */ /* This loop will take a time. Insert wai_tsk(1) here for multitask envilonment. */ if (hwtimer_now() > start + 1000000/*!Timer[0]*/) { DEBUG("%s, %d: Timeout #1\n", __FILE__, __LINE__); @@ -564,21 +564,21 @@ DSTATUS MCI_initialize(void) } while (!send_cmd(ACMD41, 0x40FF8000, 1, resp) || !(resp[0] & 0x80000000)); - ty = (resp[0] & 0x40000000) ? CT_SD2 | CT_BLOCK : CT_SD2; /* Check CCS bit in the OCR */ + ty = (resp[0] & 0x40000000) ? CT_SD2 | CT_BLOCK : CT_SD2; /* Check CCS bit in the OCR */ } - else { /* SDC Ver1 or MMC */ + else { /* SDC Ver1 or MMC */ if (send_cmd(ACMD41, 0x00FF8000, 1, resp)) { DEBUG("SDC Ver. 1\n"); ty = CT_SD1; - cmd = ACMD41; /* ACMD41 is accepted -> SDC Ver1 */ + cmd = ACMD41; /* ACMD41 is accepted -> SDC Ver1 */ } else { DEBUG("MMC\n"); ty = CT_MMC; - cmd = CMD1; /* ACMD41 is rejected -> MMC */ + cmd = CMD1; /* ACMD41 is rejected -> MMC */ } - do { /* Wait while card is busy state (use ACMD41 or CMD1) */ + do { /* Wait while card is busy state (use ACMD41 or CMD1) */ DEBUG("%s, %d: %lX\n", __FILE__, __LINE__, resp[0]); /* This loop will take a time. Insert wai_tsk(1) here for multitask envilonment. */ @@ -591,14 +591,14 @@ DSTATUS MCI_initialize(void) while (!send_cmd(cmd, 0x00FF8000, 1, resp) || !(resp[0] & 0x80000000)); } - CardType = ty; /* Save card type */ - bswap_cp(&CardInfo[32], resp); /* Save OCR */ + CardType = ty; /* Save card type */ + bswap_cp(&CardInfo[32], resp); /* Save OCR */ /*---- Card is 'ready' state ----*/ if (!send_cmd(CMD2, 0, 2, resp)) { DEBUG("%s, %d: Failed entering ident state", __FILE__, __LINE__); - goto di_fail; /* Enter ident state */ + goto di_fail; /* Enter ident state */ } for (n = 0; n < 4; n++) { @@ -607,7 +607,7 @@ DSTATUS MCI_initialize(void) /*---- Card is 'ident' state ----*/ - if (ty & CT_SDC) { /* SDC: Get generated RCA and save it */ + if (ty & CT_SDC) { /* SDC: Get generated RCA and save it */ if (!send_cmd(CMD3, 0, 1, resp)) { DEBUG("%s, %d: Failed generating RCA\n", __FILE__, __LINE__); goto di_fail; @@ -615,7 +615,7 @@ DSTATUS MCI_initialize(void) CardRCA = (unsigned short)(resp[0] >> 16); } - else { /* MMC: Assign RCA to the card */ + else { /* MMC: Assign RCA to the card */ if (!send_cmd(CMD3, 1 << 16, 1, resp)) { goto di_fail; } @@ -625,7 +625,7 @@ DSTATUS MCI_initialize(void) /*---- Card is 'stby' state ----*/ - if (!send_cmd(CMD9, (unsigned long)CardRCA << 16, 2, resp)) { /* Get CSD and save it */ + if (!send_cmd(CMD9, (unsigned long)CardRCA << 16, 2, resp)) { /* Get CSD and save it */ goto di_fail; } @@ -633,14 +633,14 @@ DSTATUS MCI_initialize(void) bswap_cp(&CardInfo[n * 4], &resp[n]); } - if (!send_cmd(CMD7, (unsigned long)CardRCA << 16, 1, resp)) { /* Select card */ + if (!send_cmd(CMD7, (unsigned long)CardRCA << 16, 1, resp)) { /* Select card */ //printf("MCI CMD7 fail\n"); goto di_fail; } /*---- Card is 'tran' state ----*/ - if (!(ty & CT_BLOCK)) { /* Set data block length to 512 (for byte addressing cards) */ + if (!(ty & CT_BLOCK)) { /* Set data block length to 512 (for byte addressing cards) */ if (!send_cmd(CMD16, 512, 1, resp) || (resp[0] & 0xFDF90000)) { //printf("MCI CMD16 fail\n"); goto di_fail; @@ -649,26 +649,26 @@ DSTATUS MCI_initialize(void) #if USE_4BIT - if (ty & CT_SDC) { /* Set wide bus mode (for SDCs) */ - if (!send_cmd(ACMD6, 2, 1, resp) /* Set bus mode of SDC */ + if (ty & CT_SDC) { /* Set wide bus mode (for SDCs) */ + if (!send_cmd(ACMD6, 2, 1, resp) /* Set bus mode of SDC */ || (resp[0] & 0xFDF90000)) { //printf("MCI ACMD6 fail\n"); goto di_fail; } - MCI_CLOCK |= 0x800; /* Set bus mode of MCI */ + MCI_CLOCK |= 0x800; /* Set bus mode of MCI */ } #endif - MCI_CLOCK = (MCI_CLOCK & 0xF00) | 0x200 | (PCLK / MCLK_RW / 2 - 1); /* Set MCICLK = MCLK_RW, power-save mode */ + MCI_CLOCK = (MCI_CLOCK & 0xF00) | 0x200 | (PCLK / MCLK_RW / 2 - 1); /* Set MCICLK = MCLK_RW, power-save mode */ - Stat &= ~STA_NOINIT; /* Clear STA_NOINIT */ + Stat &= ~STA_NOINIT; /* Clear STA_NOINIT */ return Stat; di_fail: power_off(); - Stat |= STA_NOINIT; /* Set STA_NOINIT */ + Stat |= STA_NOINIT; /* Set STA_NOINIT */ return Stat; } @@ -694,7 +694,7 @@ DSTATUS MCI_status(void) /** * @param buff Pointer to the data buffer to store read data * @param sector Start sector number (LBA) - * @param count Sector count (1..127) + * @param count Sector count (1..127) */ DRESULT MCI_read(unsigned char *buff, unsigned long sector, unsigned char count) { @@ -719,11 +719,11 @@ DRESULT MCI_read(unsigned char *buff, unsigned long sector, unsigned char count) return RES_ERROR; /* Make sure that card is tran state */ } - ready_reception(count, 512); /* Ready to receive data blocks */ + ready_reception(count, 512); /* Ready to receive data blocks */ - cmd = (count > 1) ? CMD18 : CMD17; /* Transfer type: Single block or Multiple block */ + cmd = (count > 1) ? CMD18 : CMD17; /* Transfer type: Single block or Multiple block */ - if (send_cmd(cmd, sector, 1, &resp) /* Start to read */ + if (send_cmd(cmd, sector, 1, &resp) /* Start to read */ && !(resp & 0xC0580000)) { rp = 0; @@ -797,13 +797,13 @@ DRESULT MCI_write(const unsigned char *buff, unsigned long sector, unsigned char return RES_ERROR; /* Make sure that card is tran state */ } - if (count == 1) { /* Single block write */ + if (count == 1) { /* Single block write */ cmd = CMD24; } - else { /* Multiple block write */ + else { /* Multiple block write */ cmd = (CardType & CT_SDC) ? ACMD23 : CMD23; - if (!send_cmd(cmd, count, 1, &rc) /* Preset number of blocks to write */ + if (!send_cmd(cmd, count, 1, &rc) /* Preset number of blocks to write */ || (rc & 0xC0580000)) { return RES_ERROR; } @@ -811,7 +811,7 @@ DRESULT MCI_write(const unsigned char *buff, unsigned long sector, unsigned char cmd = CMD25; } - if (!send_cmd(cmd, sector, 1, &rc) /* Send a write command */ + if (!send_cmd(cmd, sector, 1, &rc) /* Send a write command */ || (rc & 0xC0580000)) { return RES_ERROR; } @@ -819,19 +819,19 @@ DRESULT MCI_write(const unsigned char *buff, unsigned long sector, unsigned char wp = 0; xc = count; - do { /* Fill block FIFO */ - Copy_un2al(DmaBuff[wp], (unsigned char *)(unsigned int)buff, 512); /* Push a block */ - wp++; /* Next DMA buffer */ + do { /* Fill block FIFO */ + Copy_un2al(DmaBuff[wp], (unsigned char *)(unsigned int)buff, 512); /* Push a block */ + wp++; /* Next DMA buffer */ count--; - buff += 512; /* Next user buffer address */ + buff += 512; /* Next user buffer address */ } while (count && wp < N_BUF); XferWp = wp = wp % N_BUF; - start_transmission(xc); /* Start transmission */ + start_transmission(xc); /* Start transmission */ while (count) { - while ((wp == XferRp) && !(XferStat & 0xC)) { /* Wait for block FIFO not full */ + while ((wp == XferRp) && !(XferStat & 0xC)) { /* Wait for block FIFO not full */ /* This loop will take a time. Replace it with sync process for multitask envilonment. */ } @@ -839,26 +839,26 @@ DRESULT MCI_write(const unsigned char *buff, unsigned long sector, unsigned char break; /* Abort if block underrun or any MCI error has occured */ } - Copy_un2al(DmaBuff[wp], (unsigned char *)(unsigned int)buff, 512); /* Push a block */ - XferWp = wp = (wp + 1) % N_BUF; /* Next DMA buffer */ + Copy_un2al(DmaBuff[wp], (unsigned char *)(unsigned int)buff, 512); /* Push a block */ + XferWp = wp = (wp + 1) % N_BUF; /* Next DMA buffer */ if (XferStat & 0xC) { break; /* Abort if block underrun has occured */ } count--; - buff += 512; /* Next user buffer address */ + buff += 512; /* Next user buffer address */ } - while (!(XferStat & 0xC)); /* Wait for all blocks sent (block underrun) */ + while (!(XferStat & 0xC)); /* Wait for all blocks sent (block underrun) */ if (XferStat & 0x8) { count = 1; /* Abort if any MCI error has occured */ } - stop_transfer(); /* Close data path */ + stop_transfer(); /* Close data path */ - if (cmd == CMD25 && (CardType & CT_SDC)) { /* Terminate to write (SDC w/MB) */ + if (cmd == CMD25 && (CardType & CT_SDC)) { /* Terminate to write (SDC w/MB) */ send_cmd(CMD12, 0, 1, &rc); } @@ -874,8 +874,8 @@ DRESULT MCI_write(const unsigned char *buff, unsigned long sector, unsigned char /*-----------------------------------------------------------------------*/ DRESULT MCI_ioctl( - unsigned char ctrl, /* Control code */ - void *buff /* Buffer to send/receive data block */ + unsigned char ctrl, /* Control code */ + void *buff /* Buffer to send/receive data block */ ) { DRESULT res; @@ -890,19 +890,19 @@ DRESULT MCI_ioctl( res = RES_ERROR; switch(ctrl) { - case CTRL_SYNC : /* Make sure that all data has been written on the media */ - if (wait_ready(500)) { /* Wait for card enters tarn state */ + case CTRL_SYNC : /* Make sure that all data has been written on the media */ + if (wait_ready(500)) { /* Wait for card enters tarn state */ res = RES_OK; } break; - case GET_SECTOR_COUNT : /* Get number of sectors on the disk (unsigned long) */ - if ((CardInfo[0] >> 6) == 1) { /* SDC CSD v2.0 */ + case GET_SECTOR_COUNT : /* Get number of sectors on the disk (unsigned long) */ + if ((CardInfo[0] >> 6) == 1) { /* SDC CSD v2.0 */ d = ((unsigned short)CardInfo[8] << 8) + CardInfo[9] + 1; *(unsigned long *)buff = d << 10; } - else { /* MMC or SDC CSD v1.0 */ + else { /* MMC or SDC CSD v1.0 */ b = (CardInfo[5] & 15) + ((CardInfo[10] & 128) >> 7) + ((CardInfo[9] & 3) << 1) + 2; d = (CardInfo[8] >> 6) + ((unsigned short)CardInfo[7] << 2) + ((unsigned short)(CardInfo[6] & 3) << 10) + 1; *(unsigned long *)buff = d << (b - 9); @@ -911,20 +911,20 @@ DRESULT MCI_ioctl( res = RES_OK; break; - case GET_SECTOR_SIZE : /* Get sectors on the disk (unsigned short) */ + case GET_SECTOR_SIZE : /* Get sectors on the disk (unsigned short) */ *(unsigned short *)buff = 512; res = RES_OK; break; - case GET_BLOCK_SIZE : /* Get erase block size in unit of sectors (unsigned long) */ - if (CardType & CT_SD2) { /* SDC ver 2.00 */ + case GET_BLOCK_SIZE : /* Get erase block size in unit of sectors (unsigned long) */ + if (CardType & CT_SD2) { /* SDC ver 2.00 */ *(unsigned long *)buff = 16UL << (CardInfo[10] >> 4); } - else { /* SDC ver 1.XX or MMC */ - if (CardType & CT_SD1) { /* SDC v1 */ + else { /* SDC ver 1.XX or MMC */ + if (CardType & CT_SD1) { /* SDC v1 */ *(unsigned long *)buff = (((CardInfo[10] & 63) << 1) + ((unsigned short)(CardInfo[11] & 128) >> 7) + 1) << ((CardInfo[13] >> 6) - 1); } - else { /* MMC */ + else { /* MMC */ *(unsigned long *)buff = ((unsigned short)((CardInfo[10] & 124) >> 2) + 1) * (((CardInfo[11] & 3) << 3) + ((CardInfo[11] & 224) >> 5) + 1); } } @@ -932,7 +932,7 @@ DRESULT MCI_ioctl( res = RES_OK; break; - case CTRL_ERASE_SECTOR : /* Erase a block of sectors */ + case CTRL_ERASE_SECTOR : /* Erase a block of sectors */ if (!(CardType & CT_SDC) || (!(CardInfo[0] >> 6) && !(CardInfo[10] & 0x40))) { break; /* Check if sector erase can be applied to the card */ } @@ -954,12 +954,12 @@ DRESULT MCI_ioctl( case CTRL_POWER : switch(ptr[0]) { - case 0: /* Sub control code == 0 (POWER_OFF) */ - power_off(); /* Power off */ + case 0: /* Sub control code == 0 (POWER_OFF) */ + power_off(); /* Power off */ res = RES_OK; break; - case 1: /* Sub control code == 1 (POWER_GET) */ + case 1: /* Sub control code == 1 (POWER_GET) */ ptr[1] = (unsigned char)power_status(); res = RES_OK; break; @@ -970,32 +970,32 @@ DRESULT MCI_ioctl( break; - case MMC_GET_TYPE : /* Get card type flags (1 byte) */ + case MMC_GET_TYPE : /* Get card type flags (1 byte) */ *ptr = CardType; res = RES_OK; break; - case MMC_GET_CSD : /* Get CSD (16 bytes) */ + case MMC_GET_CSD : /* Get CSD (16 bytes) */ memcpy(buff, &CardInfo[0], 16); res = RES_OK; break; - case MMC_GET_CID : /* Get CID (16 bytes) */ + case MMC_GET_CID : /* Get CID (16 bytes) */ memcpy(buff, &CardInfo[16], 16); res = RES_OK; break; - case MMC_GET_OCR : /* Get OCR (4 bytes) */ + case MMC_GET_OCR : /* Get OCR (4 bytes) */ memcpy(buff, &CardInfo[32], 4); res = RES_OK; break; - case MMC_GET_SDSTAT : /* Receive SD status as a data block (64 bytes) */ - if (CardType & CT_SDC) { /* SDC */ + case MMC_GET_SDSTAT : /* Receive SD status as a data block (64 bytes) */ + if (CardType & CT_SDC) { /* SDC */ if (wait_ready(500)) { - ready_reception(1, 64); /* Ready to receive data blocks */ + ready_reception(1, 64); /* Ready to receive data blocks */ - if (send_cmd(ACMD13, 0, 1, resp) /* Start to read */ + if (send_cmd(ACMD13, 0, 1, resp) /* Start to read */ && !(resp[0] & 0xC0580000)) { while ((XferWp == 0) && !(XferStat & 0xC)); @@ -1006,7 +1006,7 @@ DRESULT MCI_ioctl( } } - stop_transfer(); /* Close data path */ + stop_transfer(); /* Close data path */ } break; diff --git a/cpu/lpc2387/rtc/lpc2387-rtc.c b/cpu/lpc2387/rtc/lpc2387-rtc.c index 96d988559285..8bd01108084e 100644 --- a/cpu/lpc2387/rtc/lpc2387-rtc.c +++ b/cpu/lpc2387/rtc/lpc2387-rtc.c @@ -12,13 +12,13 @@ See the file LICENSE in the top level directory for more details. /** * @file - * @ingroup lpc2387_rtc - * @brief LPC2387 Real-Time-Clock + * @ingroup lpc2387_rtc + * @brief LPC2387 Real-Time-Clock * - * @author Michael Baar + * @author Michael Baar * @version $Revision: 2005 $ * - * @note $Id: lpc2387-rtc.c 2005 2010-03-17 10:52:03Z baar $ + * @note $Id: lpc2387-rtc.c 2005 2010-03-17 10:52:03Z baar $ */ #include @@ -31,21 +31,21 @@ See the file LICENSE in the top level directory for more details. #include "lpc2387-rtc.h" #include "lpm.h" -#define PREINT_RTC 0x000001C8 /* Prescaler value, integer portion, PCLK = 15Mhz */ -#define PREFRAC_RTC 0x000061C0 /* Prescaler value, fraction portion, PCLK = 15Mhz */ +#define PREINT_RTC 0x000001C8 /* Prescaler value, integer portion, PCLK = 15Mhz */ +#define PREFRAC_RTC 0x000061C0 /* Prescaler value, fraction portion, PCLK = 15Mhz */ #define ENABLE_DEBUG (0) #include "debug.h" /** - * @brief epoch time in hour granularity + * @brief epoch time in hour granularity */ static volatile time_t epoch; /*---------------------------------------------------------------------------*/ /** - * @brief Sets the current time in broken down format directly from to RTC - * @param[in] localt Pointer to structure with time to set + * @brief Sets the current time in broken down format directly from to RTC + * @param[in] localt Pointer to structure with time to set */ void rtc_set_localtime(struct tm *localt) @@ -68,7 +68,7 @@ rtc_set_localtime(struct tm *localt) void rtc_set(time_t time) { struct tm *localt; - localt = localtime(&time); /* convert seconds to broken-down time */ + localt = localtime(&time); /* convert seconds to broken-down time */ rtc_set_localtime(localt); epoch = time - localt->tm_sec - localt->tm_min * 60; } @@ -92,7 +92,7 @@ rtc_set_alarm(struct tm *localt, enum rtc_alarm_mask mask) RTC_ALDOY = localt->tm_yday; RTC_ALMON = localt->tm_mon + 1; RTC_ALYEAR = localt->tm_year; - RTC_AMR = ~mask; /* set wich alarm fields to check */ + RTC_AMR = ~mask; /* set wich alarm fields to check */ DEBUG("alarm set %2lu.%2lu.%4lu %2lu:%2lu:%2lu\n", RTC_ALDOM, RTC_ALMON, RTC_ALYEAR, RTC_ALHOUR, RTC_ALMIN, RTC_ALSEC); } @@ -116,7 +116,7 @@ rtc_get_alarm(struct tm *localt) localt->tm_isdst = -1; /* not available */ } - return (~RTC_AMR) & 0xff; /* return which alarm fields are checked */ + return (~RTC_AMR) & 0xff; /* return which alarm fields are checked */ } /*---------------------------------------------------------------------------*/ void RTC_IRQHandler(void) __attribute__((interrupt("IRQ"))); @@ -131,25 +131,25 @@ void RTC_IRQHandler(void) else if (RTC_ILR & ILR_RTCCIF) { /* counter increase interrupt */ RTC_ILR |= ILR_RTCCIF; - epoch += 60 * 60; /* add 1 hour */ + epoch += 60 * 60; /* add 1 hour */ } else if (RTC_ILR & ILR_RTCALF) { RTC_ILR |= ILR_RTCALF; - RTC_AMR = 0xff; /* disable alarm irq */ + RTC_AMR = 0xff; /* disable alarm irq */ DEBUG("Ring\n"); lpm_end_awake(); } - VICVectAddr = 0; /* Acknowledge Interrupt */ + VICVectAddr = 0; /* Acknowledge Interrupt */ } /*---------------------------------------------------------------------------*/ void rtc_enable(void) { - RTC_ILR = (ILR_RTSSF | ILR_RTCCIF | ILR_RTCALF); /* clear interrupt flags */ - RTC_CCR |= CCR_CLKEN; /* enable clock */ - install_irq(RTC_INT, &RTC_IRQHandler, IRQP_RTC); /* install interrupt handler */ + RTC_ILR = (ILR_RTSSF | ILR_RTCCIF | ILR_RTCALF); /* clear interrupt flags */ + RTC_CCR |= CCR_CLKEN; /* enable clock */ + install_irq(RTC_INT, &RTC_IRQHandler, IRQP_RTC); /* install interrupt handler */ time_t now = rtc_time(NULL); epoch = now - (now % 3600); @@ -158,13 +158,13 @@ void rtc_enable(void) void rtc_init(void) { PCONP |= BIT9; - RTC_AMR = 0xff; /* disable alarm irq */ - RTC_CIIR = IMHOUR; /* enable increase irq */ - RTC_CISS = 0; /* disable subsecond irq */ + RTC_AMR = 0xff; /* disable alarm irq */ + RTC_CIIR = IMHOUR; /* enable increase irq */ + RTC_CISS = 0; /* disable subsecond irq */ - INTWAKE |= BIT15; /* rtc irq wakes up mcu from power down */ + INTWAKE |= BIT15; /* rtc irq wakes up mcu from power down */ - RTC_CCR = CCR_CLKSRC; /* Clock from external 32 kHz Osc. */ + RTC_CCR = CCR_CLKSRC; /* Clock from external 32 kHz Osc. */ /* initialize clock with valid unix compatible values * If RTC_YEAR contains an value larger unix time_t we must reset. */ @@ -193,8 +193,8 @@ time_t rtc_time(struct timeval *time) min = RTC_MIN; } - sec += min * 60; /* add number of minutes */ - sec += epoch; /* add precalculated epoch in hour granularity */ + sec += min * 60; /* add number of minutes */ + sec += epoch; /* add precalculated epoch in hour granularity */ if (time != NULL) { usec = usec * 15625; @@ -208,7 +208,7 @@ time_t rtc_time(struct timeval *time) /*---------------------------------------------------------------------------*/ void rtc_disable(void) { - RTC_CCR &= ~CCR_CLKEN; /* disable clock */ + RTC_CCR &= ~CCR_CLKEN; /* disable clock */ install_irq(RTC_INT, NULL, 0); RTC_ILR = 0; } diff --git a/cpu/lpc_common/iap.c b/cpu/lpc_common/iap.c index 56f7622c5ebe..0abe9a73fe37 100644 --- a/cpu/lpc_common/iap.c +++ b/cpu/lpc_common/iap.c @@ -37,9 +37,9 @@ /* pointer to reserved flash rom section for configuration data */ __attribute((aligned(256))) char configmem[256] __attribute__((section(".configmem"))); -static unsigned int iap_command[5]; // contains parameters for IAP command -static unsigned int iap_result[2]; // contains results -typedef void (*IAP)(unsigned int[], unsigned int[]); // typedefinition for IAP entry function +static unsigned int iap_command[5]; // contains parameters for IAP command +static unsigned int iap_result[2]; // contains results +typedef void (*IAP)(unsigned int[], unsigned int[]); // typedefinition for IAP entry function IAP IAP_Entry; /* some function prototypes */ @@ -53,7 +53,7 @@ static uint32_t iap(uint32_t code, uint32_t p1, uint32_t p2, uint32_t p3, uint32 /****************************************************************************** * P U B L I C F U N C T I O N S *****************************************************************************/ -uint8_t flashrom_write(uint8_t *dst, const uint8_t *src, size_t size) +uint8_t flashrom_write(uint8_t *dst, const uint8_t *src, size_t size) { (void) size; /* unused */ @@ -159,36 +159,36 @@ uint8_t flashrom_erase(uint8_t *addr) static uint32_t iap(uint32_t code, uint32_t p1, uint32_t p2, uint32_t p3, uint32_t p4) { - iap_command[0] = code; // set command code - iap_command[1] = p1; // set 1st param - iap_command[2] = p2; // set 2nd param - iap_command[3] = p3; // set 3rd param - iap_command[4] = p4; // set 4th param + iap_command[0] = code; // set command code + iap_command[1] = p1; // set 1st param + iap_command[2] = p2; // set 2nd param + iap_command[3] = p3; // set 3rd param + iap_command[4] = p4; // set 4th param - ((void (*)())0x7ffffff1)(iap_command, iap_result); // IAP entry point + ((void (*)())0x7ffffff1)(iap_command, iap_result); // IAP entry point return *iap_result; } /****************************************************************************** - * Function: blank_check_sector + * Function: blank_check_sector * - * Description: This command is used to blank check a sector or multiple sectors - * of on-chip Flash memory. To blank check a single sector use the - * same "Start" and "End" sector numbers. - * Command: 53 - * Param0: Start Sector Number - * Param1: End Sector Number (should be greater than equal to the start - * sector number) + * Description: This command is used to blank check a sector or multiple sectors + * of on-chip Flash memory. To blank check a single sector use the + * same "Start" and "End" sector numbers. + * Command: 53 + * Param0: Start Sector Number + * Param1: End Sector Number (should be greater than equal to the start + * sector number) * - * Parameters: long tmp_sect1: Param0 - * long tmp_sect2: Param1 + * Parameters: long tmp_sect1: Param0 + * long tmp_sect2: Param1 * - * Return: Code CMD_SUCCESS | - * BUSY | - * SECTOR_NOT_BLANK | - * INVALID_SECTOR - * Result0: Offset of the first non blank word location if the status code is SECTOR_NOT_BLANK. - * Result1: Contents of non blank wird location. + * Return: Code CMD_SUCCESS | + * BUSY | + * SECTOR_NOT_BLANK | + * INVALID_SECTOR + * Result0: Offset of the first non blank word location if the status code is SECTOR_NOT_BLANK. + * Result1: Contents of non blank wird location. *****************************************************************************/ uint32_t blank_check_sector(uint32_t tmp_sect1, uint32_t tmp_sect2) { @@ -197,31 +197,31 @@ uint32_t blank_check_sector(uint32_t tmp_sect1, uint32_t tmp_sect2) /****************************************************************************** - * Function: copy_ram_to_flash + * Function: copy_ram_to_flash * - * Description: This command is used to programm the flash memory. the affected should be - * prepared first by calling "Prepare Sector for Write Operation" command. the - * affected sectors are automatically protected again once the copy command is - * successfully executed. the boot sector cannot be written by this command. - * Command: 51 - * Param0: (DST) Destination Flash adress where data bytes are to be written. - * This address should be a 512 byte boundary. - * Param1: (SRC) Source RAM adress from which data byre are to be read. - * Param2: Number of bytes to be written. Should be 512 | 1024 | 4096 | 8192. - * Param3: System Clock Frequency (CCLK) in KHz. + * Description: This command is used to programm the flash memory. the affected should be + * prepared first by calling "Prepare Sector for Write Operation" command. the + * affected sectors are automatically protected again once the copy command is + * successfully executed. the boot sector cannot be written by this command. + * Command: 51 + * Param0: (DST) Destination Flash adress where data bytes are to be written. + * This address should be a 512 byte boundary. + * Param1: (SRC) Source RAM adress from which data byre are to be read. + * Param2: Number of bytes to be written. Should be 512 | 1024 | 4096 | 8192. + * Param3: System Clock Frequency (CCLK) in KHz. * - * Parameters: long tmp_adr_dst: Param0 - * long tmp_adr_src: Param1 - * long tmp_size: Param2 + * Parameters: long tmp_adr_dst: Param0 + * long tmp_adr_src: Param1 + * long tmp_size: Param2 * - * Return: Code CMD_SUCCESS | - * SRC_ADDR_ERROR (Address not on word boundary) | - * DST_ADDR_ERROR (Address not on correct boundary) | - * SRC_ADDR_NOT_MAPPED | - * DST_ADDR_NOT_MAPPED | - * COUNT_ERROR (Byte count is not 512 | 1024 | 4096 | 8192) | - * SECTOR_NOT_PREPARED_FOR_WRITE_OPERATION | - * BUSY + * Return: Code CMD_SUCCESS | + * SRC_ADDR_ERROR (Address not on word boundary) | + * DST_ADDR_ERROR (Address not on correct boundary) | + * SRC_ADDR_NOT_MAPPED | + * DST_ADDR_NOT_MAPPED | + * COUNT_ERROR (Byte count is not 512 | 1024 | 4096 | 8192) | + * SECTOR_NOT_PREPARED_FOR_WRITE_OPERATION | + * BUSY *****************************************************************************/ uint32_t copy_ram_to_flash(uint32_t tmp_adr_dst, uint32_t tmp_adr_src, uint32_t tmp_size) { @@ -230,22 +230,22 @@ uint32_t copy_ram_to_flash(uint32_t tmp_adr_dst, uint32_t tmp_adr_src, uint32_t /****************************************************************************** - * Function: Prepare_Sector + * Function: Prepare_Sector * - * Description: This command must be executed before executing "Copy RAM to Flash" or "Erase Sector(s)" - * command. Successful execution of the "Copy RAM to Flash" or "Erase Sector(s)" command causes - * relevant sectors to be protected again. The boot sector can not be prepared by this command. To - * prepare a single sector use the same "Start" and "End" sector numbers.. - * Command code: 50 - * Param0: Start Sector Number - * Param1: End Sector Number: Should be greater than or equal to start sector number. + * Description: This command must be executed before executing "Copy RAM to Flash" or "Erase Sector(s)" + * command. Successful execution of the "Copy RAM to Flash" or "Erase Sector(s)" command causes + * relevant sectors to be protected again. The boot sector can not be prepared by this command. To + * prepare a single sector use the same "Start" and "End" sector numbers.. + * Command code: 50 + * Param0: Start Sector Number + * Param1: End Sector Number: Should be greater than or equal to start sector number. * - * Parameters: long tmp_sect1: Param0 - * long tmp_sect2: Param1 + * Parameters: long tmp_sect1: Param0 + * long tmp_sect2: Param1 * - * Return: Code CMD_SUCCESS | - * BUSY | - * INVALID_SECTOR + * Return: Code CMD_SUCCESS | + * BUSY | + * INVALID_SECTOR *****************************************************************************/ uint32_t prepare_sectors(uint32_t tmp_sect1, uint32_t tmp_sect2) { @@ -254,23 +254,23 @@ uint32_t prepare_sectors(uint32_t tmp_sect1, uint32_t tmp_sect2) /****************************************************************************** - * Function: erase_sectors + * Function: erase_sectors * - * Description: This command is used to erase a sector or multiple sectors of on-chip Flash memory. The boot - * sector can not be erased by this command. To erase a single sector use the same "Start" and "End" - * sector numbers. - * Command code: 52 - * Param0: Start Sector Number - * Param1: End Sector Number: Should be greater than or equal to start sector number. - * Param2: System Clock Frequency (CCLK) in KHz. + * Description: This command is used to erase a sector or multiple sectors of on-chip Flash memory. The boot + * sector can not be erased by this command. To erase a single sector use the same "Start" and "End" + * sector numbers. + * Command code: 52 + * Param0: Start Sector Number + * Param1: End Sector Number: Should be greater than or equal to start sector number. + * Param2: System Clock Frequency (CCLK) in KHz. * - * Parameters: long tmp_sect1: Param0 - * long tmp_sect2: Param1 + * Parameters: long tmp_sect1: Param0 + * long tmp_sect2: Param1 * - * Return: Code CMD_SUCCESS | - * BUSY | - * SECTOR_NOT_PREPARED_FOR_WRITE_OPERATION | - * INVALID_SECTOR + * Return: Code CMD_SUCCESS | + * BUSY | + * SECTOR_NOT_PREPARED_FOR_WRITE_OPERATION | + * INVALID_SECTOR *****************************************************************************/ uint32_t erase_sectors(uint32_t tmp_sect1, uint32_t tmp_sect2) { @@ -279,28 +279,28 @@ uint32_t erase_sectors(uint32_t tmp_sect1, uint32_t tmp_sect2) /****************************************************************************** - * Function: compare + * Function: compare * - * Description: This command is used to compare the memory contents at two locations. compare result may not - * be correct when source or destination address contains any of the first 64 bytes starting - * from address zero. First 64 bytes can be re-mapped to RAM. - * Command Code: 56 - * Param0(DST): Starting Flash or RAM address from where data bytes are to be - * address should be a word boundary. - * Param1(SRC): Starting Flash or RAM address from where data bytes are to be - * address should be a word boundary. - * Param2: Number of bytes to be compared. Count should be in multiple of 4. + * Description: This command is used to compare the memory contents at two locations. compare result may not + * be correct when source or destination address contains any of the first 64 bytes starting + * from address zero. First 64 bytes can be re-mapped to RAM. + * Command Code: 56 + * Param0(DST): Starting Flash or RAM address from where data bytes are to be + * address should be a word boundary. + * Param1(SRC): Starting Flash or RAM address from where data bytes are to be + * address should be a word boundary. + * Param2: Number of bytes to be compared. Count should be in multiple of 4. * - * Parameters: long tmp_adr_dst - * long tmp_adr_src - * long tmp_size + * Parameters: long tmp_adr_dst + * long tmp_adr_src + * long tmp_size * - * Return: Code CMD_SUCCESS | - * COMPARE_ERROR | - * COUNT_ERROR (Byte count is not multiple of 4) | - * ADDR_ERROR | - * ADDR_NOT_MAPPED - * Result0: Offset of the first mismatch if the Status Code is COMPARE_ERROR. + * Return: Code CMD_SUCCESS | + * COMPARE_ERROR | + * COUNT_ERROR (Byte count is not multiple of 4) | + * ADDR_ERROR | + * ADDR_NOT_MAPPED + * Result0: Offset of the first mismatch if the Status Code is COMPARE_ERROR. *****************************************************************************/ uint32_t compare(uint32_t tmp_adr_dst, uint32_t tmp_adr_src, uint32_t tmp_size) { diff --git a/cpu/mc1322x/asm/asm.c b/cpu/mc1322x/asm/asm.c index ce8b4a7c51fb..b1e0f0728626 100644 --- a/cpu/mc1322x/asm/asm.c +++ b/cpu/mc1322x/asm/asm.c @@ -45,7 +45,7 @@ void asm_turn_off(void) * \param data A 128 bit block to encrypt/decrypt. Holds the encrypted/decrypted * data when finished \sa asm_data_t * \param ctr Structure holding the counter for the encryption/decrpytion. The user - * is responsible to provide a decend counter function. \sa asm_ctr_t + * is responsible to provide a decend counter function. \sa asm_ctr_t */ void asm_ctr_encryption_blocking(asm_keys_t *keys, asm_data_t *data, asm_ctr_t *ctr) { @@ -80,9 +80,9 @@ void asm_ctr_encryption_blocking(asm_keys_t *keys, asm_data_t *data, asm_ctr_t * /** * Usage of the MAC functions. - * 1. Initialize with the keys. ( asm_cbc_mac_init(keys) ) + * 1. Initialize with the keys. ( asm_cbc_mac_init(keys) ) * 2. Update for each 128 bit block of data ( asm_cbc_mac_update(data) ) - * 3. Finish and read the computed data ( asm_cbc_mac_finish(data) ) + * 3. Finish and read the computed data ( asm_cbc_mac_finish(data) ) */ /** @@ -145,9 +145,9 @@ void asm_ctr_cbc_mac_init(asm_keys_t *keys) /** * Updates a MAC stream and encrypts data. * \param data Structure holding 128 bits of data to use in MAC stream and to encrypt. - Holds the encrypted data when finished. \sa asm_data_t + Holds the encrypted data when finished. \sa asm_data_t * \param ctr Structure holding the counter for the encryption/decrpytion. The user - * is responsible to provide a decend counter function. \sa asm_ctr_t + * is responsible to provide a decend counter function. \sa asm_ctr_t */ void asm_ctr_cbc_mac_update(asm_data_t *data, asm_ctr_t *ctr) { diff --git a/cpu/mc1322x/asm/include/asm.h b/cpu/mc1322x/asm/include/asm.h index 150070ec7c1f..1b95a46be0a0 100644 --- a/cpu/mc1322x/asm/include/asm.h +++ b/cpu/mc1322x/asm/include/asm.h @@ -16,65 +16,65 @@ #define ASM_BASE_ADDRESS 0x80008000 struct ASM_struct { - uint32_t ENC_KEY_0; ///< Encryption key 0:31 - uint32_t ENC_KEY_1; ///< Encryption key 32:63 - uint32_t ENC_KEY_2; ///< Encryption key 64:95 - uint32_t ENC_KEY_3; ///< Encryption key 96:127 - uint32_t DATA_0; ///< Data 0:31 - uint32_t DATA_1; ///< Data 32:63 - uint32_t DATA_2; ///< Data 64:95 - uint32_t DATA_3; ///< Data 96:127 - uint32_t COUNTER_0; ///< Counter 0:31 - uint32_t COUNTER_1; ///< Counter 32:63 - uint32_t COUNTER_2; ///< Counter 64:95 - uint32_t COUNTER_3; ///< Counter 96:127 - uint32_t COUNTER_RESULT_0; ///< Result of CTR calculation 0:31 - uint32_t COUNTER_RESULT_1; ///< Result of CTR calculation 32:63 - uint32_t COUNTER_RESULT_2; ///< Result of CTR calculation 64:95 - uint32_t COUNTER_RESULT_3; ///< Result of CTR calculation 96:127 - uint32_t CBC_MAC_RESULT_0; ///< Result of CBC-MAC 0:31 - uint32_t CBC_MAC_RESULT_1; ///< Result of CBC-MAC 32:63 - uint32_t CBC_MAC_RESULT_2; ///< Result of CBC-MAC 64:95 - uint32_t CBC_MAC_RESULT_3; ///< Result of CBC-MAC 96:127 + uint32_t ENC_KEY_0; ///< Encryption key 0:31 + uint32_t ENC_KEY_1; ///< Encryption key 32:63 + uint32_t ENC_KEY_2; ///< Encryption key 64:95 + uint32_t ENC_KEY_3; ///< Encryption key 96:127 + uint32_t DATA_0; ///< Data 0:31 + uint32_t DATA_1; ///< Data 32:63 + uint32_t DATA_2; ///< Data 64:95 + uint32_t DATA_3; ///< Data 96:127 + uint32_t COUNTER_0; ///< Counter 0:31 + uint32_t COUNTER_1; ///< Counter 32:63 + uint32_t COUNTER_2; ///< Counter 64:95 + uint32_t COUNTER_3; ///< Counter 96:127 + uint32_t COUNTER_RESULT_0; ///< Result of CTR calculation 0:31 + uint32_t COUNTER_RESULT_1; ///< Result of CTR calculation 32:63 + uint32_t COUNTER_RESULT_2; ///< Result of CTR calculation 64:95 + uint32_t COUNTER_RESULT_3; ///< Result of CTR calculation 96:127 + uint32_t CBC_MAC_RESULT_0; ///< Result of CBC-MAC 0:31 + uint32_t CBC_MAC_RESULT_1; ///< Result of CBC-MAC 32:63 + uint32_t CBC_MAC_RESULT_2; ///< Result of CBC-MAC 64:95 + uint32_t CBC_MAC_RESULT_3; ///< Result of CBC-MAC 96:127 union { - uint32_t CONTROL_0; ///< Control 0 register + uint32_t CONTROL_0; ///< Control 0 register struct ASM_CONTROL_0 { uint32_t : 24; - uint32_t START: 1; ///< Start calculation - uint32_t CLEAR: 1; ///< Clear all configurations - uint32_t LOAD_MAC: 1; ///< Load an initila MAC value to continue + uint32_t START: 1; ///< Start calculation + uint32_t CLEAR: 1; ///< Clear all configurations + uint32_t LOAD_MAC: 1; ///< Load an initila MAC value to continue uint32_t : 4; - uint32_t CLEAR_IRQ; ///< Clear ASM IRQ bit + uint32_t CLEAR_IRQ; ///< Clear ASM IRQ bit } CONTROL_0_bits; }; union { - uint32_t CONTROL_1; ///< Control 1 register + uint32_t CONTROL_1; ///< Control 1 register struct ASM_CONTROL_1 { - uint32_t ON: 1; ///< Turn ASM module on + uint32_t ON: 1; ///< Turn ASM module on uint32_t NORMAL_MODE: 1;///< exit boot mode - uint32_t BYPASS: 1; ///< Data passes through unmodified + uint32_t BYPASS: 1; ///< Data passes through unmodified uint32_t : 21; - uint32_t CBC: 1; ///< enable CBC-MAC mode - uint32_t CTR: 1; ///< enable CTR mode - uint32_t SELF_TEST: 1; ///< switch to self test mode + uint32_t CBC: 1; ///< enable CBC-MAC mode + uint32_t CTR: 1; ///< enable CTR mode + uint32_t SELF_TEST: 1; ///< switch to self test mode uint32_t : 4; - uint32_t MASK_IRQ: 1; ///< disables the ASM IRQ + uint32_t MASK_IRQ: 1; ///< disables the ASM IRQ } CONTROL_1_bits; }; union { - uint32_t STATUS; ///< status register + uint32_t STATUS; ///< status register struct ASM_STATUS { uint32_t : 24; - uint32_t DONE: 1; ///< operation is done - uint32_t TEST_PASS: 1; ///< self test did pass + uint32_t DONE: 1; ///< operation is done + uint32_t TEST_PASS: 1; ///< self test did pass uint32_t : 6; } STATUS_bits; }; uint32_t reserved; - uint32_t CBC_MAC_0; ///< Result of MAC calculation 0:31 - uint32_t CBC_MAC_1; ///< Result of MAC calculation 32:63 - uint32_t CBC_MAC_2; ///< Result of MAC calculation 64:95 - uint32_t CBC_MAC_3; ///< Result of MAC calculation 96:127 + uint32_t CBC_MAC_0; ///< Result of MAC calculation 0:31 + uint32_t CBC_MAC_1; ///< Result of MAC calculation 32:63 + uint32_t CBC_MAC_2; ///< Result of MAC calculation 64:95 + uint32_t CBC_MAC_3; ///< Result of MAC calculation 96:127 }; static volatile struct ASM_struct *const ASM = (void *)(ASM_BASE_ADDRESS); diff --git a/cpu/mc1322x/include/cpu-conf.h b/cpu/mc1322x/include/cpu-conf.h index 1b851d944b01..8040b23eaef4 100644 --- a/cpu/mc1322x/include/cpu-conf.h +++ b/cpu/mc1322x/include/cpu-conf.h @@ -12,25 +12,25 @@ #define CPUCONF_H_ /** - * @ingroup conf - * @ingroup mc1322x + * @ingroup conf + * @ingroup mc1322x * * @{ */ /** * @file - * @brief MC1322X CPUconfiguration + * @brief MC1322X CPUconfiguration * - * @author Oliver Hahm + * @author Oliver Hahm */ /** * @name Stdlib configuration * @{ */ -#define __FOPEN_MAX__ 4 -#define __FILENAME_MAX__ 12 +#define __FOPEN_MAX__ 4 +#define __FILENAME_MAX__ 12 /** @} */ /** @@ -41,20 +41,20 @@ #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) diff --git a/cpu/mc1322x/include/cpu.h b/cpu/mc1322x/include/cpu.h index 66cf3b5edbf0..6569497bcc0b 100644 --- a/cpu/mc1322x/include/cpu.h +++ b/cpu/mc1322x/include/cpu.h @@ -16,8 +16,8 @@ #define CPU_H /** - * @defgroup mc1322x Freescale mc1322x - * @ingroup cpu + * @defgroup mc1322x Freescale mc1322x + * @ingroup cpu * @{ */ @@ -25,7 +25,7 @@ #include "arm_cpu.h" #include "mc1322x.h" -extern uintptr_t __stack_start; ///< end of user stack memory space +extern uintptr_t __stack_start; ///< end of user stack memory space bool install_irq(int int_number, void *handler_addr, int priority); /** @} */ diff --git a/cpu/mc1322x/include/mc1322x.h b/cpu/mc1322x/include/mc1322x.h index 94951c61c248..899191c29cb6 100644 --- a/cpu/mc1322x/include/mc1322x.h +++ b/cpu/mc1322x/include/mc1322x.h @@ -21,180 +21,180 @@ /* Structure-based CRM access */ struct CRM_struct { - union { - uint32_t SYS_CNTL; - struct CRM_SYS_CNTL { - uint32_t PWR_SOURCE:2; - uint32_t PADS_1P8V_SEL:1; - uint32_t :1; - uint32_t JTAG_SECU_OFF:1; - uint32_t XTAL32_EXISTS:1; - uint32_t :2; - uint32_t XTAL_CLKDIV:6; - uint32_t :18; - } SYS_CNTLbits; - }; - union { - uint32_t WU_CNTL; - struct CRM_WU_CNTL { - uint32_t TIMER_WU_EN:1; - uint32_t RTC_WU_EN:1; - uint32_t HOST_WAKE:1; - uint32_t AUTO_ADC:1; - uint32_t EXT_WU_EN:4; - uint32_t EXT_WU_EDGE:4; - uint32_t EXT_WU_POL:4; - uint32_t TIMER_WU_IEN:1; - uint32_t RTC_WU_IEN:1; - uint32_t :2; - uint32_t EXT_WU_IEN:4; - uint32_t :4; - uint32_t EXT_OUT_POL:4; - } WU_CNTLbits; - }; - union { - uint32_t SLEEP_CNTL; - struct CRM_SLEEP_CNTL { - uint32_t HIB:1; - uint32_t DOZE:1; - uint32_t :2; - uint32_t RAM_RET:2; - uint32_t MCU_RET:1; - uint32_t DIG_PAD_EN:1; - uint32_t :24; - } SLEEP_CNTLbits; - }; - union { - uint32_t BS_CNTL; - struct CRM_BS_CNTL { - uint32_t BS_EN:1; - uint32_t WAIT4IRQ:1; - uint32_t BS_MAN_EN:1; - uint32_t :2; - uint32_t ARM_OFF_TIME:6; - uint32_t :18; - } BS_CNTLbits; - }; - union { - uint32_t COP_CNTL; - struct CRM_COP_CNTL { - uint32_t COP_EN:1; - uint32_t COP_OUT:1; - uint32_t COP_WP:1; - uint32_t :5; - uint32_t COP_TIMEOUT:7; - uint32_t :1; - uint32_t COP_COUNT:7; - uint32_t :9; - } COP_CNTLbits; - }; - uint32_t COP_SERVICE; - union { - uint32_t STATUS; - struct CRM_STATUS { - uint32_t SLEEP_SYNC:1; - uint32_t HIB_WU_EVT:1; - uint32_t DOZE_WU_EVT:1; - uint32_t RTC_WU_EVT:1; - uint32_t EXT_WU_EVT:4; - uint32_t :1; - uint32_t CAL_DONE:1; - uint32_t COP_EVT:1; - uint32_t :6; - uint32_t VREG_BUCK_RDY:1; - uint32_t VREG_1P8V_RDY:1; - uint32_t VREG_1P5V_RDY:1; - uint32_t :12; - } STATUSbits; - }; - union { - uint32_t MOD_STATUS; - struct CRM_MOD_STATUS { - uint32_t ARM_EN:1; - uint32_t MACA_EN:1; - uint32_t ASM_EN:1; - uint32_t SPI_EN:1; - uint32_t GPIO_EN:1; - uint32_t UART1_EN:1; - uint32_t UART2_EN:1; - uint32_t TMR_EN:1; - uint32_t RIF_EN:1; - uint32_t I2C_EN:1; - uint32_t SSI_EN:1; - uint32_t SPIF_EN:1; - uint32_t ADC_EN:1; - uint32_t :1; - uint32_t JTA_EN:1; - uint32_t NEX_EN:1; - uint32_t :1; - uint32_t AIM_EN:1; - uint32_t :14; - } MOD_STATUSbits; - }; - uint32_t WU_COUNT; - uint32_t WU_TIMEOUT; - uint32_t RTC_COUNT; - uint32_t RTC_TIMEOUT; - uint32_t reserved1; - union { - uint32_t CAL_CNTL; - struct CRM_CAL_CNTL { - uint32_t CAL_TIMEOUT:16; - uint32_t CAL_EN:1; - uint32_t CAL_IEN:1; - uint32_t :14; - } CAL_CNTLbits; - }; - uint32_t CAL_COUNT; - union { - uint32_t RINGOSC_CNTL; - struct CRM_RINGOSC_CNTL { - uint32_t ROSC_EN:1; - uint32_t :3; - uint32_t ROSC_FTUNE:5; - uint32_t ROSC_CTUNE:4; - uint32_t :19; - } RINGOSC_CNTLbits; - }; - union { - uint32_t XTAL_CNTL; - struct CRM_XTAL_CNTL { - uint32_t :8; - uint32_t XTAL_IBIAS_SEL:4; - uint32_t :4; - uint32_t XTAL_FTUNE:5; - uint32_t XTAL_CTUNE:5; - uint32_t :6; - } XTAL_CNTLbits; - }; - union { - uint32_t XTAL32_CNTL; - struct CRM_XTAL32_CNTL { - uint32_t XTAL32_EN:1; - uint32_t :3; - uint32_t XTAL32_GAIN:2; - uint32_t :26; - } XTAL32_CNTLbits; - }; - union { - uint32_t VREG_CNTL; - struct CRM_VREG_CNTL { - uint32_t BUCK_EN:1; - uint32_t BUCK_SYNC_REC_EN:1; - uint32_t BUCK_BYPASS_EN:1; - uint32_t VREG_1P5V_EN:2; - uint32_t VREG_1P5V_SEL:2; - uint32_t VREG_1P8V_EN:1; - uint32_t BUCK_CLKDIV:4; - uint32_t :20; - } VREG_CNTLbits; - }; - uint32_t reserved2; - uint32_t SW_RST; - uint32_t reserved3; - uint32_t reserved4; - uint32_t reserved5; - uint32_t reserved6; + union { + uint32_t SYS_CNTL; + struct CRM_SYS_CNTL { + uint32_t PWR_SOURCE:2; + uint32_t PADS_1P8V_SEL:1; + uint32_t :1; + uint32_t JTAG_SECU_OFF:1; + uint32_t XTAL32_EXISTS:1; + uint32_t :2; + uint32_t XTAL_CLKDIV:6; + uint32_t :18; + } SYS_CNTLbits; + }; + union { + uint32_t WU_CNTL; + struct CRM_WU_CNTL { + uint32_t TIMER_WU_EN:1; + uint32_t RTC_WU_EN:1; + uint32_t HOST_WAKE:1; + uint32_t AUTO_ADC:1; + uint32_t EXT_WU_EN:4; + uint32_t EXT_WU_EDGE:4; + uint32_t EXT_WU_POL:4; + uint32_t TIMER_WU_IEN:1; + uint32_t RTC_WU_IEN:1; + uint32_t :2; + uint32_t EXT_WU_IEN:4; + uint32_t :4; + uint32_t EXT_OUT_POL:4; + } WU_CNTLbits; + }; + union { + uint32_t SLEEP_CNTL; + struct CRM_SLEEP_CNTL { + uint32_t HIB:1; + uint32_t DOZE:1; + uint32_t :2; + uint32_t RAM_RET:2; + uint32_t MCU_RET:1; + uint32_t DIG_PAD_EN:1; + uint32_t :24; + } SLEEP_CNTLbits; + }; + union { + uint32_t BS_CNTL; + struct CRM_BS_CNTL { + uint32_t BS_EN:1; + uint32_t WAIT4IRQ:1; + uint32_t BS_MAN_EN:1; + uint32_t :2; + uint32_t ARM_OFF_TIME:6; + uint32_t :18; + } BS_CNTLbits; + }; + union { + uint32_t COP_CNTL; + struct CRM_COP_CNTL { + uint32_t COP_EN:1; + uint32_t COP_OUT:1; + uint32_t COP_WP:1; + uint32_t :5; + uint32_t COP_TIMEOUT:7; + uint32_t :1; + uint32_t COP_COUNT:7; + uint32_t :9; + } COP_CNTLbits; + }; + uint32_t COP_SERVICE; + union { + uint32_t STATUS; + struct CRM_STATUS { + uint32_t SLEEP_SYNC:1; + uint32_t HIB_WU_EVT:1; + uint32_t DOZE_WU_EVT:1; + uint32_t RTC_WU_EVT:1; + uint32_t EXT_WU_EVT:4; + uint32_t :1; + uint32_t CAL_DONE:1; + uint32_t COP_EVT:1; + uint32_t :6; + uint32_t VREG_BUCK_RDY:1; + uint32_t VREG_1P8V_RDY:1; + uint32_t VREG_1P5V_RDY:1; + uint32_t :12; + } STATUSbits; + }; + union { + uint32_t MOD_STATUS; + struct CRM_MOD_STATUS { + uint32_t ARM_EN:1; + uint32_t MACA_EN:1; + uint32_t ASM_EN:1; + uint32_t SPI_EN:1; + uint32_t GPIO_EN:1; + uint32_t UART1_EN:1; + uint32_t UART2_EN:1; + uint32_t TMR_EN:1; + uint32_t RIF_EN:1; + uint32_t I2C_EN:1; + uint32_t SSI_EN:1; + uint32_t SPIF_EN:1; + uint32_t ADC_EN:1; + uint32_t :1; + uint32_t JTA_EN:1; + uint32_t NEX_EN:1; + uint32_t :1; + uint32_t AIM_EN:1; + uint32_t :14; + } MOD_STATUSbits; + }; + uint32_t WU_COUNT; + uint32_t WU_TIMEOUT; + uint32_t RTC_COUNT; + uint32_t RTC_TIMEOUT; + uint32_t reserved1; + union { + uint32_t CAL_CNTL; + struct CRM_CAL_CNTL { + uint32_t CAL_TIMEOUT:16; + uint32_t CAL_EN:1; + uint32_t CAL_IEN:1; + uint32_t :14; + } CAL_CNTLbits; + }; + uint32_t CAL_COUNT; + union { + uint32_t RINGOSC_CNTL; + struct CRM_RINGOSC_CNTL { + uint32_t ROSC_EN:1; + uint32_t :3; + uint32_t ROSC_FTUNE:5; + uint32_t ROSC_CTUNE:4; + uint32_t :19; + } RINGOSC_CNTLbits; + }; + union { + uint32_t XTAL_CNTL; + struct CRM_XTAL_CNTL { + uint32_t :8; + uint32_t XTAL_IBIAS_SEL:4; + uint32_t :4; + uint32_t XTAL_FTUNE:5; + uint32_t XTAL_CTUNE:5; + uint32_t :6; + } XTAL_CNTLbits; + }; + union { + uint32_t XTAL32_CNTL; + struct CRM_XTAL32_CNTL { + uint32_t XTAL32_EN:1; + uint32_t :3; + uint32_t XTAL32_GAIN:2; + uint32_t :26; + } XTAL32_CNTLbits; + }; + union { + uint32_t VREG_CNTL; + struct CRM_VREG_CNTL { + uint32_t BUCK_EN:1; + uint32_t BUCK_SYNC_REC_EN:1; + uint32_t BUCK_BYPASS_EN:1; + uint32_t VREG_1P5V_EN:2; + uint32_t VREG_1P5V_SEL:2; + uint32_t VREG_1P8V_EN:1; + uint32_t BUCK_CLKDIV:4; + uint32_t :20; + } VREG_CNTLbits; + }; + uint32_t reserved2; + uint32_t SW_RST; + uint32_t reserved3; + uint32_t reserved4; + uint32_t reserved5; + uint32_t reserved6; }; static volatile struct CRM_struct * const CRM = (void*) (CRM_BASE); @@ -212,81 +212,81 @@ static volatile struct CRM_struct * const CRM = (void*) (CRM_BASE); #define TMR3_BASE (TMR_BASE + TMR_OFFSET*3) struct TMR_struct { - uint16_t COMP1; - uint16_t COMP2; - uint16_t CAPT; - uint16_t LOAD; - uint16_t HOLD; - uint16_t CNTR; - union { - uint16_t CTRL; - struct TMR_CTRL { - uint16_t OUTPUT_MODE:3; - uint16_t CO_INIT:1; - uint16_t DIR:1; - uint16_t LENGTH:1; - uint16_t ONCE:1; - uint16_t SECONDARY_CNT_SOURCE:2; - uint16_t PRIMARY_CNT_SOURCE:4; - uint16_t COUNT_MODE:3; - } CTRLbits; - }; - union { - uint16_t SCTRL; - struct TMR_SCTRL { - uint16_t OEN:1; - uint16_t OPS:1; - uint16_t FORCE:1; - uint16_t VAL:1; - uint16_t EEOF:1; - uint16_t MSTR:1; - uint16_t CAPTURE_MODE:2; - uint16_t INPUT:1; - uint16_t IPS:1; - uint16_t IEFIE:1; - uint16_t IEF:1; - uint16_t TOFIE:1; - uint16_t TOF:1; - uint16_t TCFIE:1; - uint16_t TCF:1; - } SCTRLbits; - }; - uint16_t CMPLD1; - uint16_t CMPLD2; - union { - uint16_t CSCTRL; - struct TMR_CSCTRL { - uint16_t CL1:2; - uint16_t CL2:2; - uint16_t TCF1:1; - uint16_t TCF2:1; - uint16_t TCF1EN:1; - uint16_t TCF2EN:1; - uint16_t :5; - uint16_t FILT_EN:1; - uint16_t DBG_EN:2; - } CSCTRLbits; - }; - - uint16_t reserved[4]; - - union { - uint16_t ENBL; - struct TMR_ENBL { - union { - struct { - uint16_t ENBL:4; - }; - struct { - uint16_t ENBL3:1; - uint16_t ENBL2:1; - uint16_t ENBL1:1; - uint16_t ENBL0:1; - }; - }; - uint16_t :12; - } ENBLbits; - }; + uint16_t COMP1; + uint16_t COMP2; + uint16_t CAPT; + uint16_t LOAD; + uint16_t HOLD; + uint16_t CNTR; + union { + uint16_t CTRL; + struct TMR_CTRL { + uint16_t OUTPUT_MODE:3; + uint16_t CO_INIT:1; + uint16_t DIR:1; + uint16_t LENGTH:1; + uint16_t ONCE:1; + uint16_t SECONDARY_CNT_SOURCE:2; + uint16_t PRIMARY_CNT_SOURCE:4; + uint16_t COUNT_MODE:3; + } CTRLbits; + }; + union { + uint16_t SCTRL; + struct TMR_SCTRL { + uint16_t OEN:1; + uint16_t OPS:1; + uint16_t FORCE:1; + uint16_t VAL:1; + uint16_t EEOF:1; + uint16_t MSTR:1; + uint16_t CAPTURE_MODE:2; + uint16_t INPUT:1; + uint16_t IPS:1; + uint16_t IEFIE:1; + uint16_t IEF:1; + uint16_t TOFIE:1; + uint16_t TOF:1; + uint16_t TCFIE:1; + uint16_t TCF:1; + } SCTRLbits; + }; + uint16_t CMPLD1; + uint16_t CMPLD2; + union { + uint16_t CSCTRL; + struct TMR_CSCTRL { + uint16_t CL1:2; + uint16_t CL2:2; + uint16_t TCF1:1; + uint16_t TCF2:1; + uint16_t TCF1EN:1; + uint16_t TCF2EN:1; + uint16_t :5; + uint16_t FILT_EN:1; + uint16_t DBG_EN:2; + } CSCTRLbits; + }; + + uint16_t reserved[4]; + + union { + uint16_t ENBL; + struct TMR_ENBL { + union { + struct { + uint16_t ENBL:4; + }; + struct { + uint16_t ENBL3:1; + uint16_t ENBL2:1; + uint16_t ENBL1:1; + uint16_t ENBL0:1; + }; + }; + uint16_t :12; + } ENBLbits; + }; }; static volatile struct TMR_struct * const TMR0 = (void *) (TMR0_BASE); diff --git a/cpu/msp430-common/include/cpu-conf.h b/cpu/msp430-common/include/cpu-conf.h index 64de02e7f2e0..3ce1ba1ea5f0 100644 --- a/cpu/msp430-common/include/cpu-conf.h +++ b/cpu/msp430-common/include/cpu-conf.h @@ -21,7 +21,7 @@ See the file LICENSE in the top level directory for more details. #define KERNEL_CONF_STACKSIZE_PRINTF_FLOAT (KERNEL_CONF_STACKSIZE_PRINTF) #ifndef KERNEL_CONF_STACKSIZE_DEFAULT -#define KERNEL_CONF_STACKSIZE_DEFAULT (256) +#define KERNEL_CONF_STACKSIZE_DEFAULT (256) #endif #define KERNEL_CONF_STACKSIZE_IDLE (96) diff --git a/cpu/sam3x8e/include/system_sam3xa.h b/cpu/sam3x8e/include/system_sam3xa.h index 89dad6eecbf6..b703c8ead600 100644 --- a/cpu/sam3x8e/include/system_sam3xa.h +++ b/cpu/sam3x8e/include/system_sam3xa.h @@ -50,7 +50,7 @@ extern "C" { #include -extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */ +extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */ /** * @brief Setup the microcontroller system. diff --git a/cpu/stm32f0/include/stm32f051x8.h b/cpu/stm32f0/include/stm32f051x8.h index 98199b2996ac..b43a547ead63 100644 --- a/cpu/stm32f0/include/stm32f051x8.h +++ b/cpu/stm32f0/include/stm32f051x8.h @@ -308,8 +308,8 @@ typedef struct uint16_t RESERVED1; /*!< Reserved, 0x12 */ __IO uint16_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ uint16_t RESERVED2; /*!< Reserved, 0x16 */ - __IO uint16_t BSRRL; /*!< GPIO port bit set/reset low register, Address offset: 0x18 */ - __IO uint16_t BSRRH; /*!< GPIO port bit set/reset high register, Address offset: 0x1A */ + __IO uint16_t BSRRL; /*!< GPIO port bit set/reset low register, Address offset: 0x18 */ + __IO uint16_t BSRRH; /*!< GPIO port bit set/reset high register, Address offset: 0x1A */ __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ __IO uint32_t AFR[2]; /*!< GPIO alternate function low register, Address offset: 0x20-0x24 */ __IO uint16_t BRR; /*!< GPIO bit reset register, Address offset: 0x28 */ diff --git a/cpu/stm32f4/include/stm32f407xx.h b/cpu/stm32f4/include/stm32f407xx.h index a6dcb99dff7c..c2ac498525a5 100644 --- a/cpu/stm32f4/include/stm32f407xx.h +++ b/cpu/stm32f4/include/stm32f407xx.h @@ -6919,7 +6919,7 @@ USB_OTG_HostChannelTypeDef; /******************************************************************************/ /* */ -/* USB_OTG */ +/* USB_OTG */ /* */ /******************************************************************************/ /******************** Bit definition forUSB_OTG_GOTGCTL register ********************/