diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/CortexM3.h b/Demo/CORTEX_LPC1768_GCC_Rowley/CortexM3.h new file mode 100644 index 000000000..fa9544cef --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/CortexM3.h @@ -0,0 +1,149 @@ +/******************************************************************************/ +/* CortexM3.H: Header file for Cortex-M3 */ +/******************************************************************************/ +/* This file is part of the uVision/ARM development tools. */ +/* Copyright (c) 2008 Keil Software. All rights reserved. */ +/******************************************************************************/ + +#ifndef __CortexM3_H +#define __CortexM3_H + + +#define REG8(x) (*((volatile unsigned char *)(x))) +#define REG16(x) (*((volatile unsigned short *)(x))) +#define REG32(x) (*((volatile unsigned long *)(x))) + + +/* NVIC Registers */ +#define NVIC_INT_TYPE REG32(0xE000E004) +#define NVIC_ST_CTRL REG32(0xE000E010) +#define NVIC_ST_RELOAD REG32(0xE000E014) +#define NVIC_ST_CURRENT REG32(0xE000E018) +#define NVIC_ST_CALIB REG32(0xE000E01C) +#define NVIC_ENABLE0 REG32(0xE000E100) +#define NVIC_ENABLE1 REG32(0xE000E104) +#define NVIC_ENABLE2 REG32(0xE000E108) +#define NVIC_ENABLE3 REG32(0xE000E10C) +#define NVIC_ENABLE4 REG32(0xE000E110) +#define NVIC_ENABLE5 REG32(0xE000E114) +#define NVIC_ENABLE6 REG32(0xE000E118) +#define NVIC_ENABLE7 REG32(0xE000E11C) +#define NVIC_DISABLE0 REG32(0xE000E180) +#define NVIC_DISABLE1 REG32(0xE000E184) +#define NVIC_DISABLE2 REG32(0xE000E188) +#define NVIC_DISABLE3 REG32(0xE000E18C) +#define NVIC_DISABLE4 REG32(0xE000E190) +#define NVIC_DISABLE5 REG32(0xE000E194) +#define NVIC_DISABLE6 REG32(0xE000E198) +#define NVIC_DISABLE7 REG32(0xE000E19C) +#define NVIC_PEND0 REG32(0xE000E200) +#define NVIC_PEND1 REG32(0xE000E204) +#define NVIC_PEND2 REG32(0xE000E208) +#define NVIC_PEND3 REG32(0xE000E20C) +#define NVIC_PEND4 REG32(0xE000E210) +#define NVIC_PEND5 REG32(0xE000E214) +#define NVIC_PEND6 REG32(0xE000E218) +#define NVIC_PEND7 REG32(0xE000E21C) +#define NVIC_UNPEND0 REG32(0xE000E280) +#define NVIC_UNPEND1 REG32(0xE000E284) +#define NVIC_UNPEND2 REG32(0xE000E288) +#define NVIC_UNPEND3 REG32(0xE000E28C) +#define NVIC_UNPEND4 REG32(0xE000E290) +#define NVIC_UNPEND5 REG32(0xE000E294) +#define NVIC_UNPEND6 REG32(0xE000E298) +#define NVIC_UNPEND7 REG32(0xE000E29C) +#define NVIC_ACTIVE0 REG32(0xE000E300) +#define NVIC_ACTIVE1 REG32(0xE000E304) +#define NVIC_ACTIVE2 REG32(0xE000E308) +#define NVIC_ACTIVE3 REG32(0xE000E30C) +#define NVIC_ACTIVE4 REG32(0xE000E310) +#define NVIC_ACTIVE5 REG32(0xE000E314) +#define NVIC_ACTIVE6 REG32(0xE000E318) +#define NVIC_ACTIVE7 REG32(0xE000E31C) +#define NVIC_PRI0 REG32(0xE000E400) +#define NVIC_PRI1 REG32(0xE000E404) +#define NVIC_PRI2 REG32(0xE000E408) +#define NVIC_PRI3 REG32(0xE000E40C) +#define NVIC_PRI4 REG32(0xE000E410) +#define NVIC_PRI5 REG32(0xE000E414) +#define NVIC_PRI6 REG32(0xE000E418) +#define NVIC_PRI7 REG32(0xE000E41C) +#define NVIC_PRI8 REG32(0xE000E420) +#define NVIC_PRI9 REG32(0xE000E424) +#define NVIC_PRI10 REG32(0xE000E428) +#define NVIC_PRI11 REG32(0xE000E42C) +#define NVIC_PRI12 REG32(0xE000E430) +#define NVIC_PRI13 REG32(0xE000E434) +#define NVIC_PRI14 REG32(0xE000E438) +#define NVIC_PRI15 REG32(0xE000E43C) +#define NVIC_PRI16 REG32(0xE000E440) +#define NVIC_PRI17 REG32(0xE000E444) +#define NVIC_PRI18 REG32(0xE000E448) +#define NVIC_PRI19 REG32(0xE000E44C) +#define NVIC_PRI20 REG32(0xE000E450) +#define NVIC_PRI21 REG32(0xE000E454) +#define NVIC_PRI22 REG32(0xE000E458) +#define NVIC_PRI23 REG32(0xE000E45C) +#define NVIC_PRI24 REG32(0xE000E460) +#define NVIC_PRI25 REG32(0xE000E464) +#define NVIC_PRI26 REG32(0xE000E468) +#define NVIC_PRI27 REG32(0xE000E46C) +#define NVIC_PRI28 REG32(0xE000E470) +#define NVIC_PRI29 REG32(0xE000E474) +#define NVIC_PRI30 REG32(0xE000E478) +#define NVIC_PRI31 REG32(0xE000E47C) +#define NVIC_PRI32 REG32(0xE000E480) +#define NVIC_PRI33 REG32(0xE000E484) +#define NVIC_PRI34 REG32(0xE000E488) +#define NVIC_PRI35 REG32(0xE000E48C) +#define NVIC_PRI36 REG32(0xE000E490) +#define NVIC_PRI37 REG32(0xE000E494) +#define NVIC_PRI38 REG32(0xE000E498) +#define NVIC_PRI39 REG32(0xE000E49C) +#define NVIC_PRI40 REG32(0xE000E4A0) +#define NVIC_PRI41 REG32(0xE000E4A4) +#define NVIC_PRI42 REG32(0xE000E4A8) +#define NVIC_PRI43 REG32(0xE000E4AC) +#define NVIC_PRI44 REG32(0xE000E4B0) +#define NVIC_PRI45 REG32(0xE000E4B4) +#define NVIC_PRI46 REG32(0xE000E4B8) +#define NVIC_PRI47 REG32(0xE000E4BC) +#define NVIC_PRI48 REG32(0xE000E4C0) +#define NVIC_PRI49 REG32(0xE000E4C4) +#define NVIC_PRI50 REG32(0xE000E4C8) +#define NVIC_PRI51 REG32(0xE000E4CC) +#define NVIC_PRI52 REG32(0xE000E4D0) +#define NVIC_PRI53 REG32(0xE000E4D4) +#define NVIC_PRI54 REG32(0xE000E4D8) +#define NVIC_PRI55 REG32(0xE000E4DC) +#define NVIC_PRI56 REG32(0xE000E4E0) +#define NVIC_PRI57 REG32(0xE000E4E4) +#define NVIC_PRI58 REG32(0xE000E4E8) +#define NVIC_PRI59 REG32(0xE000E4EC) +#define NVIC_CPUID REG32(0xE000ED00) +#define NVIC_INT_CTRL REG32(0xE000ED04) +#define NVIC_VECT_TABLE REG32(0xE000ED08) +#define NVIC_AP_INT_RST REG32(0xE000ED0C) +#define NVIC_SYS_CTRL REG32(0xE000ED10) +#define NVIC_CFG_CTRL REG32(0xE000ED14) +#define NVIC_SYS_H_PRI1 REG32(0xE000ED18) +#define NVIC_SYS_H_PRI2 REG32(0xE000ED1C) +#define NVIC_SYS_H_PRI3 REG32(0xE000ED20) +#define NVIC_SYS_H_CTRL REG32(0xE000ED24) +#define NVIC_FAULT_STA REG32(0xE000ED28) +#define NVIC_HARD_F_STA REG32(0xE000ED2C) +#define NVIC_DBG_F_STA REG32(0xE000ED30) +#define NVIC_MM_F_ADR REG32(0xE000ED34) +#define NVIC_BUS_F_ADR REG32(0xE000ED38) +#define NVIC_SW_TRIG REG32(0xE000EF00) + + +/* MPU Registers */ +#define MPU_TYPE REG32(0xE000ED90) +#define MPU_CTRL REG32(0xE000ED94) +#define MPU_RG_NUM REG32(0xE000ED98) +#define MPU_RG_ADDR REG32(0xE000ED9C) +#define MPU_RG_AT_SZ REG32(0xE000EDA0) + + +#endif // __CortexM3_H diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/FreeRTOSConfig.h b/Demo/CORTEX_LPC1768_GCC_Rowley/FreeRTOSConfig.h new file mode 100644 index 000000000..ea52ef075 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/FreeRTOSConfig.h @@ -0,0 +1,158 @@ +/* + FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry. + + This file is part of the FreeRTOS.org distribution. + + FreeRTOS.org is free software; you can redistribute it and/or modify it + under the terms of the GNU General Public License (version 2) as published + by the Free Software Foundation and modified by the FreeRTOS exception. + **NOTE** The exception to the GPL is included to allow you to distribute a + combined work that includes FreeRTOS.org without being obliged to provide + the source code for any proprietary components. Alternative commercial + license and support terms are also available upon request. See the + licensing section of http://www.FreeRTOS.org for full details. + + FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. + + You should have received a copy of the GNU General Public License along + with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 + Temple Place, Suite 330, Boston, MA 02111-1307 USA. + + + *************************************************************************** + * * + * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * + * * + * This is a concise, step by step, 'hands on' guide that describes both * + * general multitasking concepts and FreeRTOS specifics. It presents and * + * explains numerous examples that are written using the FreeRTOS API. * + * Full source code for all the examples is provided in an accompanying * + * .zip file. * + * * + *************************************************************************** + + 1 tab == 4 spaces! + + Please ensure to read the configuration and relevant port sections of the + online documentation. + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef FREERTOS_CONFIG_H +#define FREERTOS_CONFIG_H + +#include "LPC17xx.h" +#include "LPC17xx_defs.h" + +/*----------------------------------------------------------- + * Application specific definitions. + * + * These definitions should be adjusted for your particular hardware and + * application requirements. + * + * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE + * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. + *----------------------------------------------------------*/ + +#define configUSE_PREEMPTION 1 +#define configUSE_IDLE_HOOK 0 +#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) +#define configUSE_TICK_HOOK 1 +#define configCPU_CLOCK_HZ ( ( unsigned portLONG ) 64000000 ) +#define configTICK_RATE_HZ ( ( portTickType ) 1000 ) +#define configMINIMAL_STACK_SIZE ( ( unsigned portSHORT ) 80 ) +#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 19 * 1024 ) ) +#define configMAX_TASK_NAME_LEN ( 12 ) +#define configUSE_TRACE_FACILITY 1 +#define configUSE_16_BIT_TICKS 0 +#define configIDLE_SHOULD_YIELD 0 +#define configUSE_CO_ROUTINES 0 +#define configUSE_MUTEXES 1 + +#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) + +#define configUSE_COUNTING_SEMAPHORES 0 +#define configUSE_ALTERNATIVE_API 0 +#define configCHECK_FOR_STACK_OVERFLOW 2 +#define configUSE_RECURSIVE_MUTEXES 1 +#define configQUEUE_REGISTRY_SIZE 10 +#define configGENERATE_RUN_TIME_STATS 1 + +/* Set the following definitions to 1 to include the API function, or zero +to exclude the API function. */ + +#define INCLUDE_vTaskPrioritySet 1 +#define INCLUDE_uxTaskPriorityGet 1 +#define INCLUDE_vTaskDelete 1 +#define INCLUDE_vTaskCleanUpResources 0 +#define INCLUDE_vTaskSuspend 1 +#define INCLUDE_vTaskDelayUntil 1 +#define INCLUDE_vTaskDelay 1 +#define INCLUDE_uxTaskGetStackHighWaterMark 1 + +/*----------------------------------------------------------- + * Ethernet configuration. + *-----------------------------------------------------------*/ + +/* MAC address configuration. */ +#define configMAC_ADDR0 0x00 +#define configMAC_ADDR1 0x12 +#define configMAC_ADDR2 0x13 +#define configMAC_ADDR3 0x10 +#define configMAC_ADDR4 0x15 +#define configMAC_ADDR5 0x11 + +/* IP address configuration. */ +#define configIP_ADDR0 192 +#define configIP_ADDR1 168 +#define configIP_ADDR2 0 +#define configIP_ADDR3 201 + +/* Netmask configuration. */ +#define configNET_MASK0 255 +#define configNET_MASK1 255 +#define configNET_MASK2 255 +#define configNET_MASK3 0 + +/* Use the system definition, if there is one */ +#ifdef __NVIC_PRIO_BITS + #define configPRIO_BITS __NVIC_PRIO_BITS +#else + #define configPRIO_BITS 5 /* 32 priority levels */ +#endif + +/* The lowest priority. */ +#define configKERNEL_INTERRUPT_PRIORITY ( 31 << (8 - configPRIO_BITS) ) +/* Priority 5, or 160 as only the top three bits are implemented. */ +#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( 5 << (8 - configPRIO_BITS) ) + + + + + +/*----------------------------------------------------------- + * Macros required to setup the timer for the run time stats. + *-----------------------------------------------------------*/ +extern void vConfigureTimerForRunTimeStats( void ); +#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() vConfigureTimerForRunTimeStats() +#define portGET_RUN_TIME_COUNTER_VALUE() T0TC + + +/* The structure that is passed on the xLCDQueue. Put here for convenience. */ +typedef struct +{ + char *pcMessage; +} xLCDMessage; + +#endif /* FREERTOS_CONFIG_H */ diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/LED.h b/Demo/CORTEX_LPC1768_GCC_Rowley/LED.h new file mode 100644 index 000000000..a4c6d8f81 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/LED.h @@ -0,0 +1,59 @@ +/* + FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry. + + This file is part of the FreeRTOS.org distribution. + + FreeRTOS.org is free software; you can redistribute it and/or modify it + under the terms of the GNU General Public License (version 2) as published + by the Free Software Foundation and modified by the FreeRTOS exception. + **NOTE** The exception to the GPL is included to allow you to distribute a + combined work that includes FreeRTOS.org without being obliged to provide + the source code for any proprietary components. Alternative commercial + license and support terms are also available upon request. See the + licensing section of http://www.FreeRTOS.org for full details. + + FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. + + You should have received a copy of the GNU General Public License along + with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 + Temple Place, Suite 330, Boston, MA 02111-1307 USA. + + + *************************************************************************** + * * + * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * + * * + * This is a concise, step by step, 'hands on' guide that describes both * + * general multitasking concepts and FreeRTOS specifics. It presents and * + * explains numerous examples that are written using the FreeRTOS API. * + * Full source code for all the examples is provided in an accompanying * + * .zip file. * + * * + *************************************************************************** + + 1 tab == 4 spaces! + + Please ensure to read the configuration and relevant port sections of the + online documentation. + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef LED_HH +#define LED_HH + +void vToggleLED( unsigned long ulLED ); +void vSetLEDState( unsigned long ulLED, long lState ); +long lGetLEDState( unsigned long ulLED ); + +#endif diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/LPC1700_Startup.s b/Demo/CORTEX_LPC1768_GCC_Rowley/LPC1700_Startup.s new file mode 100644 index 000000000..5c7a94ea1 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/LPC1700_Startup.s @@ -0,0 +1,364 @@ +/***************************************************************************** + * Copyright (c) 2009 Rowley Associates Limited. * + * * + * This file may be distributed under the terms of the License Agreement * + * provided with this software. * + * * + * THIS FILE IS PROVIDED AS IS WITH NO WARRANTY OF ANY KIND, INCLUDING THE * + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. * + *****************************************************************************/ + +/***************************************************************************** + * Preprocessor Definitions + * ------------------------ + * + * STARTUP_FROM_RESET + * + * If defined, the program will startup from power-on/reset. If not defined + * the program will just loop endlessly from power-on/reset. + * + * This definition is not defined by default on this target because the + * debugger is unable to reset this target and maintain control of it over the + * JTAG interface. The advantage of doing this is that it allows the debugger + * to reset the CPU and run programs from a known reset CPU state on each run. + * It also acts as a safety net if you accidently download a program in FLASH + * that crashes and prevents the debugger from taking control over JTAG + * rendering the target unusable over JTAG. The obvious disadvantage of doing + * this is that your application will not startup without the debugger. + * + * We advise that on this target you keep STARTUP_FROM_RESET undefined whilst + * you are developing and only define STARTUP_FROM_RESET when development is + * complete.A + * + * + * CONFIGURE_USB + * + * If defined, the USB clock will be configured. + * + *****************************************************************************/ + +#include + +#if OSCILLATOR_CLOCK_FREQUENCY==12000000 + +#ifdef FULL_SPEED + +/* Fosc = 12Mhz, Fcco = 400Mhz, cclk = 100Mhz */ +#ifndef PLL0CFG_VAL +#define PLL0CFG_VAL ((49 << PLL0CFG_MSEL0_BIT) | (2 << PLL0CFG_NSEL0_BIT)) +#endif + +#ifndef CCLKCFG_VAL +#define CCLKCFG_VAL 3 +#endif + +#ifndef FLASHCFG_VAL +#define FLASHCFG_VAL 0x0000403A +#endif + +#else + +/* Fosc = 12Mhz, Fcco = 288Mhz, cclk = 72Mhz */ +#ifndef PLL0CFG_VAL +#define PLL0CFG_VAL ((11 << PLL0CFG_MSEL0_BIT) | (0 << PLL0CFG_NSEL0_BIT)) +#endif + +#ifndef CCLKCFG_VAL +#define CCLKCFG_VAL 3 +#endif + +#ifndef FLASHCFG_VAL +#define FLASHCFG_VAL 0x0000303A +#endif + +#endif + +/* Fosc = 12Mhz, Fcco = 192Mhz, usbclk = 48Mhz */ +#ifndef PLL1CFG_VAL +#define PLL1CFG_VAL ((3 << PLL1CFG_MSEL1_BIT) | (1 << PLL1CFG_PSEL1_BIT)) +#endif + +#endif + + .global reset_handler + + .syntax unified + + .section .vectors, "ax" + .code 16 + .align 0 + .global _vectors + +.macro DEFAULT_ISR_HANDLER name= + .thumb_func + .weak \name +\name: +1: b 1b /* endless loop */ +.endm + +.extern xPortPendSVHandler +.extern xPortSysTickHandler +.extern vPortSVCHandler +.extern vEMAC_ISR; + +_vectors: + .word __stack_end__ +#ifdef STARTUP_FROM_RESET + .word reset_handler +#else + .word reset_wait +#endif /* STARTUP_FROM_RESET */ + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 // Reserved + .word 0 // Reserved + .word 0 // Reserved + .word 0 // Reserved + .word vPortSVCHandler + .word DebugMon_Handler + .word 0 // Reserved + .word xPortPendSVHandler + .word xPortSysTickHandler + .word WDT_IRQHandler + .word TIMER0_IRQHandler + .word TIMER1_IRQHandler + .word TIMER2_IRQHandler + .word TIMER3_IRQHandler + .word UART0_IRQHandler + .word UART1_IRQHandler + .word UART2_IRQHandler + .word UART3_IRQHandler + .word PWM1_IRQHandler + .word I2C0_IRQHandler + .word I2C1_IRQHandler + .word I2C2_IRQHandler + .word SPI_IRQHandler + .word SSP0_IRQHandler + .word SSP1_IRQHandler + .word PLL0_IRQHandler + .word RTC_IRQHandler + .word EINT0_IRQHandler + .word EINT1_IRQHandler + .word EINT2_IRQHandler + .word EINT3_IRQHandler + .word ADC_IRQHandler + .word BOD_IRQHandler + .word USB_IRQHandler + .word CAN_IRQHandler + .word GPDMA_IRQHandler + .word I2S_IRQHandler + .word vEMAC_ISR + .word RIT_IRQHandler + .word MCPWM_IRQHandler + .word QEI_IRQHandler + .word PLL1_IRQHandler + .word USBACT_IRQHandler + .word CANACT_IRQHandler + + .section .init, "ax" + .thumb_func + + reset_handler: +#ifndef __FLASH_BUILD + /* If this is a RAM build, configure vector table offset register to point + to the RAM vector table. */ + ldr r0, =0xE000ED08 + ldr r1, =_vectors + str r1, [r0] +#endif + + ldr r0, =SC_BASE_ADDRESS + + /* Configure PLL0 Multiplier/Divider */ + ldr r1, [r0, #PLL0STAT_OFFSET] + tst r1, #PLL0STAT_PLLC0_STAT + beq 1f + + /* Disconnect PLL0 */ + ldr r1, =PLL0CON_PLLE0 + str r1, [r0, #PLL0CON_OFFSET] + mov r1, #0xAA + str r1, [r0, #PLL0FEED_OFFSET] + mov r1, #0x55 + str r1, [r0, #PLL0FEED_OFFSET] +1: + /* Disable PLL0 */ + ldr r1, =0 + str r1, [r0, #PLL0CON_OFFSET] + mov r1, #0xAA + str r1, [r0, #PLL0FEED_OFFSET] + mov r1, #0x55 + str r1, [r0, #PLL0FEED_OFFSET] + + /* Enable main oscillator */ + ldr r1, [r0, #SCS_OFFSET] + orr r1, r1, #SCS_OSCEN + str r1, [r0, #SCS_OFFSET] +1: + ldr r1, [r0, #SCS_OFFSET] + tst r1, #SCS_OSCSTAT + beq 1b + + /* Select main oscillator as the PLL0 clock source */ + ldr r1, =1 + str r1, [r0, #CLKSRCSEL_OFFSET] + + /* Set PLL0CFG */ + ldr r1, =PLL0CFG_VAL + str r1, [r0, #PLL0CFG_OFFSET] + mov r1, #0xAA + str r1, [r0, #PLL0FEED_OFFSET] + mov r1, #0x55 + str r1, [r0, #PLL0FEED_OFFSET] + + /* Enable PLL0 */ + ldr r1, =PLL0CON_PLLE0 + str r1, [r0, #PLL0CON_OFFSET] + mov r1, #0xAA + str r1, [r0, #PLL0FEED_OFFSET] + mov r1, #0x55 + str r1, [r0, #PLL0FEED_OFFSET] + +#ifdef CCLKCFG_VAL + /* Set the CPU clock divider */ + ldr r1, =CCLKCFG_VAL + str r1, [r0, #CCLKCFG_OFFSET] +#endif + +#ifdef FLASHCFG_VAL + /* Configure the FLASH accelerator */ + ldr r1, =FLASHCFG_VAL + str r1, [r0, #FLASHCFG_OFFSET] +#endif + + /* Wait for PLL0 to lock */ +1: + ldr r1, [r0, #PLL0STAT_OFFSET] + tst r1, #PLL0STAT_PLOCK0 + beq 1b + + /* PLL0 Locked, connect PLL as clock source */ + mov r1, #(PLL0CON_PLLE0 | PLL0CON_PLLC0) + str r1, [r0, #PLL0CON_OFFSET] + mov r1, #0xAA + str r1, [r0, #PLL0FEED_OFFSET] + mov r1, #0x55 + str r1, [r0, #PLL0FEED_OFFSET] + /* Wait for PLL0 to connect */ +1: + ldr r1, [r0, #PLL0STAT_OFFSET] + tst r1, #PLL0STAT_PLLC0_STAT + beq 1b + +#ifdef CONFIGURE_USB + /* Configure PLL1 Multiplier/Divider */ + ldr r1, [r0, #PLL1STAT_OFFSET] + tst r1, #PLL1STAT_PLLC1_STAT + beq 1f + + /* Disconnect PLL1 */ + ldr r1, =PLL1CON_PLLE1 + str r1, [r0, #PLL1CON_OFFSET] + mov r1, #0xAA + str r1, [r0, #PLL1FEED_OFFSET] + mov r1, #0x55 + str r1, [r0, #PLL1FEED_OFFSET] +1: + /* Disable PLL1 */ + ldr r1, =0 + str r1, [r0, #PLL1CON_OFFSET] + mov r1, #0xAA + str r1, [r0, #PLL1FEED_OFFSET] + mov r1, #0x55 + str r1, [r0, #PLL1FEED_OFFSET] + + /* Set PLL1CFG */ + ldr r1, =PLL1CFG_VAL + str r1, [r0, #PLL1CFG_OFFSET] + mov r1, #0xAA + str r1, [r0, #PLL1FEED_OFFSET] + mov r1, #0x55 + str r1, [r0, #PLL1FEED_OFFSET] + + /* Enable PLL1 */ + ldr r1, =PLL1CON_PLLE1 + str r1, [r0, #PLL1CON_OFFSET] + mov r1, #0xAA + str r1, [r0, #PLL1FEED_OFFSET] + mov r1, #0x55 + str r1, [r0, #PLL1FEED_OFFSET] + + /* Wait for PLL1 to lock */ +1: + ldr r1, [r0, #PLL1STAT_OFFSET] + tst r1, #PLL1STAT_PLOCK1 + beq 1b + + /* PLL1 Locked, connect PLL as clock source */ + mov r1, #(PLL1CON_PLLE1 | PLL1CON_PLLC1) + str r1, [r0, #PLL1CON_OFFSET] + mov r1, #0xAA + str r1, [r0, #PLL1FEED_OFFSET] + mov r1, #0x55 + str r1, [r0, #PLL1FEED_OFFSET] + /* Wait for PLL1 to connect */ +1: + ldr r1, [r0, #PLL1STAT_OFFSET] + tst r1, #PLL1STAT_PLLC1_STAT + beq 1b +#endif + + b _start + +DEFAULT_ISR_HANDLER NMI_Handler +DEFAULT_ISR_HANDLER HardFault_Handler +DEFAULT_ISR_HANDLER MemManage_Handler +DEFAULT_ISR_HANDLER BusFault_Handler +DEFAULT_ISR_HANDLER UsageFault_Handler +DEFAULT_ISR_HANDLER SVC_Handler +DEFAULT_ISR_HANDLER DebugMon_Handler +DEFAULT_ISR_HANDLER PendSV_Handler +DEFAULT_ISR_HANDLER SysTick_Handler +DEFAULT_ISR_HANDLER WDT_IRQHandler +DEFAULT_ISR_HANDLER TIMER0_IRQHandler +DEFAULT_ISR_HANDLER TIMER1_IRQHandler +DEFAULT_ISR_HANDLER TIMER2_IRQHandler +DEFAULT_ISR_HANDLER TIMER3_IRQHandler +DEFAULT_ISR_HANDLER UART0_IRQHandler +DEFAULT_ISR_HANDLER UART1_IRQHandler +DEFAULT_ISR_HANDLER UART2_IRQHandler +DEFAULT_ISR_HANDLER UART3_IRQHandler +DEFAULT_ISR_HANDLER PWM1_IRQHandler +DEFAULT_ISR_HANDLER I2C0_IRQHandler +DEFAULT_ISR_HANDLER I2C1_IRQHandler +DEFAULT_ISR_HANDLER I2C2_IRQHandler +DEFAULT_ISR_HANDLER SPI_IRQHandler +DEFAULT_ISR_HANDLER SSP0_IRQHandler +DEFAULT_ISR_HANDLER SSP1_IRQHandler +DEFAULT_ISR_HANDLER PLL0_IRQHandler +DEFAULT_ISR_HANDLER RTC_IRQHandler +DEFAULT_ISR_HANDLER EINT0_IRQHandler +DEFAULT_ISR_HANDLER EINT1_IRQHandler +DEFAULT_ISR_HANDLER EINT2_IRQHandler +DEFAULT_ISR_HANDLER EINT3_IRQHandler +DEFAULT_ISR_HANDLER ADC_IRQHandler +DEFAULT_ISR_HANDLER BOD_IRQHandler +DEFAULT_ISR_HANDLER USB_IRQHandler +DEFAULT_ISR_HANDLER CAN_IRQHandler +DEFAULT_ISR_HANDLER GPDMA_IRQHandler +DEFAULT_ISR_HANDLER I2S_IRQHandler +DEFAULT_ISR_HANDLER ENET_IRQHandler +DEFAULT_ISR_HANDLER RIT_IRQHandler +DEFAULT_ISR_HANDLER MCPWM_IRQHandler +DEFAULT_ISR_HANDLER QEI_IRQHandler +DEFAULT_ISR_HANDLER PLL1_IRQHandler +DEFAULT_ISR_HANDLER USBACT_IRQHandler +DEFAULT_ISR_HANDLER CANACT_IRQHandler + +#ifndef STARTUP_FROM_RESET +DEFAULT_ISR_HANDLER reset_wait +#endif /* STARTUP_FROM_RESET */ + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/LPC17xx.h b/Demo/CORTEX_LPC1768_GCC_Rowley/LPC17xx.h new file mode 100644 index 000000000..88acef3e4 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/LPC17xx.h @@ -0,0 +1,1302 @@ +#ifndef __LPC17xx_H +#define __LPC17xx_H + +#include "CortexM3.h" + + +/* System Control Block (SCB) includes: + Flash Accelerator Module, Clocking and Power Control, External Interrupts, + Reset, System Control and Status +*/ +#define SCB_BASE_ADDR 0x400FC000 + +/* Flash Accelerator Module */ +#define FLASHCTRL (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x000)) +#define FLASHTIM (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x004)) + +/* Phase Locked Loop (Main PLL0) */ +#define PLL0CON (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x080)) +#define PLL0CFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x084)) +#define PLL0STAT (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x088)) +#define PLL0FEED (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x08C)) + +/* Phase Locked Loop (USB PLL1) */ +#define PLL1CON (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0A0)) +#define PLL1CFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0A4)) +#define PLL1STAT (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0A8)) +#define PLL1FEED (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0AC)) + +/* Power Control */ +#define PCON (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0C0)) +#define PCONP (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0C4)) + +/* Clock Selection and Dividers */ +#define CCLKCFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x104)) +#define USBCLKCFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x108)) +#define CLKSRCSEL (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x10C)) +#define IRCTRIM (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1A4)) +#define PCLKSEL0 (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1A8)) +#define PCLKSEL1 (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1AC)) + +/* External Interrupts */ +#define EXTINT (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x140)) +#define EXTMODE (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x148)) +#define EXTPOLAR (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x14C)) + +/* Reset */ +#define RSIR (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x180)) + +/* System Controls and Status */ +#define SCS (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1A0)) + + +/* Pin Connect Block */ +#define PINCON_BASE_ADDR 0x4002C000 +#define PINSEL0 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x00)) +#define PINSEL1 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x04)) +#define PINSEL2 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x08)) +#define PINSEL3 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x0C)) +#define PINSEL4 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x10)) +#define PINSEL5 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x14)) +#define PINSEL6 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x18)) +#define PINSEL7 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x1C)) +#define PINSEL8 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x20)) +#define PINSEL9 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x24)) +#define PINSEL10 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x28)) + +#define PINMODE0 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x40)) +#define PINMODE1 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x44)) +#define PINMODE2 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x48)) +#define PINMODE3 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x4C)) +#define PINMODE4 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x50)) +#define PINMODE5 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x54)) +#define PINMODE6 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x58)) +#define PINMODE7 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x5C)) +#define PINMODE8 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x60)) +#define PINMODE9 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x64)) +#define PINMODE_OD0 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x68)) +#define PINMODE_OD1 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x6C)) +#define PINMODE_OD2 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x70)) +#define PINMODE_OD3 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x74)) +#define PINMODE_OD4 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x78)) + + +/* General Purpose Input/Output (GPIO) - Fast GPIO */ +// #define GPIO_BASE_ADDR 0x50014000 /* For the first silicon v0.00 */ +#define GPIO_BASE_ADDR 0x2009C000 /* For silicon v0.01 or newer */ +#define FIO0DIR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x00)) +#define FIO0MASK (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x10)) +#define FIO0PIN (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x14)) +#define FIO0SET (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x18)) +#define FIO0CLR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x1C)) + +#define FIO1DIR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x20)) +#define FIO1MASK (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x30)) +#define FIO1PIN (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x34)) +#define FIO1SET (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x38)) +#define FIO1CLR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x3C)) + +#define FIO2DIR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x40)) +#define FIO2MASK (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x50)) +#define FIO2PIN (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x54)) +#define FIO2SET (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x58)) +#define FIO2CLR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x5C)) + +#define FIO3DIR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x60)) +#define FIO3MASK (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x70)) +#define FIO3PIN (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x74)) +#define FIO3SET (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x78)) +#define FIO3CLR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x7C)) + +#define FIO4DIR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x80)) +#define FIO4MASK (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x90)) +#define FIO4PIN (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x94)) +#define FIO4SET (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x98)) +#define FIO4CLR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x9C)) + +/* FIOs can be accessed through WORD, HALF-WORD or BYTE. */ +#define FIO0DIR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x00)) +#define FIO1DIR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x20)) +#define FIO2DIR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x40)) +#define FIO3DIR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x60)) +#define FIO4DIR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x80)) + +#define FIO0DIR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x01)) +#define FIO1DIR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x21)) +#define FIO2DIR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x41)) +#define FIO3DIR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x61)) +#define FIO4DIR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x81)) + +#define FIO0DIR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x02)) +#define FIO1DIR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x22)) +#define FIO2DIR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x42)) +#define FIO3DIR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x62)) +#define FIO4DIR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x82)) + +#define FIO0DIR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x03)) +#define FIO1DIR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x23)) +#define FIO2DIR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x43)) +#define FIO3DIR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x63)) +#define FIO4DIR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x83)) + +#define FIO0DIRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x00)) +#define FIO1DIRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x20)) +#define FIO2DIRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x40)) +#define FIO3DIRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x60)) +#define FIO4DIRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x80)) + +#define FIO0DIRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x02)) +#define FIO1DIRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x22)) +#define FIO2DIRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x42)) +#define FIO3DIRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x62)) +#define FIO4DIRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x82)) + +#define FIO0MASK0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x10)) +#define FIO1MASK0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x30)) +#define FIO2MASK0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x40)) +#define FIO3MASK0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x50)) +#define FIO4MASK0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x90)) + +#define FIO0MASK1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x11)) +#define FIO1MASK1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x31)) +#define FIO2MASK1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x41)) +#define FIO3MASK1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x51)) +#define FIO4MASK1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x91)) + +#define FIO0MASK2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x12)) +#define FIO1MASK2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x32)) +#define FIO2MASK2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x42)) +#define FIO3MASK2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x52)) +#define FIO4MASK2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x92)) + +#define FIO0MASK3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x13)) +#define FIO1MASK3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x33)) +#define FIO2MASK3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x43)) +#define FIO3MASK3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x53)) +#define FIO4MASK3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x93)) + +#define FIO0MASKL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x10)) +#define FIO1MASKL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x30)) +#define FIO2MASKL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x40)) +#define FIO3MASKL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x50)) +#define FIO4MASKL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x90)) + +#define FIO0MASKU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x12)) +#define FIO1MASKU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x32)) +#define FIO2MASKU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x42)) +#define FIO3MASKU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x52)) +#define FIO4MASKU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x92)) + +#define FIO0PIN0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x14)) +#define FIO1PIN0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x34)) +#define FIO2PIN0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x44)) +#define FIO3PIN0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x54)) +#define FIO4PIN0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x94)) + +#define FIO0PIN1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x15)) +#define FIO1PIN1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x35)) +#define FIO2PIN1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x45)) +#define FIO3PIN1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x55)) +#define FIO4PIN1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x95)) + +#define FIO0PIN2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x16)) +#define FIO1PIN2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x36)) +#define FIO2PIN2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x46)) +#define FIO3PIN2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x56)) +#define FIO4PIN2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x96)) + +#define FIO0PIN3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x17)) +#define FIO1PIN3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x37)) +#define FIO2PIN3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x47)) +#define FIO3PIN3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x57)) +#define FIO4PIN3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x97)) + +#define FIO0PINL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x14)) +#define FIO1PINL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x34)) +#define FIO2PINL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x44)) +#define FIO3PINL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x54)) +#define FIO4PINL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x94)) + +#define FIO0PINU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x16)) +#define FIO1PINU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x36)) +#define FIO2PINU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x46)) +#define FIO3PINU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x56)) +#define FIO4PINU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x96)) + +#define FIO0SET0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x18)) +#define FIO1SET0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x38)) +#define FIO2SET0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x48)) +#define FIO3SET0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x58)) +#define FIO4SET0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x98)) + +#define FIO0SET1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x19)) +#define FIO1SET1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x39)) +#define FIO2SET1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x49)) +#define FIO3SET1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x59)) +#define FIO4SET1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x99)) + +#define FIO0SET2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x1A)) +#define FIO1SET2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x3A)) +#define FIO2SET2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x4A)) +#define FIO3SET2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x5A)) +#define FIO4SET2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x9A)) + +#define FIO0SET3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x1B)) +#define FIO1SET3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x3B)) +#define FIO2SET3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x4B)) +#define FIO3SET3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x5B)) +#define FIO4SET3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x9B)) + +#define FIO0SETL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x18)) +#define FIO1SETL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x38)) +#define FIO2SETL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x48)) +#define FIO3SETL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x58)) +#define FIO4SETL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x98)) + +#define FIO0SETU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x1A)) +#define FIO1SETU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x3A)) +#define FIO2SETU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x4A)) +#define FIO3SETU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x5A)) +#define FIO4SETU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x9A)) + +#define FIO0CLR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x1C)) +#define FIO1CLR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x3C)) +#define FIO2CLR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x4C)) +#define FIO3CLR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x5C)) +#define FIO4CLR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x9C)) + +#define FIO0CLR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x1D)) +#define FIO1CLR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x3D)) +#define FIO2CLR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x4D)) +#define FIO3CLR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x5D)) +#define FIO4CLR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x9D)) + +#define FIO0CLR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x1E)) +#define FIO1CLR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x3E)) +#define FIO2CLR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x4E)) +#define FIO3CLR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x5E)) +#define FIO4CLR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x9E)) + +#define FIO0CLR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x1F)) +#define FIO1CLR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x3F)) +#define FIO2CLR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x4F)) +#define FIO3CLR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x5F)) +#define FIO4CLR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x9F)) + +#define FIO0CLRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x1C)) +#define FIO1CLRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x3C)) +#define FIO2CLRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x4C)) +#define FIO3CLRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x5C)) +#define FIO4CLRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x9C)) + +#define FIO0CLRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x1E)) +#define FIO1CLRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x3E)) +#define FIO2CLRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x4E)) +#define FIO3CLRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x5E)) +#define FIO4CLRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x9E)) + +/* GPIO Interrupt Registers */ +#define GPIO_INT_BASE_ADDR 0x40028000 +#define IO0IntEnR (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0x90)) +#define IO0IntEnF (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0x94)) +#define IO0IntStatR (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0x84)) +#define IO0IntStatF (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0x88)) +#define IO0IntClr (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0x8C)) + +#define IO2IntEnR (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0xB0)) +#define IO2IntEnF (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0xB4)) +#define IO2IntStatR (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0xA4)) +#define IO2IntStatF (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0xA8)) +#define IO2IntClr (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0xAC)) + +#define IOIntStatus (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0x80)) + + +/* Timer 0 */ +#define TMR0_BASE_ADDR 0x40004000 +#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)) +#define T0PR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x0C)) +#define T0PC (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x10)) +#define T0MCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x14)) +#define T0MR0 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x18)) +#define T0MR1 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x1C)) +#define T0MR2 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x20)) +#define T0MR3 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x24)) +#define T0CCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x28)) +#define T0CR0 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x2C)) +#define T0CR1 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x30)) +#define T0CR2 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x34)) +#define T0CR3 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x38)) +#define T0EMR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x3C)) +#define T0CTCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x70)) + +/* Timer 1 */ +#define TMR1_BASE_ADDR 0x40008000 +#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)) +#define T1PR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x0C)) +#define T1PC (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x10)) +#define T1MCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x14)) +#define T1MR0 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x18)) +#define T1MR1 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x1C)) +#define T1MR2 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x20)) +#define T1MR3 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x24)) +#define T1CCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x28)) +#define T1CR0 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x2C)) +#define T1CR1 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x30)) +#define T1CR2 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x34)) +#define T1CR3 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x38)) +#define T1EMR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x3C)) +#define T1CTCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x70)) + +/* Timer 2 */ +#define TMR2_BASE_ADDR 0x40090000 +#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)) +#define T2PR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x0C)) +#define T2PC (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x10)) +#define T2MCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x14)) +#define T2MR0 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x18)) +#define T2MR1 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x1C)) +#define T2MR2 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x20)) +#define T2MR3 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x24)) +#define T2CCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x28)) +#define T2CR0 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x2C)) +#define T2CR1 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x30)) +#define T2CR2 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x34)) +#define T2CR3 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x38)) +#define T2EMR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x3C)) +#define T2CTCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x70)) + +/* Timer 3 */ +#define TMR3_BASE_ADDR 0x40094000 +#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)) +#define T3PR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x0C)) +#define T3PC (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x10)) +#define T3MCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x14)) +#define T3MR0 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x18)) +#define T3MR1 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x1C)) +#define T3MR2 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x20)) +#define T3MR3 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x24)) +#define T3CCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x28)) +#define T3CR0 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x2C)) +#define T3CR1 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x30)) +#define T3CR2 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x34)) +#define T3CR3 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x38)) +#define T3EMR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x3C)) +#define T3CTCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x70)) + + +/* Pulse Width Modulator (PWM) */ +#define PWM1_BASE_ADDR 0x40018000 +#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)) +#define PWM1PR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x0C)) +#define PWM1PC (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x10)) +#define PWM1MCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x14)) +#define PWM1MR0 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x18)) +#define PWM1MR1 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x1C)) +#define PWM1MR2 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x20)) +#define PWM1MR3 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x24)) +#define PWM1CCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x28)) +#define PWM1CR0 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x2C)) +#define PWM1CR1 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x30)) +#define PWM1CR2 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x34)) +#define PWM1CR3 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x38)) +#define PWM1MR4 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x40)) +#define PWM1MR5 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x44)) +#define PWM1MR6 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x48)) +#define PWM1PCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x4C)) +#define PWM1LER (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x50)) +#define PWM1CTCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x70)) + + +/* Universal Asynchronous Receiver Transmitter 0 (UART0) */ +#define UART0_BASE_ADDR 0x4000C000 +#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)) +#define U0DLM (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x04)) +#define U0IER (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x04)) +#define U0IIR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x08)) +#define U0FCR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x08)) +#define U0LCR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x0C)) +#define U0LSR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x14)) +#define U0SCR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x1C)) +#define U0ACR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x20)) +#define U0FDR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x28)) +#define U0TER (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x30)) +#define U0RS485CTRL (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x4C)) +#define U0ADRMATCH (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x50)) + +/* Universal Asynchronous Receiver Transmitter 1 (UART1) */ +#define UART1_BASE_ADDR 0x40010000 +#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)) +#define U1DLM (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x04)) +#define U1IER (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x04)) +#define U1IIR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x08)) +#define U1FCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x08)) +#define U1LCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x0C)) +#define U1MCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x10)) +#define U1LSR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x14)) +#define U1MSR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x18)) +#define U1SCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x1C)) +#define U1ACR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x20)) +#define U1FDR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x28)) +#define U1TER (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x30)) +#define U1RS485CTRL (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x4C)) +#define U1ADRMATCH (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x50)) +#define U1RS485DLY (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x54)) + +/* Universal Asynchronous Receiver Transmitter 2 (UART2) */ +#define UART2_BASE_ADDR 0x40098000 +#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)) +#define U2DLM (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x04)) +#define U2IER (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x04)) +#define U2IIR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x08)) +#define U2FCR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x08)) +#define U2LCR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x0C)) +#define U2LSR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x14)) +#define U2SCR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x1C)) +#define U2ACR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x20)) +#define U2FDR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x28)) +#define U2TER (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x30)) +#define U2RS485CTRL (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x4C)) +#define U2ADRMATCH (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x50)) + +/* Universal Asynchronous Receiver Transmitter 3 (UART3) */ +#define UART3_BASE_ADDR 0x4009C000 +#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)) +#define U3DLM (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x04)) +#define U3IER (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x04)) +#define U3IIR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x08)) +#define U3FCR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x08)) +#define U3LCR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x0C)) +#define U3LSR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x14)) +#define U3SCR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x1C)) +#define U3ACR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x20)) +#define U3ICR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x24)) +#define U3FDR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x28)) +#define U3TER (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x30)) +#define U3RS485CTRL (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x4C)) +#define U3ADRMATCH (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x50)) + + +/* SPI0 (Serial Peripheral Interface 0) */ +#define SPI0_BASE_ADDR 0x40020000 +#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)) +#define S0SPCCR (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x0C)) +#define S0SPINT (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x1C)) + +/* SSP0 Controller */ +#define SSP0_BASE_ADDR 0x40088000 +#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)) +#define SSP0SR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x0C)) +#define SSP0CPSR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x10)) +#define SSP0IMSC (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x14)) +#define SSP0RIS (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x18)) +#define SSP0MIS (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x1C)) +#define SSP0ICR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x20)) +#define SSP0DMACR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x24)) + +/* SSP1 Controller */ +#define SSP1_BASE_ADDR 0x40030000 +#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)) +#define SSP1SR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x0C)) +#define SSP1CPSR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x10)) +#define SSP1IMSC (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x14)) +#define SSP1RIS (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x18)) +#define SSP1MIS (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x1C)) +#define SSP1ICR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x20)) +#define SSP1DMACR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x24)) + + +/* I2C Interface 0 */ +#define I2C0_BASE_ADDR 0x4001C000 +#define I2C0CONSET (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x00)) +#define I2C0STAT (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x04)) +#define I2C0DAT (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x08)) +#define I2C0ADR0 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x0C)) +#define I2C0SCLH (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x10)) +#define I2C0SCLL (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x14)) +#define I2C0CONCLR (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x18)) +#define I2C0MMCLR (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x1C)) +#define I2C0ADR1 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x20)) +#define I2C0ADR2 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x24)) +#define I2C0ADR3 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x28)) +#define I2C0DATBUFFER (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x2C)) +#define I2C0MASK0 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x30)) +#define I2C0MASK1 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x34)) +#define I2C0MASK2 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x38)) +#define I2C0MASK3 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x3C)) + +/* I2C Interface 1 */ +#define I2C1_BASE_ADDR 0x4005C000 +#define I2C1CONSET (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x00)) +#define I2C1STAT (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x04)) +#define I2C1DAT (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x08)) +#define I2C1ADR0 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x0C)) +#define I2C1SCLH (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x10)) +#define I2C1SCLL (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x14)) +#define I2C1CONCLR (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x18)) +#define I2C1MMCLR (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x1C)) +#define I2C1ADR1 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x20)) +#define I2C1ADR2 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x24)) +#define I2C1ADR3 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x28)) +#define I2C1DATBUFFER (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x2C)) +#define I2C1MASK0 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x30)) +#define I2C1MASK1 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x34)) +#define I2C1MASK2 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x38)) +#define I2C1MASK3 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x3C)) + +/* I2C Interface 2 */ +#define I2C2_BASE_ADDR 0x400A0000 +#define I2C2CONSET (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x00)) +#define I2C2STAT (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x04)) +#define I2C2DAT (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x08)) +#define I2C2ADR0 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x0C)) +#define I2C2SCLH (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x10)) +#define I2C2SCLL (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x14)) +#define I2C2CONCLR (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x18)) +#define I2C2MMCLR (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x1C)) +#define I2C2ADR1 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x20)) +#define I2C2ADR2 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x24)) +#define I2C2ADR3 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x28)) +#define I2C2DATBUFFER (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x2C)) +#define I2C2MASK0 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x30)) +#define I2C2MASK1 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x34)) +#define I2C2MASK2 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x38)) +#define I2C2MASK3 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x3C)) + + +/* I2S Interface Controller (I2S) */ +#define I2S_BASE_ADDR 0x400A8000 +#define I2SDAO (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x00)) +#define I2SDAI (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x04)) +#define I2STXFIFO (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x08)) +#define I2SRXFIFO (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x0C)) +#define I2SSTATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x10)) +#define I2SDMA1 (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x14)) +#define I2SDMA2 (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x18)) +#define I2SIRQ (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x1C)) +#define I2STXRATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x20)) +#define I2SRXRATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x24)) +#define I2STXBITRATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x28)) +#define I2SRXBITRATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x2C)) +#define I2STXMODE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x30)) +#define I2SRXMODE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x34)) + + +/* Repetitive Interrupt Timer (RIT) */ +#define RIT_BASE_ADDR 0x400B4000 +#define RICOMPVAL (*(volatile unsigned long *)(RIT_BASE_ADDR + 0x00)) +#define RIMASK (*(volatile unsigned long *)(RIT_BASE_ADDR + 0x04)) +#define RICTRL (*(volatile unsigned long *)(RIT_BASE_ADDR + 0x08)) +#define RICOUNTER (*(volatile unsigned long *)(RIT_BASE_ADDR + 0x0C)) + + +/* Real Time Clock (RTC) */ +#define RTC_BASE_ADDR 0x40024000 +#define RTC_ILR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x00)) +#define RTC_CCR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x08)) +#define RTC_CIIR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x0C)) +#define RTC_AMR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x10)) +#define RTC_CTIME0 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x14)) +#define RTC_CTIME1 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x18)) +#define RTC_CTIME2 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x1C)) +#define RTC_SEC (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x20)) +#define RTC_MIN (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x24)) +#define RTC_HOUR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x28)) +#define RTC_DOM (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x2C)) +#define RTC_DOW (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x30)) +#define RTC_DOY (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x34)) +#define RTC_MONTH (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x38)) +#define RTC_YEAR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x3C)) +#define RTC_CALIBRATION (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x40)) +#define RTC_GPREG0 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x44)) +#define RTC_GPREG1 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x48)) +#define RTC_GPREG2 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x4C)) +#define RTC_GPREG3 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x50)) +#define RTC_GPREG4 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x54)) +#define RTC_WAKEUPDIS (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x58)) +#define RTC_PWRCTRL (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x5c)) +#define RTC_ALSEC (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x60)) +#define RTC_ALMIN (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x64)) +#define RTC_ALHOUR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x68)) +#define RTC_ALDOM (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x6C)) +#define RTC_ALDOW (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x70)) +#define RTC_ALDOY (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x74)) +#define RTC_ALMON (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x78)) +#define RTC_ALYEAR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x7C)) + + +/* Watchdog Timer (WDT) */ +#define WDT_BASE_ADDR 0x40000000 +#define WDMOD (*(volatile unsigned long *)(WDT_BASE_ADDR + 0x00)) +#define WDTC (*(volatile unsigned long *)(WDT_BASE_ADDR + 0x04)) +#define WDFEED (*(volatile unsigned long *)(WDT_BASE_ADDR + 0x08)) +#define WDTV (*(volatile unsigned long *)(WDT_BASE_ADDR + 0x0C)) +#define WDCLKSEL (*(volatile unsigned long *)(WDT_BASE_ADDR + 0x10)) + + +/* A/D Converter 0 (ADC0) */ +#define AD0_BASE_ADDR 0x40034000 +#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)) +#define AD0DR0 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x10)) +#define AD0DR1 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x14)) +#define AD0DR2 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x18)) +#define AD0DR3 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x1C)) +#define AD0DR4 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x20)) +#define AD0DR5 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x24)) +#define AD0DR6 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x28)) +#define AD0DR7 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x2C)) +#define AD0STAT (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x30)) +#define ADTRIM (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x34)) + + +/* D/A Converter (DAC) */ +#define DAC_BASE_ADDR 0x4008C000 +#define DACR (*(volatile unsigned long *)(DAC_BASE_ADDR + 0x00)) +#define DACCTRL (*(volatile unsigned long *)(DAC_BASE_ADDR + 0x04)) +#define DACCNTVAL (*(volatile unsigned long *)(DAC_BASE_ADDR + 0x08)) + + +/* Motor Control PWM */ +#define MCPWM_BASE_ADDR 0x400B8000 +#define MCCON (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x00)) +#define MCCON_SET (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x04)) +#define MCCON_CLR (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x08)) +#define MCCAPCON (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x0C)) +#define MCCAPCON_SET (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x10)) +#define MCCAPCON_CLR (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x14)) +#define MCTIM0 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x18)) +#define MCTIM1 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x1C)) +#define MCTIM2 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x20)) +#define MCPER0 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x24)) +#define MCPER1 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x28)) +#define MCPER2 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x2C)) +#define MCPW0 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x30)) +#define MCPW1 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x34)) +#define MCPW2 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x38)) +#define MCDEADTIME (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x3C)) +#define MCCCP (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x40)) +#define MCCR0 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x44)) +#define MCCR1 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x48)) +#define MCCR2 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x4C)) +#define MCINTEN (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x50)) +#define MCINTEN_SET (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x54)) +#define MCINTEN_CLR (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x58)) +#define MCCNTCON (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x5C)) +#define MCCNTCON_SET (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x60)) +#define MCCNTCON_CLR (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x64)) +#define MCINTFLAG (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x68)) +#define MCINTFLAG_SET (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x6C)) +#define MCINTFLAG_CLR (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x70)) +#define MCCAP_CLR (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x74)) + + +/* Quadrature Encoder Interface (QEI) */ +#define QEI_BASE_ADDR 0x400BC000 + +/* QEI Control Registers */ +#define QEICON (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x000)) +#define QEISTAT (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x004)) +#define QEICONF (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x008)) + +/* QEI Position, Index, and Timer Registers */ +#define QEIPOS (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x00C)) +#define QEIMAXPSOS (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x010)) +#define CMPOS0 (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x014)) +#define CMPOS1 (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x018)) +#define CMPOS2 (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x01C)) +#define INXCNT (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x020)) +#define INXCMP (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x024)) +#define QEILOAD (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x028)) +#define QEITIME (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x02C)) +#define QEIVEL (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x030)) +#define QEICAP (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x034)) +#define VELCOMP (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x038)) +#define FILTER (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x03C)) + +/* QEI Interrupt registers */ +#define QEIIES (*(volatile unsigned long *)(QEI_BASE_ADDR + 0xFDC)) +#define QEIIEC (*(volatile unsigned long *)(QEI_BASE_ADDR + 0xFD8)) +#define QEIINTSTAT (*(volatile unsigned long *)(QEI_BASE_ADDR + 0xFE0)) +#define QEIIE (*(volatile unsigned long *)(QEI_BASE_ADDR + 0xFE4)) +#define QEICLR (*(volatile unsigned long *)(QEI_BASE_ADDR + 0xFE8)) +#define QEISET (*(volatile unsigned long *)(QEI_BASE_ADDR + 0xFEC)) + + +/* CAN Controllers and Acceptance Filter */ + +/* CAN Acceptance Filter */ +#define CAN_AF_BASE_ADDR 0x4003C000 +#define AFMR (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x00)) +#define SFF_sa (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x04)) +#define SFF_GRP_sa (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x08)) +#define EFF_sa (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x0C)) +#define EFF_GRP_sa (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x10)) +#define ENDofTable (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x14)) +#define LUTerrAd (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x18)) +#define LUTerr (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x1C)) +#define FCANIE (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x20)) +#define FCANIC0 (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x24)) +#define FCANIC1 (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x28)) + +/* CAN Centralized Registers */ +#define CAN_BASE_ADDR 0x40040000 +#define CANTxSR (*(volatile unsigned long *)(CAN_BASE_ADDR + 0x00)) +#define CANRxSR (*(volatile unsigned long *)(CAN_BASE_ADDR + 0x04)) +#define CANMSR (*(volatile unsigned long *)(CAN_BASE_ADDR + 0x08)) + +/* CAN1 Controller */ +#define CAN1_BASE_ADDR 0x40044000 +#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)) + +/* CAN2 Controller */ +#define CAN2_BASE_ADDR 0x40048000 +#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)) + + +/* General Purpose DMA Controller (GPDMA) */ +#define DMA_BASE_ADDR 0x50004000 +#define DMACIntStat (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x000)) +#define DMACIntTCStat (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x004)) +#define DMACIntTCClear (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x008)) +#define DMACIntErrStat (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x00C)) +#define DMACIntErrClr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x010)) +#define DMACRawIntTCStat (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x014)) +#define DMACRawIntErrStat (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x018)) +#define DMACEnbldChns (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x01C)) +#define DMACSoftBReq (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x020)) +#define DMACSoftSReq (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x024)) +#define DMACSoftLBReq (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x028)) +#define DMACSoftLSReq (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x02C)) +#define DMACConfig (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x030)) +#define DMACSync (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x034)) + +/* DMA Channel 0 Registers */ +#define DMACC0SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x100)) +#define DMACC0DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x104)) +#define DMACC0LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x108)) +#define DMACC0Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x10C)) +#define DMACC0Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x110)) + +/* DMA Channel 1 Registers */ +#define DMACC1SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x120)) +#define DMACC1DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x124)) +#define DMACC1LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x128)) +#define DMACC1Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x12C)) +#define DMACC1Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x130)) + +/* DMA Channel 2 Registers */ +#define DMACC2SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x140)) +#define DMACC2DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x144)) +#define DMACC2LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x148)) +#define DMACC2Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x14C)) +#define DMACC2Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x150)) + +/* DMA Channel 3 Registers */ +#define DMACC3SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x160)) +#define DMACC3DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x164)) +#define DMACC3LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x168)) +#define DMACC3Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x16C)) +#define DMACC3Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x170)) + +/* DMA Channel 4 Registers */ +#define DMACC4SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x180)) +#define DMACC4DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x184)) +#define DMACC4LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x188)) +#define DMACC4Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x18C)) +#define DMACC4Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x190)) + +/* DMA Channel 5 Registers */ +#define DMACC5SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1A0)) +#define DMACC5DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1A4)) +#define DMACC5LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1A8)) +#define DMACC5Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1AC)) +#define DMACC5Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1B0)) + +/* DMA Channel 6 Registers */ +#define DMACC6SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1C0)) +#define DMACC6DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1C4)) +#define DMACC6LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1C8)) +#define DMACC6Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1CC)) +#define DMACC6Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1D0)) + +/* DMA Channel 7 Registers */ +#define DMACC7SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1E0)) +#define DMACC7DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1E4)) +#define DMACC7LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1E8)) +#define DMACC7Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1EC)) +#define DMACC7Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1F0)) + + +/* USB Controller */ +#define USB_BASE_ADDR 0x5000C000 + +#define USBIntSt (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1C0)) + + +/* USB Device Controller */ + +/* USB Device Clock Control Registers */ +#define USBClkCtrl (*(volatile unsigned long *)(USB_BASE_ADDR + 0xFF4)) +#define USBClkSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0xFF8)) + +/* USB Device Interrupt Registers */ +#define USBDevIntSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x200)) +#define USBDevIntEn (*(volatile unsigned long *)(USB_BASE_ADDR + 0x204)) +#define USBDevIntClr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x208)) +#define USBDevIntSet (*(volatile unsigned long *)(USB_BASE_ADDR + 0x20C)) +#define USBDevIntPri (*(volatile unsigned long *)(USB_BASE_ADDR + 0x22C)) + +/* USB Device Endpoint Interrupt Registers */ +#define USBEpIntSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x230)) +#define USBEpIntEn (*(volatile unsigned long *)(USB_BASE_ADDR + 0x234)) +#define USBEpIntClr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x238)) +#define USBEpIntSet (*(volatile unsigned long *)(USB_BASE_ADDR + 0x23C)) +#define USBEpIntPri (*(volatile unsigned long *)(USB_BASE_ADDR + 0x240)) + +/* USB Device Endpoint Realization Registers */ +#define USBReEp (*(volatile unsigned long *)(USB_BASE_ADDR + 0x244)) +#define USBEpInd (*(volatile unsigned long *)(USB_BASE_ADDR + 0x248)) +#define USBMaxPSize (*(volatile unsigned long *)(USB_BASE_ADDR + 0x24C)) + +/* USB Device SIE Command Reagisters */ +#define USBCmdCode (*(volatile unsigned long *)(USB_BASE_ADDR + 0x210)) +#define USBCmdData (*(volatile unsigned long *)(USB_BASE_ADDR + 0x214)) + +/* USB Device Data Transfer Registers */ +#define USBRxData (*(volatile unsigned long *)(USB_BASE_ADDR + 0x218)) +#define USBTxData (*(volatile unsigned long *)(USB_BASE_ADDR + 0x21C)) +#define USBRxPLen (*(volatile unsigned long *)(USB_BASE_ADDR + 0x220)) +#define USBTxPLen (*(volatile unsigned long *)(USB_BASE_ADDR + 0x224)) +#define USBCtrl (*(volatile unsigned long *)(USB_BASE_ADDR + 0x228)) + +/* USB Device DMA Registers */ +#define USBDMARSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x250)) +#define USBDMARClr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x254)) +#define USBDMARSet (*(volatile unsigned long *)(USB_BASE_ADDR + 0x258)) +#define USBUDCAH (*(volatile unsigned long *)(USB_BASE_ADDR + 0x280)) +#define USBEpDMASt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x284)) +#define USBEpDMAEn (*(volatile unsigned long *)(USB_BASE_ADDR + 0x288)) +#define USBEpDMADis (*(volatile unsigned long *)(USB_BASE_ADDR + 0x28C)) +#define USBDMAIntSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x290)) +#define USBDMAIntEn (*(volatile unsigned long *)(USB_BASE_ADDR + 0x294)) +#define USBEoTIntSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2A0)) +#define USBEoTIntClr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2A4)) +#define USBEoTIntSet (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2A8)) +#define USBNDDRIntSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2AC)) +#define USBNDDRIntClr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2B0)) +#define USBNDDRIntSet (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2B4)) +#define USBSysErrIntSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2B8)) +#define USBSysErrIntClr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2BC)) +#define USBSysErrIntSet (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2C0)) + + +/* USB Host Controller */ +#define HcRevision (*(volatile unsigned long *)(USB_BASE_ADDR + 0x000)) +#define HcControl (*(volatile unsigned long *)(USB_BASE_ADDR + 0x004)) +#define HcCommandStatus (*(volatile unsigned long *)(USB_BASE_ADDR + 0x008)) +#define HcInterruptStatus (*(volatile unsigned long *)(USB_BASE_ADDR + 0x00C)) +#define HcInterruptEnable (*(volatile unsigned long *)(USB_BASE_ADDR + 0x010)) +#define HcInterruptDisable (*(volatile unsigned long *)(USB_BASE_ADDR + 0x014)) +#define HcHCCA (*(volatile unsigned long *)(USB_BASE_ADDR + 0x018)) +#define HcPeriodCurrentED (*(volatile unsigned long *)(USB_BASE_ADDR + 0x01C)) +#define HcControlHeadED (*(volatile unsigned long *)(USB_BASE_ADDR + 0x020)) +#define HcControlCurrentED (*(volatile unsigned long *)(USB_BASE_ADDR + 0x024)) +#define HcBulkHeadED (*(volatile unsigned long *)(USB_BASE_ADDR + 0x028)) +#define HcBulkCurrentED (*(volatile unsigned long *)(USB_BASE_ADDR + 0x02C)) +#define HcDoneHead (*(volatile unsigned long *)(USB_BASE_ADDR + 0x030)) +#define HcFmInterval (*(volatile unsigned long *)(USB_BASE_ADDR + 0x034)) +#define HcFmRemaining (*(volatile unsigned long *)(USB_BASE_ADDR + 0x038)) +#define HcFmNumber (*(volatile unsigned long *)(USB_BASE_ADDR + 0x03C)) +#define HcPeriodStart (*(volatile unsigned long *)(USB_BASE_ADDR + 0x040)) +#define HcLSThreshold (*(volatile unsigned long *)(USB_BASE_ADDR + 0x044)) +#define HcRhDescriptorA (*(volatile unsigned long *)(USB_BASE_ADDR + 0x048)) +#define HcRhDescriptorB (*(volatile unsigned long *)(USB_BASE_ADDR + 0x04C)) +#define HcRhStatus (*(volatile unsigned long *)(USB_BASE_ADDR + 0x050)) +#define HcRhPortStatus1 (*(volatile unsigned long *)(USB_BASE_ADDR + 0x054)) +#define HcRhPortStatus2 (*(volatile unsigned long *)(USB_BASE_ADDR + 0x058)) + + +/* USB OTG Controller */ + +/* USB OTG Registers */ +#define OTGIntSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x100)) +#define OTGIntEn (*(volatile unsigned long *)(USB_BASE_ADDR + 0x104)) +#define OTGIntSet (*(volatile unsigned long *)(USB_BASE_ADDR + 0x108)) +#define OTGIntClr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x10C)) +#define OTGIntCtrl (*(volatile unsigned long *)(USB_BASE_ADDR + 0x110)) +#define OTGTmr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x114)) + +/* USB OTG I2C Registers */ +#define I2C_RX (*(volatile unsigned long *)(USB_BASE_ADDR + 0x300)) +#define I2C_TX (*(volatile unsigned long *)(USB_BASE_ADDR + 0x300)) +#define I2C_STS (*(volatile unsigned long *)(USB_BASE_ADDR + 0x304)) +#define I2C_CTL (*(volatile unsigned long *)(USB_BASE_ADDR + 0x308)) +#define I2C_CLKHI (*(volatile unsigned long *)(USB_BASE_ADDR + 0x30C)) +#define I2C_CLKLO (*(volatile unsigned long *)(USB_BASE_ADDR + 0x310)) + +/* USB OTG Clock Control Registers */ +#define OTGClkCtrl (*(volatile unsigned long *)(USB_BASE_ADDR + 0xFF4)) +#define OTGClkSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0xFF8)) + + +/* Ethernet MAC */ +#define MAC_BASE_ADDR 0x50000000 + +/* MAC Registers */ +#define ETH_MAC1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x000)) +#define ETH_MAC2 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x004)) +#define ETH_IPGT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x008)) +#define ETH_IPGR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x00C)) +#define ETH_CLRT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x010)) +#define ETH_MAXF (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x014)) +#define ETH_PHYSUPP (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x018)) +#define ETH_TEST (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x01C)) +#define ETH_MIICFG (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x020)) +#define ETH_MIICMD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x024)) +#define ETH_MIIADR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x028)) +#define ETH_MIIWTD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x02C)) +#define ETH_MIIRDD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x030)) +#define ETH_MIIIND (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x034)) +#define ETH_SA0 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x040)) +#define ETH_SA1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x044)) +#define ETH_SA2 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x048)) + +/* MAC Control Registers */ +#define ETH_COMMAND (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x100)) +#define ETH_STATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x104)) +#define ETH_RXDESC (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x108)) +#define ETH_RXSTAT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x10C)) +#define ETH_RXDESCRNO (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x110)) +#define ETH_RXPRODIX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x114)) +#define ETH_RXCONSIX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x118)) +#define ETH_TXDESC (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x11C)) +#define ETH_TXSTAT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x120)) +#define ETH_TXDESCRNO (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x124)) +#define ETH_TXPRODIX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x128)) +#define ETH_TXCONSIX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x12C)) +#define ETH_TSV0 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x158)) +#define ETH_TSV1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x15C)) +#define ETH_RSV (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x160)) +#define ETH_FLOWCNTCOUNT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x170)) +#define ETH_FLOWCNTSTAT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x174)) + +/* MAX Rx Filter Registers */ +#define ETH_RXFILTERCTL (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x200)) +#define ETH_RXFILTERWOLSTAT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x204)) +#define ETH_RXFILTERWOLCLR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x208)) +#define ETH_HASHFILTERL (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x210)) +#define ETH_HASHFILTERH (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x214)) + +/* MAC Module Control Registers */ +#define ETH_INSTSTAT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE0)) +#define ETH_INTENABLE (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE4)) +#define ETH_INTCLEAR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE8)) +#define ETH_INTSET (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFEC)) +#define ETH_POWERDOWN (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFF4)) + +#define MAC_Module_ID (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFFC)) + +/* Ethernet MAC (32 bit data bus) -- all registers are RW unless indicated in parentheses */ +#define MAC_BASE_ADDR 0x50000000 +#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 */ +#define MAC_IPGR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x00C)) /* non b2b InterPacketGap reg */ +#define MAC_CLRT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x010)) /* CoLlision window/ReTry reg */ +#define MAC_MAXF (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x014)) /* MAXimum Frame reg */ +#define MAC_SUPP (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x018)) /* PHY SUPPort reg */ +#define MAC_TEST (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x01C)) /* TEST reg */ +#define MAC_MCFG (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x020)) /* MII Mgmt ConFiG reg */ +#define MAC_MCMD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x024)) /* MII Mgmt CoMmanD reg */ +#define MAC_MADR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x028)) /* MII Mgmt ADdRess reg */ +#define MAC_MWTD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x02C)) /* MII Mgmt WriTe Data reg (WO) */ +#define MAC_MRDD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x030)) /* MII Mgmt ReaD Data reg (RO) */ +#define MAC_MIND (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x034)) /* MII Mgmt INDicators reg (RO) */ + +#define MAC_SA0 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x040)) /* Station Address 0 reg */ +#define MAC_SA1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x044)) /* Station Address 1 reg */ +#define MAC_SA2 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x048)) /* Station Address 2 reg */ + +#define MAC_COMMAND (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x100)) /* Command reg */ +#define MAC_STATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x104)) /* Status reg (RO) */ +#define MAC_RXDESCRIPTOR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x108)) /* Rx descriptor base address reg */ +#define MAC_RXSTATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x10C)) /* Rx status base address reg */ +#define MAC_RXDESCRIPTORNUM (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x110)) /* Rx number of descriptors reg */ +#define MAC_RXPRODUCEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x114)) /* Rx produce index reg (RO) */ +#define MAC_RXCONSUMEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x118)) /* Rx consume index reg */ +#define MAC_TXDESCRIPTOR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x11C)) /* Tx descriptor base address reg */ +#define MAC_TXSTATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x120)) /* Tx status base address reg */ +#define MAC_TXDESCRIPTORNUM (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x124)) /* Tx number of descriptors reg */ +#define MAC_TXPRODUCEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x128)) /* Tx produce index reg */ +#define MAC_TXCONSUMEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x12C)) /* Tx consume index reg (RO) */ + +#define MAC_TSV0 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x158)) /* Tx status vector 0 reg (RO) */ +#define MAC_TSV1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x15C)) /* Tx status vector 1 reg (RO) */ +#define MAC_RSV (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x160)) /* Rx status vector reg (RO) */ + +#define MAC_FLOWCONTROLCNT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x170)) /* Flow control counter reg */ +#define MAC_FLOWCONTROLSTS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x174)) /* Flow control status reg */ + +#define MAC_RXFILTERCTRL (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x200)) /* Rx filter ctrl reg */ +#define MAC_RXFILTERWOLSTS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x204)) /* Rx filter WoL status reg (RO) */ +#define MAC_RXFILTERWOLCLR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x208)) /* Rx filter WoL clear reg (WO) */ + +#define MAC_HASHFILTERL (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x210)) /* Hash filter LSBs reg */ +#define MAC_HASHFILTERH (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x214)) /* Hash filter MSBs reg */ + +#define MAC_INTSTATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE0)) /* Interrupt status reg (RO) */ +#define MAC_INTENABLE (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE4)) /* Interrupt enable reg */ +#define MAC_INTCLEAR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE8)) /* Interrupt clear reg (WO) */ +#define MAC_INTSET (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFEC)) /* Interrupt set reg (WO) */ + +#define MAC_POWERDOWN (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFF4)) /* Power-down reg */ +#define MAC_MODULEID (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFFC)) /* Module ID reg (RO) */ + +#define PCONP_PCTIM0 0x00000002 +#define PCONP_PCTIM1 0x00000004 +#define PCONP_PCUART0 0x00000008 +#define PCONP_PCUART1 0x00000010 +#define PCONP_PCPWM1 0x00000040 +#define PCONP_PCI2C0 0x00000080 +#define PCONP_PCSPI 0x00000100 +#define PCONP_PCRTC 0x00000200 +#define PCONP_PCSSP1 0x00000400 +#define PCONP_PCAD 0x00001000 +#define PCONP_PCCAN1 0x00002000 +#define PCONP_PCCAN2 0x00004000 +#define PCONP_PCGPIO 0x00008000 +#define PCONP_PCRIT 0x00010000 +#define PCONP_PCMCPWM 0x00020000 +#define PCONP_PCQEI 0x00040000 +#define PCONP_PCI2C1 0x00080000 +#define PCONP_PCSSP0 0x00200000 +#define PCONP_PCTIM2 0x00400000 +#define PCONP_PCTIM3 0x00800000 +#define PCONP_PCUART2 0x01000000 +#define PCONP_PCUART3 0x02000000 +#define PCONP_PCI2C2 0x04000000 +#define PCONP_PCI2S 0x08000000 +#define PCONP_PCGPDMA 0x20000000 +#define PCONP_PCENET 0x40000000 +#define PCONP_PCUSB 0x80000000 + +#define PLLCON_PLLE 0x00000001 +#define PLLCON_PLLC 0x00000002 +#define PLLCON_MASK 0x00000003 + +#define PLLCFG_MUL1 0x00000000 +#define PLLCFG_MUL2 0x00000001 +#define PLLCFG_MUL3 0x00000002 +#define PLLCFG_MUL4 0x00000003 +#define PLLCFG_MUL5 0x00000004 +#define PLLCFG_MUL6 0x00000005 +#define PLLCFG_MUL7 0x00000006 +#define PLLCFG_MUL8 0x00000007 +#define PLLCFG_MUL9 0x00000008 +#define PLLCFG_MUL10 0x00000009 +#define PLLCFG_MUL11 0x0000000A +#define PLLCFG_MUL12 0x0000000B +#define PLLCFG_MUL13 0x0000000C +#define PLLCFG_MUL14 0x0000000D +#define PLLCFG_MUL15 0x0000000E +#define PLLCFG_MUL16 0x0000000F +#define PLLCFG_MUL17 0x00000010 +#define PLLCFG_MUL18 0x00000011 +#define PLLCFG_MUL19 0x00000012 +#define PLLCFG_MUL20 0x00000013 +#define PLLCFG_MUL21 0x00000014 +#define PLLCFG_MUL22 0x00000015 +#define PLLCFG_MUL23 0x00000016 +#define PLLCFG_MUL24 0x00000017 +#define PLLCFG_MUL25 0x00000018 +#define PLLCFG_MUL26 0x00000019 +#define PLLCFG_MUL27 0x0000001A +#define PLLCFG_MUL28 0x0000001B +#define PLLCFG_MUL29 0x0000001C +#define PLLCFG_MUL30 0x0000001D +#define PLLCFG_MUL31 0x0000001E +#define PLLCFG_MUL32 0x0000001F +#define PLLCFG_MUL33 0x00000020 +#define PLLCFG_MUL34 0x00000021 +#define PLLCFG_MUL35 0x00000022 +#define PLLCFG_MUL36 0x00000023 + +#define PLLCFG_DIV1 0x00000000 +#define PLLCFG_DIV2 0x00010000 +#define PLLCFG_DIV3 0x00020000 +#define PLLCFG_DIV4 0x00030000 +#define PLLCFG_DIV5 0x00040000 +#define PLLCFG_DIV6 0x00050000 +#define PLLCFG_DIV7 0x00060000 +#define PLLCFG_DIV8 0x00070000 +#define PLLCFG_DIV9 0x00080000 +#define PLLCFG_DIV10 0x00090000 +#define PLLCFG_MASK 0x00FF7FFF + +#define PLLSTAT_MSEL_MASK 0x00007FFF +#define PLLSTAT_NSEL_MASK 0x00FF0000 + +#define PLLSTAT_PLLE (1 << 24) +#define PLLSTAT_PLLC (1 << 25) +#define PLLSTAT_PLOCK (1 << 26) + +#define PLLFEED_FEED1 0x000000AA +#define PLLFEED_FEED2 0x00000055 + +#define NVIC_IRQ_WDT 0u // IRQ0, exception number 16 +#define NVIC_IRQ_TIMER0 1u // IRQ1, exception number 17 +#define NVIC_IRQ_TIMER1 2u // IRQ2, exception number 18 +#define NVIC_IRQ_TIMER2 3u // IRQ3, exception number 19 +#define NVIC_IRQ_TIMER3 4u // IRQ4, exception number 20 +#define NVIC_IRQ_UART0 5u // IRQ5, exception number 21 +#define NVIC_IRQ_UART1 6u // IRQ6, exception number 22 +#define NVIC_IRQ_UART2 7u // IRQ7, exception number 23 +#define NVIC_IRQ_UART3 8u // IRQ8, exception number 24 +#define NVIC_IRQ_PWM1 9u // IRQ9, exception number 25 +#define NVIC_IRQ_I2C0 10u // IRQ10, exception number 26 +#define NVIC_IRQ_I2C1 11u // IRQ11, exception number 27 +#define NVIC_IRQ_I2C2 12u // IRQ12, exception number 28 +#define NVIC_IRQ_SPI 13u // IRQ13, exception number 29 +#define NVIC_IRQ_SSP0 14u // IRQ14, exception number 30 +#define NVIC_IRQ_SSP1 15u // IRQ15, exception number 31 +#define NVIC_IRQ_PLL0 16u // IRQ16, exception number 32 +#define NVIC_IRQ_RTC 17u // IRQ17, exception number 33 +#define NVIC_IRQ_EINT0 18u // IRQ18, exception number 34 +#define NVIC_IRQ_EINT1 19u // IRQ19, exception number 35 +#define NVIC_IRQ_EINT2 20u // IRQ20, exception number 36 +#define NVIC_IRQ_EINT3 21u // IRQ21, exception number 37 +#define NVIC_IRQ_ADC 22u // IRQ22, exception number 38 +#define NVIC_IRQ_BOD 23u // IRQ23, exception number 39 +#define NVIC_IRQ_USB 24u // IRQ24, exception number 40 +#define NVIC_IRQ_CAN 25u // IRQ25, exception number 41 +#define NVIC_IRQ_GPDMA 26u // IRQ26, exception number 42 +#define NVIC_IRQ_I2S 27u // IRQ27, exception number 43 +#define NVIC_IRQ_ETHERNET 28u // IRQ28, exception number 44 +#define NVIC_IRQ_RIT 29u // IRQ29, exception number 45 +#define NVIC_IRQ_MCPWM 30u // IRQ30, exception number 46 +#define NVIC_IRQ_QE 31u // IRQ31, exception number 47 +#define NVIC_IRQ_PLL1 32u // IRQ32, exception number 48 +#define NVIC_IRQ_USB_ACT 33u // IRQ33, exception number 49 +#define NVIC_IRQ_CAN_ACT 34u // IRQ34, exception number 50 + +typedef enum IRQn +{ +/****** Cortex-M3 Processor Exceptions Numbers ***************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + MemoryManagement_IRQn = -12, /*!< 4 Cortex-M3 Memory Management Interrupt */ + BusFault_IRQn = -11, /*!< 5 Cortex-M3 Bus Fault Interrupt */ + UsageFault_IRQn = -10, /*!< 6 Cortex-M3 Usage Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M3 SV Call Interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 Cortex-M3 Debug Monitor Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M3 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M3 System Tick Interrupt */ + +/****** LPC17xx Specific Interrupt Numbers *******************************************************/ + WDT_IRQn = 0, /*!< Watchdog Timer Interrupt */ + TIMER0_IRQn = 1, /*!< Timer0 Interrupt */ + TIMER1_IRQn = 2, /*!< Timer1 Interrupt */ + TIMER2_IRQn = 3, /*!< Timer2 Interrupt */ + TIMER3_IRQn = 4, /*!< Timer3 Interrupt */ + UART0_IRQn = 5, /*!< UART0 Interrupt */ + UART1_IRQn = 6, /*!< UART1 Interrupt */ + UART2_IRQn = 7, /*!< UART2 Interrupt */ + UART3_IRQn = 8, /*!< UART3 Interrupt */ + PWM1_IRQn = 9, /*!< PWM1 Interrupt */ + I2C0_IRQn = 10, /*!< I2C0 Interrupt */ + I2C1_IRQn = 11, /*!< I2C1 Interrupt */ + I2C2_IRQn = 12, /*!< I2C2 Interrupt */ + SPI_IRQn = 13, /*!< SPI Interrupt */ + SSP0_IRQn = 14, /*!< SSP0 Interrupt */ + SSP1_IRQn = 15, /*!< SSP1 Interrupt */ + PLL0_IRQn = 16, /*!< PLL0 Lock (Main PLL) Interrupt */ + RTC_IRQn = 17, /*!< Real Time Clock Interrupt */ + EINT0_IRQn = 18, /*!< External Interrupt 0 Interrupt */ + EINT1_IRQn = 19, /*!< External Interrupt 1 Interrupt */ + EINT2_IRQn = 20, /*!< External Interrupt 2 Interrupt */ + EINT3_IRQn = 21, /*!< External Interrupt 3 Interrupt */ + ADC_IRQn = 22, /*!< A/D Converter Interrupt */ + BOD_IRQn = 23, /*!< Brown-Out Detect Interrupt */ + USB_IRQn = 24, /*!< USB Interrupt */ + CAN_IRQn = 25, /*!< CAN Interrupt */ + DMA_IRQn = 26, /*!< General Purpose DMA Interrupt */ + I2S_IRQn = 27, /*!< I2S Interrupt */ + ENET_IRQn = 28, /*!< Ethernet Interrupt */ + RIT_IRQn = 29, /*!< Repetitive Interrupt Timer Interrupt */ + MCPWM_IRQn = 30, /*!< Motor Control PWM Interrupt */ + QEI_IRQn = 31, /*!< Quadrature Encoder Interface Interrupt */ + PLL1_IRQn = 32, /*!< PLL1 Lock (USB PLL) Interrupt */ +} IRQn_Type; + +#endif // __LPC17xx_H diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/LPC17xx_defs.h b/Demo/CORTEX_LPC1768_GCC_Rowley/LPC17xx_defs.h new file mode 100644 index 000000000..e7f2b2213 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/LPC17xx_defs.h @@ -0,0 +1,1510 @@ +/****************************************************************************** + * LPC17xx.h: Header file for NXP LPC17xx Cortex-M3 Family Microprocessors + * The header file is the super set of all hardware definitions of the + * peripherals for the LPC17xx/24xx microprocessor. + * + * Copyright(C) 2006-2008, NXP Semiconductor + * All rights reserved. + * + * History + * +******************************************************************************/ + +#ifndef __LPC17xx_H +#define __LPC17xx_H + +//#include "sysdefs.h" + +#define SRAM_BASE_LOCAL ((unsigned long)0x10000000) // 32 Kb +#define SRAM_BASE_AHB ((unsigned long)0x20000000) // 32 Kb + +/* System Control Space memory map */ +#ifndef SCS_BASE + #define SCS_BASE ((unsigned long)0xE000E000) +#endif + +#define SysTick_BASE (SCS_BASE + 0x0010) +#define NVIC_BASE (SCS_BASE + 0x0100) +#define CM3_PERIPH_BASE_ADDR (SCS_BASE + 0x0D00) + +typedef struct +{ + unsigned long CPUID; + unsigned long IRQControlState; + unsigned long ExceptionTableOffset; + unsigned long AIRC; + unsigned long SysCtrl; + unsigned long ConfigCtrl; + unsigned long SystemPriority[3]; + unsigned long SysHandlerCtrl; + unsigned long ConfigFaultStatus; + unsigned long HardFaultStatus; + unsigned long DebugFaultStatus; + unsigned long MemoryManageFaultAddr; + unsigned long BusFaultAddr; +} CM3_t; + +/* Vector Table Base Address */ +#define NVIC_VectorTable_RAM SRAM_BASE_AHB +#define NVIC_VectorTable_FLASH ((unsigned long)0x00000000) + +#define IS_NVIC_VECTORTBL(TABLE_BASE) ((TABLE_BASE == NVIC_VectorTable_RAM) || \ + (TABLE_BASE == NVIC_VectorTable_FLASH)) + +/* Pin Connect Block */ +#define PINSEL_BASE_ADDR 0x4002C000 +#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)) +#define PINSEL3 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x0C)) +#define PINSEL4 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x10)) +#define PINSEL5 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x14)) +#define PINSEL6 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x18)) +#define PINSEL7 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x1C)) +#define PINSEL8 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x20)) +#define PINSEL9 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x24)) +#define PINSEL10 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x28)) + +#define PINMODE0 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x40)) +#define PINMODE1 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x44)) +#define PINMODE2 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x48)) +#define PINMODE3 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x4C)) +#define PINMODE4 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x50)) +#define PINMODE5 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x54)) +#define PINMODE6 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x58)) +#define PINMODE7 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x5C)) +#define PINMODE8 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x60)) +#define PINMODE9 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x64)) + +/* Open drain mode control */ +#define PINMODE_OD0 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x68)) +#define PINMODE_OD1 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x6C)) +#define PINMODE_OD2 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x70)) +#define PINMODE_OD3 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x74)) +#define PINMODE_OD4 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x78)) + +#define PINSEL0_P00_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P00_TXD0 ((unsigned int) 0x00000001) +#define PINSEL0_P00_PWM1 ((unsigned int) 0x00000002) +#define PINSEL0_P00_RSVD3 ((unsigned int) 0x00000003) +#define PINSEL0_P00_MASK ((unsigned int) 0x00000003) + +#define PINSEL0_P01_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P01_RXD0 ((unsigned int) 0x00000004) +#define PINSEL0_P01_PWM3 ((unsigned int) 0x00000008) +#define PINSEL0_P01_EINT0 ((unsigned int) 0x0000000C) +#define PINSEL0_P01_MASK ((unsigned int) 0x0000000C) + +#define PINSEL0_P02_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P02_SCL0 ((unsigned int) 0x00000010) +#define PINSEL0_P02_CAP00 ((unsigned int) 0x00000020) +#define PINSEL0_P02_RSVD3 ((unsigned int) 0x00000030) +#define PINSEL0_P02_MASK ((unsigned int) 0x00000030) + +#define PINSEL0_P03_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P03_SDA0 ((unsigned int) 0x00000040) +#define PINSEL0_P03_MAT00 ((unsigned int) 0x00000080) +#define PINSEL0_P03_EINT1 ((unsigned int) 0x000000C0) +#define PINSEL0_P03_MASK ((unsigned int) 0x000000C0) + +#define PINSEL0_P04_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P04_SCK0 ((unsigned int) 0x00000100) +#define PINSEL0_P04_CAP01 ((unsigned int) 0x00000200) +#define PINSEL0_P04_RSVD3 ((unsigned int) 0x00000300) +#define PINSEL0_P04_MASK ((unsigned int) 0x00000300) + +#define PINSEL0_P05_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P05_MISO0 ((unsigned int) 0x00000400) +#define PINSEL0_P05_MAT01 ((unsigned int) 0x00000800) +#define PINSEL0_P05_AD06 ((unsigned int) 0x00000C00) +#define PINSEL0_P05_MASK ((unsigned int) 0x00000C00) + +#define PINSEL0_P06_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P06_MOSI0 ((unsigned int) 0x00001000) +#define PINSEL0_P06_CAP02 ((unsigned int) 0x00002000) +#define PINSEL0_P06_AD10 ((unsigned int) 0x00003000) +#define PINSEL0_P06_MASK ((unsigned int) 0x00003000) + +#define PINSEL0_P07_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P07_SSEL0 ((unsigned int) 0x00004000) +#define PINSEL0_P07_PWM2 ((unsigned int) 0x00008000) +#define PINSEL0_P07_EINT2 ((unsigned int) 0x0000C000) +#define PINSEL0_P07_MASK ((unsigned int) 0x0000C000) + +#define PINSEL0_P08_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P08_TXD1 ((unsigned int) 0x00010000) +#define PINSEL0_P08_PWM4 ((unsigned int) 0x00020000) +#define PINSEL0_P08_AD11 ((unsigned int) 0x00030000) +#define PINSEL0_P08_MASK ((unsigned int) 0x00030000) + +#define PINSEL0_P09_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P09_RXD1 ((unsigned int) 0x00040000) +#define PINSEL0_P09_PWM6 ((unsigned int) 0x00080000) +#define PINSEL0_P09_EINT3 ((unsigned int) 0x000C0000) +#define PINSEL0_P09_MASK ((unsigned int) 0x000C0000) + +#define PINSEL0_P010_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P010_RTS1 ((unsigned int) 0x00100000) +#define PINSEL0_P010_CAP10 ((unsigned int) 0x00200000) +#define PINSEL0_P010_AD12 ((unsigned int) 0x00300000) +#define PINSEL0_P010_MASK ((unsigned int) 0x00300000) + +#define PINSEL0_P011_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P011_CTS1 ((unsigned int) 0x00400000) +#define PINSEL0_P011_CAP11 ((unsigned int) 0x00800000) +#define PINSEL0_P011_SCL1 ((unsigned int) 0x00C00000) +#define PINSEL0_P011_MASK ((unsigned int) 0x00C00000) + +#define PINSEL0_P012_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P012_DSR1 ((unsigned int) 0x01000000) +#define PINSEL0_P012_MAT10 ((unsigned int) 0x02000000) +#define PINSEL0_P012_AD13 ((unsigned int) 0x03000000) +#define PINSEL0_P012_MASK ((unsigned int) 0x03000000) + +#define PINSEL0_P013_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P013_DTR1 ((unsigned int) 0x04000000) +#define PINSEL0_P013_MAT11 ((unsigned int) 0x08000000) +#define PINSEL0_P013_AD14 ((unsigned int) 0x0C000000) +#define PINSEL0_P013_MASK ((unsigned int) 0x0C000000) + +#define PINSEL0_P014_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P014_DCD1 ((unsigned int) 0x10000000) +#define PINSEL0_P014_EINT1 ((unsigned int) 0x20000000) +#define PINSEL0_P014_SDA1 ((unsigned int) 0x30000000) +#define PINSEL0_P014_MASK ((unsigned int) 0x30000000) + +#define PINSEL0_P015_GPIO ((unsigned int) 0x00000000) +#define PINSEL0_P015_RI1 ((unsigned int) 0x40000000) +#define PINSEL0_P015_EINT2 ((unsigned int) 0x80000000) +#define PINSEL0_P015_AD15 ((unsigned int) 0xC0000000) +#define PINSEL0_P015_MASK ((unsigned int) 0xC0000000) + +#define PINSEL1_P016_GPIO ((unsigned int) 0x00000000) +#define PINSEL1_P016_EINT0 ((unsigned int) 0x00000001) +#define PINSEL1_P016_MAT02 ((unsigned int) 0x00000002) +#define PINSEL1_P016_CAP02 ((unsigned int) 0x00000003) +#define PINSEL1_P016_MASK ((unsigned int) 0x00000003) + +#define PINSEL1_P017_GPIO ((unsigned int) 0x00000000) +#define PINSEL1_P017_CAP12 ((unsigned int) 0x00000004) +#define PINSEL1_P017_SCK1 ((unsigned int) 0x00000008) +#define PINSEL1_P017_MAT12 ((unsigned int) 0x0000000c) +#define PINSEL1_P017_MASK ((unsigned int) 0x0000000c) + +#define PINSEL1_P018_GPIO ((unsigned int) 0x00000000) +#define PINSEL1_P018_CAP13 ((unsigned int) 0x00000010) +#define PINSEL1_P018_MISO1 ((unsigned int) 0x00000020) +#define PINSEL1_P018_MAT13 ((unsigned int) 0x00000030) +#define PINSEL1_P018_MASK ((unsigned int) 0x00000030) + +#define PINSEL1_P019_GPIO ((unsigned int) 0x00000000) +#define PINSEL1_P019_MAT12 ((unsigned int) 0x00000040) +#define PINSEL1_P019_MOSI1 ((unsigned int) 0x00000080) +#define PINSEL1_P019_CAP12 ((unsigned int) 0x000000c0) + +#define PINSEL1_P020_GPIO ((unsigned int) 0x00000000) +#define PINSEL1_P020_MAT13 ((unsigned int) 0x00000100) +#define PINSEL1_P020_SSEL1 ((unsigned int) 0x00000200) +#define PINSEL1_P020_EINT3 ((unsigned int) 0x00000300) +#define PINSEL1_P020_MASK ((unsigned int) 0x00000300) + +#define PINSEL1_P021_GPIO ((unsigned int) 0x00000000) +#define PINSEL1_P021_PWM5 ((unsigned int) 0x00000400) +#define PINSEL1_P021_AD16 ((unsigned int) 0x00000800) +#define PINSEL1_P021_CAP13 ((unsigned int) 0x00000c00) +#define PINSEL1_P021_MASK ((unsigned int) 0x00000c00) + +#define PINSEL1_P022_GPIO ((unsigned int) 0x00000000) +#define PINSEL1_P022_AD17 ((unsigned int) 0x00001000) +#define PINSEL1_P022_CAP00 ((unsigned int) 0x00002000) +#define PINSEL1_P022_MAT00 ((unsigned int) 0x00003000) +#define PINSEL1_P022_MASK ((unsigned int) 0x00003000) + +#define PINSEL1_P023_GPIO ((unsigned int) 0x00000000) +#define PINSEL1_P023_VBUS ((unsigned int) 0x00004000) +#define PINSEL1_P023_RSVD2 ((unsigned int) 0x00008000) +#define PINSEL1_P023_RSVD3 ((unsigned int) 0x0000c000) +#define PINSEL1_P023_MASK ((unsigned int) 0x0000c000) + +#define PINSEL1_P024_RSVD0 ((unsigned int) 0x00000000) +#define PINSEL1_P024_RSVD1 ((unsigned int) 0x00010000) +#define PINSEL1_P024_RSVD2 ((unsigned int) 0x00020000) +#define PINSEL1_P024_RSVD3 ((unsigned int) 0x00030000) +#define PINSEL1_P024_MASK ((unsigned int) 0x00030000) + +#define PINSEL1_P025_GPIO ((unsigned int) 0x00000000) +#define PINSEL1_P025_AD04 ((unsigned int) 0x00040000) +#define PINSEL1_P025_AOUT ((unsigned int) 0x00080000) +#define PINSEL1_P025_RSVD3 ((unsigned int) 0x000c0000) +#define PINSEL1_P025_MASK ((unsigned int) 0x000c0000) + +#define PINSEL1_P026_RSVD0 ((unsigned int) 0x00000000) +#define PINSEL1_P026_RSVD1 ((unsigned int) 0x00100000) +#define PINSEL1_P026_RSVD2 ((unsigned int) 0x00200000) +#define PINSEL1_P026_RSVD3 ((unsigned int) 0x00300000) +#define PINSEL1_P026_MASK ((unsigned int) 0x00300000) + +#define PINSEL1_P027_RSVD0 ((unsigned int) 0x00000000) +#define PINSEL1_P027_RSVD1 ((unsigned int) 0x00400000) +#define PINSEL1_P027_RSVD2 ((unsigned int) 0x00800000) +#define PINSEL1_P027_RSVD3 ((unsigned int) 0x00c00000) +#define PINSEL1_P027_MASK ((unsigned int) 0x00c00000) + +#define PINSEL1_P028_GPIO ((unsigned int) 0x00000000) +#define PINSEL1_P028_AD01 ((unsigned int) 0x01000000) +#define PINSEL1_P028_CAP02 ((unsigned int) 0x02000000) +#define PINSEL1_P028_MAT02 ((unsigned int) 0x03000000) +#define PINSEL1_P028_MASK ((unsigned int) 0x03000000) + +#define PINSEL1_P029_GPIO ((unsigned int) 0x00000000) +#define PINSEL1_P029_AD02 ((unsigned int) 0x04000000) +#define PINSEL1_P029_CAP03 ((unsigned int) 0x08000000) +#define PINSEL1_P029_MAT03 ((unsigned int) 0x0c000000) +#define PINSEL1_P029_MASK ((unsigned int) 0x0c000000) + +#define PINSEL1_P030_GPIO ((unsigned int) 0x00000000) +#define PINSEL1_P030_AD03 ((unsigned int) 0x10000000) +#define PINSEL1_P030_EINT3 ((unsigned int) 0x20000000) +#define PINSEL1_P030_CAP00 ((unsigned int) 0x30000000) +#define PINSEL1_P030_MASK ((unsigned int) 0x30000000) + +#define PINSEL1_P031_GPIO ((unsigned int) 0x00000000) +#define PINSEL1_P031_UPLED ((unsigned int) 0x40000000) +#define PINSEL1_P031_CONNECT ((unsigned int) 0x80000000) +#define PINSEL1_P031_RSVD3 ((unsigned int) 0xc0000000) +#define PINSEL1_P031_MASK ((unsigned int) 0xc0000000) + +#define PINSEL2_P13626_GPIO ((unsigned int) 0x00000000) +#define PINSEL2_P13626_DEBUG ((unsigned int) 0x00000004) +#define PINSEL2_P13626_MASK ((unsigned int) 0x00000004) + +#define PINSEL2_P12516_GPIO ((unsigned int) 0x00000000) +#define PINSEL2_P12516_TRACE ((unsigned int) 0x00000008) +#define PINSEL2_P12516_MASK ((unsigned int) 0x00000008) + +/* General Purpose Input/Output (GPIO) */ +/* Fast I/O setup */ + +#define FIO_BASE_ADDR 0x50014000 + +#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)) +#define FIO0SET (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x18)) +#define FIO0CLR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x1C)) + +#ifdef LPC1766_UM_DEFS +/* Fast GPIO Register Access */ +#define FIO0SET0 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x38)) +#define FIO0SET1 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x39)) +#define FIO0SET2 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x3A)) +#define FIO0SET3 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x3B)) +#define FIO0SETL (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x38)) +#define FIO0SETU (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x3A)) +#endif + +#define FIO1DIR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x20)) +#define FIO1MASK (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x30)) +#define FIO1PIN (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x34)) +#define FIO1SET (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x38)) +#define FIO1CLR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x3C)) + +#ifdef LPC1766_UM_DEFS +/* Fast GPIO Register Access */ +#define FIO1SET0 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x78)) +#define FIO1SET1 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x79)) +#define FIO1SET2 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x7A)) +#define FIO1SET3 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x7B)) +#define FIO1SETL (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x78)) +#define FIO1SETU (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x7A)) +#endif + +#define FIO2DIR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x40)) +#define FIO2MASK (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x50)) +#define FIO2PIN (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x54)) +#define FIO2SET (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x58)) +#define FIO2CLR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x5C)) + +#ifdef LPC1766_UM_DEFS +/* Fast GPIO Register Access */ +#define FIO2SET0 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xB8)) +#define FIO2SET1 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xB9)) +#define FIO2SET2 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xBA)) +#define FIO2SET3 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xBB)) +#define FIO2SETL (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xB8)) +#define FIO2SETU (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xBA)) +#endif + +#define FIO3DIR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x60)) +#define FIO3MASK (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x70)) +#define FIO3PIN (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x74)) +#define FIO3SET (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x78)) +#define FIO3CLR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x7C)) + +#ifdef LPC1766_UM_DEFS +/* Fast GPIO Register Access */ +#define FIO3SET0 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xF8)) +#define FIO3SET1 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xF9)) +#define FIO3SET2 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xFA)) +#define FIO3SET3 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xFB)) +#define FIO3SETL (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xF8)) +#define FIO3SETU (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xFA)) +#endif + +#define FIO4DIR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x80)) +#define FIO4MASK (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x90)) +#define FIO4PIN (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x94)) +#define FIO4SET (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x98)) +#define FIO4CLR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x9C)) + +#ifdef LPC1766_UM_DEFS +/* Fast GPIO Register Access */ +#define FIO4SET0 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x138)) +#define FIO4SET1 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x139)) +#define FIO4SET2 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x13A)) +#define FIO0SET3 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x3B)) +#define FIO4SET3 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x13B)) +#define FIO4SETL (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x138)) +#define FIO4SETU (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x13A)) +#endif + +/* General Purpose Input/Output (GPIO) */ +#define GPIO_BASE_ADDR 0x40028000 +#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)) +#define IOCLR0 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x0C)) +#define IOPIN1 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x10)) +#define IOSET1 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x14)) +#define IODIR1 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x18)) +#define IOCLR1 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x1C)) + +#define GPIO_IO_P0 ((unsigned int) 0x00000001) +#define GPIO_IO_P1 ((unsigned int) 0x00000002) +#define GPIO_IO_P2 ((unsigned int) 0x00000004) +#define GPIO_IO_P3 ((unsigned int) 0x00000008) +#define GPIO_IO_P4 ((unsigned int) 0x00000010) +#define GPIO_IO_P5 ((unsigned int) 0x00000020) +#define GPIO_IO_P6 ((unsigned int) 0x00000040) +#define GPIO_IO_P7 ((unsigned int) 0x00000080) +#define GPIO_IO_P8 ((unsigned int) 0x00000100) +#define GPIO_IO_P9 ((unsigned int) 0x00000200) +#define GPIO_IO_P10 ((unsigned int) 0x00000400) +#define GPIO_IO_P11 ((unsigned int) 0x00000800) +#define GPIO_IO_P12 ((unsigned int) 0x00001000) +#define GPIO_IO_P13 ((unsigned int) 0x00002000) +#define GPIO_IO_P14 ((unsigned int) 0x00004000) +#define GPIO_IO_P15 ((unsigned int) 0x00008000) +#define GPIO_IO_P16 ((unsigned int) 0x00010000) +#define GPIO_IO_P17 ((unsigned int) 0x00020000) +#define GPIO_IO_P18 ((unsigned int) 0x00040000) +#define GPIO_IO_P19 ((unsigned int) 0x00080000) +#define GPIO_IO_P20 ((unsigned int) 0x00100000) +#define GPIO_IO_P21 ((unsigned int) 0x00200000) +#define GPIO_IO_P22 ((unsigned int) 0x00400000) +#define GPIO_IO_P23 ((unsigned int) 0x00800000) +#define GPIO_IO_P24 ((unsigned int) 0x01000000) +#define GPIO_IO_P25 ((unsigned int) 0x02000000) +#define GPIO_IO_P26 ((unsigned int) 0x04000000) +#define GPIO_IO_P27 ((unsigned int) 0x08000000) +#define GPIO_IO_P28 ((unsigned int) 0x10000000) +#define GPIO_IO_P29 ((unsigned int) 0x20000000) +#define GPIO_IO_P30 ((unsigned int) 0x40000000) +#define GPIO_IO_P31 ((unsigned int) 0x80000000) +#define GPIO_IO_JTAG ((unsigned int) 0x003E0000) + +/* GPIO Interrupt Registers */ +#define IO0_INT_EN_R (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x90)) +#define IO0_INT_EN_F (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x94)) +#define IO0_INT_STAT_R (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x84)) +#define IO0_INT_STAT_F (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x88)) +#define IO0_INT_CLR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x8C)) + +#define IO2_INT_EN_R (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0xB0)) +#define IO2_INT_EN_F (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0xB4)) +#define IO2_INT_STAT_R (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0xA4)) +#define IO2_INT_STAT_F (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0xA8)) +#define IO2_INT_CLR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0xAC)) + +#define IO_INT_STAT (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x80)) + +#define PARTCFG_BASE_ADDR 0x3FFF8000 +#define PARTCFG (*(volatile unsigned long *)(PARTCFG_BASE_ADDR + 0x00)) + +/* 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 0x400FC000 + +/* Memory Accelerator Module */ + +/* Phase Locked Loop (PLL0) */ +#define PLL0CON (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x080)) +#define PLL0CFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x084)) +#define PLL0STAT (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x088)) +#define PLL0FEED (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x08C)) + +/* Phase Locked Loop (PLL1) */ +#define PLL1CON (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0A0)) +#define PLL1CFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0A4)) +#define PLL1STAT (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0A8)) +#define PLL1FEED (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0AC)) + +#define PLLCON_PLLE 0x00000001 +#define PLLCON_PLLC 0x00000002 +#define PLLCON_MASK 0x00000003 + +#define PLLCFG_MUL1 0x00000000 +#define PLLCFG_MUL2 0x00000001 +#define PLLCFG_MUL3 0x00000002 +#define PLLCFG_MUL4 0x00000003 +#define PLLCFG_MUL5 0x00000004 +#define PLLCFG_MUL6 0x00000005 +#define PLLCFG_MUL7 0x00000006 +#define PLLCFG_MUL8 0x00000007 +#define PLLCFG_MUL9 0x00000008 +#define PLLCFG_MUL10 0x00000009 +#define PLLCFG_MUL11 0x0000000A +#define PLLCFG_MUL12 0x0000000B +#define PLLCFG_MUL13 0x0000000C +#define PLLCFG_MUL14 0x0000000D +#define PLLCFG_MUL15 0x0000000E +#define PLLCFG_MUL16 0x0000000F +#define PLLCFG_MUL17 0x00000010 +#define PLLCFG_MUL18 0x00000011 +#define PLLCFG_MUL19 0x00000012 +#define PLLCFG_MUL20 0x00000013 +#define PLLCFG_MUL21 0x00000014 +#define PLLCFG_MUL22 0x00000015 +#define PLLCFG_MUL23 0x00000016 +#define PLLCFG_MUL24 0x00000017 +#define PLLCFG_MUL25 0x00000018 +#define PLLCFG_MUL26 0x00000019 +#define PLLCFG_MUL27 0x0000001A +#define PLLCFG_MUL28 0x0000001B +#define PLLCFG_MUL29 0x0000001C +#define PLLCFG_MUL30 0x0000001D +#define PLLCFG_MUL31 0x0000001E +#define PLLCFG_MUL32 0x0000001F +#define PLLCFG_MUL33 0x00000020 +#define PLLCFG_MUL34 0x00000021 +#define PLLCFG_MUL35 0x00000022 +#define PLLCFG_MUL36 0x00000023 + +#define PLLCFG_DIV1 0x00000000 +#define PLLCFG_DIV2 0x00010000 +#define PLLCFG_DIV3 0x00020000 +#define PLLCFG_DIV4 0x00030000 +#define PLLCFG_DIV5 0x00040000 +#define PLLCFG_DIV6 0x00050000 +#define PLLCFG_DIV7 0x00060000 +#define PLLCFG_DIV8 0x00070000 +#define PLLCFG_DIV9 0x00080000 +#define PLLCFG_DIV10 0x00090000 +#define PLLCFG_MASK 0x00FF7FFF + +#define PLLSTAT_MSEL_MASK 0x00007FFF +#define PLLSTAT_NSEL_MASK 0x00FF0000 + +#define PLLSTAT_PLLE (1 << 24) +#define PLLSTAT_PLLC (1 << 25) +#define PLLSTAT_PLOCK (1 << 26) + +#define PLLFEED_FEED1 0x000000AA +#define PLLFEED_FEED2 0x00000055 + +/* Power Control */ +#define PCON (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0C0)) +#define PCONP (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0C4)) + +#define PCON_IDL 0x00000001 +#define PCON_PD 0x00000002 +#define PCON_PDBOD 0x00000004 +#define PCON_BODPDM 0x00000008 +#define PCON_BOGD 0x00000010 +#define PCON_BORD 0x00000020 +#define PCON_MASK 0x0000003F + +#define PCONP_PCTIM0 0x00000002 +#define PCONP_PCTIM1 0x00000004 +#define PCONP_PCUART0 0x00000008 +#define PCONP_PCUART1 0x00000010 +#define PCONP_PCPWM1 0x00000040 +#define PCONP_PCI2C0 0x00000080 +#define PCONP_PCSPI 0x00000100 +#define PCONP_PCRTC 0x00000200 +#define PCONP_PCSSP1 0x00000400 +#define PCONP_PCAD 0x00001000 +#define PCONP_PCCAN1 0x00002000 +#define PCONP_PCCAN2 0x00004000 +#define PCONP_PCGPIO 0x00008000 +#define PCONP_PCRIT 0x00010000 +#define PCONP_PCMCPWM 0x00020000 +#define PCONP_PCQEI 0x00040000 +#define PCONP_PCI2C1 0x00080000 +#define PCONP_PCSSP0 0x00200000 +#define PCONP_PCTIM2 0x00400000 +#define PCONP_PCTIM3 0x00800000 +#define PCONP_PCUART2 0x01000000 +#define PCONP_PCUART3 0x02000000 +#define PCONP_PCI2C2 0x04000000 +#define PCONP_PCI2S 0x08000000 +#define PCONP_PCGPDMA 0x20000000 +#define PCONP_PCENET 0x40000000 +#define PCONP_PCUSB 0x80000000 +#define PCONP_MASK 0x801817BE + +// Each peripheral clock source uses 2 bits +#define PCLK_25 0x0 // divide by 4 +#define PCLK_100 0x1 // divide by 1 +#define PCLK_50 0x2 // divide by 2 +#define PCLK_RSVD 0x3 // divide by 8* +#define PCLK_MASK 0x3 + +#define EXTINT_EINT0 0x00000001 +#define EXTINT_EINT1 0x00000002 +#define EXTINT_EINT2 0x00000004 +#define EXTINT_EINT3 0x00000008 +#define EXTINT_MASK 0x0000000F + +#define INTWAKE_EINT0 0x00000001 +#define INTWAKE_EINT1 0x00000002 +#define INTWAKE_EINT2 0x00000004 +#define INTWAKE_EINT3 0x00000008 +#define INTWAKE_USB 0x00000020 +#define INTWAKE_BOD 0x00004000 +#define INTWAKE_RTC 0x00008000 +#define INTWAKE_MASK 0x0000C02F + +#define EXTMODE_EINT0 0x00000001 +#define EXTMODE_EINT1 0x00000002 +#define EXTMODE_EINT2 0x00000004 +#define EXTMODE_EINT3 0x00000008 +#define EXTMODE_MASK 0x0000000F + +#define EXTPOLAR_EINT0 0x00000001 +#define EXTPOLAR_EINT1 0x00000002 +#define EXTPOLAR_EINT2 0x00000004 +#define EXTPOLAR_EINT3 0x00000008 +#define EXTPOLAR_MASK 0x0000000F + +#define RSIR_POR 0x00000001 +#define RSIR_EXTR 0x00000002 +#define RSIR_WDTR 0x00000004 +#define RSIR_BODR 0x00000008 +#define RSIR_MASK 0x0000000F + +#define SCS_GPIO0M 0x00000001 +#define SCS_GPIO1M 0x00000002 +#define SCS_MASK 0x00000003 + +/* Clock Divider */ +// #define APBDIV (*(volatile unsigned long *)(BASE_ADDR + 0x100)) +#define CCLKCFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x104)) +#define USBCLKCFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x108)) +#define CLKSRCSEL (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x10C)) +#define PCLKSEL0 (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1A8)) +#define PCLKSEL1 (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1AC)) + +/* External Interrupts */ +#define EXTINT (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x140)) +#define INTWAKE (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x144)) +#define EXTMODE (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x148)) +#define EXTPOLAR (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x14C)) + +/* Reset, reset source identification */ +#define RSIR (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x180)) + +/* RSID, code security protection */ +#define CSPR (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x184)) + +/* AHB configuration */ +#define AHBCFG1 (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x188)) +#define AHBCFG2 (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x18C)) + +/* System Controls and Status */ +#define SCS (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1A0)) + +/* 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 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_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)) + +/* Dynamic RAM access registers */ +#define EMC_DYN_CTRL (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x020)) +#define EMC_DYN_RFSH (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x024)) +#define EMC_DYN_RD_CFG (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x028)) +#define EMC_DYN_RP (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x030)) +#define EMC_DYN_RAS (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x034)) +#define EMC_DYN_SREX (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x038)) +#define EMC_DYN_APR (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x03C)) +#define EMC_DYN_DAL (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x040)) +#define EMC_DYN_WR (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x044)) +#define EMC_DYN_RC (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x048)) +#define EMC_DYN_RFC (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x04C)) +#define EMC_DYN_XSR (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x050)) +#define EMC_DYN_RRD (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x054)) +#define EMC_DYN_MRD (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x058)) + +#define EMC_DYN_CFG0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x100)) +#define EMC_DYN_RASCAS0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x104)) +#define EMC_DYN_CFG1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x120)) +#define EMC_DYN_RASCAS1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x124)) +#define EMC_DYN_CFG2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x140)) +#define EMC_DYN_RASCAS2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x144)) +#define EMC_DYN_CFG3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x160)) +#define EMC_DYN_RASCAS3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x164)) + +/* static RAM access registers */ +#define EMC_STA_CFG0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x200)) +#define EMC_STA_WAITWEN0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x204)) +#define EMC_STA_WAITOEN0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x208)) +#define EMC_STA_WAITRD0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x20C)) +#define EMC_STA_WAITPAGE0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x210)) +#define EMC_STA_WAITWR0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x214)) +#define EMC_STA_WAITTURN0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x218)) + +#define EMC_STA_CFG1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x220)) +#define EMC_STA_WAITWEN1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x224)) +#define EMC_STA_WAITOEN1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x228)) +#define EMC_STA_WAITRD1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x22C)) +#define EMC_STA_WAITPAGE1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x230)) +#define EMC_STA_WAITWR1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x234)) +#define EMC_STA_WAITTURN1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x238)) + +#define EMC_STA_CFG2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x240)) +#define EMC_STA_WAITWEN2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x244)) +#define EMC_STA_WAITOEN2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x248)) +#define EMC_STA_WAITRD2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x24C)) +#define EMC_STA_WAITPAGE2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x250)) +#define EMC_STA_WAITWR2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x254)) +#define EMC_STA_WAITTURN2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x258)) + +#define EMC_STA_CFG3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x260)) +#define EMC_STA_WAITWEN3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x264)) +#define EMC_STA_WAITOEN3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x268)) +#define EMC_STA_WAITRD3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x26C)) +#define EMC_STA_WAITPAGE3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x270)) +#define EMC_STA_WAITWR3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x274)) +#define EMC_STA_WAITTURN3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x278)) + +#define EMC_STA_EXT_WAIT (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x880)) + +/* Timer 0 */ +#define TMR0_BASE_ADDR 0x40004000 +#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)) +#define T0PR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x0C)) +#define T0PC (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x10)) +#define T0MCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x14)) +#define T0MR0 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x18)) +#define T0MR1 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x1C)) +#define T0MR2 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x20)) +#define T0MR3 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x24)) +#define T0CCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x28)) +#define T0CR0 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x2C)) +#define T0CR1 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x30)) +#define T0CR2 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x34)) +#define T0CR3 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x38)) +#define T0EMR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x3C)) +#define T0CTCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x70)) + +/* Timer 1 */ +#define TMR1_BASE_ADDR 0x40008000 +#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)) +#define T1PR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x0C)) +#define T1PC (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x10)) +#define T1MCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x14)) +#define T1MR0 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x18)) +#define T1MR1 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x1C)) +#define T1MR2 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x20)) +#define T1MR3 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x24)) +#define T1CCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x28)) +#define T1CR0 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x2C)) +#define T1CR1 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x30)) +#define T1CR2 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x34)) +#define T1CR3 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x38)) +#define T1EMR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x3C)) +#define T1CTCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x70)) + +/* Timer 2 */ +#define TMR2_BASE_ADDR 0x40090000 +#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)) +#define T2PR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x0C)) +#define T2PC (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x10)) +#define T2MCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x14)) +#define T2MR0 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x18)) +#define T2MR1 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x1C)) +#define T2MR2 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x20)) +#define T2MR3 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x24)) +#define T2CCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x28)) +#define T2CR0 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x2C)) +#define T2CR1 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x30)) +#define T2CR2 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x34)) +#define T2CR3 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x38)) +#define T2EMR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x3C)) +#define T2CTCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x70)) + +/* Timer 3 */ +#define TMR3_BASE_ADDR 0x40094000 +#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)) +#define T3PR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x0C)) +#define T3PC (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x10)) +#define T3MCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x14)) +#define T3MR0 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x18)) +#define T3MR1 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x1C)) +#define T3MR2 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x20)) +#define T3MR3 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x24)) +#define T3CCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x28)) +#define T3CR0 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x2C)) +#define T3CR1 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x30)) +#define T3CR2 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x34)) +#define T3CR3 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x38)) +#define T3EMR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x3C)) +#define T3CTCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x70)) + +#define T_IR_MR0 0x00000001 +#define T_IR_MR1 0x00000002 +#define T_IR_MR2 0x00000004 +#define T_IR_MR3 0x00000008 +#define T_IR_CR0 0x00000010 +#define T_IR_CR1 0x00000020 +#define T_IR_CR2 0x00000040 +#define T_IR_CR3 0x00000080 +#define T_IR_MASK 0x000000FF + +#define T_TCR_CE 0x00000001 +#define T_TCR_CR 0x00000002 + +#define T_CTCR_MODE_PCLK 0x00000000 +#define T_CTCR_MODE_CAPRISE 0x00000001 +#define T_CTCR_MODE_CAPFALL 0x00000002 +#define T_CTCR_MODE_CAPBOTH 0x00000003 +#define T_CTCR_MODE_MASK 0x00000003 +#define T_CTCR_CIS_CAPN0 0x00000000 +#define T_CTCR_CIS_CAPN1 0x00000004 +#define T_CTCR_CIS_CAPN2 0x00000008 +#define T_CTCR_CIS_CAPN3 0x0000000C +#define T_CTCR_CIS_MASK 0x0000000C + +#define T_MCR_MR0I 0x00000001 +#define T_MCR_MR0R 0x00000002 +#define T_MCR_MR0S 0x00000004 +#define T_MCR_MR1I 0x00000008 +#define T_MCR_MR1R 0x00000010 +#define T_MCR_MR1S 0x00000020 +#define T_MCR_MR2I 0x00000040 +#define T_MCR_MR2R 0x00000080 +#define T_MCR_MR2S 0x00000100 +#define T_MCR_MR3I 0x00000200 +#define T_MCR_MR3R 0x00000400 +#define T_MCR_MR3S 0x00000800 + +#define T_CCR_CAP0RE 0x00000001 +#define T_CCR_CAP0FE 0x00000002 +#define T_CCR_CAP0I 0x00000004 +#define T_CCR_CAP1RE 0x00000008 +#define T_CCR_CAP1FE 0x00000010 +#define T_CCR_CAP1I 0x00000020 +#define T_CCR_CAP2RE 0x00000040 +#define T_CCR_CAP2FE 0x00000080 +#define T_CCR_CAP2I 0x00000100 +#define T_CCR_CAP3RE 0x00000200 +#define T_CCR_CAP3FE 0x00000400 +#define T_CCR_CAP3I 0x00000800 + +#define T_EMR_EM0 0x00000001 +#define T_EMR_EM1 0x00000002 +#define T_EMR_EM2 0x00000004 +#define T_EMR_EM3 0x00000008 +#define T_EMR_EMC0_NONE 0x00000000 +#define T_EMR_EMC0_CLEAR 0x00000010 +#define T_EMR_EMC0_SET 0x00000020 +#define T_EMR_EMC0_TOGGLE 0x00000030 +#define T_EMR_EMC0_MASK 0x00000030 +#define T_EMR_EMC1_NONE 0x00000000 +#define T_EMR_EMC1_CLEAR 0x00000040 +#define T_EMR_EMC1_SET 0x00000080 +#define T_EMR_EMC1_TOGGLE 0x000000C0 +#define T_EMR_EMC1_MASK 0x000000C0 +#define T_EMR_EMC2_NONE 0x00000000 +#define T_EMR_EMC2_CLEAR 0x00000100 +#define T_EMR_EMC2_SET 0x00000200 +#define T_EMR_EMC2_TOGGLE 0x00000300 +#define T_EMR_EMC2_MASK 0x00000300 +#define T_EMR_EMC3_NONE 0x00000000 +#define T_EMR_EMC3_CLEAR 0x00000400 +#define T_EMR_EMC3_SET 0x00000800 +#define T_EMR_EMC3_TOGGLE 0x00000C00 +#define T_EMR_EMC3_MASK 0x00000C00 + +/* Pulse Width Modulator (PWM1) */ +#define PWM1_BASE_ADDR 0x40018000 +#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)) +#define PWM1PR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x0C)) +#define PWM1PC (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x10)) +#define PWM1MCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x14)) +#define PWM1MR0 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x18)) +#define PWM1MR1 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x1C)) +#define PWM1MR2 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x20)) +#define PWM1MR3 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x24)) +#define PWM1CCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x28)) +#define PWM1CR0 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x2C)) +#define PWM1CR1 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x30)) +#define PWM1CR2 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x34)) +#define PWM1CR3 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x38)) +#define PWM1EMR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x3C)) +#define PWM1MR4 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x40)) +#define PWM1MR5 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x44)) +#define PWM1MR6 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x48)) +#define PWM1PCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x4C)) +#define PWM1LER (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x50)) +#define PWM1CTCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x70)) + +/* Universal Asynchronous Receiver Transmitter 0 (UART0) */ +#define UART0_BASE_ADDR 0x4000C000 +#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)) +#define U0DLM (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x04)) +#define U0IER (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x04)) +#define U0IIR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x08)) +#define U0FCR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x08)) +#define U0LCR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x0C)) +#define U0LSR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x14)) +#define U0SCR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x1C)) +#define U0ACR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x20)) +#define U0ICR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x24)) +#define U0FDR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x28)) +#define U0TER (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x30)) + +#define UART0_RBR U0RBR +#define UART0_THR U0THR +#define UART0_IER U0IER +#define UART0_IIR U0IIR +#define UART0_FCR U0FCR +#define UART0_LCR U0LCR +#define UART0_LSR U0LSR +#define UART0_SCR U0SCR +#define UART0_ACR U0ACR +#define UART0_FDR U0FDR +#define UART0_TER U0TER +#define UART0_DLL U0DLL +#define UART0_DLM U0DLM + +/* Universal Asynchronous Receiver Transmitter 1 (UART1) */ +#define UART1_BASE_ADDR 0x40010000 +#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)) +#define U1DLM (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x04)) +#define U1IER (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x04)) +#define U1IIR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x08)) +#define U1FCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x08)) +#define U1LCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x0C)) +#define U1MCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x10)) +#define U1LSR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x14)) +#define U1MSR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x18)) +#define U1SCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x1C)) +#define U1ACR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x20)) +#define U1FDR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x28)) +#define U1TER (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x30)) + +#define UART1_RBR U1RBR +#define UART1_THR U1THR +#define UART1_IER U1IER +#define UART1_IIR U1IIR +#define UART1_FCR U1FCR +#define UART1_LCR U1LCR +#define UART1_LSR U1LSR +#define UART1_SCR U1SCR +#define UART1_ACR U1ACR +#define UART1_FDR U1FDR +#define UART1_TER U1TER +#define UART1_DLL U1DLL +#define UART1_DLM U1DLM +#define UART1_MCR U1MCR +#define UART1_MSR U1MSR + +/* Universal Asynchronous Receiver Transmitter 2 (UART2) */ +#define UART2_BASE_ADDR 0x40098000 +#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)) +#define U2DLM (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x04)) +#define U2IER (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x04)) +#define U2IIR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x08)) +#define U2FCR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x08)) +#define U2LCR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x0C)) +#define U2LSR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x14)) +#define U2SCR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x1C)) +#define U2ACR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x20)) +#define U2ICR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x24)) +#define U2FDR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x28)) +#define U2TER (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x30)) + +/* Universal Asynchronous Receiver Transmitter 3 (UART3) */ +#define UART3_BASE_ADDR 0x4009C000 +#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)) +#define U3DLM (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x04)) +#define U3IER (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x04)) +#define U3IIR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x08)) +#define U3FCR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x08)) +#define U3LCR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x0C)) +#define U3LSR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x14)) +#define U3SCR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x1C)) +#define U3ACR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x20)) +#define U3ICR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x24)) +#define U3FDR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x28)) +#define U3TER (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x30)) + +#define UART_LCR_DLAB 0x00000080 +#define UART_LCR_NOPAR 0x00000000 +#define UART_LCR_1STOP 0x00000000 +#define UART_LCR_8BITS 0x00000003 +#define UART_IER_EI 0x00000003 +#define UART_FCR_EN 0x00000001 +#define UART_FCR_CLR 0x00000006 + +/* I2C Interface 0 */ +#define I2C0_BASE_ADDR 0x4001C000 +#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)) +#define I20ADR (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x0C)) +#define I20SCLH (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x10)) +#define I20SCLL (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x14)) +#define I20CONCLR (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x18)) + +/* I2C Interface 1 */ +#define I2C1_BASE_ADDR 0x4005C000 +#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)) +#define I21ADR (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x0C)) +#define I21SCLH (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x10)) +#define I21SCLL (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x14)) +#define I21CONCLR (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x18)) + +/* I2C Interface 2 */ +#define I2C2_BASE_ADDR 0x400A000 +#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)) +#define I22ADR (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x0C)) +#define I22SCLH (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x10)) +#define I22SCLL (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x14)) +#define I22CONCLR (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x18)) + +/* SPI0 (Serial Peripheral Interface 0) */ +#define SPI0_BASE_ADDR 0x40020000 +#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)) +#define S0SPCCR (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x0C)) +#define S0SPINT (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x1C)) + +/* SSP0 Controller */ +#define SSP0_BASE_ADDR 0x40088000 +#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)) +#define SSP0SR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x0C)) +#define SSP0CPSR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x10)) +#define SSP0IMSC (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x14)) +#define SSP0RIS (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x18)) +#define SSP0MIS (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x1C)) +#define SSP0ICR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x20)) +#define SSP0DMACR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x24)) + +/* SSP1 Controller */ +#define SSP1_BASE_ADDR 0x40030000 +#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)) +#define SSP1SR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x0C)) +#define SSP1CPSR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x10)) +#define SSP1IMSC (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x14)) +#define SSP1RIS (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x18)) +#define SSP1MIS (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x1C)) +#define SSP1ICR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x20)) +#define SSP1DMACR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x24)) + +/* Real Time Clock */ +#define RTC_BASE_ADDR 0x40024000 +#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)) +#define RTC_CIIR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x0C)) +#define RTC_AMR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x10)) +#define RTC_CTIME0 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x14)) +#define RTC_CTIME1 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x18)) +#define RTC_CTIME2 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x1C)) + +#define RTC_SEC (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x20)) +#define RTC_MIN (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x24)) +#define RTC_HOUR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x28)) +#define RTC_DOM (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x2C)) +#define RTC_DOW (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x30)) +#define RTC_DOY (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x34)) +#define RTC_MONTH (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x38)) +#define RTC_YEAR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x3C)) + +#define RTC_CISS (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x40)) +#define RTC_GPREG0 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x44)) +#define RTC_GPREG1 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x48)) +#define RTC_GPREG2 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x4C)) +#define RTC_GPREG3 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x50)) +#define RTC_GPREG4 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x54)) +#define RTC_WAKEUPDIS (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x58)) +#define RTC_PWRCTRL (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x5C)) + +#define RTC_ALSEC (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x60)) +#define RTC_ALMIN (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x64)) +#define RTC_ALHOUR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x68)) +#define RTC_ALDOM (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x6C)) +#define RTC_ALDOW (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x70)) +#define RTC_ALDOY (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x74)) +#define RTC_ALMON (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x78)) +#define RTC_ALYEAR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x7C)) +#define RTC_PREINT (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x80)) +#define RTC_PREFRAC (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x84)) + +#define RTC_ILR_RTCCIF 0x00000001 +#define RTC_ILR_RTCALF 0x00000002 +#define RTC_ILR_MASK 0x00000003 + +#define RTC_CCR_CLKEN 0x00000001 +#define RTC_CCR_CTCRST 0x00000002 +#define RTC_CCR_TEST 0x0000000c +#define RTC_CCR_CLKSRC 0x00000010 + +#define RTC_CIIR_IMSEC 0x00000001 +#define RTC_CIIR_IMMIN 0x00000002 +#define RTC_CIIR_IMHOUR 0x00000004 +#define RTC_CIIR_IMDOM 0x00000008 +#define RTC_CIIR_IMDOW 0x00000010 +#define RTC_CIIR_IMDOY 0x00000020 +#define RTC_CIIR_IMMON 0x00000040 +#define RTC_CIIR_IMYEAR 0x00000080 +#define RTC_CIIR_IMMASK 0x000000FF + +#define RTC_AMR_AMRSEC 0x00000001 +#define RTC_AMR_AMRMIN 0x00000002 +#define RTC_AMR_AMRHOUR 0x00000004 +#define RTC_AMR_AMRDOM 0x00000008 +#define RTC_AMR_AMRDOW 0x00000010 +#define RTC_AMR_AMRDOY 0x00000020 +#define RTC_AMR_AMRMON 0x00000040 +#define RTC_AMR_AMRYEAR 0x00000080 +#define RTC_AMR_AMRMASK 0x000000FF + +typedef struct __attribute__ ((packed)) +{ + union + { + struct + { + unsigned int counter : 14; + unsigned int rsvd15_31 : 18; + }; + + unsigned int i; + }; +} +rtcCTC_t; + +typedef struct __attribute__ ((packed)) +{ + union + { + struct + { + unsigned int seconds : 6; + unsigned int rsvd7_6 : 2; + unsigned int minutes : 6; + unsigned int rsvd14_15 : 2; + unsigned int hours : 5; + unsigned int rsvd21_23 : 3; + unsigned int dow : 3; + unsigned int rsvd27_31 : 5; + }; + + unsigned int i; + }; +} +rtcCTIME0_t; + +typedef struct __attribute__ ((packed)) +{ + union + { + struct + { + unsigned int dom : 5; + unsigned int rsvd5_7 : 3; + unsigned int month : 4; + unsigned int rsvd12_15 : 4; + unsigned int year : 12; + unsigned int rsvd28_31 : 4; + }; + + unsigned int i; + }; +} +rtcCTIME1_t; + +typedef struct __attribute__ ((packed)) +{ + union + { + struct + { + unsigned int doy : 12; + unsigned int rsvd12_31 : 20; + }; + + unsigned int i; + }; +} +rtcCTIME2_t; + +/* A/D Converter 0 (AD0) */ +#define AD0_BASE_ADDR 0x40034000 +#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)) +#define AD0DR0 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x10)) +#define AD0DR1 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x14)) +#define AD0DR2 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x18)) +#define AD0DR3 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x1C)) +#define AD0DR4 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x20)) +#define AD0DR5 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x24)) +#define AD0DR6 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x28)) +#define AD0DR7 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x2C)) +#define AD0STAT (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x30)) + +/* D/A Converter */ +#define DAC_BASE_ADDR 0x4008C000 +#define DACR (*(volatile unsigned long *)(DAC_BASE_ADDR + 0x00)) + +/* Watchdog */ +#define WDG_BASE_ADDR 0x40000000 +#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)) +#define WDTV (*(volatile unsigned long *)(WDG_BASE_ADDR + 0x0C)) +#define WDCLKSEL (*(volatile unsigned long *)(WDG_BASE_ADDR + 0x10)) + +/* CAN CONTROLLERS AND ACCEPTANCE FILTER */ +#define CAN_ACCEPT_BASE_ADDR 0x4003C000 +#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 0x40044000 +#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 0x40048000 +#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)) + +/* I2S Interface Controller (I2S) */ +#define I2S_BASE_ADDR 0x400A8000 +#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)) +#define I2S_RX_FIFO (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x0C)) +#define I2S_STATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x10)) +#define I2S_DMA1 (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x14)) +#define I2S_DMA2 (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x18)) +#define I2S_IRQ (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x1C)) +#define I2S_TXRATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x20)) +#define I2S_RXRATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x24)) + +/* General-purpose DMA Controller */ +#define DMA_BASE_ADDR 0x50004000 +#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)) +#define GPDMA_INT_ERR_STAT (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x00C)) +#define GPDMA_INT_ERR_CLR (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x010)) +#define GPDMA_RAW_INT_TCSTAT (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x014)) +#define GPDMA_RAW_INT_ERR_STAT (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x018)) +#define GPDMA_ENABLED_CHNS (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x01C)) +#define GPDMA_SOFT_BREQ (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x020)) +#define GPDMA_SOFT_SREQ (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x024)) +#define GPDMA_SOFT_LBREQ (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x028)) +#define GPDMA_SOFT_LSREQ (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x02C)) +#define GPDMA_CONFIG (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x030)) +#define GPDMA_SYNC (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x034)) + +/* DMA channel 0 registers */ +#define GPDMA_CH0_SRC (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x100)) +#define GPDMA_CH0_DEST (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x104)) +#define GPDMA_CH0_LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x108)) +#define GPDMA_CH0_CTRL (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x10C)) +#define GPDMA_CH0_CFG (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x110)) + +/* DMA channel 1 registers */ +#define GPDMA_CH1_SRC (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x120)) +#define GPDMA_CH1_DEST (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x124)) +#define GPDMA_CH1_LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x128)) +#define GPDMA_CH1_CTRL (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x12C)) +#define GPDMA_CH1_CFG (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x130)) + + +/* USB Controller */ +#define USB_INT_BASE_ADDR 0x400FC1C0 +#define USB_BASE_ADDR 0x5000C200 /* USB Base Address */ + +#define USB_INT_STAT (*(volatile unsigned long *)(USB_INT_BASE_ADDR + 0x00)) + +/* USB Device Interrupt Registers */ +#define DEV_INT_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0x00)) +#define DEV_INT_EN (*(volatile unsigned long *)(USB_BASE_ADDR + 0x04)) +#define DEV_INT_CLR (*(volatile unsigned long *)(USB_BASE_ADDR + 0x08)) +#define DEV_INT_SET (*(volatile unsigned long *)(USB_BASE_ADDR + 0x0C)) +#define DEV_INT_PRIO (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2C)) + +/* USB Device Endpoint Interrupt Registers */ +#define EP_INT_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0x30)) +#define EP_INT_EN (*(volatile unsigned long *)(USB_BASE_ADDR + 0x34)) +#define EP_INT_CLR (*(volatile unsigned long *)(USB_BASE_ADDR + 0x38)) +#define EP_INT_SET (*(volatile unsigned long *)(USB_BASE_ADDR + 0x3C)) +#define EP_INT_PRIO (*(volatile unsigned long *)(USB_BASE_ADDR + 0x40)) + +/* USB Device Endpoint Realization Registers */ +#define REALIZE_EP (*(volatile unsigned long *)(USB_BASE_ADDR + 0x44)) +#define EP_INDEX (*(volatile unsigned long *)(USB_BASE_ADDR + 0x48)) +#define MAXPACKET_SIZE (*(volatile unsigned long *)(USB_BASE_ADDR + 0x4C)) + +/* USB Device Command Reagisters */ +#define CMD_CODE (*(volatile unsigned long *)(USB_BASE_ADDR + 0x10)) +#define CMD_DATA (*(volatile unsigned long *)(USB_BASE_ADDR + 0x14)) + +/* USB Device Data Transfer Registers */ +#define RX_DATA (*(volatile unsigned long *)(USB_BASE_ADDR + 0x18)) +#define TX_DATA (*(volatile unsigned long *)(USB_BASE_ADDR + 0x1C)) +#define RX_PLENGTH (*(volatile unsigned long *)(USB_BASE_ADDR + 0x20)) +#define TX_PLENGTH (*(volatile unsigned long *)(USB_BASE_ADDR + 0x24)) +#define USB_CTRL (*(volatile unsigned long *)(USB_BASE_ADDR + 0x28)) + +/* USB Device DMA Registers */ +#define DMA_REQ_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0x50)) +#define DMA_REQ_CLR (*(volatile unsigned long *)(USB_BASE_ADDR + 0x54)) +#define DMA_REQ_SET (*(volatile unsigned long *)(USB_BASE_ADDR + 0x58)) +#define UDCA_HEAD (*(volatile unsigned long *)(USB_BASE_ADDR + 0x80)) +#define EP_DMA_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0x84)) +#define EP_DMA_EN (*(volatile unsigned long *)(USB_BASE_ADDR + 0x88)) +#define EP_DMA_DIS (*(volatile unsigned long *)(USB_BASE_ADDR + 0x8C)) +#define DMA_INT_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0x90)) +#define DMA_INT_EN (*(volatile unsigned long *)(USB_BASE_ADDR + 0x94)) +#define EOT_INT_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0xA0)) +#define EOT_INT_CLR (*(volatile unsigned long *)(USB_BASE_ADDR + 0xA4)) +#define EOT_INT_SET (*(volatile unsigned long *)(USB_BASE_ADDR + 0xA8)) +#define NDD_REQ_INT_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0xAC)) +#define NDD_REQ_INT_CLR (*(volatile unsigned long *)(USB_BASE_ADDR + 0xB0)) +#define NDD_REQ_INT_SET (*(volatile unsigned long *)(USB_BASE_ADDR + 0xB4)) +#define SYS_ERR_INT_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0xB8)) +#define SYS_ERR_INT_CLR (*(volatile unsigned long *)(USB_BASE_ADDR + 0xBC)) +#define SYS_ERR_INT_SET (*(volatile unsigned long *)(USB_BASE_ADDR + 0xC0)) + +/* USB Host and OTG registers are for LPC24xx only */ +/* USB Host Controller */ +#define USBHC_BASE_ADDR 0x5000C000 +#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)) +#define HC_INT_STAT (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x0C)) +#define HC_INT_EN (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x10)) +#define HC_INT_DIS (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x14)) +#define HC_HCCA (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x18)) +#define HC_PERIOD_CUR_ED (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x1C)) +#define HC_CTRL_HEAD_ED (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x20)) +#define HC_CTRL_CUR_ED (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x24)) +#define HC_BULK_HEAD_ED (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x28)) +#define HC_BULK_CUR_ED (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x2C)) +#define HC_DONE_HEAD (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x30)) +#define HC_FM_INTERVAL (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x34)) +#define HC_FM_REMAINING (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x38)) +#define HC_FM_NUMBER (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x3C)) +#define HC_PERIOD_START (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x40)) +#define HC_LS_THRHLD (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x44)) +#define HC_RH_DESCA (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x48)) +#define HC_RH_DESCB (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x4C)) +#define HC_RH_STAT (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x50)) +#define HC_RH_PORT_STAT1 (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x54)) +#define HC_RH_PORT_STAT2 (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x58)) + +/* USB OTG Controller */ +#define USBOTG_BASE_ADDR 0x5000C100 +#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)) +#define OTG_INT_CLR (*(volatile unsigned long *)(USBOTG_BASE_ADDR + 0x0C)) +/* On LPC17xx, the name is USBPortSel */ +#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 0x5000C300 +#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)) +#define OTG_I2C_CTL (*(volatile unsigned long *)(USBOTG_I2C_BASE_ADDR + 0x08)) +#define OTG_I2C_CLKHI (*(volatile unsigned long *)(USBOTG_I2C_BASE_ADDR + 0x0C)) +#define OTG_I2C_CLKLO (*(volatile unsigned long *)(USBOTG_I2C_BASE_ADDR + 0x10)) + +/* On LPC17xx, the names are USBClkCtrl and USBClkSt */ +#define USBOTG_CLK_BASE_ADDR 0x5000CFF0 +#define OTG_CLK_CTRL (*(volatile unsigned long *)(USBOTG_CLK_BASE_ADDR + 0x04)) +#define OTG_CLK_STAT (*(volatile unsigned long *)(USBOTG_CLK_BASE_ADDR + 0x08)) + +/* Note: below three register name convention is for LPC17xx USB device only, match +with the spec. update in USB Device Section. */ +#define USBPortSel (*(volatile unsigned long *)(USBOTG_BASE_ADDR + 0x10)) +#define USBClkCtrl (*(volatile unsigned long *)(USBOTG_CLK_BASE_ADDR + 0x04)) +#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 0x50000000 +#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 */ +#define MAC_IPGR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x00C)) /* non b2b InterPacketGap reg */ +#define MAC_CLRT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x010)) /* CoLlision window/ReTry reg */ +#define MAC_MAXF (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x014)) /* MAXimum Frame reg */ +#define MAC_SUPP (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x018)) /* PHY SUPPort reg */ +#define MAC_TEST (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x01C)) /* TEST reg */ +#define MAC_MCFG (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x020)) /* MII Mgmt ConFiG reg */ +#define MAC_MCMD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x024)) /* MII Mgmt CoMmanD reg */ +#define MAC_MADR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x028)) /* MII Mgmt ADdRess reg */ +#define MAC_MWTD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x02C)) /* MII Mgmt WriTe Data reg (WO) */ +#define MAC_MRDD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x030)) /* MII Mgmt ReaD Data reg (RO) */ +#define MAC_MIND (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x034)) /* MII Mgmt INDicators reg (RO) */ + +#define MAC_SA0 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x040)) /* Station Address 0 reg */ +#define MAC_SA1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x044)) /* Station Address 1 reg */ +#define MAC_SA2 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x048)) /* Station Address 2 reg */ + +#define MAC_COMMAND (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x100)) /* Command reg */ +#define MAC_STATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x104)) /* Status reg (RO) */ +#define MAC_RXDESCRIPTOR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x108)) /* Rx descriptor base address reg */ +#define MAC_RXSTATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x10C)) /* Rx status base address reg */ +#define MAC_RXDESCRIPTORNUM (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x110)) /* Rx number of descriptors reg */ +#define MAC_RXPRODUCEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x114)) /* Rx produce index reg (RO) */ +#define MAC_RXCONSUMEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x118)) /* Rx consume index reg */ +#define MAC_TXDESCRIPTOR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x11C)) /* Tx descriptor base address reg */ +#define MAC_TXSTATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x120)) /* Tx status base address reg */ +#define MAC_TXDESCRIPTORNUM (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x124)) /* Tx number of descriptors reg */ +#define MAC_TXPRODUCEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x128)) /* Tx produce index reg */ +#define MAC_TXCONSUMEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x12C)) /* Tx consume index reg (RO) */ + +#define MAC_TSV0 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x158)) /* Tx status vector 0 reg (RO) */ +#define MAC_TSV1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x15C)) /* Tx status vector 1 reg (RO) */ +#define MAC_RSV (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x160)) /* Rx status vector reg (RO) */ + +#define MAC_FLOWCONTROLCNT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x170)) /* Flow control counter reg */ +#define MAC_FLOWCONTROLSTS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x174)) /* Flow control status reg */ + +#define MAC_RXFILTERCTRL (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x200)) /* Rx filter ctrl reg */ +#define MAC_RXFILTERWOLSTS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x204)) /* Rx filter WoL status reg (RO) */ +#define MAC_RXFILTERWOLCLR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x208)) /* Rx filter WoL clear reg (WO) */ + +#define MAC_HASHFILTERL (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x210)) /* Hash filter LSBs reg */ +#define MAC_HASHFILTERH (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x214)) /* Hash filter MSBs reg */ + +#define MAC_INTSTATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE0)) /* Interrupt status reg (RO) */ +#define MAC_INTENABLE (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE4)) /* Interrupt enable reg */ +#define MAC_INTCLEAR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE8)) /* Interrupt clear reg (WO) */ +#define MAC_INTSET (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFEC)) /* Interrupt set reg (WO) */ + +#define MAC_POWERDOWN (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFF4)) /* Power-down reg */ +#define MAC_MODULEID (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFFC)) /* Module ID reg (RO) */ + + +#define FLASHCFG (*(volatile unsigned long * ) (0x400F C000)) + +#endif // __LPC17xx_H + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/ParTest.c b/Demo/CORTEX_LPC1768_GCC_Rowley/ParTest.c new file mode 100644 index 000000000..c789356c8 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/ParTest.c @@ -0,0 +1,147 @@ +/* + FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry. + + This file is part of the FreeRTOS.org distribution. + + FreeRTOS.org is free software; you can redistribute it and/or modify it + under the terms of the GNU General Public License (version 2) as published + by the Free Software Foundation and modified by the FreeRTOS exception. + **NOTE** The exception to the GPL is included to allow you to distribute a + combined work that includes FreeRTOS.org without being obliged to provide + the source code for any proprietary components. Alternative commercial + license and support terms are also available upon request. See the + licensing section of http://www.FreeRTOS.org for full details. + + FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. + + You should have received a copy of the GNU General Public License along + with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 + Temple Place, Suite 330, Boston, MA 02111-1307 USA. + + + *************************************************************************** + * * + * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * + * * + * This is a concise, step by step, 'hands on' guide that describes both * + * general multitasking concepts and FreeRTOS specifics. It presents and * + * explains numerous examples that are written using the FreeRTOS API. * + * Full source code for all the examples is provided in an accompanying * + * .zip file. * + * * + *************************************************************************** + + 1 tab == 4 spaces! + + Please ensure to read the configuration and relevant port sections of the + online documentation. + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/* FreeRTOS.org includes. */ +#include "FreeRTOS.h" + +/* Demo application includes. */ +#include "partest.h" + +#define partstFIRST_IO ( ( unsigned portLONG ) 0x04 ) +#define partstNUM_LEDS ( 5 ) +#define partstALL_OUTPUTS_OFF ( ( unsigned portLONG ) 0xff ) + +/*----------------------------------------------------------- + * Simple parallel port IO routines. + *-----------------------------------------------------------*/ + +void vParTestInitialise( void ) +{ + PINSEL10 = 0; + FIO2DIR = 0x000000FF; + FIO2MASK = 0x00000000; + FIO2CLR = 0xFF; + SCS |= (1<<0); //fast mode for port 0 and 1 + + FIO2CLR = partstALL_OUTPUTS_OFF; +} +/*-----------------------------------------------------------*/ + +void vParTestSetLED( unsigned portBASE_TYPE uxLED, signed portBASE_TYPE xValue ) +{ +unsigned portLONG ulLED = partstFIRST_IO; + + if( uxLED < partstNUM_LEDS ) + { + /* Rotate to the wanted bit of port */ + ulLED <<= ( unsigned portLONG ) uxLED; + + /* Set of clear the output. */ + if( xValue ) + { + FIO2CLR = ulLED; + } + else + { + FIO2SET = ulLED; + } + } +} +/*-----------------------------------------------------------*/ + +void vParTestToggleLED( unsigned portBASE_TYPE uxLED ) +{ +unsigned portLONG ulLED = partstFIRST_IO, ulCurrentState; + + if( uxLED < partstNUM_LEDS ) + { + /* Rotate to the wanted bit of port 0. Only P10 to P13 have an LED + attached. */ + ulLED <<= ( unsigned portLONG ) uxLED; + + /* If this bit is already set, clear it, and visa versa. */ + ulCurrentState = FIO2PIN; + if( ulCurrentState & ulLED ) + { + FIO2CLR = ulLED; + } + else + { + FIO2SET = ulLED; + } + } +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxParTextGetLED( unsigned portBASE_TYPE uxLED ) +{ +unsigned portLONG ulLED = partstFIRST_IO; + + ulLED <<= ( unsigned portLONG ) uxLED; + + return ( FIO2PIN & ulLED ); +} +/*-----------------------------------------------------------*/ + +long lParTestGetLEDState( unsigned portBASE_TYPE uxLED ) +{ + return 0; +} +/*-----------------------------------------------------------*/ + +int __putchar( int x ) +{ + /* Not used. */ +} + + + + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/RTOSDemo.hzp b/Demo/CORTEX_LPC1768_GCC_Rowley/RTOSDemo.hzp new file mode 100644 index 000000000..284f7827f --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/RTOSDemo.hzp @@ -0,0 +1,57 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/RTOSDemo.hzs b/Demo/CORTEX_LPC1768_GCC_Rowley/RTOSDemo.hzs new file mode 100644 index 000000000..a7228d4d7 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/RTOSDemo.hzs @@ -0,0 +1,55 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/core_cm3.h b/Demo/CORTEX_LPC1768_GCC_Rowley/core_cm3.h new file mode 100644 index 000000000..b6f9696bf --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/core_cm3.h @@ -0,0 +1,1367 @@ +/****************************************************************************** + * @file: core_cm3.h + * @purpose: CMSIS Cortex-M3 Core Peripheral Access Layer Header File + * @version: V1.20 + * @date: 22. May 2009 + *---------------------------------------------------------------------------- + * + * Copyright (C) 2009 ARM Limited. All rights reserved. + * + * ARM Limited (ARM) is supplying this software for use with Cortex-Mx + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#ifndef __CM3_CORE_H__ +#define __CM3_CORE_H__ + +#ifdef __cplusplus + extern "C" { +#endif + +#define __CM3_CMSIS_VERSION_MAIN (0x01) /*!< [31:16] CMSIS HAL main version */ +#define __CM3_CMSIS_VERSION_SUB (0x20) /*!< [15:0] CMSIS HAL sub version */ +#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16) | __CM3_CMSIS_VERSION_SUB) /*!< CMSIS HAL version number */ + +#define __CORTEX_M (0x03) /*!< Cortex core */ + +/** + * Lint configuration \n + * ----------------------- \n + * + * The following Lint messages will be suppressed and not shown: \n + * \n + * --- Error 10: --- \n + * register uint32_t __regBasePri __asm("basepri"); \n + * Error 10: Expecting ';' \n + * \n + * --- Error 530: --- \n + * return(__regBasePri); \n + * Warning 530: Symbol '__regBasePri' (line 264) not initialized \n + * \n + * --- Error 550: --- \n + * __regBasePri = (basePri & 0x1ff); \n + * } \n + * Warning 550: Symbol '__regBasePri' (line 271) not accessed \n + * \n + * --- Error 754: --- \n + * uint32_t RESERVED0[24]; \n + * Info 754: local structure member '' (line 109, file ./cm3_core.h) not referenced \n + * \n + * --- Error 750: --- \n + * #define __CM3_CORE_H__ \n + * Info 750: local macro '__CM3_CORE_H__' (line 43, file./cm3_core.h) not referenced \n + * \n + * --- Error 528: --- \n + * static __INLINE void NVIC_DisableIRQ(uint32_t IRQn) \n + * Warning 528: Symbol 'NVIC_DisableIRQ(unsigned int)' (line 419, file ./cm3_core.h) not referenced \n + * \n + * --- Error 751: --- \n + * } InterruptType_Type; \n + * Info 751: local typedef 'InterruptType_Type' (line 170, file ./cm3_core.h) not referenced \n + * \n + * \n + * Note: To re-enable a Message, insert a space before 'lint' * \n + * + */ + +/*lint -save */ +/*lint -e10 */ +/*lint -e530 */ +/*lint -e550 */ +/*lint -e754 */ +/*lint -e750 */ +/*lint -e528 */ +/*lint -e751 */ + + +#include /* Include standard types */ + +#if defined (__ICCARM__) + #include /* IAR Intrinsics */ +#endif + + +#ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 4 /*!< standard definition for NVIC Priority Bits */ +#endif + + + + +/** + * IO definitions + * + * define access restrictions to peripheral registers + */ + +#ifdef __cplusplus +#define __I volatile /*!< defines 'read only' permissions */ +#else +#define __I volatile const /*!< defines 'read only' permissions */ +#endif +#define __O volatile /*!< defines 'write only' permissions */ +#define __IO volatile /*!< defines 'read / write' permissions */ + + + +/******************************************************************************* + * Register Abstraction + ******************************************************************************/ + + +/* System Reset */ +#define NVIC_VECTRESET 0 /*!< Vector Reset Bit */ +#define NVIC_SYSRESETREQ 2 /*!< System Reset Request */ +#define NVIC_AIRCR_VECTKEY (0x5FA << 16) /*!< AIRCR Key for write access */ +#define NVIC_AIRCR_ENDIANESS 15 /*!< Endianess */ + +/* Core Debug */ +#define CoreDebug_DEMCR_TRCENA (1 << 24) /*!< DEMCR TRCENA enable */ +#define ITM_TCR_ITMENA 1 /*!< ITM enable */ + + + + +/* memory mapping struct for Nested Vectored Interrupt Controller (NVIC) */ +typedef struct +{ + __IO uint32_t ISER[8]; /*!< Interrupt Set Enable Register */ + uint32_t RESERVED0[24]; + __IO uint32_t ICER[8]; /*!< Interrupt Clear Enable Register */ + uint32_t RSERVED1[24]; + __IO uint32_t ISPR[8]; /*!< Interrupt Set Pending Register */ + uint32_t RESERVED2[24]; + __IO uint32_t ICPR[8]; /*!< Interrupt Clear Pending Register */ + uint32_t RESERVED3[24]; + __IO uint32_t IABR[8]; /*!< Interrupt Active bit Register */ + uint32_t RESERVED4[56]; + __IO uint8_t IP[240]; /*!< Interrupt Priority Register, 8Bit wide */ + uint32_t RESERVED5[644]; + __O uint32_t STIR; /*!< Software Trigger Interrupt Register */ +} NVIC_Type; + + +/* memory mapping struct for System Control Block */ +typedef struct +{ + __I uint32_t CPUID; /*!< CPU ID Base Register */ + __IO uint32_t ICSR; /*!< Interrupt Control State Register */ + __IO uint32_t VTOR; /*!< Vector Table Offset Register */ + __IO uint32_t AIRCR; /*!< Application Interrupt / Reset Control Register */ + __IO uint32_t SCR; /*!< System Control Register */ + __IO uint32_t CCR; /*!< Configuration Control Register */ + __IO uint8_t SHP[12]; /*!< System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IO uint32_t SHCSR; /*!< System Handler Control and State Register */ + __IO uint32_t CFSR; /*!< Configurable Fault Status Register */ + __IO uint32_t HFSR; /*!< Hard Fault Status Register */ + __IO uint32_t DFSR; /*!< Debug Fault Status Register */ + __IO uint32_t MMFAR; /*!< Mem Manage Address Register */ + __IO uint32_t BFAR; /*!< Bus Fault Address Register */ + __IO uint32_t AFSR; /*!< Auxiliary Fault Status Register */ + __I uint32_t PFR[2]; /*!< Processor Feature Register */ + __I uint32_t DFR; /*!< Debug Feature Register */ + __I uint32_t ADR; /*!< Auxiliary Feature Register */ + __I uint32_t MMFR[4]; /*!< Memory Model Feature Register */ + __I uint32_t ISAR[5]; /*!< ISA Feature Register */ +} SCB_Type; + + +/* memory mapping struct for SysTick */ +typedef struct +{ + __IO uint32_t CTRL; /*!< SysTick Control and Status Register */ + __IO uint32_t LOAD; /*!< SysTick Reload Value Register */ + __IO uint32_t VAL; /*!< SysTick Current Value Register */ + __I uint32_t CALIB; /*!< SysTick Calibration Register */ +} SysTick_Type; + + +/* memory mapping structur for ITM */ +typedef struct +{ + __O union + { + __O uint8_t u8; /*!< ITM Stimulus Port 8-bit */ + __O uint16_t u16; /*!< ITM Stimulus Port 16-bit */ + __O uint32_t u32; /*!< ITM Stimulus Port 32-bit */ + } PORT [32]; /*!< ITM Stimulus Port Registers */ + uint32_t RESERVED0[864]; + __IO uint32_t TER; /*!< ITM Trace Enable Register */ + uint32_t RESERVED1[15]; + __IO uint32_t TPR; /*!< ITM Trace Privilege Register */ + uint32_t RESERVED2[15]; + __IO uint32_t TCR; /*!< ITM Trace Control Register */ + uint32_t RESERVED3[29]; + __IO uint32_t IWR; /*!< ITM Integration Write Register */ + __IO uint32_t IRR; /*!< ITM Integration Read Register */ + __IO uint32_t IMCR; /*!< ITM Integration Mode Control Register */ + uint32_t RESERVED4[43]; + __IO uint32_t LAR; /*!< ITM Lock Access Register */ + __IO uint32_t LSR; /*!< ITM Lock Status Register */ + uint32_t RESERVED5[6]; + __I uint32_t PID4; /*!< ITM Product ID Registers */ + __I uint32_t PID5; + __I uint32_t PID6; + __I uint32_t PID7; + __I uint32_t PID0; + __I uint32_t PID1; + __I uint32_t PID2; + __I uint32_t PID3; + __I uint32_t CID0; + __I uint32_t CID1; + __I uint32_t CID2; + __I uint32_t CID3; +} ITM_Type; + + +/* memory mapped struct for Interrupt Type */ +typedef struct +{ + uint32_t RESERVED0; + __I uint32_t ICTR; /*!< Interrupt Control Type Register */ +#if ((defined __CM3_REV) && (__CM3_REV >= 0x200)) + __IO uint32_t ACTLR; /*!< Auxiliary Control Register */ +#else + uint32_t RESERVED1; +#endif +} InterruptType_Type; + + +/* Memory Protection Unit */ +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1) +typedef struct +{ + __I uint32_t TYPE; /*!< MPU Type Register */ + __IO uint32_t CTRL; /*!< MPU Control Register */ + __IO uint32_t RNR; /*!< MPU Region RNRber Register */ + __IO uint32_t RBAR; /*!< MPU Region Base Address Register */ + __IO uint32_t RASR; /*!< MPU Region Attribute and Size Register */ + __IO uint32_t RBAR_A1; /*!< MPU Alias 1 Region Base Address Register */ + __IO uint32_t RASR_A1; /*!< MPU Alias 1 Region Attribute and Size Register */ + __IO uint32_t RBAR_A2; /*!< MPU Alias 2 Region Base Address Register */ + __IO uint32_t RASR_A2; /*!< MPU Alias 2 Region Attribute and Size Register */ + __IO uint32_t RBAR_A3; /*!< MPU Alias 3 Region Base Address Register */ + __IO uint32_t RASR_A3; /*!< MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; +#endif + + +/* Core Debug Register */ +typedef struct +{ + __IO uint32_t DHCSR; /*!< Debug Halting Control and Status Register */ + __O uint32_t DCRSR; /*!< Debug Core Register Selector Register */ + __IO uint32_t DCRDR; /*!< Debug Core Register Data Register */ + __IO uint32_t DEMCR; /*!< Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + + +/* Memory mapping of Cortex-M3 Hardware */ +#define SCS_BASE (0xE000E000) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000) /*!< ITM Base Address */ +#define CoreDebug_BASE (0xE000EDF0) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00) /*!< System Control Block Base Address */ + +#define InterruptType ((InterruptType_Type *) SCS_BASE) /*!< Interrupt Type Register */ +#define SCB ((SCB_Type *) SCB_BASE) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE) /*!< ITM configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1) + #define MPU_BASE (SCS_BASE + 0x0D90) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type*) MPU_BASE) /*!< Memory Protection Unit */ +#endif + + + +/******************************************************************************* + * Hardware Abstraction Layer + ******************************************************************************/ + + +#if defined ( __CC_ARM ) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + +#elif defined ( __ICCARM__ ) + #define __ASM __asm /*!< asm keyword for IAR Compiler */ + #define __INLINE inline /*!< inline keyword for IAR Compiler. Only avaiable in High optimization mode! */ + +#elif defined ( __GNUC__ ) + #define __ASM __asm /*!< asm keyword for GNU Compiler */ + #define __INLINE inline /*!< inline keyword for GNU Compiler */ + +#elif defined ( __TASKING__ ) + #define __ASM __asm /*!< asm keyword for TASKING Compiler */ + #define __INLINE inline /*!< inline keyword for TASKING Compiler */ + +#endif + + +/* ################### Compiler specific Intrinsics ########################### */ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +#define __enable_fault_irq __enable_fiq +#define __disable_fault_irq __disable_fiq + +#define __NOP __nop +#define __WFI __wfi +#define __WFE __wfe +#define __SEV __sev +#define __ISB() __isb(0) +#define __DSB() __dsb(0) +#define __DMB() __dmb(0) +#define __REV __rev +#define __RBIT __rbit +#define __LDREXB(ptr) ((unsigned char ) __ldrex(ptr)) +#define __LDREXH(ptr) ((unsigned short) __ldrex(ptr)) +#define __LDREXW(ptr) ((unsigned int ) __ldrex(ptr)) +#define __STREXB(value, ptr) __strex(value, ptr) +#define __STREXH(value, ptr) __strex(value, ptr) +#define __STREXW(value, ptr) __strex(value, ptr) + + +/* intrinsic unsigned long long __ldrexd(volatile void *ptr) */ +/* intrinsic int __strexd(unsigned long long val, volatile void *ptr) */ +/* intrinsic void __enable_irq(); */ +/* intrinsic void __disable_irq(); */ + + +/** + * @brief Return the Process Stack Pointer + * + * @param none + * @return uint32_t ProcessStackPointer + * + * Return the actual process stack pointer + */ +extern uint32_t __get_PSP(void); + +/** + * @brief Set the Process Stack Pointer + * + * @param uint32_t Process Stack Pointer + * @return none + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +extern void __set_PSP(uint32_t topOfProcStack); + +/** + * @brief Return the Main Stack Pointer + * + * @param none + * @return uint32_t Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +extern uint32_t __get_MSP(void); + +/** + * @brief Set the Main Stack Pointer + * + * @param uint32_t Main Stack Pointer + * @return none + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +extern void __set_MSP(uint32_t topOfMainStack); + +/** + * @brief Reverse byte order in unsigned short value + * + * @param uint16_t value to reverse + * @return uint32_t reversed value + * + * Reverse byte order in unsigned short value + */ +extern uint32_t __REV16(uint16_t value); + +/* + * @brief Reverse byte order in signed short value with sign extension to integer + * + * @param int16_t value to reverse + * @return int32_t reversed value + * + * Reverse byte order in signed short value with sign extension to integer + */ +extern int32_t __REVSH(int16_t value); + + +#if (__ARMCC_VERSION < 400000) + +/** + * @brief Remove the exclusive lock created by ldrex + * + * @param none + * @return none + * + * Removes the exclusive lock which is created by ldrex. + */ +extern void __CLREX(void); + +/** + * @brief Return the Base Priority value + * + * @param none + * @return uint32_t BasePriority + * + * Return the content of the base priority register + */ +extern uint32_t __get_BASEPRI(void); + +/** + * @brief Set the Base Priority value + * + * @param uint32_t BasePriority + * @return none + * + * Set the base priority register + */ +extern void __set_BASEPRI(uint32_t basePri); + +/** + * @brief Return the Priority Mask value + * + * @param none + * @return uint32_t PriMask + * + * Return the state of the priority mask bit from the priority mask + * register + */ +extern uint32_t __get_PRIMASK(void); + +/** + * @brief Set the Priority Mask value + * + * @param uint32_t PriMask + * @return none + * + * Set the priority mask bit in the priority mask register + */ +extern void __set_PRIMASK(uint32_t priMask); + +/** + * @brief Return the Fault Mask value + * + * @param none + * @return uint32_t FaultMask + * + * Return the content of the fault mask register + */ +extern uint32_t __get_FAULTMASK(void); + +/** + * @brief Set the Fault Mask value + * + * @param uint32_t faultMask value + * @return none + * + * Set the fault mask register + */ +extern void __set_FAULTMASK(uint32_t faultMask); + +/** + * @brief Return the Control Register value + * + * @param none + * @return uint32_t Control value + * + * Return the content of the control register + */ +extern uint32_t __get_CONTROL(void); + +/** + * @brief Set the Control Register value + * + * @param uint32_t Control value + * @return none + * + * Set the control register + */ +extern void __set_CONTROL(uint32_t control); + +#else /* (__ARMCC_VERSION >= 400000) */ + + +/** + * @brief Remove the exclusive lock created by ldrex + * + * @param none + * @return none + * + * Removes the exclusive lock which is created by ldrex. + */ +#define __CLREX __clrex + +/** + * @brief Return the Base Priority value + * + * @param none + * @return uint32_t BasePriority + * + * Return the content of the base priority register + */ +static __INLINE uint32_t __get_BASEPRI(void) +{ + register uint32_t __regBasePri __ASM("basepri"); + return(__regBasePri); +} + +/** + * @brief Set the Base Priority value + * + * @param uint32_t BasePriority + * @return none + * + * Set the base priority register + */ +static __INLINE void __set_BASEPRI(uint32_t basePri) +{ + register uint32_t __regBasePri __ASM("basepri"); + __regBasePri = (basePri & 0x1ff); +} + +/** + * @brief Return the Priority Mask value + * + * @param none + * @return uint32_t PriMask + * + * Return the state of the priority mask bit from the priority mask + * register + */ +static __INLINE uint32_t __get_PRIMASK(void) +{ + register uint32_t __regPriMask __ASM("primask"); + return(__regPriMask); +} + +/** + * @brief Set the Priority Mask value + * + * @param uint32_t PriMask + * @return none + * + * Set the priority mask bit in the priority mask register + */ +static __INLINE void __set_PRIMASK(uint32_t priMask) +{ + register uint32_t __regPriMask __ASM("primask"); + __regPriMask = (priMask); +} + +/** + * @brief Return the Fault Mask value + * + * @param none + * @return uint32_t FaultMask + * + * Return the content of the fault mask register + */ +static __INLINE uint32_t __get_FAULTMASK(void) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + return(__regFaultMask); +} + +/** + * @brief Set the Fault Mask value + * + * @param uint32_t faultMask value + * @return none + * + * Set the fault mask register + */ +static __INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + __regFaultMask = (faultMask & 1); +} + +/** + * @brief Return the Control Register value + * + * @param none + * @return uint32_t Control value + * + * Return the content of the control register + */ +static __INLINE uint32_t __get_CONTROL(void) +{ + register uint32_t __regControl __ASM("control"); + return(__regControl); +} + +/** + * @brief Set the Control Register value + * + * @param uint32_t Control value + * @return none + * + * Set the control register + */ +static __INLINE void __set_CONTROL(uint32_t control) +{ + register uint32_t __regControl __ASM("control"); + __regControl = control; +} + +#endif /* __ARMCC_VERSION */ + + + +#elif (defined (__ICCARM__)) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ + +#define __enable_irq __enable_interrupt /*!< global Interrupt enable */ +#define __disable_irq __disable_interrupt /*!< global Interrupt disable */ + +static __INLINE void __enable_fault_irq() { __ASM ("cpsie f"); } +static __INLINE void __disable_fault_irq() { __ASM ("cpsid f"); } + +#define __NOP __no_operation() /*!< no operation intrinsic in IAR Compiler */ +static __INLINE void __WFI() { __ASM ("wfi"); } +static __INLINE void __WFE() { __ASM ("wfe"); } +static __INLINE void __SEV() { __ASM ("sev"); } +static __INLINE void __CLREX() { __ASM ("clrex"); } + +/* intrinsic void __ISB(void) */ +/* intrinsic void __DSB(void) */ +/* intrinsic void __DMB(void) */ +/* intrinsic void __set_PRIMASK(); */ +/* intrinsic void __get_PRIMASK(); */ +/* intrinsic void __set_FAULTMASK(); */ +/* intrinsic void __get_FAULTMASK(); */ +/* intrinsic uint32_t __REV(uint32_t value); */ +/* intrinsic uint32_t __REVSH(uint32_t value); */ +/* intrinsic unsigned long __STREX(unsigned long, unsigned long); */ +/* intrinsic unsigned long __LDREX(unsigned long *); */ + + +/** + * @brief Return the Process Stack Pointer + * + * @param none + * @return uint32_t ProcessStackPointer + * + * Return the actual process stack pointer + */ +extern uint32_t __get_PSP(void); + +/** + * @brief Set the Process Stack Pointer + * + * @param uint32_t Process Stack Pointer + * @return none + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +extern void __set_PSP(uint32_t topOfProcStack); + +/** + * @brief Return the Main Stack Pointer + * + * @param none + * @return uint32_t Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +extern uint32_t __get_MSP(void); + +/** + * @brief Set the Main Stack Pointer + * + * @param uint32_t Main Stack Pointer + * @return none + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +extern void __set_MSP(uint32_t topOfMainStack); + +/** + * @brief Reverse byte order in unsigned short value + * + * @param uint16_t value to reverse + * @return uint32_t reversed value + * + * Reverse byte order in unsigned short value + */ +extern uint32_t __REV16(uint16_t value); + +/** + * @brief Reverse bit order of value + * + * @param uint32_t value to reverse + * @return uint32_t reversed value + * + * Reverse bit order of value + */ +extern uint32_t __RBIT(uint32_t value); + +/** + * @brief LDR Exclusive + * + * @param uint8_t* address + * @return uint8_t value of (*address) + * + * Exclusive LDR command + */ +extern uint8_t __LDREXB(uint8_t *addr); + +/** + * @brief LDR Exclusive + * + * @param uint16_t* address + * @return uint16_t value of (*address) + * + * Exclusive LDR command + */ +extern uint16_t __LDREXH(uint16_t *addr); + +/** + * @brief LDR Exclusive + * + * @param uint32_t* address + * @return uint32_t value of (*address) + * + * Exclusive LDR command + */ +extern uint32_t __LDREXW(uint32_t *addr); + +/** + * @brief STR Exclusive + * + * @param uint8_t *address + * @param uint8_t value to store + * @return uint32_t successful / failed + * + * Exclusive STR command + */ +extern uint32_t __STREXB(uint8_t value, uint8_t *addr); + +/** + * @brief STR Exclusive + * + * @param uint16_t *address + * @param uint16_t value to store + * @return uint32_t successful / failed + * + * Exclusive STR command + */ +extern uint32_t __STREXH(uint16_t value, uint16_t *addr); + +/** + * @brief STR Exclusive + * + * @param uint32_t *address + * @param uint32_t value to store + * @return uint32_t successful / failed + * + * Exclusive STR command + */ +extern uint32_t __STREXW(uint32_t value, uint32_t *addr); + + + +#elif (defined (__GNUC__)) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +static __INLINE void __enable_irq() { __ASM volatile ("cpsie i"); } +static __INLINE void __disable_irq() { __ASM volatile ("cpsid i"); } + +static __INLINE void __enable_fault_irq() { __ASM volatile ("cpsie f"); } +static __INLINE void __disable_fault_irq() { __ASM volatile ("cpsid f"); } + +static __INLINE void __NOP() { __ASM volatile ("nop"); } +static __INLINE void __WFI() { __ASM volatile ("wfi"); } +static __INLINE void __WFE() { __ASM volatile ("wfe"); } +static __INLINE void __SEV() { __ASM volatile ("sev"); } +static __INLINE void __ISB() { __ASM volatile ("isb"); } +static __INLINE void __DSB() { __ASM volatile ("dsb"); } +static __INLINE void __DMB() { __ASM volatile ("dmb"); } +static __INLINE void __CLREX() { __ASM volatile ("clrex"); } + + +/** + * @brief Return the Process Stack Pointer + * + * @param none + * @return uint32_t ProcessStackPointer + * + * Return the actual process stack pointer + */ +extern uint32_t __get_PSP(void); + +/** + * @brief Set the Process Stack Pointer + * + * @param uint32_t Process Stack Pointer + * @return none + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +extern void __set_PSP(uint32_t topOfProcStack); + +/** + * @brief Return the Main Stack Pointer + * + * @param none + * @return uint32_t Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +extern uint32_t __get_MSP(void); + +/** + * @brief Set the Main Stack Pointer + * + * @param uint32_t Main Stack Pointer + * @return none + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +extern void __set_MSP(uint32_t topOfMainStack); + +/** + * @brief Return the Base Priority value + * + * @param none + * @return uint32_t BasePriority + * + * Return the content of the base priority register + */ +extern uint32_t __get_BASEPRI(void); + +/** + * @brief Set the Base Priority value + * + * @param uint32_t BasePriority + * @return none + * + * Set the base priority register + */ +extern void __set_BASEPRI(uint32_t basePri); + +/** + * @brief Return the Priority Mask value + * + * @param none + * @return uint32_t PriMask + * + * Return the state of the priority mask bit from the priority mask + * register + */ +extern uint32_t __get_PRIMASK(void); + +/** + * @brief Set the Priority Mask value + * + * @param uint32_t PriMask + * @return none + * + * Set the priority mask bit in the priority mask register + */ +extern void __set_PRIMASK(uint32_t priMask); + +/** + * @brief Return the Fault Mask value + * + * @param none + * @return uint32_t FaultMask + * + * Return the content of the fault mask register + */ +extern uint32_t __get_FAULTMASK(void); + +/** + * @brief Set the Fault Mask value + * + * @param uint32_t faultMask value + * @return none + * + * Set the fault mask register + */ +extern void __set_FAULTMASK(uint32_t faultMask); + +/** + * @brief Return the Control Register value +* +* @param none +* @return uint32_t Control value + * + * Return the content of the control register + */ +extern uint32_t __get_CONTROL(void); + +/** + * @brief Set the Control Register value + * + * @param uint32_t Control value + * @return none + * + * Set the control register + */ +extern void __set_CONTROL(uint32_t control); + +/** + * @brief Reverse byte order in integer value + * + * @param uint32_t value to reverse + * @return uint32_t reversed value + * + * Reverse byte order in integer value + */ +extern uint32_t __REV(uint32_t value); + +/** + * @brief Reverse byte order in unsigned short value + * + * @param uint16_t value to reverse + * @return uint32_t reversed value + * + * Reverse byte order in unsigned short value + */ +extern uint32_t __REV16(uint16_t value); + +/* + * Reverse byte order in signed short value with sign extension to integer + * + * @param int16_t value to reverse + * @return int32_t reversed value + * + * @brief Reverse byte order in signed short value with sign extension to integer + */ +extern int32_t __REVSH(int16_t value); + +/** + * @brief Reverse bit order of value + * + * @param uint32_t value to reverse + * @return uint32_t reversed value + * + * Reverse bit order of value + */ +extern uint32_t __RBIT(uint32_t value); + +/** + * @brief LDR Exclusive + * + * @param uint8_t* address + * @return uint8_t value of (*address) + * + * Exclusive LDR command + */ +extern uint8_t __LDREXB(uint8_t *addr); + +/** + * @brief LDR Exclusive + * + * @param uint16_t* address + * @return uint16_t value of (*address) + * + * Exclusive LDR command + */ +extern uint16_t __LDREXH(uint16_t *addr); + +/** + * @brief LDR Exclusive + * + * @param uint32_t* address + * @return uint32_t value of (*address) + * + * Exclusive LDR command + */ +extern uint32_t __LDREXW(uint32_t *addr); + +/** + * @brief STR Exclusive + * + * @param uint8_t *address + * @param uint8_t value to store + * @return uint32_t successful / failed + * + * Exclusive STR command + */ +extern uint32_t __STREXB(uint8_t value, uint8_t *addr); + +/** + * @brief STR Exclusive + * + * @param uint16_t *address + * @param uint16_t value to store + * @return uint32_t successful / failed + * + * Exclusive STR command + */ +extern uint32_t __STREXH(uint16_t value, uint16_t *addr); + +/** + * @brief STR Exclusive + * + * @param uint32_t *address + * @param uint32_t value to store + * @return uint32_t successful / failed + * + * Exclusive STR command + */ +extern uint32_t __STREXW(uint32_t value, uint32_t *addr); + + +#elif (defined (__TASKING__)) /*------------------ TASKING Compiler ---------------------*/ +/* TASKING carm specific functions */ + +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all instrinsics, + * Including the CMSIS ones. + */ + +#endif + + + +/* ########################## NVIC functions #################################### */ + + +/** + * @brief Set the Priority Grouping in NVIC Interrupt Controller + * + * @param uint32_t priority_grouping is priority grouping field + * @return none + * + * Set the priority grouping field using the required unlock sequence. + * The parameter priority_grouping is assigned to the field + * SCB->AIRCR [10:8] PRIGROUP field. Only values from 0..7 are used. + * In case of a conflict between priority grouping and available + * priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + */ +static __INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~((0xFFFFU << 16) | (0x0F << 8)); /* clear bits to change */ + reg_value = ((reg_value | NVIC_AIRCR_VECTKEY | (PriorityGroupTmp << 8))); /* Insert write key and priorty group */ + SCB->AIRCR = reg_value; +} + +/** + * @brief Get the Priority Grouping from NVIC Interrupt Controller + * + * @param none + * @return uint32_t priority grouping field + * + * Get the priority grouping from NVIC Interrupt Controller. + * priority grouping is SCB->AIRCR [10:8] PRIGROUP field. + */ +static __INLINE uint32_t NVIC_GetPriorityGrouping(void) +{ + return ((SCB->AIRCR >> 8) & 0x07); /* read priority grouping field */ +} + +/** + * @brief Enable Interrupt in NVIC Interrupt Controller + * + * @param IRQn_Type IRQn specifies the interrupt number + * @return none + * + * Enable a device specific interupt in the NVIC interrupt controller. + * The interrupt number cannot be a negative value. + */ +static __INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) +{ + NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* enable interrupt */ +} + +/** + * @brief Disable the interrupt line for external interrupt specified + * + * @param IRQn_Type IRQn is the positive number of the external interrupt + * @return none + * + * Disable a device specific interupt in the NVIC interrupt controller. + * The interrupt number cannot be a negative value. + */ +static __INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) +{ + NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */ +} + +/** + * @brief Read the interrupt pending bit for a device specific interrupt source + * + * @param IRQn_Type IRQn is the number of the device specifc interrupt + * @return uint32_t 1 if pending interrupt else 0 + * + * Read the pending register in NVIC and return 1 if its status is pending, + * otherwise it returns 0 + */ +static __INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */ +} + +/** + * @brief Set the pending bit for an external interrupt + * + * @param IRQn_Type IRQn is the Number of the interrupt + * @return none + * + * Set the pending bit for the specified interrupt. + * The interrupt number cannot be a negative value. + */ +static __INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */ +} + +/** + * @brief Clear the pending bit for an external interrupt + * + * @param IRQn_Type IRQn is the Number of the interrupt + * @return none + * + * Clear the pending bit for the specified interrupt. + * The interrupt number cannot be a negative value. + */ +static __INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ +} + +/** + * @brief Read the active bit for an external interrupt + * + * @param IRQn_Type IRQn is the Number of the interrupt + * @return uint32_t 1 if active else 0 + * + * Read the active register in NVIC and returns 1 if its status is active, + * otherwise it returns 0. + */ +static __INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) +{ + return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */ +} + +/** + * @brief Set the priority for an interrupt + * + * @param IRQn_Type IRQn is the Number of the interrupt + * @param priority is the priority for the interrupt + * @return none + * + * Set the priority for the specified interrupt. The interrupt + * number can be positive to specify an external (device specific) + * interrupt, or negative to specify an internal (core) interrupt. \n + * + * Note: The priority cannot be set for every core interrupt. + */ +static __INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if(IRQn < 0) { + SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M3 System Interrupts */ + else { + NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */ +} + +/** + * @brief Read the priority for an interrupt + * + * @param IRQn_Type IRQn is the Number of the interrupt + * @return uint32_t priority is the priority for the interrupt + * + * Read the priority for the specified interrupt. The interrupt + * number can be positive to specify an external (device specific) + * interrupt, or negative to specify an internal (core) interrupt. + * + * The returned priority value is automatically aligned to the implemented + * priority bits of the microcontroller. + * + * Note: The priority cannot be set for every core interrupt. + */ +static __INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) +{ + + if(IRQn < 0) { + return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M3 system interrupts */ + else { + return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ +} + + +/** + * @brief Encode the priority for an interrupt + * + * @param uint32_t PriorityGroup is the used priority group + * @param uint32_t PreemptPriority is the preemptive priority value (starting from 0) + * @param uint32_t SubPriority is the sub priority value (starting from 0) + * @return uint32_t the priority for the interrupt + * + * Encode the priority for an interrupt with the given priority group, + * preemptive priority value and sub priority value. + * In case of a conflict between priority grouping and available + * priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. + * + * The returned priority value can be used for NVIC_SetPriority(...) function + */ +static __INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + return ( + ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) | + ((SubPriority & ((1 << (SubPriorityBits )) - 1))) + ); +} + + +/** + * @brief Decode the priority of an interrupt + * + * @param uint32_t Priority the priority for the interrupt + * @param uint32_t PrioGroup is the used priority group + * @param uint32_t* pPreemptPrio is the preemptive priority value (starting from 0) + * @param uint32_t* pSubPrio is the sub priority value (starting from 0) + * @return none + * + * Decode an interrupt priority value with the given priority group to + * preemptive priority value and sub priority value. + * In case of a conflict between priority grouping and available + * priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. + * + * The priority value can be retrieved with NVIC_GetPriority(...) function + */ +static __INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1); + *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1); +} + + + +/* ################################## SysTick function ############################################ */ + +#if (!defined (__Vendor_SysTickConfig)) || (__Vendor_SysTickConfig == 0) + +/* SysTick constants */ +#define SYSTICK_ENABLE 0 /* Config-Bit to start or stop the SysTick Timer */ +#define SYSTICK_TICKINT 1 /* Config-Bit to enable or disable the SysTick interrupt */ +#define SYSTICK_CLKSOURCE 2 /* Clocksource has the offset 2 in SysTick Control and Status Register */ +#define SYSTICK_MAXCOUNT ((1<<24) -1) /* SysTick MaxCount */ + +/** + * @brief Initialize and start the SysTick counter and its interrupt. + * + * @param uint32_t ticks is the number of ticks between two interrupts + * @return none + * + * Initialise the system tick timer and its interrupt and start the + * system tick timer / counter in free running mode to generate + * periodical interrupts. + */ +static __INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if (ticks > SYSTICK_MAXCOUNT) return (1); /* Reload value impossible */ + + SysTick->LOAD = (ticks & SYSTICK_MAXCOUNT) - 1; /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Cortex-M0 System Interrupts */ + SysTick->VAL = (0x00); /* Load the SysTick Counter Value */ + SysTick->CTRL = (1 << SYSTICK_CLKSOURCE) | (1<AIRCR = (NVIC_AIRCR_VECTKEY | (SCB->AIRCR & (0x700)) | (1<DEMCR & CoreDebug_DEMCR_TRCENA) && + (ITM->TCR & ITM_TCR_ITMENA) && + (ITM->TER & (1UL << 0)) ) + { + while (ITM->PORT[0].u32 == 0); + ITM->PORT[0].u8 = (uint8_t) ch; + } + return (ch); +} + +#ifdef __cplusplus +} +#endif + +#endif /* __CM3_CORE_H__ */ + +/*lint -restore */ diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/main.c b/Demo/CORTEX_LPC1768_GCC_Rowley/main.c new file mode 100644 index 000000000..049897b41 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/main.c @@ -0,0 +1,405 @@ +/* + FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry. + + This file is part of the FreeRTOS.org distribution. + + FreeRTOS.org is free software; you can redistribute it and/or modify it + under the terms of the GNU General Public License (version 2) as published + by the Free Software Foundation and modified by the FreeRTOS exception. + **NOTE** The exception to the GPL is included to allow you to distribute a + combined work that includes FreeRTOS.org without being obliged to provide + the source code for any proprietary components. Alternative commercial + license and support terms are also available upon request. See the + licensing section of http://www.FreeRTOS.org for full details. + + FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. + + You should have received a copy of the GNU General Public License along + with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 + Temple Place, Suite 330, Boston, MA 02111-1307 USA. + + + *************************************************************************** + * * + * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * + * * + * This is a concise, step by step, 'hands on' guide that describes both * + * general multitasking concepts and FreeRTOS specifics. It presents and * + * explains numerous examples that are written using the FreeRTOS API. * + * Full source code for all the examples is provided in an accompanying * + * .zip file. * + * * + *************************************************************************** + + 1 tab == 4 spaces! + + Please ensure to read the configuration and relevant port sections of the + online documentation. + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +/* + * Creates all the demo application tasks, then starts the scheduler. The WEB + * documentation provides more details of the standard demo application tasks + * (which just exist to test the kernel port and provide an example of how to use + * each FreeRTOS API function). + * + * In addition to the standard demo tasks, the following tasks and tests are + * defined and/or created within this file: + * + * "LCD" task - the LCD task is a 'gatekeeper' task. It is the only task that + * is permitted to access the display directly. Other tasks wishing to write a + * message to the LCD send the message on a queue to the LCD task instead of + * accessing the LCD themselves. The LCD task just blocks on the queue waiting + * for messages - waking and displaying the messages as they arrive. The use + * of a gatekeeper in this manner permits both tasks and interrupts to write to + * the LCD without worrying about mutual exclusion. This is demonstrated by the + * check hook (see below) which sends messages to the display even though it + * executes from an interrupt context. + * + * "Check" hook - This only executes fully every five seconds from the tick + * hook. Its main function is to check that all the standard demo tasks are + * still operational. Should any unexpected behaviour be discovered within a + * demo task then the tick hook will write an error to the LCD (via the LCD task). + * If all the demo tasks are executing with their expected behaviour then the + * check hook writes PASS to the LCD (again via the LCD task), as described above. + * The check hook also toggles LED 4 each time it executes. + * + * LED tasks - These just demonstrate how multiple instances of a single task + * definition can be created. Each LED task simply toggles an LED. The task + * parameter is used to pass the number of the LED to be toggled into the task. + * + * "uIP" task - This is the task that handles the uIP stack. All TCP/IP + * processing is performed in this task. + */ + +/* Standard includes. */ +#include + +/* Scheduler includes. */ +#include "FreeRTOS.h" +#include "task.h" +#include "queue.h" +#include "semphr.h" + +/* Hardware library includes. */ +#include "LPC17xx_defs.h" + +/* Demo app includes. */ +#include "BlockQ.h" +#include "integer.h" +#include "blocktim.h" +#include "flash.h" +#include "partest.h" +#include "semtest.h" +#include "PollQ.h" +#include "GenQTest.h" +#include "QPeek.h" +#include "recmutex.h" + +/*-----------------------------------------------------------*/ + +/* The number of LED tasks that will be created. */ +#define mainNUM_LED_TASKS ( 6 ) + +/* The time between cycles of the 'check' functionality (defined within the +tick hook. */ +#define mainCHECK_DELAY ( ( portTickType ) 5000 / portTICK_RATE_MS ) + +/* Task priorities. */ +#define mainQUEUE_POLL_PRIORITY ( tskIDLE_PRIORITY + 2 ) +#define mainSEM_TEST_PRIORITY ( tskIDLE_PRIORITY + 1 ) +#define mainBLOCK_Q_PRIORITY ( tskIDLE_PRIORITY + 2 ) +#define mainUIP_TASK_PRIORITY ( tskIDLE_PRIORITY + 3 ) +#define mainLCD_TASK_PRIORITY ( tskIDLE_PRIORITY + 2 ) +#define mainINTEGER_TASK_PRIORITY ( tskIDLE_PRIORITY ) +#define mainGEN_QUEUE_TASK_PRIORITY ( tskIDLE_PRIORITY ) +#define mainFLASH_TASK_PRIORITY ( tskIDLE_PRIORITY + 2 ) + +/* The WEB server has a larger stack as it utilises stack hungry string +handling library calls. */ +#define mainBASIC_WEB_STACK_SIZE ( configMINIMAL_STACK_SIZE * 4 ) + +/* The length of the queue used to send messages to the LCD task. */ +#define mainQUEUE_SIZE ( 3 ) + +/* The task that is toggled by the check task. */ +#define mainCHECK_TASK_LED ( 4 ) +/*-----------------------------------------------------------*/ + +/* + * Configure the hardware for the demo. + */ +static void prvSetupHardware( void ); + +/* + * Very simple task that toggles an LED. + */ +static void vLEDTask( void *pvParameters ); + +/* + * The task that handles the uIP stack. All TCP/IP processing is performed in + * this task. + */ +extern void vuIP_Task( void *pvParameters ); + +/* + * The LCD gatekeeper task as described in the comments at the top of this file. + * */ +static void vLCDTask( void *pvParameters ); + +/*-----------------------------------------------------------*/ + +/* The queue used to send messages to the LCD task. */ +xQueueHandle xLCDQueue; + + + +/*-----------------------------------------------------------*/ + +int main( void ) +{ +long l; + + /* Configure the hardware for use by this demo. */ + prvSetupHardware(); + + /* Start the standard demo tasks. These are just here to exercise the + kernel port and provide examples of how the FreeRTOS API can be used. */ + vStartBlockingQueueTasks( mainBLOCK_Q_PRIORITY ); + vCreateBlockTimeTasks(); + vStartSemaphoreTasks( mainSEM_TEST_PRIORITY ); + vStartPolledQueueTasks( mainQUEUE_POLL_PRIORITY ); + vStartIntegerMathTasks( mainINTEGER_TASK_PRIORITY ); + vStartGenericQueueTasks( mainGEN_QUEUE_TASK_PRIORITY ); + vStartQueuePeekTasks(); + vStartRecursiveMutexTasks(); + + vStartLEDFlashTasks( mainFLASH_TASK_PRIORITY ); + + /* Create the uIP task. The WEB server runs in this task. */ + xTaskCreate( vuIP_Task, ( signed char * ) "uIP", mainBASIC_WEB_STACK_SIZE, ( void * ) NULL, mainUIP_TASK_PRIORITY, NULL ); + + /* Create the queue used by the LCD task. Messages for display on the LCD + are received via this queue. */ + xLCDQueue = xQueueCreate( mainQUEUE_SIZE, sizeof( xLCDMessage ) ); + + /* Start the LCD gatekeeper task - as described in the comments at the top + of this file. */ + xTaskCreate( vLCDTask, ( signed portCHAR * ) "LCD", configMINIMAL_STACK_SIZE * 2, NULL, mainLCD_TASK_PRIORITY, NULL ); + + /* Start the scheduler. */ + vTaskStartScheduler(); + + /* Will only get here if there was insufficient memory to create the idle + task. The idle task is created within vTaskStartScheduler(). */ + for( ;; ); +} +/*-----------------------------------------------------------*/ + +void vLCDTask( void *pvParameters ) +{ +xLCDMessage xMessage; +unsigned long ulRow = 0; +char cIPAddr[ 17 ]; /* To fit max IP address length of xxx.xxx.xxx.xxx\0 */ + + ( void ) pvParameters; + + /* The LCD gatekeeper task as described in the comments at the top of this + file. */ + + /* Initialise the LCD and display a startup message that includes the + configured IP address. */ + sprintf( cIPAddr, "%d.%d.%d.%d", configIP_ADDR0, configIP_ADDR1, configIP_ADDR2, configIP_ADDR3 ); + + for( ;; ) + { + /* Wait for a message to arrive to be displayed. */ + while( xQueueReceive( xLCDQueue, &xMessage, portMAX_DELAY ) != pdPASS ); + + } +} +/*-----------------------------------------------------------*/ + +void vApplicationTickHook( void ) +{ +static xLCDMessage xMessage = { "PASS" }; +static unsigned portLONG ulTicksSinceLastDisplay = 0; +portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + + /* Called from every tick interrupt as described in the comments at the top + of this file. + + Have enough ticks passed to make it time to perform our health status + check again? */ + ulTicksSinceLastDisplay++; + if( ulTicksSinceLastDisplay >= mainCHECK_DELAY ) + { + /* Reset the counter so these checks run again in mainCHECK_DELAY + ticks time. */ + ulTicksSinceLastDisplay = 0; + + /* Has an error been found in any task? */ + if( xAreGenericQueueTasksStillRunning() != pdTRUE ) + { + xMessage.pcMessage = "ERROR: GEN Q"; + } + else if( xAreQueuePeekTasksStillRunning() != pdTRUE ) + { + xMessage.pcMessage = "ERROR: PEEK Q"; + } + else if( xAreBlockingQueuesStillRunning() != pdTRUE ) + { + xMessage.pcMessage = "ERROR: BLOCK Q"; + } + else if( xAreBlockTimeTestTasksStillRunning() != pdTRUE ) + { + xMessage.pcMessage = "ERROR: BLOCK TIME"; + } + else if( xAreSemaphoreTasksStillRunning() != pdTRUE ) + { + xMessage.pcMessage = "ERROR: SEMAPHR"; + } + else if( xArePollingQueuesStillRunning() != pdTRUE ) + { + xMessage.pcMessage = "ERROR: POLL Q"; + } + else if( xAreIntegerMathsTaskStillRunning() != pdTRUE ) + { + xMessage.pcMessage = "ERROR: INT MATH"; + } + else if( xAreRecursiveMutexTasksStillRunning() != pdTRUE ) + { + xMessage.pcMessage = "ERROR: REC MUTEX"; + } + + /* Send the message to the OLED gatekeeper for display. The + xHigherPriorityTaskWoken parameter is not actually used here + as this function is running in the tick interrupt anyway - but + it must still be supplied. */ + xHigherPriorityTaskWoken = pdFALSE; + xQueueSendFromISR( xLCDQueue, &xMessage, &xHigherPriorityTaskWoken ); + + /* Also toggle and LED. This can be done from here because in this port + the LED toggling functions don't use critical sections. */ + vParTestToggleLED( mainCHECK_TASK_LED ); + } +} +/*-----------------------------------------------------------*/ + +void prvSetupHardware( void ) +{ + /* Disable peripherals power. */ + PCONP = 0; + + /* Enable GPIO power. */ + PCONP = PCONP_PCGPIO; + + /* Disable TPIU. */ + PINSEL10 = 0; + + /* Disconnect the main PLL. */ + PLL0CON &= ~PLLCON_PLLC; + PLL0FEED = PLLFEED_FEED1; + PLL0FEED = PLLFEED_FEED2; + while ((PLL0STAT & PLLSTAT_PLLC) != 0); + + /* Turn off the main PLL. */ + PLL0CON &= ~PLLCON_PLLE; + PLL0FEED = PLLFEED_FEED1; + PLL0FEED = PLLFEED_FEED2; + while ((PLL0STAT & PLLSTAT_PLLE) != 0); + + /* No CPU clock divider. */ + CCLKCFG = 0; + + /* OSCEN. */ + SCS = 0x20; + while ((SCS & 0x40) == 0); + + /* Use main oscillator. */ + CLKSRCSEL = 1; + PLL0CFG = (PLLCFG_MUL16 | PLLCFG_DIV1); + + PLL0FEED = PLLFEED_FEED1; + PLL0FEED = PLLFEED_FEED2; + + /* Activate the PLL by turning it on then feeding the correct + sequence of bytes. */ + PLL0CON = PLLCON_PLLE; + PLL0FEED = PLLFEED_FEED1; + PLL0FEED = PLLFEED_FEED2; + + /* 6x CPU clock divider (64 MHz) */ + CCLKCFG = 5; + + /* Wait for the PLL to lock. */ + while ((PLL0STAT & PLLSTAT_PLOCK) == 0); + + /* Connect the PLL. */ + PLL0CON = PLLCON_PLLC | PLLCON_PLLE; + PLL0FEED = PLLFEED_FEED1; + PLL0FEED = PLLFEED_FEED2; + + /* Setup the peripheral bus to be the same as the PLL output (64 MHz). */ + PCLKSEL0 = 0x05555555; + + /* Configure LED GPIOs as outputs. */ + FIO2DIR = 0xff; + FIO2CLR = 0xff; + FIO2MASK = 0; +} +/*-----------------------------------------------------------*/ + +void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed portCHAR *pcTaskName ) +{ + /* This function will get called if a task overflows its stack. */ + + ( void ) pxTask; + ( void ) pcTaskName; + + for( ;; ); +} +/*-----------------------------------------------------------*/ + +void vConfigureTimerForRunTimeStats( void ) +{ +const unsigned long TCR_COUNT_RESET = 2, CTCR_CTM_TIMER = 0x00, TCR_COUNT_ENABLE = 0x01; + + /* This function configures a timer that is used as the time base when + collecting run time statistical information - basically the percentage + of CPU time that each task is utilising. It is called automatically when + the scheduler is started (assuming configGENERATE_RUN_TIME_STATS is set + to 1. */ + + /* Power up and feed the timer. */ + PCONP |= 0x02UL; + PCLKSEL0 = (PCLKSEL0 & (~(0x3<<2))) | (0x01 << 2); + + /* Reset Timer 0 */ + T0TCR = TCR_COUNT_RESET; + + /* Just count up. */ + T0CTCR = CTCR_CTM_TIMER; + + /* Prescale to a frequency that is good enough to get a decent resolution, + but not too fast so as to overflow all the time. */ + T0PR = ( configCPU_CLOCK_HZ / 10000UL ) - 1UL; + + /* Start the counter. */ + T0TCR = TCR_COUNT_ENABLE; +} +/*-----------------------------------------------------------*/ + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/printf-stdarg.c b/Demo/CORTEX_LPC1768_GCC_Rowley/printf-stdarg.c new file mode 100644 index 000000000..b5ac41be7 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/printf-stdarg.c @@ -0,0 +1,293 @@ +/* + Copyright 2001, 2002 Georges Menie (www.menie.org) + stdarg version contributed by Christian Ettinger + + This program is free software; you can redistribute it and/or modify + it under the terms of the GNU Lesser General Public License as published by + the Free Software Foundation; either version 2 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public License + along with this program; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +/* + putchar is the only external dependency for this file, + if you have a working putchar, leave it commented out. + If not, uncomment the define below and + replace outbyte(c) by your own function call. + +*/ + +#define putchar(c) c + +#include + +static void printchar(char **str, int c) +{ + //extern int putchar(int c); + + if (str) { + **str = (char)c; + ++(*str); + } + else + { + (void)putchar(c); + } +} + +#define PAD_RIGHT 1 +#define PAD_ZERO 2 + +static int prints(char **out, const char *string, int width, int pad) +{ + register int pc = 0, padchar = ' '; + + if (width > 0) { + register int len = 0; + register const char *ptr; + for (ptr = string; *ptr; ++ptr) ++len; + if (len >= width) width = 0; + else width -= len; + if (pad & PAD_ZERO) padchar = '0'; + } + if (!(pad & PAD_RIGHT)) { + for ( ; width > 0; --width) { + printchar (out, padchar); + ++pc; + } + } + for ( ; *string ; ++string) { + printchar (out, *string); + ++pc; + } + for ( ; width > 0; --width) { + printchar (out, padchar); + ++pc; + } + + return pc; +} + +/* the following should be enough for 32 bit int */ +#define PRINT_BUF_LEN 12 + +static int printi(char **out, int i, int b, int sg, int width, int pad, int letbase) +{ + char print_buf[PRINT_BUF_LEN]; + register char *s; + register int t, neg = 0, pc = 0; + register unsigned int u = (unsigned int)i; + + if (i == 0) { + print_buf[0] = '0'; + print_buf[1] = '\0'; + return prints (out, print_buf, width, pad); + } + + if (sg && b == 10 && i < 0) { + neg = 1; + u = (unsigned int)-i; + } + + s = print_buf + PRINT_BUF_LEN-1; + *s = '\0'; + + while (u) { + t = (unsigned int)u % b; + if( t >= 10 ) + t += letbase - '0' - 10; + *--s = (char)(t + '0'); + u /= b; + } + + if (neg) { + if( width && (pad & PAD_ZERO) ) { + printchar (out, '-'); + ++pc; + --width; + } + else { + *--s = '-'; + } + } + + return pc + prints (out, s, width, pad); +} + +static int print( char **out, const char *format, va_list args ) +{ + register int width, pad; + register int pc = 0; + char scr[2]; + + for (; *format != 0; ++format) { + if (*format == '%') { + ++format; + width = pad = 0; + if (*format == '\0') break; + if (*format == '%') goto out; + if (*format == '-') { + ++format; + pad = PAD_RIGHT; + } + while (*format == '0') { + ++format; + pad |= PAD_ZERO; + } + for ( ; *format >= '0' && *format <= '9'; ++format) { + width *= 10; + width += *format - '0'; + } + if( *format == 's' ) { + register char *s = (char *)va_arg( args, int ); + pc += prints (out, s?s:"(null)", width, pad); + continue; + } + if( *format == 'd' ) { + pc += printi (out, va_arg( args, int ), 10, 1, width, pad, 'a'); + continue; + } + if( *format == 'x' ) { + pc += printi (out, va_arg( args, int ), 16, 0, width, pad, 'a'); + continue; + } + if( *format == 'X' ) { + pc += printi (out, va_arg( args, int ), 16, 0, width, pad, 'A'); + continue; + } + if( *format == 'u' ) { + pc += printi (out, va_arg( args, int ), 10, 0, width, pad, 'a'); + continue; + } + if( *format == 'c' ) { + /* char are converted to int then pushed on the stack */ + scr[0] = (char)va_arg( args, int ); + scr[1] = '\0'; + pc += prints (out, scr, width, pad); + continue; + } + } + else { + out: + printchar (out, *format); + ++pc; + } + } + if (out) **out = '\0'; + va_end( args ); + return pc; +} + +int printf(const char *format, ...) +{ + va_list args; + + va_start( args, format ); + return print( 0, format, args ); +} + +int sprintf(char *out, const char *format, ...) +{ + va_list args; + + va_start( args, format ); + return print( &out, format, args ); +} + + +int snprintf( char *buf, unsigned int count, const char *format, ... ) +{ + va_list args; + + ( void ) count; + + va_start( args, format ); + return print( &buf, format, args ); +} + + +#ifdef TEST_PRINTF +int main(void) +{ + char *ptr = "Hello world!"; + char *np = 0; + int i = 5; + unsigned int bs = sizeof(int)*8; + int mi; + char buf[80]; + + mi = (1 << (bs-1)) + 1; + printf("%s\n", ptr); + printf("printf test\n"); + printf("%s is null pointer\n", np); + printf("%d = 5\n", i); + printf("%d = - max int\n", mi); + printf("char %c = 'a'\n", 'a'); + printf("hex %x = ff\n", 0xff); + printf("hex %02x = 00\n", 0); + printf("signed %d = unsigned %u = hex %x\n", -3, -3, -3); + printf("%d %s(s)%", 0, "message"); + printf("\n"); + printf("%d %s(s) with %%\n", 0, "message"); + sprintf(buf, "justif: \"%-10s\"\n", "left"); printf("%s", buf); + sprintf(buf, "justif: \"%10s\"\n", "right"); printf("%s", buf); + sprintf(buf, " 3: %04d zero padded\n", 3); printf("%s", buf); + sprintf(buf, " 3: %-4d left justif.\n", 3); printf("%s", buf); + sprintf(buf, " 3: %4d right justif.\n", 3); printf("%s", buf); + sprintf(buf, "-3: %04d zero padded\n", -3); printf("%s", buf); + sprintf(buf, "-3: %-4d left justif.\n", -3); printf("%s", buf); + sprintf(buf, "-3: %4d right justif.\n", -3); printf("%s", buf); + + return 0; +} + +/* + * if you compile this file with + * gcc -Wall $(YOUR_C_OPTIONS) -DTEST_PRINTF -c printf.c + * you will get a normal warning: + * printf.c:214: warning: spurious trailing `%' in format + * this line is testing an invalid % at the end of the format string. + * + * this should display (on 32bit int machine) : + * + * Hello world! + * printf test + * (null) is null pointer + * 5 = 5 + * -2147483647 = - max int + * char a = 'a' + * hex ff = ff + * hex 00 = 00 + * signed -3 = unsigned 4294967293 = hex fffffffd + * 0 message(s) + * 0 message(s) with % + * justif: "left " + * justif: " right" + * 3: 0003 zero padded + * 3: 3 left justif. + * 3: 3 right justif. + * -3: -003 zero padded + * -3: -3 left justif. + * -3: -3 right justif. + */ + +#endif + + +/* To keep linker happy. */ +int write( int i, char* c, int n) +{ + (void)i; + (void)n; + (void)c; + return 0; +} + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/system_LPC17xx.h b/Demo/CORTEX_LPC1768_GCC_Rowley/system_LPC17xx.h new file mode 100644 index 000000000..a5c9727d4 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/system_LPC17xx.h @@ -0,0 +1,40 @@ +/****************************************************************************** + * @file: system_LPC17xx.h + * @purpose: CMSIS Cortex-M3 Device Peripheral Access Layer Header File + * for the NXP LPC17xx Device Series + * @version: V1.0 + * @date: 25. Nov. 2008 + *---------------------------------------------------------------------------- + * + * Copyright (C) 2008 ARM Limited. All rights reserved. + * + * ARM Limited (ARM) is supplying this software for use with Cortex-M3 + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + + +#ifndef __SYSTEM_LPC17xx_H +#define __SYSTEM_LPC17xx_H + +extern uint32_t SystemFrequency; /*!< System Clock Frequency (Core Clock) */ + + +/** + * Initialize the system + * + * @param none + * @return none + * + * @brief Setup the microcontroller system. + * Initialize the System and update the SystemFrequency variable. + */ +extern void SystemInit (void); +#endif diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/clock-arch.h b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/clock-arch.h new file mode 100644 index 000000000..cde657b62 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/clock-arch.h @@ -0,0 +1,42 @@ +/* + * Copyright (c) 2006, Swedish Institute of Computer Science. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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. + * + * This file is part of the uIP TCP/IP stack + * + * $Id: clock-arch.h,v 1.2 2006/06/12 08:00:31 adam Exp $ + */ + +#ifndef __CLOCK_ARCH_H__ +#define __CLOCK_ARCH_H__ + +#include "FreeRTOS.h" + +typedef unsigned long clock_time_t; +#define CLOCK_CONF_SECOND configTICK_RATE_HZ + +#endif /* __CLOCK_ARCH_H__ */ diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/emac.c b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/emac.c new file mode 100644 index 000000000..1368c2157 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/emac.c @@ -0,0 +1,465 @@ +/****************************************************************** + ***** ***** + ***** Ver.: 1.0 ***** + ***** Date: 07/05/2001 ***** + ***** Auth: Andreas Dannenberg ***** + ***** HTWK Leipzig ***** + ***** university of applied sciences ***** + ***** Germany ***** + ***** Func: ethernet packet-driver for use with LAN- ***** + ***** controller CS8900 from Crystal/Cirrus Logic ***** + ***** ***** + ***** Keil: Module modified for use with Philips ***** + ***** LPC2378 EMAC Ethernet controller ***** + ***** ***** + ******************************************************************/ + +/* Adapted from file originally written by Andreas Dannenberg. Supplied with permission. */ +#include "FreeRTOS.h" +#include "semphr.h" +#include "task.h" +#include "emac.h" +#include "LPC17xx_defs.h" + +#define configPINSEL2_VALUE 0x50150105 + +/* The semaphore used to wake the uIP task when data arives. */ +xSemaphoreHandle xEMACSemaphore = NULL; + +static unsigned short *rptr; +static unsigned short *tptr; + +static unsigned short SwapBytes( unsigned short Data ) +{ + return( Data >> 8 ) | ( Data << 8 ); +} + +// Keil: function added to write PHY +int write_PHY( int PhyReg, int Value ) +{ + unsigned int tout; + const unsigned int uiMaxTime = 10; + + MAC_MADR = DP83848C_DEF_ADR | PhyReg; + MAC_MWTD = Value; + + /* Wait utill operation completed */ + tout = 0; + for( tout = 0; tout < uiMaxTime; tout++ ) + { + if( (MAC_MIND & MIND_BUSY) == 0 ) + { + break; + } + + vTaskDelay( 2 ); + } + + if( tout < uiMaxTime ) + { + return pdPASS; + } + else + { + return pdFAIL; + } +} + +// Keil: function added to read PHY +unsigned short read_PHY( unsigned char PhyReg, portBASE_TYPE *pxStatus ) +{ + unsigned int tout; + const unsigned int uiMaxTime = 10; + + MAC_MADR = DP83848C_DEF_ADR | PhyReg; + MAC_MCMD = MCMD_READ; + + /* Wait until operation completed */ + tout = 0; + for( tout = 0; tout < uiMaxTime; tout++ ) + { + if( (MAC_MIND & MIND_BUSY) == 0 ) + { + break; + } + + vTaskDelay( 2 ); + } + + MAC_MCMD = 0; + + if( tout >= uiMaxTime ) + { + *pxStatus = pdFAIL; + } + + return( MAC_MRDD ); +} + +// Keil: function added to initialize Rx Descriptors +void rx_descr_init( void ) +{ + unsigned int i; + + for( i = 0; i < NUM_RX_FRAG; i++ ) + { + RX_DESC_PACKET( i ) = RX_BUF( i ); + RX_DESC_CTRL( i ) = RCTRL_INT | ( ETH_FRAG_SIZE - 1 ); + RX_STAT_INFO( i ) = 0; + RX_STAT_HASHCRC( i ) = 0; + } + + /* Set EMAC Receive Descriptor Registers. */ + MAC_RXDESCRIPTOR = RX_DESC_BASE; + MAC_RXSTATUS = RX_STAT_BASE; + MAC_RXDESCRIPTORNUM = NUM_RX_FRAG - 1; + + /* Rx Descriptors Point to 0 */ + MAC_RXCONSUMEINDEX = 0; +} + +// Keil: function added to initialize Tx Descriptors +void tx_descr_init( void ) +{ + unsigned int i; + + for( i = 0; i < NUM_TX_FRAG; i++ ) + { + TX_DESC_PACKET( i ) = TX_BUF( i ); + TX_DESC_CTRL( i ) = 0; + TX_STAT_INFO( i ) = 0; + } + + /* Set EMAC Transmit Descriptor Registers. */ + MAC_TXDESCRIPTOR = TX_DESC_BASE; + MAC_TXSTATUS = TX_STAT_BASE; + MAC_TXDESCRIPTORNUM = NUM_TX_FRAG - 1; + + /* Tx Descriptors Point to 0 */ + MAC_TXPRODUCEINDEX = 0; +} + +// configure port-pins for use with LAN-controller, +// reset it and send the configuration-sequence +portBASE_TYPE Init_EMAC( void ) +{ + portBASE_TYPE xReturn = pdPASS; + + // Keil: function modified to access the EMAC + // Initializes the EMAC ethernet controller + volatile unsigned int regv, tout, id1, id2; + + /* Enable P1 Ethernet Pins. */ + PINSEL2 = configPINSEL2_VALUE; + PINSEL3 = ( PINSEL3 &~0x0000000F ) | 0x00000005; + + /* Power Up the EMAC controller. */ + PCONP |= PCONP_PCENET; + vTaskDelay( 2 ); + + /* Reset all EMAC internal modules. */ + MAC_MAC1 = MAC1_RES_TX | MAC1_RES_MCS_TX | MAC1_RES_RX | MAC1_RES_MCS_RX | MAC1_SIM_RES | MAC1_SOFT_RES; + MAC_COMMAND = CR_REG_RES | CR_TX_RES | CR_RX_RES | CR_PASS_RUNT_FRM; + + /* A short delay after reset. */ + vTaskDelay( 2 ); + + /* Initialize MAC control registers. */ + MAC_MAC1 = MAC1_PASS_ALL; + MAC_MAC2 = MAC2_CRC_EN | MAC2_PAD_EN; + MAC_MAXF = ETH_MAX_FLEN; + MAC_CLRT = CLRT_DEF; + MAC_IPGR = IPGR_DEF; + + /* Enable Reduced MII interface. */ + MAC_COMMAND = CR_RMII | CR_PASS_RUNT_FRM; + + /* Reset Reduced MII Logic. */ + MAC_SUPP = SUPP_RES_RMII; + vTaskDelay( 2 ); + MAC_SUPP = 0; + + /* Put the PHY in reset mode */ + write_PHY( PHY_REG_BMCR, 0x8000 ); + xReturn = write_PHY( PHY_REG_BMCR, 0x8000 ); + + /* Wait for hardware reset to end. */ + for( tout = 0; tout < 100; tout++ ) + { + vTaskDelay( 10 ); + regv = read_PHY( PHY_REG_BMCR, &xReturn ); + if( !(regv & 0x8000) ) + { + /* Reset complete */ + break; + } + } + + /* Check if this is a DP83848C PHY. */ + id1 = read_PHY( PHY_REG_IDR1, &xReturn ); + id2 = read_PHY( PHY_REG_IDR2, &xReturn ); + if( ((id1 << 16) | (id2 & 0xFFF0)) == DP83848C_ID ) + { + /* Set the Ethernet MAC Address registers */ + MAC_SA0 = ( emacETHADDR0 << 8 ) | emacETHADDR1; + MAC_SA1 = ( emacETHADDR2 << 8 ) | emacETHADDR3; + MAC_SA2 = ( emacETHADDR4 << 8 ) | emacETHADDR5; + + /* Initialize Tx and Rx DMA Descriptors */ + rx_descr_init(); + tx_descr_init(); + + /* Receive Broadcast and Perfect Match Packets */ + MAC_RXFILTERCTRL = RFC_UCAST_EN | RFC_BCAST_EN | RFC_PERFECT_EN; + + /* Create the semaphore used ot wake the uIP task. */ + vSemaphoreCreateBinary( xEMACSemaphore ); + + /* Configure the PHY device */ + + /* Use autonegotiation about the link speed. */ + if( write_PHY(PHY_REG_BMCR, PHY_AUTO_NEG) ) + { + /* Wait to complete Auto_Negotiation. */ + for( tout = 0; tout < 10; tout++ ) + { + vTaskDelay( 100 ); + regv = read_PHY( PHY_REG_BMSR, &xReturn ); + if( regv & 0x0020 ) + { + /* Autonegotiation Complete. */ + break; + } + } + } + } + else + { + xReturn = pdFAIL; + } + + /* Check the link status. */ + if( xReturn == pdPASS ) + { + xReturn = pdFAIL; + for( tout = 0; tout < 10; tout++ ) + { + vTaskDelay( 100 ); + regv = read_PHY( PHY_REG_STS, &xReturn ); + if( regv & 0x0001 ) + { + /* Link is on. */ + xReturn = pdPASS; + break; + } + } + } + + if( xReturn == pdPASS ) + { + /* Configure Full/Half Duplex mode. */ + if( regv & 0x0004 ) + { + /* Full duplex is enabled. */ + MAC_MAC2 |= MAC2_FULL_DUP; + MAC_COMMAND |= CR_FULL_DUP; + MAC_IPGT = IPGT_FULL_DUP; + } + else + { + /* Half duplex mode. */ + MAC_IPGT = IPGT_HALF_DUP; + } + + /* Configure 100MBit/10MBit mode. */ + if( regv & 0x0002 ) + { + /* 10MBit mode. */ + MAC_SUPP = 0; + } + else + { + /* 100MBit mode. */ + MAC_SUPP = SUPP_SPEED; + } + + /* Reset all interrupts */ + MAC_INTCLEAR = 0xFFFF; + + /* Enable receive and transmit mode of MAC Ethernet core */ + MAC_COMMAND |= ( CR_RX_EN | CR_TX_EN ); + MAC_MAC1 |= MAC1_REC_EN; + } + + return xReturn; +} + +// reads a word in little-endian byte order from RX_BUFFER +unsigned short ReadFrame_EMAC( void ) +{ + return( *rptr++ ); +} + +// reads a word in big-endian byte order from RX_FRAME_PORT +// (useful to avoid permanent byte-swapping while reading +// TCP/IP-data) +unsigned short ReadFrameBE_EMAC( void ) +{ + unsigned short ReturnValue; + + ReturnValue = SwapBytes( *rptr++ ); + return( ReturnValue ); +} + +// copies bytes from frame port to MCU-memory +// NOTES: * an odd number of byte may only be transfered +// if the frame is read to the end! +// * MCU-memory MUST start at word-boundary +void CopyFromFrame_EMAC( void *Dest, unsigned short Size ) +{ + unsigned short *piDest; // Keil: Pointer added to correct expression + piDest = Dest; // Keil: Line added + while( Size > 1 ) + { + *piDest++ = ReadFrame_EMAC(); + Size -= 2; + } + + if( Size ) + { // check for leftover byte... + *( unsigned char * ) piDest = ( char ) ReadFrame_EMAC(); // the LAN-Controller will return 0 + } // for the highbyte +} + +// does a dummy read on frame-I/O-port +// NOTE: only an even number of bytes is read! +void DummyReadFrame_EMAC( unsigned short Size ) // discards an EVEN number of bytes +{ // from RX-fifo + while( Size > 1 ) + { + ReadFrame_EMAC(); + Size -= 2; + } +} + +// Reads the length of the received ethernet frame and checks if the +// destination address is a broadcast message or not +// returns the frame length +unsigned short StartReadFrame( void ) +{ + unsigned short RxLen; + unsigned int idx; + + idx = MAC_RXCONSUMEINDEX; + RxLen = ( RX_STAT_INFO(idx) & RINFO_SIZE ) - 3; + rptr = ( unsigned short * ) RX_DESC_PACKET( idx ); + return( RxLen ); +} + +void EndReadFrame( void ) +{ + unsigned int idx; + + /* DMA free packet. */ + idx = MAC_RXCONSUMEINDEX; + + if( ++idx == NUM_RX_FRAG ) + { + idx = 0; + } + + MAC_RXCONSUMEINDEX = idx; +} + +unsigned int CheckFrameReceived( void ) +{ + // Packet received ? + if( MAC_RXPRODUCEINDEX != MAC_RXCONSUMEINDEX ) + { // more packets received ? + return( 1 ); + } + else + { + return( 0 ); + } +} + +unsigned int uiGetEMACRxData( unsigned char *ucBuffer ) +{ + unsigned int uiLen = 0; + + if( MAC_RXPRODUCEINDEX != MAC_RXCONSUMEINDEX ) + { + uiLen = StartReadFrame(); + CopyFromFrame_EMAC( ucBuffer, uiLen ); + EndReadFrame(); + } + + return uiLen; +} + +// requests space in EMAC memory for storing an outgoing frame +void RequestSend( void ) +{ + unsigned int idx; + + idx = MAC_TXPRODUCEINDEX; + tptr = ( unsigned short * ) TX_DESC_PACKET( idx ); +} + +// check if ethernet controller is ready to accept the +// frame we want to send +unsigned int Rdy4Tx( void ) +{ + return( 1 ); // the ethernet controller transmits much faster +} // than the CPU can load its buffers + +// writes a word in little-endian byte order to TX_BUFFER +void WriteFrame_EMAC( unsigned short Data ) +{ + *tptr++ = Data; +} + +// copies bytes from MCU-memory to frame port +// NOTES: * an odd number of byte may only be transfered +// if the frame is written to the end! +// * MCU-memory MUST start at word-boundary +void CopyToFrame_EMAC( void *Source, unsigned int Size ) +{ + unsigned short *piSource; + + piSource = Source; + Size = ( Size + 1 ) & 0xFFFE; // round Size up to next even number + while( Size > 0 ) + { + WriteFrame_EMAC( *piSource++ ); + Size -= 2; + } +} + +void DoSend_EMAC( unsigned short FrameSize ) +{ + unsigned int idx; + + idx = MAC_TXPRODUCEINDEX; + TX_DESC_CTRL( idx ) = FrameSize | TCTRL_LAST; + if( ++idx == NUM_TX_FRAG ) + { + idx = 0; + } + + MAC_TXPRODUCEINDEX = idx; +} + +void vEMAC_ISR( void ) +{ + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + + /* Clear the interrupt. */ + MAC_INTCLEAR = 0xffff; + + /* Ensure the uIP task is not blocked as data has arrived. */ + xSemaphoreGiveFromISR( xEMACSemaphore, &xHigherPriorityTaskWoken ); + + portEND_SWITCHING_ISR( xHigherPriorityTaskWoken ); +} diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/emac.h b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/emac.h new file mode 100644 index 000000000..6aa5249e2 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/emac.h @@ -0,0 +1,324 @@ +/*---------------------------------------------------------------------------- + * LPC2378 Ethernet Definitions + *---------------------------------------------------------------------------- + * Name: EMAC.H + * Purpose: Philips LPC2378 EMAC hardware definitions + *---------------------------------------------------------------------------- + * Copyright (c) 2006 KEIL - An ARM Company. All rights reserved. + *---------------------------------------------------------------------------*/ +#ifndef __EMAC_H +#define __EMAC_H + +/* MAC address definition. The MAC address must be unique on the network. */ +#define emacETHADDR0 0 +#define emacETHADDR1 0xbd +#define emacETHADDR2 0x33 +#define emacETHADDR3 0x02 +#define emacETHADDR4 0x64 +#define emacETHADDR5 0x24 + + +/* EMAC Memory Buffer configuration for 16K Ethernet RAM. */ +#define NUM_RX_FRAG 4 /* Num.of RX Fragments 4*1536= 6.0kB */ +#define NUM_TX_FRAG 2 /* Num.of TX Fragments 2*1536= 3.0kB */ +#define ETH_FRAG_SIZE 1536 /* Packet Fragment size 1536 Bytes */ + +#define ETH_MAX_FLEN 1536 /* Max. Ethernet Frame Size */ + +/* EMAC variables located in 16K Ethernet SRAM */ +//extern unsigned char xEthDescriptors[]; +#define RX_DESC_BASE (0x2007c000UL) +#define RX_STAT_BASE (RX_DESC_BASE + NUM_RX_FRAG*8) +#define TX_DESC_BASE (RX_STAT_BASE + NUM_RX_FRAG*8) +#define TX_STAT_BASE (TX_DESC_BASE + NUM_TX_FRAG*8) +#define RX_BUF_BASE (TX_STAT_BASE + NUM_TX_FRAG*4) +#define TX_BUF_BASE (RX_BUF_BASE + NUM_RX_FRAG*ETH_FRAG_SIZE) +#define TX_BUF_END (TX_BUF_BASE + NUM_TX_FRAG*ETH_FRAG_SIZE) + +/* RX and TX descriptor and status definitions. */ +#define RX_DESC_PACKET(i) (*(unsigned int *)(RX_DESC_BASE + 8*i)) +#define RX_DESC_CTRL(i) (*(unsigned int *)(RX_DESC_BASE+4 + 8*i)) +#define RX_STAT_INFO(i) (*(unsigned int *)(RX_STAT_BASE + 8*i)) +#define RX_STAT_HASHCRC(i) (*(unsigned int *)(RX_STAT_BASE+4 + 8*i)) +#define TX_DESC_PACKET(i) (*(unsigned int *)(TX_DESC_BASE + 8*i)) +#define TX_DESC_CTRL(i) (*(unsigned int *)(TX_DESC_BASE+4 + 8*i)) +#define TX_STAT_INFO(i) (*(unsigned int *)(TX_STAT_BASE + 4*i)) +#define RX_BUF(i) (RX_BUF_BASE + ETH_FRAG_SIZE*i) +#define TX_BUF(i) (TX_BUF_BASE + ETH_FRAG_SIZE*i) + +/* MAC Configuration Register 1 */ +#define MAC1_REC_EN 0x00000001 /* Receive Enable */ +#define MAC1_PASS_ALL 0x00000002 /* Pass All Receive Frames */ +#define MAC1_RX_FLOWC 0x00000004 /* RX Flow Control */ +#define MAC1_TX_FLOWC 0x00000008 /* TX Flow Control */ +#define MAC1_LOOPB 0x00000010 /* Loop Back Mode */ +#define MAC1_RES_TX 0x00000100 /* Reset TX Logic */ +#define MAC1_RES_MCS_TX 0x00000200 /* Reset MAC TX Control Sublayer */ +#define MAC1_RES_RX 0x00000400 /* Reset RX Logic */ +#define MAC1_RES_MCS_RX 0x00000800 /* Reset MAC RX Control Sublayer */ +#define MAC1_SIM_RES 0x00004000 /* Simulation Reset */ +#define MAC1_SOFT_RES 0x00008000 /* Soft Reset MAC */ + +/* MAC Configuration Register 2 */ +#define MAC2_FULL_DUP 0x00000001 /* Full Duplex Mode */ +#define MAC2_FRM_LEN_CHK 0x00000002 /* Frame Length Checking */ +#define MAC2_HUGE_FRM_EN 0x00000004 /* Huge Frame Enable */ +#define MAC2_DLY_CRC 0x00000008 /* Delayed CRC Mode */ +#define MAC2_CRC_EN 0x00000010 /* Append CRC to every Frame */ +#define MAC2_PAD_EN 0x00000020 /* Pad all Short Frames */ +#define MAC2_VLAN_PAD_EN 0x00000040 /* VLAN Pad Enable */ +#define MAC2_ADET_PAD_EN 0x00000080 /* Auto Detect Pad Enable */ +#define MAC2_PPREAM_ENF 0x00000100 /* Pure Preamble Enforcement */ +#define MAC2_LPREAM_ENF 0x00000200 /* Long Preamble Enforcement */ +#undef MAC2_NO_BACKOFF /* Remove compiler warning. */ +#define MAC2_NO_BACKOFF 0x00001000 /* No Backoff Algorithm */ +#define MAC2_BACK_PRESSURE 0x00002000 /* Backoff Presurre / No Backoff */ +#define MAC2_EXCESS_DEF 0x00004000 /* Excess Defer */ + +/* Back-to-Back Inter-Packet-Gap Register */ +#define IPGT_FULL_DUP 0x00000015 /* Recommended value for Full Duplex */ +#define IPGT_HALF_DUP 0x00000012 /* Recommended value for Half Duplex */ + +/* Non Back-to-Back Inter-Packet-Gap Register */ +#define IPGR_DEF 0x00000012 /* Recommended value */ + +/* Collision Window/Retry Register */ +#define CLRT_DEF 0x0000370F /* Default value */ + +/* PHY Support Register */ +#undef SUPP_SPEED /* Remove compiler warning. */ +#define SUPP_SPEED 0x00000100 /* Reduced MII Logic Current Speed */ +#define SUPP_RES_RMII 0x00000800 /* Reset Reduced MII Logic */ + +/* Test Register */ +#define TEST_SHCUT_PQUANTA 0x00000001 /* Shortcut Pause Quanta */ +#define TEST_TST_PAUSE 0x00000002 /* Test Pause */ +#define TEST_TST_BACKP 0x00000004 /* Test Back Pressure */ + +/* MII Management Configuration Register */ +#define MCFG_SCAN_INC 0x00000001 /* Scan Increment PHY Address */ +#define MCFG_SUPP_PREAM 0x00000002 /* Suppress Preamble */ +#define MCFG_CLK_SEL 0x0000001C /* Clock Select Mask */ +#define MCFG_RES_MII 0x00008000 /* Reset MII Management Hardware */ + +/* MII Management Command Register */ +#undef MCMD_READ /* Remove compiler warning. */ +#define MCMD_READ 0x00000001 /* MII Read */ +#undef MCMD_SCAN /* Remove compiler warning. */ +#define MCMD_SCAN 0x00000002 /* MII Scan continuously */ + +#define MII_WR_TOUT 0x00050000 /* MII Write timeout count */ +#define MII_RD_TOUT 0x00050000 /* MII Read timeout count */ + +/* MII Management Address Register */ +#define MADR_REG_ADR 0x0000001F /* MII Register Address Mask */ +#define MADR_PHY_ADR 0x00001F00 /* PHY Address Mask */ + +/* MII Management Indicators Register */ +#undef MIND_BUSY /* Remove compiler warning. */ +#define MIND_BUSY 0x00000001 /* MII is Busy */ +#define MIND_SCAN 0x00000002 /* MII Scanning in Progress */ +#define MIND_NOT_VAL 0x00000004 /* MII Read Data not valid */ +#define MIND_MII_LINK_FAIL 0x00000008 /* MII Link Failed */ + +/* Command Register */ +#define CR_RX_EN 0x00000001 /* Enable Receive */ +#define CR_TX_EN 0x00000002 /* Enable Transmit */ +#define CR_REG_RES 0x00000008 /* Reset Host Registers */ +#define CR_TX_RES 0x00000010 /* Reset Transmit Datapath */ +#define CR_RX_RES 0x00000020 /* Reset Receive Datapath */ +#define CR_PASS_RUNT_FRM 0x00000040 /* Pass Runt Frames */ +#define CR_PASS_RX_FILT 0x00000080 /* Pass RX Filter */ +#define CR_TX_FLOW_CTRL 0x00000100 /* TX Flow Control */ +#define CR_RMII 0x00000200 /* Reduced MII Interface */ +#define CR_FULL_DUP 0x00000400 /* Full Duplex */ + +/* Status Register */ +#define SR_RX_EN 0x00000001 /* Enable Receive */ +#define SR_TX_EN 0x00000002 /* Enable Transmit */ + +/* Transmit Status Vector 0 Register */ +#define TSV0_CRC_ERR 0x00000001 /* CRC error */ +#define TSV0_LEN_CHKERR 0x00000002 /* Length Check Error */ +#define TSV0_LEN_OUTRNG 0x00000004 /* Length Out of Range */ +#define TSV0_DONE 0x00000008 /* Tramsmission Completed */ +#define TSV0_MCAST 0x00000010 /* Multicast Destination */ +#define TSV0_BCAST 0x00000020 /* Broadcast Destination */ +#define TSV0_PKT_DEFER 0x00000040 /* Packet Deferred */ +#define TSV0_EXC_DEFER 0x00000080 /* Excessive Packet Deferral */ +#define TSV0_EXC_COLL 0x00000100 /* Excessive Collision */ +#define TSV0_LATE_COLL 0x00000200 /* Late Collision Occured */ +#define TSV0_GIANT 0x00000400 /* Giant Frame */ +#define TSV0_UNDERRUN 0x00000800 /* Buffer Underrun */ +#define TSV0_BYTES 0x0FFFF000 /* Total Bytes Transferred */ +#define TSV0_CTRL_FRAME 0x10000000 /* Control Frame */ +#define TSV0_PAUSE 0x20000000 /* Pause Frame */ +#define TSV0_BACK_PRESS 0x40000000 /* Backpressure Method Applied */ +#define TSV0_VLAN 0x80000000 /* VLAN Frame */ + +/* Transmit Status Vector 1 Register */ +#define TSV1_BYTE_CNT 0x0000FFFF /* Transmit Byte Count */ +#define TSV1_COLL_CNT 0x000F0000 /* Transmit Collision Count */ + +/* Receive Status Vector Register */ +#define RSV_BYTE_CNT 0x0000FFFF /* Receive Byte Count */ +#define RSV_PKT_IGNORED 0x00010000 /* Packet Previously Ignored */ +#define RSV_RXDV_SEEN 0x00020000 /* RXDV Event Previously Seen */ +#define RSV_CARR_SEEN 0x00040000 /* Carrier Event Previously Seen */ +#define RSV_REC_CODEV 0x00080000 /* Receive Code Violation */ +#define RSV_CRC_ERR 0x00100000 /* CRC Error */ +#define RSV_LEN_CHKERR 0x00200000 /* Length Check Error */ +#define RSV_LEN_OUTRNG 0x00400000 /* Length Out of Range */ +#define RSV_REC_OK 0x00800000 /* Frame Received OK */ +#define RSV_MCAST 0x01000000 /* Multicast Frame */ +#define RSV_BCAST 0x02000000 /* Broadcast Frame */ +#define RSV_DRIB_NIBB 0x04000000 /* Dribble Nibble */ +#define RSV_CTRL_FRAME 0x08000000 /* Control Frame */ +#define RSV_PAUSE 0x10000000 /* Pause Frame */ +#define RSV_UNSUPP_OPC 0x20000000 /* Unsupported Opcode */ +#define RSV_VLAN 0x40000000 /* VLAN Frame */ + +/* Flow Control Counter Register */ +#define FCC_MIRR_CNT 0x0000FFFF /* Mirror Counter */ +#define FCC_PAUSE_TIM 0xFFFF0000 /* Pause Timer */ + +/* Flow Control Status Register */ +#define FCS_MIRR_CNT 0x0000FFFF /* Mirror Counter Current */ + +/* Receive Filter Control Register */ +#define RFC_UCAST_EN 0x00000001 /* Accept Unicast Frames Enable */ +#define RFC_BCAST_EN 0x00000002 /* Accept Broadcast Frames Enable */ +#define RFC_MCAST_EN 0x00000004 /* Accept Multicast Frames Enable */ +#define RFC_UCAST_HASH_EN 0x00000008 /* Accept Unicast Hash Filter Frames */ +#define RFC_MCAST_HASH_EN 0x00000010 /* Accept Multicast Hash Filter Fram.*/ +#define RFC_PERFECT_EN 0x00000020 /* Accept Perfect Match Enable */ +#define RFC_MAGP_WOL_EN 0x00001000 /* Magic Packet Filter WoL Enable */ +#define RFC_PFILT_WOL_EN 0x00002000 /* Perfect Filter WoL Enable */ + +/* Receive Filter WoL Status/Clear Registers */ +#define WOL_UCAST 0x00000001 /* Unicast Frame caused WoL */ +#define WOL_BCAST 0x00000002 /* Broadcast Frame caused WoL */ +#define WOL_MCAST 0x00000004 /* Multicast Frame caused WoL */ +#define WOL_UCAST_HASH 0x00000008 /* Unicast Hash Filter Frame WoL */ +#define WOL_MCAST_HASH 0x00000010 /* Multicast Hash Filter Frame WoL */ +#define WOL_PERFECT 0x00000020 /* Perfect Filter WoL */ +#define WOL_RX_FILTER 0x00000080 /* RX Filter caused WoL */ +#define WOL_MAG_PACKET 0x00000100 /* Magic Packet Filter caused WoL */ + +/* Interrupt Status/Enable/Clear/Set Registers */ +#define INT_RX_OVERRUN 0x00000001 /* Overrun Error in RX Queue */ +#define INT_RX_ERR 0x00000002 /* Receive Error */ +#define INT_RX_FIN 0x00000004 /* RX Finished Process Descriptors */ +#define INT_RX_DONE 0x00000008 /* Receive Done */ +#define INT_TX_UNDERRUN 0x00000010 /* Transmit Underrun */ +#define INT_TX_ERR 0x00000020 /* Transmit Error */ +#define INT_TX_FIN 0x00000040 /* TX Finished Process Descriptors */ +#define INT_TX_DONE 0x00000080 /* Transmit Done */ +#define INT_SOFT_INT 0x00001000 /* Software Triggered Interrupt */ +#define INT_WAKEUP 0x00002000 /* Wakeup Event Interrupt */ + +/* Power Down Register */ +#define PD_POWER_DOWN 0x80000000 /* Power Down MAC */ + +/* RX Descriptor Control Word */ +#define RCTRL_SIZE 0x000007FF /* Buffer size mask */ +#define RCTRL_INT 0x80000000 /* Generate RxDone Interrupt */ + +/* RX Status Hash CRC Word */ +#define RHASH_SA 0x000001FF /* Hash CRC for Source Address */ +#define RHASH_DA 0x001FF000 /* Hash CRC for Destination Address */ + +/* RX Status Information Word */ +#define RINFO_SIZE 0x000007FF /* Data size in bytes */ +#define RINFO_CTRL_FRAME 0x00040000 /* Control Frame */ +#define RINFO_VLAN 0x00080000 /* VLAN Frame */ +#define RINFO_FAIL_FILT 0x00100000 /* RX Filter Failed */ +#define RINFO_MCAST 0x00200000 /* Multicast Frame */ +#define RINFO_BCAST 0x00400000 /* Broadcast Frame */ +#define RINFO_CRC_ERR 0x00800000 /* CRC Error in Frame */ +#define RINFO_SYM_ERR 0x01000000 /* Symbol Error from PHY */ +#define RINFO_LEN_ERR 0x02000000 /* Length Error */ +#define RINFO_RANGE_ERR 0x04000000 /* Range Error (exceeded max. size) */ +#define RINFO_ALIGN_ERR 0x08000000 /* Alignment Error */ +#define RINFO_OVERRUN 0x10000000 /* Receive overrun */ +#define RINFO_NO_DESCR 0x20000000 /* No new Descriptor available */ +#define RINFO_LAST_FLAG 0x40000000 /* Last Fragment in Frame */ +#define RINFO_ERR 0x80000000 /* Error Occured (OR of all errors) */ + +#define RINFO_ERR_MASK (RINFO_FAIL_FILT | RINFO_CRC_ERR | RINFO_SYM_ERR | \ + RINFO_LEN_ERR | RINFO_ALIGN_ERR | RINFO_OVERRUN) + +/* TX Descriptor Control Word */ +#define TCTRL_SIZE 0x000007FF /* Size of data buffer in bytes */ +#define TCTRL_OVERRIDE 0x04000000 /* Override Default MAC Registers */ +#define TCTRL_HUGE 0x08000000 /* Enable Huge Frame */ +#define TCTRL_PAD 0x10000000 /* Pad short Frames to 64 bytes */ +#define TCTRL_CRC 0x20000000 /* Append a hardware CRC to Frame */ +#define TCTRL_LAST 0x40000000 /* Last Descriptor for TX Frame */ +#define TCTRL_INT 0x80000000 /* Generate TxDone Interrupt */ + +/* TX Status Information Word */ +#define TINFO_COL_CNT 0x01E00000 /* Collision Count */ +#define TINFO_DEFER 0x02000000 /* Packet Deferred (not an error) */ +#define TINFO_EXCESS_DEF 0x04000000 /* Excessive Deferral */ +#define TINFO_EXCESS_COL 0x08000000 /* Excessive Collision */ +#define TINFO_LATE_COL 0x10000000 /* Late Collision Occured */ +#define TINFO_UNDERRUN 0x20000000 /* Transmit Underrun */ +#define TINFO_NO_DESCR 0x40000000 /* No new Descriptor available */ +#define TINFO_ERR 0x80000000 /* Error Occured (OR of all errors) */ + +/* DP83848C PHY Registers */ +#define PHY_REG_BMCR 0x00 /* Basic Mode Control Register */ +#define PHY_REG_BMSR 0x01 /* Basic Mode Status Register */ +#define PHY_REG_IDR1 0x02 /* PHY Identifier 1 */ +#define PHY_REG_IDR2 0x03 /* PHY Identifier 2 */ +#define PHY_REG_ANAR 0x04 /* Auto-Negotiation Advertisement */ +#define PHY_REG_ANLPAR 0x05 /* Auto-Neg. Link Partner Abitily */ +#define PHY_REG_ANER 0x06 /* Auto-Neg. Expansion Register */ +#define PHY_REG_ANNPTR 0x07 /* Auto-Neg. Next Page TX */ + +/* PHY Extended Registers */ +#define PHY_REG_STS 0x10 /* Status Register */ +#define PHY_REG_MICR 0x11 /* MII Interrupt Control Register */ +#define PHY_REG_MISR 0x12 /* MII Interrupt Status Register */ +#define PHY_REG_FCSCR 0x14 /* False Carrier Sense Counter */ +#define PHY_REG_RECR 0x15 /* Receive Error Counter */ +#define PHY_REG_PCSR 0x16 /* PCS Sublayer Config. and Status */ +#define PHY_REG_RBR 0x17 /* RMII and Bypass Register */ +#define PHY_REG_LEDCR 0x18 /* LED Direct Control Register */ +#define PHY_REG_PHYCR 0x19 /* PHY Control Register */ +#define PHY_REG_10BTSCR 0x1A /* 10Base-T Status/Control Register */ +#define PHY_REG_CDCTRL1 0x1B /* CD Test Control and BIST Extens. */ +#define PHY_REG_EDCR 0x1D /* Energy Detect Control Register */ + +#define PHY_FULLD_100M 0x2100 /* Full Duplex 100Mbit */ +#define PHY_HALFD_100M 0x2000 /* Half Duplex 100Mbit */ +#define PHY_FULLD_10M 0x0100 /* Full Duplex 10Mbit */ +#define PHY_HALFD_10M 0x0000 /* Half Duplex 10MBit */ +#define PHY_AUTO_NEG 0x3000 /* Select Auto Negotiation */ + +#define DP83848C_DEF_ADR 0x0100 /* Default PHY device address */ +#define DP83848C_ID 0x20005C90 /* PHY Identifier */ + +// prototypes +portBASE_TYPE Init_EMAC(void); +unsigned short ReadFrameBE_EMAC(void); +void CopyToFrame_EMAC(void *Source, unsigned int Size); +void CopyFromFrame_EMAC(void *Dest, unsigned short Size); +void DummyReadFrame_EMAC(unsigned short Size); +unsigned short StartReadFrame(void); +void EndReadFrame(void); +unsigned int CheckFrameReceived(void); +void RequestSend(void); +unsigned int Rdy4Tx(void); +void DoSend_EMAC(unsigned short FrameSize); +void vEMACWaitForInput( void ); +unsigned int uiGetEMACRxData( unsigned char *ucBuffer ); + + +#endif + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/http-strings b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/http-strings new file mode 100644 index 000000000..0d3c30cdd --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/http-strings @@ -0,0 +1,35 @@ +http_http "http://" +http_200 "200 " +http_301 "301 " +http_302 "302 " +http_get "GET " +http_10 "HTTP/1.0" +http_11 "HTTP/1.1" +http_content_type "content-type: " +http_texthtml "text/html" +http_location "location: " +http_host "host: " +http_crnl "\r\n" +http_index_html "/index.html" +http_404_html "/404.html" +http_referer "Referer:" +http_header_200 "HTTP/1.0 200 OK\r\nServer: uIP/1.0 http://www.sics.se/~adam/uip/\r\nConnection: close\r\n" +http_header_404 "HTTP/1.0 404 Not found\r\nServer: uIP/1.0 http://www.sics.se/~adam/uip/\r\nConnection: close\r\n" +http_content_type_plain "Content-type: text/plain\r\n\r\n" +http_content_type_html "Content-type: text/html\r\n\r\n" +http_content_type_css "Content-type: text/css\r\n\r\n" +http_content_type_text "Content-type: text/text\r\n\r\n" +http_content_type_png "Content-type: image/png\r\n\r\n" +http_content_type_gif "Content-type: image/gif\r\n\r\n" +http_content_type_jpg "Content-type: image/jpeg\r\n\r\n" +http_content_type_binary "Content-type: application/octet-stream\r\n\r\n" +http_html ".html" +http_shtml ".shtml" +http_htm ".htm" +http_css ".css" +http_png ".png" +http_gif ".gif" +http_jpg ".jpg" +http_text ".txt" +http_txt ".txt" + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/http-strings.c b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/http-strings.c new file mode 100644 index 000000000..ef7a41c7d --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/http-strings.c @@ -0,0 +1,102 @@ +const char http_http[8] = +/* "http://" */ +{0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, 0x2f, }; +const char http_200[5] = +/* "200 " */ +{0x32, 0x30, 0x30, 0x20, }; +const char http_301[5] = +/* "301 " */ +{0x33, 0x30, 0x31, 0x20, }; +const char http_302[5] = +/* "302 " */ +{0x33, 0x30, 0x32, 0x20, }; +const char http_get[5] = +/* "GET " */ +{0x47, 0x45, 0x54, 0x20, }; +const char http_10[9] = +/* "HTTP/1.0" */ +{0x48, 0x54, 0x54, 0x50, 0x2f, 0x31, 0x2e, 0x30, }; +const char http_11[9] = +/* "HTTP/1.1" */ +{0x48, 0x54, 0x54, 0x50, 0x2f, 0x31, 0x2e, 0x31, }; +const char http_content_type[15] = +/* "content-type: " */ +{0x63, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, }; +const char http_texthtml[10] = +/* "text/html" */ +{0x74, 0x65, 0x78, 0x74, 0x2f, 0x68, 0x74, 0x6d, 0x6c, }; +const char http_location[11] = +/* "location: " */ +{0x6c, 0x6f, 0x63, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x3a, 0x20, }; +const char http_host[7] = +/* "host: " */ +{0x68, 0x6f, 0x73, 0x74, 0x3a, 0x20, }; +const char http_crnl[3] = +/* "\r\n" */ +{0xd, 0xa, }; +const char http_index_html[12] = +/* "/index.html" */ +{0x2f, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x68, 0x74, 0x6d, 0x6c, }; +const char http_404_html[10] = +/* "/404.html" */ +{0x2f, 0x34, 0x30, 0x34, 0x2e, 0x68, 0x74, 0x6d, 0x6c, }; +const char http_referer[9] = +/* "Referer:" */ +{0x52, 0x65, 0x66, 0x65, 0x72, 0x65, 0x72, 0x3a, }; +const char http_header_200[84] = +/* "HTTP/1.0 200 OK\r\nServer: uIP/1.0 http://www.sics.se/~adam/uip/\r\nConnection: close\r\n" */ +{0x48, 0x54, 0x54, 0x50, 0x2f, 0x31, 0x2e, 0x30, 0x20, 0x32, 0x30, 0x30, 0x20, 0x4f, 0x4b, 0xd, 0xa, 0x53, 0x65, 0x72, 0x76, 0x65, 0x72, 0x3a, 0x20, 0x75, 0x49, 0x50, 0x2f, 0x31, 0x2e, 0x30, 0x20, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x73, 0x69, 0x63, 0x73, 0x2e, 0x73, 0x65, 0x2f, 0x7e, 0x61, 0x64, 0x61, 0x6d, 0x2f, 0x75, 0x69, 0x70, 0x2f, 0xd, 0xa, 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x3a, 0x20, 0x63, 0x6c, 0x6f, 0x73, 0x65, 0xd, 0xa, }; +const char http_header_404[91] = +/* "HTTP/1.0 404 Not found\r\nServer: uIP/1.0 http://www.sics.se/~adam/uip/\r\nConnection: close\r\n" */ +{0x48, 0x54, 0x54, 0x50, 0x2f, 0x31, 0x2e, 0x30, 0x20, 0x34, 0x30, 0x34, 0x20, 0x4e, 0x6f, 0x74, 0x20, 0x66, 0x6f, 0x75, 0x6e, 0x64, 0xd, 0xa, 0x53, 0x65, 0x72, 0x76, 0x65, 0x72, 0x3a, 0x20, 0x75, 0x49, 0x50, 0x2f, 0x31, 0x2e, 0x30, 0x20, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x73, 0x69, 0x63, 0x73, 0x2e, 0x73, 0x65, 0x2f, 0x7e, 0x61, 0x64, 0x61, 0x6d, 0x2f, 0x75, 0x69, 0x70, 0x2f, 0xd, 0xa, 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x3a, 0x20, 0x63, 0x6c, 0x6f, 0x73, 0x65, 0xd, 0xa, }; +const char http_content_type_plain[29] = +/* "Content-type: text/plain\r\n\r\n" */ +{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x74, 0x65, 0x78, 0x74, 0x2f, 0x70, 0x6c, 0x61, 0x69, 0x6e, 0xd, 0xa, 0xd, 0xa, }; +const char http_content_type_html[28] = +/* "Content-type: text/html\r\n\r\n" */ +{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x74, 0x65, 0x78, 0x74, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0xd, 0xa, 0xd, 0xa, }; +const char http_content_type_css [27] = +/* "Content-type: text/css\r\n\r\n" */ +{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x74, 0x65, 0x78, 0x74, 0x2f, 0x63, 0x73, 0x73, 0xd, 0xa, 0xd, 0xa, }; +const char http_content_type_text[28] = +/* "Content-type: text/text\r\n\r\n" */ +{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x74, 0x65, 0x78, 0x74, 0x2f, 0x74, 0x65, 0x78, 0x74, 0xd, 0xa, 0xd, 0xa, }; +const char http_content_type_png [28] = +/* "Content-type: image/png\r\n\r\n" */ +{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x69, 0x6d, 0x61, 0x67, 0x65, 0x2f, 0x70, 0x6e, 0x67, 0xd, 0xa, 0xd, 0xa, }; +const char http_content_type_gif [28] = +/* "Content-type: image/gif\r\n\r\n" */ +{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x69, 0x6d, 0x61, 0x67, 0x65, 0x2f, 0x67, 0x69, 0x66, 0xd, 0xa, 0xd, 0xa, }; +const char http_content_type_jpg [29] = +/* "Content-type: image/jpeg\r\n\r\n" */ +{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x69, 0x6d, 0x61, 0x67, 0x65, 0x2f, 0x6a, 0x70, 0x65, 0x67, 0xd, 0xa, 0xd, 0xa, }; +const char http_content_type_binary[43] = +/* "Content-type: application/octet-stream\r\n\r\n" */ +{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x61, 0x70, 0x70, 0x6c, 0x69, 0x63, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x2f, 0x6f, 0x63, 0x74, 0x65, 0x74, 0x2d, 0x73, 0x74, 0x72, 0x65, 0x61, 0x6d, 0xd, 0xa, 0xd, 0xa, }; +const char http_html[6] = +/* ".html" */ +{0x2e, 0x68, 0x74, 0x6d, 0x6c, }; +const char http_shtml[7] = +/* ".shtml" */ +{0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, }; +const char http_htm[5] = +/* ".htm" */ +{0x2e, 0x68, 0x74, 0x6d, }; +const char http_css[5] = +/* ".css" */ +{0x2e, 0x63, 0x73, 0x73, }; +const char http_png[5] = +/* ".png" */ +{0x2e, 0x70, 0x6e, 0x67, }; +const char http_gif[5] = +/* ".gif" */ +{0x2e, 0x67, 0x69, 0x66, }; +const char http_jpg[5] = +/* ".jpg" */ +{0x2e, 0x6a, 0x70, 0x67, }; +const char http_text[5] = +/* ".txt" */ +{0x2e, 0x74, 0x78, 0x74, }; +const char http_txt[5] = +/* ".txt" */ +{0x2e, 0x74, 0x78, 0x74, }; diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/http-strings.h b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/http-strings.h new file mode 100644 index 000000000..acbe7e17f --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/http-strings.h @@ -0,0 +1,34 @@ +extern const char http_http[8]; +extern const char http_200[5]; +extern const char http_301[5]; +extern const char http_302[5]; +extern const char http_get[5]; +extern const char http_10[9]; +extern const char http_11[9]; +extern const char http_content_type[15]; +extern const char http_texthtml[10]; +extern const char http_location[11]; +extern const char http_host[7]; +extern const char http_crnl[3]; +extern const char http_index_html[12]; +extern const char http_404_html[10]; +extern const char http_referer[9]; +extern const char http_header_200[84]; +extern const char http_header_404[91]; +extern const char http_content_type_plain[29]; +extern const char http_content_type_html[28]; +extern const char http_content_type_css [27]; +extern const char http_content_type_text[28]; +extern const char http_content_type_png [28]; +extern const char http_content_type_gif [28]; +extern const char http_content_type_jpg [29]; +extern const char http_content_type_binary[43]; +extern const char http_html[6]; +extern const char http_shtml[7]; +extern const char http_htm[5]; +extern const char http_css[5]; +extern const char http_png[5]; +extern const char http_gif[5]; +extern const char http_jpg[5]; +extern const char http_text[5]; +extern const char http_txt[5]; diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-cgi.c b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-cgi.c new file mode 100644 index 000000000..7967c175c --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-cgi.c @@ -0,0 +1,305 @@ +/** + * \addtogroup httpd + * @{ + */ + +/** + * \file + * Web server script interface + * \author + * Adam Dunkels + * + */ + +/* + * Copyright (c) 2001-2006, Adam Dunkels. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. The name of the author may not be used to endorse or promote + * products derived from this software without specific prior + * written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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. + * + * This file is part of the uIP TCP/IP stack. + * + * $Id: httpd-cgi.c,v 1.2 2006/06/11 21:46:37 adam Exp $ + * + */ + +#include "uip.h" +#include "psock.h" +#include "httpd.h" +#include "httpd-cgi.h" +#include "httpd-fs.h" + +#include +#include + +HTTPD_CGI_CALL(file, "file-stats", file_stats); +HTTPD_CGI_CALL(tcp, "tcp-connections", tcp_stats); +HTTPD_CGI_CALL(net, "net-stats", net_stats); +HTTPD_CGI_CALL(rtos, "rtos-stats", rtos_stats ); +HTTPD_CGI_CALL(run, "run-time", run_time ); +HTTPD_CGI_CALL(io, "led-io", led_io ); + + +static const struct httpd_cgi_call *calls[] = { &file, &tcp, &net, &rtos, &run, &io, NULL }; + +/*---------------------------------------------------------------------------*/ +static +PT_THREAD(nullfunction(struct httpd_state *s, char *ptr)) +{ + PSOCK_BEGIN(&s->sout); + ( void ) ptr; + PSOCK_END(&s->sout); +} +/*---------------------------------------------------------------------------*/ +httpd_cgifunction +httpd_cgi(char *name) +{ + const struct httpd_cgi_call **f; + + /* Find the matching name in the table, return the function. */ + for(f = calls; *f != NULL; ++f) { + if(strncmp((*f)->name, name, strlen((*f)->name)) == 0) { + return (*f)->function; + } + } + return nullfunction; +} +/*---------------------------------------------------------------------------*/ +static unsigned short +generate_file_stats(void *arg) +{ + char *f = (char *)arg; + return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE, "%5u", httpd_fs_count(f)); +} +/*---------------------------------------------------------------------------*/ +static +PT_THREAD(file_stats(struct httpd_state *s, char *ptr)) +{ + PSOCK_BEGIN(&s->sout); + + PSOCK_GENERATOR_SEND(&s->sout, generate_file_stats, strchr(ptr, ' ') + 1); + + PSOCK_END(&s->sout); +} +/*---------------------------------------------------------------------------*/ +static const char closed[] = /* "CLOSED",*/ +{0x43, 0x4c, 0x4f, 0x53, 0x45, 0x44, 0}; +static const char syn_rcvd[] = /* "SYN-RCVD",*/ +{0x53, 0x59, 0x4e, 0x2d, 0x52, 0x43, 0x56, + 0x44, 0}; +static const char syn_sent[] = /* "SYN-SENT",*/ +{0x53, 0x59, 0x4e, 0x2d, 0x53, 0x45, 0x4e, + 0x54, 0}; +static const char established[] = /* "ESTABLISHED",*/ +{0x45, 0x53, 0x54, 0x41, 0x42, 0x4c, 0x49, 0x53, 0x48, + 0x45, 0x44, 0}; +static const char fin_wait_1[] = /* "FIN-WAIT-1",*/ +{0x46, 0x49, 0x4e, 0x2d, 0x57, 0x41, 0x49, + 0x54, 0x2d, 0x31, 0}; +static const char fin_wait_2[] = /* "FIN-WAIT-2",*/ +{0x46, 0x49, 0x4e, 0x2d, 0x57, 0x41, 0x49, + 0x54, 0x2d, 0x32, 0}; +static const char closing[] = /* "CLOSING",*/ +{0x43, 0x4c, 0x4f, 0x53, 0x49, + 0x4e, 0x47, 0}; +static const char time_wait[] = /* "TIME-WAIT,"*/ +{0x54, 0x49, 0x4d, 0x45, 0x2d, 0x57, 0x41, + 0x49, 0x54, 0}; +static const char last_ack[] = /* "LAST-ACK"*/ +{0x4c, 0x41, 0x53, 0x54, 0x2d, 0x41, 0x43, + 0x4b, 0}; + +static const char *states[] = { + closed, + syn_rcvd, + syn_sent, + established, + fin_wait_1, + fin_wait_2, + closing, + time_wait, + last_ack}; + + +static unsigned short +generate_tcp_stats(void *arg) +{ + struct uip_conn *conn; + struct httpd_state *s = (struct httpd_state *)arg; + + conn = &uip_conns[s->count]; + return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE, + "%d%u.%u.%u.%u:%u%s%u%u%c %c\r\n", + htons(conn->lport), + htons(conn->ripaddr[0]) >> 8, + htons(conn->ripaddr[0]) & 0xff, + htons(conn->ripaddr[1]) >> 8, + htons(conn->ripaddr[1]) & 0xff, + htons(conn->rport), + states[conn->tcpstateflags & UIP_TS_MASK], + conn->nrtx, + conn->timer, + (uip_outstanding(conn))? '*':' ', + (uip_stopped(conn))? '!':' '); +} +/*---------------------------------------------------------------------------*/ +static +PT_THREAD(tcp_stats(struct httpd_state *s, char *ptr)) +{ + + PSOCK_BEGIN(&s->sout); + ( void ) ptr; + for(s->count = 0; s->count < UIP_CONNS; ++s->count) { + if((uip_conns[s->count].tcpstateflags & UIP_TS_MASK) != UIP_CLOSED) { + PSOCK_GENERATOR_SEND(&s->sout, generate_tcp_stats, s); + } + } + + PSOCK_END(&s->sout); +} +/*---------------------------------------------------------------------------*/ +static unsigned short +generate_net_stats(void *arg) +{ + struct httpd_state *s = (struct httpd_state *)arg; + return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE, + "%5u\n", ((uip_stats_t *)&uip_stat)[s->count]); +} + +static +PT_THREAD(net_stats(struct httpd_state *s, char *ptr)) +{ + PSOCK_BEGIN(&s->sout); + + ( void ) ptr; +#if UIP_STATISTICS + + for(s->count = 0; s->count < sizeof(uip_stat) / sizeof(uip_stats_t); + ++s->count) { + PSOCK_GENERATOR_SEND(&s->sout, generate_net_stats, s); + } + +#endif /* UIP_STATISTICS */ + + PSOCK_END(&s->sout); +} +/*---------------------------------------------------------------------------*/ + +extern void vTaskList( signed char *pcWriteBuffer ); +static char cCountBuf[ 32 ]; +long lRefreshCount = 0; +static unsigned short +generate_rtos_stats(void *arg) +{ + ( void ) arg; + lRefreshCount++; + sprintf( cCountBuf, "


Refresh count = %d", (int)lRefreshCount ); + vTaskList( uip_appdata ); + strcat( uip_appdata, cCountBuf ); + + return strlen( uip_appdata ); +} +/*---------------------------------------------------------------------------*/ + + +static +PT_THREAD(rtos_stats(struct httpd_state *s, char *ptr)) +{ + PSOCK_BEGIN(&s->sout); + ( void ) ptr; + PSOCK_GENERATOR_SEND(&s->sout, generate_rtos_stats, NULL); + PSOCK_END(&s->sout); +} +/*---------------------------------------------------------------------------*/ + +char *pcStatus; +unsigned long ulString; + +static unsigned short generate_io_state( void *arg ) +{ +extern long lParTestGetLEDState( unsigned long ulLED ); + + ( void ) arg; + + if( lParTestGetLEDState( 1 << 7 ) == 0 ) + { + pcStatus = ""; + } + else + { + pcStatus = "checked"; + } + + sprintf( uip_appdata, + "LED 7"\ + "

"\ + "", + pcStatus ); + + return strlen( uip_appdata ); +} +/*---------------------------------------------------------------------------*/ + +extern void vTaskGetRunTimeStats( signed char *pcWriteBuffer ); +static unsigned short +generate_runtime_stats(void *arg) +{ + ( void ) arg; + lRefreshCount++; + sprintf( cCountBuf, "


Refresh count = %d", (int)lRefreshCount ); + vTaskGetRunTimeStats( uip_appdata ); + strcat( uip_appdata, cCountBuf ); + + return strlen( uip_appdata ); +} +/*---------------------------------------------------------------------------*/ + + +static +PT_THREAD(run_time(struct httpd_state *s, char *ptr)) +{ + PSOCK_BEGIN(&s->sout); + ( void ) ptr; + PSOCK_GENERATOR_SEND(&s->sout, generate_runtime_stats, NULL); + PSOCK_END(&s->sout); +} +/*---------------------------------------------------------------------------*/ + + +static PT_THREAD(led_io(struct httpd_state *s, char *ptr)) +{ + PSOCK_BEGIN(&s->sout); + ( void ) ptr; + PSOCK_GENERATOR_SEND(&s->sout, generate_io_state, NULL); + PSOCK_END(&s->sout); +} + +/** @} */ + + + + + + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-cgi.h b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-cgi.h new file mode 100644 index 000000000..7ae928321 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-cgi.h @@ -0,0 +1,84 @@ +/** + * \addtogroup httpd + * @{ + */ + +/** + * \file + * Web server script interface header file + * \author + * Adam Dunkels + * + */ + + + +/* + * Copyright (c) 2001, Adam Dunkels. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. The name of the author may not be used to endorse or promote + * products derived from this software without specific prior + * written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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. + * + * This file is part of the uIP TCP/IP stack. + * + * $Id: httpd-cgi.h,v 1.2 2006/06/11 21:46:38 adam Exp $ + * + */ + +#ifndef __HTTPD_CGI_H__ +#define __HTTPD_CGI_H__ + +#include "psock.h" +#include "httpd.h" + +typedef PT_THREAD((* httpd_cgifunction)(struct httpd_state *, char *)); + +httpd_cgifunction httpd_cgi(char *name); + +struct httpd_cgi_call { + const char *name; + const httpd_cgifunction function; +}; + +/** + * \brief HTTPD CGI function declaration + * \param name The C variable name of the function + * \param str The string name of the function, used in the script file + * \param function A pointer to the function that implements it + * + * This macro is used for declaring a HTTPD CGI + * function. This function is then added to the list of + * HTTPD CGI functions with the httpd_cgi_add() function. + * + * \hideinitializer + */ +#define HTTPD_CGI_CALL(name, str, function) \ +static PT_THREAD(function(struct httpd_state *, char *)); \ +static const struct httpd_cgi_call name = {str, function} + +void httpd_cgi_init(void); +#endif /* __HTTPD_CGI_H__ */ + +/** @} */ diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs.c b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs.c new file mode 100644 index 000000000..dc4aef011 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs.c @@ -0,0 +1,132 @@ +/* + * Copyright (c) 2001, Swedish Institute of Computer Science. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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. + * + * This file is part of the lwIP TCP/IP stack. + * + * Author: Adam Dunkels + * + * $Id: httpd-fs.c,v 1.1 2006/06/07 09:13:08 adam Exp $ + */ + +#include "httpd.h" +#include "httpd-fs.h" +#include "httpd-fsdata.h" + +#ifndef NULL +#define NULL 0 +#endif /* NULL */ + +#include "httpd-fsdata.c" + +#if HTTPD_FS_STATISTICS +static u16_t count[HTTPD_FS_NUMFILES]; +#endif /* HTTPD_FS_STATISTICS */ + +/*-----------------------------------------------------------------------------------*/ +static u8_t +httpd_fs_strcmp(const char *str1, const char *str2) +{ + u8_t i; + i = 0; + loop: + + if(str2[i] == 0 || + str1[i] == '\r' || + str1[i] == '\n') { + return 0; + } + + if(str1[i] != str2[i]) { + return 1; + } + + + ++i; + goto loop; +} +/*-----------------------------------------------------------------------------------*/ +int +httpd_fs_open(const char *name, struct httpd_fs_file *file) +{ +#if HTTPD_FS_STATISTICS + u16_t i = 0; +#endif /* HTTPD_FS_STATISTICS */ + struct httpd_fsdata_file_noconst *f; + + for(f = (struct httpd_fsdata_file_noconst *)HTTPD_FS_ROOT; + f != NULL; + f = (struct httpd_fsdata_file_noconst *)f->next) { + + if(httpd_fs_strcmp(name, f->name) == 0) { + file->data = f->data; + file->len = f->len; +#if HTTPD_FS_STATISTICS + ++count[i]; +#endif /* HTTPD_FS_STATISTICS */ + return 1; + } +#if HTTPD_FS_STATISTICS + ++i; +#endif /* HTTPD_FS_STATISTICS */ + + } + return 0; +} +/*-----------------------------------------------------------------------------------*/ +void +httpd_fs_init(void) +{ +#if HTTPD_FS_STATISTICS + u16_t i; + for(i = 0; i < HTTPD_FS_NUMFILES; i++) { + count[i] = 0; + } +#endif /* HTTPD_FS_STATISTICS */ +} +/*-----------------------------------------------------------------------------------*/ +#if HTTPD_FS_STATISTICS +u16_t httpd_fs_count +(char *name) +{ + struct httpd_fsdata_file_noconst *f; + u16_t i; + + i = 0; + for(f = (struct httpd_fsdata_file_noconst *)HTTPD_FS_ROOT; + f != NULL; + f = (struct httpd_fsdata_file_noconst *)f->next) { + + if(httpd_fs_strcmp(name, f->name) == 0) { + return count[i]; + } + ++i; + } + return 0; +} +#endif /* HTTPD_FS_STATISTICS */ +/*-----------------------------------------------------------------------------------*/ diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs.h b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs.h new file mode 100644 index 000000000..b594eea56 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs.h @@ -0,0 +1,57 @@ +/* + * Copyright (c) 2001, Swedish Institute of Computer Science. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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. + * + * This file is part of the lwIP TCP/IP stack. + * + * Author: Adam Dunkels + * + * $Id: httpd-fs.h,v 1.1 2006/06/07 09:13:08 adam Exp $ + */ +#ifndef __HTTPD_FS_H__ +#define __HTTPD_FS_H__ + +#define HTTPD_FS_STATISTICS 1 + +struct httpd_fs_file { + char *data; + int len; +}; + +/* file must be allocated by caller and will be filled in + by the function. */ +int httpd_fs_open(const char *name, struct httpd_fs_file *file); + +#ifdef HTTPD_FS_STATISTICS +#if HTTPD_FS_STATISTICS == 1 +u16_t httpd_fs_count(char *name); +#endif /* HTTPD_FS_STATISTICS */ +#endif /* HTTPD_FS_STATISTICS */ + +void httpd_fs_init(void); + +#endif /* __HTTPD_FS_H__ */ diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/404.html b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/404.html new file mode 100644 index 000000000..43e7f4cad --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/404.html @@ -0,0 +1,8 @@ + + +

+

404 - file not found

+

Go here instead.

+
+ + \ No newline at end of file diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/index.html b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/index.html new file mode 100644 index 000000000..4937dc69a --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/index.html @@ -0,0 +1,13 @@ + + + + FreeRTOS.org uIP WEB server demo + + + +Loading index.shtml. Click here if not automatically redirected. + + + + + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/index.shtml b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/index.shtml new file mode 100644 index 000000000..29d242c05 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/index.shtml @@ -0,0 +1,20 @@ + + + + FreeRTOS.org uIP WEB server demo + + + +Task Stats | Run Time Stats | TCP Stats | Connections | FreeRTOS.org Homepage | IO +

+


+

+

Task statistics

+Page will refresh every 2 seconds.

+

Task          State  Priority  Stack	#
************************************************
+%! rtos-stats +
+
+ + + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/io.shtml b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/io.shtml new file mode 100644 index 000000000..fd0697d2a --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/io.shtml @@ -0,0 +1,28 @@ + + + + FreeRTOS.org uIP WEB server demo + + + +Task Stats | Run Time Stats | TCP Stats | Connections | FreeRTOS.org Homepage | IO +

+


+LED and LCD IO
+ +

+ +Use the check box to turn on or off the LED, enter text to display on the OLED display, then click "Update IO". + + +

+

+%! led-io +

+ +

+

+ + + + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/runtime.shtml b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/runtime.shtml new file mode 100644 index 000000000..67cae4657 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/runtime.shtml @@ -0,0 +1,20 @@ + + + + FreeRTOS.org uIP WEB server demo + + + +Task Stats | Run Time Stats | TCP Stats | Connections | FreeRTOS.org Homepage | IO +

+


+

+

Run-time statistics

+Page will refresh every 2 seconds.

+

Task            Abs Time      % Time
****************************************
+%! run-time +
+
+ + + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/stats.shtml b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/stats.shtml new file mode 100644 index 000000000..d95a69340 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/stats.shtml @@ -0,0 +1,41 @@ + + + + FreeRTOS.org uIP WEB server demo + + + +Task Stats | Run Time Stats | TCP Stats | Connections | FreeRTOS.org Homepage | IO +

+


+

+

Network statistics

+ +
+IP           Packets dropped
+             Packets received
+             Packets sent
+IP errors    IP version/header length
+             IP length, high byte
+             IP length, low byte
+             IP fragments
+             Header checksum
+             Wrong protocol
+ICMP	     Packets dropped
+             Packets received
+             Packets sent
+             Type errors
+TCP          Packets dropped
+             Packets received
+             Packets sent
+             Checksum errors
+             Data packets without ACKs
+             Resets
+             Retransmissions
+	     No connection avaliable
+	     Connection attempts to closed ports
+
%! net-stats
+
+
+ + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/tcp.shtml b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/tcp.shtml new file mode 100644 index 000000000..41053679d --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fs/tcp.shtml @@ -0,0 +1,21 @@ + + + + FreeRTOS.org uIP WEB server demo + + + +Task Stats | Run Time Stats | TCP Stats | Connections | FreeRTOS.org Homepage | IO +

+


+
+

Network connections

+

+ + +%! tcp-connections + + + + + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fsdata.c b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fsdata.c new file mode 100644 index 000000000..c8b2a8026 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fsdata.c @@ -0,0 +1,557 @@ +static const char data_404_html[] = { + /* /404.html */ + 0x2f, 0x34, 0x30, 0x34, 0x2e, 0x68, 0x74, 0x6d, 0x6c, 0, + 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, 0x20, 0x20, 0x3c, + 0x62, 0x6f, 0x64, 0x79, 0x20, 0x62, 0x67, 0x63, 0x6f, 0x6c, + 0x6f, 0x72, 0x3d, 0x22, 0x77, 0x68, 0x69, 0x74, 0x65, 0x22, + 0x3e, 0xa, 0x20, 0x20, 0x20, 0x20, 0x3c, 0x63, 0x65, 0x6e, + 0x74, 0x65, 0x72, 0x3e, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x3c, 0x68, 0x31, 0x3e, 0x34, 0x30, 0x34, 0x20, 0x2d, + 0x20, 0x66, 0x69, 0x6c, 0x65, 0x20, 0x6e, 0x6f, 0x74, 0x20, + 0x66, 0x6f, 0x75, 0x6e, 0x64, 0x3c, 0x2f, 0x68, 0x31, 0x3e, + 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x3c, 0x68, 0x33, + 0x3e, 0x47, 0x6f, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, + 0x66, 0x3d, 0x22, 0x2f, 0x22, 0x3e, 0x68, 0x65, 0x72, 0x65, + 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x69, 0x6e, 0x73, 0x74, 0x65, + 0x61, 0x64, 0x2e, 0x3c, 0x2f, 0x68, 0x33, 0x3e, 0xa, 0x20, + 0x20, 0x20, 0x20, 0x3c, 0x2f, 0x63, 0x65, 0x6e, 0x74, 0x65, + 0x72, 0x3e, 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x62, 0x6f, 0x64, + 0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x3e, +0}; + +static const char data_index_html[] = { + /* /index.html */ + 0x2f, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x68, 0x74, 0x6d, 0x6c, 0, + 0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20, + 0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49, + 0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f, + 0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20, + 0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73, + 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45, + 0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, + 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72, + 0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34, + 0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64, + 0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, + 0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20, + 0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, + 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, + 0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42, + 0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65, + 0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, + 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e, + 0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x20, 0x6f, + 0x6e, 0x4c, 0x6f, 0x61, 0x64, 0x3d, 0x22, 0x77, 0x69, 0x6e, + 0x64, 0x6f, 0x77, 0x2e, 0x73, 0x65, 0x74, 0x54, 0x69, 0x6d, + 0x65, 0x6f, 0x75, 0x74, 0x28, 0x26, 0x71, 0x75, 0x6f, 0x74, + 0x3b, 0x6c, 0x6f, 0x63, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x2e, + 0x68, 0x72, 0x65, 0x66, 0x3d, 0x27, 0x69, 0x6e, 0x64, 0x65, + 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x27, 0x26, 0x71, + 0x75, 0x6f, 0x74, 0x3b, 0x2c, 0x31, 0x30, 0x30, 0x29, 0x22, + 0x3e, 0xa, 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61, + 0x63, 0x65, 0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c, 0x22, + 0x3e, 0xa, 0x4c, 0x6f, 0x61, 0x64, 0x69, 0x6e, 0x67, 0x20, + 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, + 0x6c, 0x2e, 0x20, 0x20, 0x43, 0x6c, 0x69, 0x63, 0x6b, 0x20, + 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, + 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, + 0x22, 0x3e, 0x68, 0x65, 0x72, 0x65, 0x3c, 0x2f, 0x61, 0x3e, + 0x20, 0x69, 0x66, 0x20, 0x6e, 0x6f, 0x74, 0x20, 0x61, 0x75, + 0x74, 0x6f, 0x6d, 0x61, 0x74, 0x69, 0x63, 0x61, 0x6c, 0x6c, + 0x79, 0x20, 0x72, 0x65, 0x64, 0x69, 0x72, 0x65, 0x63, 0x74, + 0x65, 0x64, 0x2e, 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, + 0x3e, 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, + 0x3c, 0x2f, 0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f, + 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, 0xa, 0}; + +static const char data_index_shtml[] = { + /* /index.shtml */ + 0x2f, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0, + 0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20, + 0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49, + 0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f, + 0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20, + 0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73, + 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45, + 0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, + 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72, + 0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34, + 0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64, + 0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, + 0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20, + 0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, + 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, + 0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42, + 0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65, + 0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, + 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e, + 0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x20, 0x6f, + 0x6e, 0x4c, 0x6f, 0x61, 0x64, 0x3d, 0x22, 0x77, 0x69, 0x6e, + 0x64, 0x6f, 0x77, 0x2e, 0x73, 0x65, 0x74, 0x54, 0x69, 0x6d, + 0x65, 0x6f, 0x75, 0x74, 0x28, 0x26, 0x71, 0x75, 0x6f, 0x74, + 0x3b, 0x6c, 0x6f, 0x63, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x2e, + 0x68, 0x72, 0x65, 0x66, 0x3d, 0x27, 0x69, 0x6e, 0x64, 0x65, + 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x27, 0x26, 0x71, + 0x75, 0x6f, 0x74, 0x3b, 0x2c, 0x32, 0x30, 0x30, 0x30, 0x29, + 0x22, 0x3e, 0xa, 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, + 0x61, 0x63, 0x65, 0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c, + 0x22, 0x3e, 0xa, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, + 0x3d, 0x22, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, + 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, + 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, + 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, + 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x72, 0x75, + 0x6e, 0x74, 0x69, 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, + 0x6c, 0x22, 0x3e, 0x52, 0x75, 0x6e, 0x20, 0x54, 0x69, 0x6d, + 0x65, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, + 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, + 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, + 0x73, 0x74, 0x61, 0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d, + 0x6c, 0x22, 0x3e, 0x54, 0x43, 0x50, 0x20, 0x53, 0x74, 0x61, + 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, + 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, + 0x72, 0x65, 0x66, 0x3d, 0x22, 0x74, 0x63, 0x70, 0x2e, 0x73, + 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x43, 0x6f, 0x6e, 0x6e, + 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x61, + 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, + 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, + 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, + 0x2e, 0x66, 0x72, 0x65, 0x65, 0x72, 0x74, 0x6f, 0x73, 0x2e, + 0x6f, 0x72, 0x67, 0x2f, 0x22, 0x3e, 0x46, 0x72, 0x65, 0x65, + 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, 0x72, 0x67, 0x20, 0x48, + 0x6f, 0x6d, 0x65, 0x70, 0x61, 0x67, 0x65, 0x3c, 0x2f, 0x61, + 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, + 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, + 0x69, 0x6f, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, + 0x49, 0x4f, 0x3c, 0x2f, 0x61, 0x3e, 0xa, 0x3c, 0x62, 0x72, + 0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x68, 0x72, 0x3e, 0xa, + 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x68, + 0x32, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x73, 0x74, 0x61, + 0x74, 0x69, 0x73, 0x74, 0x69, 0x63, 0x73, 0x3c, 0x2f, 0x68, + 0x32, 0x3e, 0xa, 0x50, 0x61, 0x67, 0x65, 0x20, 0x77, 0x69, + 0x6c, 0x6c, 0x20, 0x72, 0x65, 0x66, 0x72, 0x65, 0x73, 0x68, + 0x20, 0x65, 0x76, 0x65, 0x72, 0x79, 0x20, 0x32, 0x20, 0x73, + 0x65, 0x63, 0x6f, 0x6e, 0x64, 0x73, 0x2e, 0x3c, 0x70, 0x3e, + 0xa, 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61, 0x63, + 0x65, 0x3d, 0x22, 0x63, 0x6f, 0x75, 0x72, 0x69, 0x65, 0x72, + 0x22, 0x3e, 0x3c, 0x70, 0x72, 0x65, 0x3e, 0x54, 0x61, 0x73, + 0x6b, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x53, 0x74, 0x61, 0x74, 0x65, 0x20, 0x20, 0x50, 0x72, + 0x69, 0x6f, 0x72, 0x69, 0x74, 0x79, 0x20, 0x20, 0x53, 0x74, + 0x61, 0x63, 0x6b, 0x9, 0x23, 0x3c, 0x62, 0x72, 0x3e, 0x2a, + 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, + 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, + 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, + 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, + 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x3c, 0x62, 0x72, + 0x3e, 0xa, 0x25, 0x21, 0x20, 0x72, 0x74, 0x6f, 0x73, 0x2d, + 0x73, 0x74, 0x61, 0x74, 0x73, 0xa, 0x3c, 0x2f, 0x70, 0x72, + 0x65, 0x3e, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, + 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, 0x3c, 0x2f, + 0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68, 0x74, + 0x6d, 0x6c, 0x3e, 0xa, 0xa, 0}; + +static const char data_io_shtml[] = { + /* /io.shtml */ + 0x2f, 0x69, 0x6f, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0, + 0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20, + 0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49, + 0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f, + 0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20, + 0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73, + 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45, + 0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, + 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72, + 0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34, + 0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64, + 0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, + 0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20, + 0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, + 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, + 0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42, + 0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65, + 0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, + 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e, + 0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x3e, 0xa, + 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61, 0x63, 0x65, + 0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c, 0x22, 0x3e, 0xa, + 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, + 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, + 0x22, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x53, 0x74, 0x61, + 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, + 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, + 0x72, 0x65, 0x66, 0x3d, 0x22, 0x72, 0x75, 0x6e, 0x74, 0x69, + 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, + 0x52, 0x75, 0x6e, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x20, 0x53, + 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, + 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, + 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x73, 0x74, 0x61, + 0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, + 0x54, 0x43, 0x50, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, + 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, + 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, + 0x3d, 0x22, 0x74, 0x63, 0x70, 0x2e, 0x73, 0x68, 0x74, 0x6d, + 0x6c, 0x22, 0x3e, 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, + 0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, + 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, + 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x68, 0x74, 0x74, + 0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x66, 0x72, + 0x65, 0x65, 0x72, 0x74, 0x6f, 0x73, 0x2e, 0x6f, 0x72, 0x67, + 0x2f, 0x22, 0x3e, 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, + 0x53, 0x2e, 0x6f, 0x72, 0x67, 0x20, 0x48, 0x6f, 0x6d, 0x65, + 0x70, 0x61, 0x67, 0x65, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, + 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, + 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, 0x6f, 0x2e, + 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x49, 0x4f, 0x3c, + 0x2f, 0x61, 0x3e, 0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, + 0x3e, 0xa, 0x3c, 0x68, 0x72, 0x3e, 0xa, 0x3c, 0x62, 0x3e, + 0x4c, 0x45, 0x44, 0x20, 0x61, 0x6e, 0x64, 0x20, 0x4c, 0x43, + 0x44, 0x20, 0x49, 0x4f, 0x3c, 0x2f, 0x62, 0x3e, 0x3c, 0x62, + 0x72, 0x3e, 0xa, 0xa, 0x3c, 0x70, 0x3e, 0xa, 0xa, 0x55, + 0x73, 0x65, 0x20, 0x74, 0x68, 0x65, 0x20, 0x63, 0x68, 0x65, + 0x63, 0x6b, 0x20, 0x62, 0x6f, 0x78, 0x20, 0x74, 0x6f, 0x20, + 0x74, 0x75, 0x72, 0x6e, 0x20, 0x6f, 0x6e, 0x20, 0x6f, 0x72, + 0x20, 0x6f, 0x66, 0x66, 0x20, 0x74, 0x68, 0x65, 0x20, 0x4c, + 0x45, 0x44, 0x2c, 0x20, 0x65, 0x6e, 0x74, 0x65, 0x72, 0x20, + 0x74, 0x65, 0x78, 0x74, 0x20, 0x74, 0x6f, 0x20, 0x64, 0x69, + 0x73, 0x70, 0x6c, 0x61, 0x79, 0x20, 0x6f, 0x6e, 0x20, 0x74, + 0x68, 0x65, 0x20, 0x4f, 0x4c, 0x45, 0x44, 0x20, 0x64, 0x69, + 0x73, 0x70, 0x6c, 0x61, 0x79, 0x2c, 0x20, 0x74, 0x68, 0x65, + 0x6e, 0x20, 0x63, 0x6c, 0x69, 0x63, 0x6b, 0x20, 0x22, 0x55, + 0x70, 0x64, 0x61, 0x74, 0x65, 0x20, 0x49, 0x4f, 0x22, 0x2e, + 0xa, 0xa, 0xa, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x66, 0x6f, + 0x72, 0x6d, 0x20, 0x6e, 0x61, 0x6d, 0x65, 0x3d, 0x22, 0x61, + 0x46, 0x6f, 0x72, 0x6d, 0x22, 0x20, 0x61, 0x63, 0x74, 0x69, + 0x6f, 0x6e, 0x3d, 0x22, 0x2f, 0x69, 0x6f, 0x2e, 0x73, 0x68, + 0x74, 0x6d, 0x6c, 0x22, 0x20, 0x6d, 0x65, 0x74, 0x68, 0x6f, + 0x64, 0x3d, 0x22, 0x67, 0x65, 0x74, 0x22, 0x3e, 0xa, 0x25, + 0x21, 0x20, 0x6c, 0x65, 0x64, 0x2d, 0x69, 0x6f, 0xa, 0x3c, + 0x70, 0x3e, 0xa, 0x3c, 0x69, 0x6e, 0x70, 0x75, 0x74, 0x20, + 0x74, 0x79, 0x70, 0x65, 0x3d, 0x22, 0x73, 0x75, 0x62, 0x6d, + 0x69, 0x74, 0x22, 0x20, 0x76, 0x61, 0x6c, 0x75, 0x65, 0x3d, + 0x22, 0x55, 0x70, 0x64, 0x61, 0x74, 0x65, 0x20, 0x49, 0x4f, + 0x22, 0x3e, 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x72, 0x6d, 0x3e, + 0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, + 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, 0x3c, 0x2f, 0x62, + 0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68, 0x74, 0x6d, + 0x6c, 0x3e, 0xa, 0xa, 0}; + +static const char data_runtime_shtml[] = { + /* /runtime.shtml */ + 0x2f, 0x72, 0x75, 0x6e, 0x74, 0x69, 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0, + 0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20, + 0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49, + 0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f, + 0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20, + 0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73, + 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45, + 0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, + 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72, + 0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34, + 0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64, + 0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, + 0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20, + 0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, + 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, + 0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42, + 0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65, + 0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, + 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e, + 0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x20, 0x6f, + 0x6e, 0x4c, 0x6f, 0x61, 0x64, 0x3d, 0x22, 0x77, 0x69, 0x6e, + 0x64, 0x6f, 0x77, 0x2e, 0x73, 0x65, 0x74, 0x54, 0x69, 0x6d, + 0x65, 0x6f, 0x75, 0x74, 0x28, 0x26, 0x71, 0x75, 0x6f, 0x74, + 0x3b, 0x6c, 0x6f, 0x63, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x2e, + 0x68, 0x72, 0x65, 0x66, 0x3d, 0x27, 0x72, 0x75, 0x6e, 0x74, + 0x69, 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x27, + 0x26, 0x71, 0x75, 0x6f, 0x74, 0x3b, 0x2c, 0x32, 0x30, 0x30, + 0x30, 0x29, 0x22, 0x3e, 0xa, 0x3c, 0x66, 0x6f, 0x6e, 0x74, + 0x20, 0x66, 0x61, 0x63, 0x65, 0x3d, 0x22, 0x61, 0x72, 0x69, + 0x61, 0x6c, 0x22, 0x3e, 0xa, 0x3c, 0x61, 0x20, 0x68, 0x72, + 0x65, 0x66, 0x3d, 0x22, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, + 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x54, 0x61, 0x73, + 0x6b, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, + 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, + 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, + 0x72, 0x75, 0x6e, 0x74, 0x69, 0x6d, 0x65, 0x2e, 0x73, 0x68, + 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x52, 0x75, 0x6e, 0x20, 0x54, + 0x69, 0x6d, 0x65, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, + 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, + 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, + 0x3d, 0x22, 0x73, 0x74, 0x61, 0x74, 0x73, 0x2e, 0x73, 0x68, + 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x54, 0x43, 0x50, 0x20, 0x53, + 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, + 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, + 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x74, 0x63, 0x70, + 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x43, 0x6f, + 0x6e, 0x6e, 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x73, 0x3c, + 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, + 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, + 0x3d, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, 0x2f, 0x77, + 0x77, 0x77, 0x2e, 0x66, 0x72, 0x65, 0x65, 0x72, 0x74, 0x6f, + 0x73, 0x2e, 0x6f, 0x72, 0x67, 0x2f, 0x22, 0x3e, 0x46, 0x72, + 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, 0x72, 0x67, + 0x20, 0x48, 0x6f, 0x6d, 0x65, 0x70, 0x61, 0x67, 0x65, 0x3c, + 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, + 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, + 0x3d, 0x22, 0x69, 0x6f, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, + 0x22, 0x3e, 0x49, 0x4f, 0x3c, 0x2f, 0x61, 0x3e, 0xa, 0x3c, + 0x62, 0x72, 0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x68, 0x72, + 0x3e, 0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, 0x3e, 0xa, + 0x3c, 0x68, 0x32, 0x3e, 0x52, 0x75, 0x6e, 0x2d, 0x74, 0x69, + 0x6d, 0x65, 0x20, 0x73, 0x74, 0x61, 0x74, 0x69, 0x73, 0x74, + 0x69, 0x63, 0x73, 0x3c, 0x2f, 0x68, 0x32, 0x3e, 0xa, 0x50, + 0x61, 0x67, 0x65, 0x20, 0x77, 0x69, 0x6c, 0x6c, 0x20, 0x72, + 0x65, 0x66, 0x72, 0x65, 0x73, 0x68, 0x20, 0x65, 0x76, 0x65, + 0x72, 0x79, 0x20, 0x32, 0x20, 0x73, 0x65, 0x63, 0x6f, 0x6e, + 0x64, 0x73, 0x2e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x66, 0x6f, + 0x6e, 0x74, 0x20, 0x66, 0x61, 0x63, 0x65, 0x3d, 0x22, 0x63, + 0x6f, 0x75, 0x72, 0x69, 0x65, 0x72, 0x22, 0x3e, 0x3c, 0x70, + 0x72, 0x65, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x41, + 0x62, 0x73, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x25, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x3c, + 0x62, 0x72, 0x3e, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, + 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, + 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, + 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, + 0x2a, 0x2a, 0x2a, 0x3c, 0x62, 0x72, 0x3e, 0xa, 0x25, 0x21, + 0x20, 0x72, 0x75, 0x6e, 0x2d, 0x74, 0x69, 0x6d, 0x65, 0xa, + 0x3c, 0x2f, 0x70, 0x72, 0x65, 0x3e, 0x3c, 0x2f, 0x66, 0x6f, + 0x6e, 0x74, 0x3e, 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, + 0x3e, 0xa, 0x3c, 0x2f, 0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa, + 0x3c, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, 0xa, 0}; + +static const char data_stats_shtml[] = { + /* /stats.shtml */ + 0x2f, 0x73, 0x74, 0x61, 0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0, + 0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20, + 0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49, + 0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f, + 0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20, + 0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73, + 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45, + 0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, + 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72, + 0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34, + 0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64, + 0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, + 0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20, + 0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, + 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, + 0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42, + 0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65, + 0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, + 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e, + 0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x3e, 0xa, + 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61, 0x63, 0x65, + 0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c, 0x22, 0x3e, 0xa, + 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, + 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, + 0x22, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x53, 0x74, 0x61, + 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, + 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, + 0x72, 0x65, 0x66, 0x3d, 0x22, 0x72, 0x75, 0x6e, 0x74, 0x69, + 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, + 0x52, 0x75, 0x6e, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x20, 0x53, + 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, + 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, + 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x73, 0x74, 0x61, + 0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, + 0x54, 0x43, 0x50, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, + 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, + 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, + 0x3d, 0x22, 0x74, 0x63, 0x70, 0x2e, 0x73, 0x68, 0x74, 0x6d, + 0x6c, 0x22, 0x3e, 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, + 0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, + 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, + 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x68, 0x74, 0x74, + 0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x66, 0x72, + 0x65, 0x65, 0x72, 0x74, 0x6f, 0x73, 0x2e, 0x6f, 0x72, 0x67, + 0x2f, 0x22, 0x3e, 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, + 0x53, 0x2e, 0x6f, 0x72, 0x67, 0x20, 0x48, 0x6f, 0x6d, 0x65, + 0x70, 0x61, 0x67, 0x65, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, + 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, + 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, 0x6f, 0x2e, + 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x49, 0x4f, 0x3c, + 0x2f, 0x61, 0x3e, 0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, + 0x3e, 0xa, 0x3c, 0x68, 0x72, 0x3e, 0xa, 0x3c, 0x62, 0x72, + 0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x68, 0x32, 0x3e, 0x4e, + 0x65, 0x74, 0x77, 0x6f, 0x72, 0x6b, 0x20, 0x73, 0x74, 0x61, + 0x74, 0x69, 0x73, 0x74, 0x69, 0x63, 0x73, 0x3c, 0x2f, 0x68, + 0x32, 0x3e, 0xa, 0x3c, 0x74, 0x61, 0x62, 0x6c, 0x65, 0x20, + 0x77, 0x69, 0x64, 0x74, 0x68, 0x3d, 0x22, 0x33, 0x30, 0x30, + 0x22, 0x20, 0x62, 0x6f, 0x72, 0x64, 0x65, 0x72, 0x3d, 0x22, + 0x30, 0x22, 0x3e, 0xa, 0x3c, 0x74, 0x72, 0x3e, 0x3c, 0x74, + 0x64, 0x20, 0x61, 0x6c, 0x69, 0x67, 0x6e, 0x3d, 0x22, 0x6c, + 0x65, 0x66, 0x74, 0x22, 0x3e, 0x3c, 0x66, 0x6f, 0x6e, 0x74, + 0x20, 0x66, 0x61, 0x63, 0x65, 0x3d, 0x22, 0x63, 0x6f, 0x75, + 0x72, 0x69, 0x65, 0x72, 0x22, 0x3e, 0x3c, 0x70, 0x72, 0x65, + 0x3e, 0xa, 0x49, 0x50, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, + 0x74, 0x73, 0x20, 0x64, 0x72, 0x6f, 0x70, 0x70, 0x65, 0x64, + 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74, + 0x73, 0x20, 0x72, 0x65, 0x63, 0x65, 0x69, 0x76, 0x65, 0x64, + 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74, + 0x73, 0x20, 0x73, 0x65, 0x6e, 0x74, 0xa, 0x49, 0x50, 0x20, + 0x65, 0x72, 0x72, 0x6f, 0x72, 0x73, 0x20, 0x20, 0x20, 0x20, + 0x49, 0x50, 0x20, 0x76, 0x65, 0x72, 0x73, 0x69, 0x6f, 0x6e, + 0x2f, 0x68, 0x65, 0x61, 0x64, 0x65, 0x72, 0x20, 0x6c, 0x65, + 0x6e, 0x67, 0x74, 0x68, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x49, 0x50, + 0x20, 0x6c, 0x65, 0x6e, 0x67, 0x74, 0x68, 0x2c, 0x20, 0x68, + 0x69, 0x67, 0x68, 0x20, 0x62, 0x79, 0x74, 0x65, 0xa, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x49, 0x50, 0x20, 0x6c, 0x65, 0x6e, 0x67, 0x74, + 0x68, 0x2c, 0x20, 0x6c, 0x6f, 0x77, 0x20, 0x62, 0x79, 0x74, + 0x65, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x20, 0x49, 0x50, 0x20, 0x66, 0x72, + 0x61, 0x67, 0x6d, 0x65, 0x6e, 0x74, 0x73, 0xa, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x48, 0x65, 0x61, 0x64, 0x65, 0x72, 0x20, 0x63, 0x68, + 0x65, 0x63, 0x6b, 0x73, 0x75, 0x6d, 0xa, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x57, 0x72, 0x6f, 0x6e, 0x67, 0x20, 0x70, 0x72, 0x6f, 0x74, + 0x6f, 0x63, 0x6f, 0x6c, 0xa, 0x49, 0x43, 0x4d, 0x50, 0x9, + 0x20, 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, + 0x74, 0x73, 0x20, 0x64, 0x72, 0x6f, 0x70, 0x70, 0x65, 0x64, + 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74, + 0x73, 0x20, 0x72, 0x65, 0x63, 0x65, 0x69, 0x76, 0x65, 0x64, + 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74, + 0x73, 0x20, 0x73, 0x65, 0x6e, 0x74, 0xa, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x54, 0x79, 0x70, 0x65, 0x20, 0x65, 0x72, 0x72, 0x6f, 0x72, + 0x73, 0xa, 0x54, 0x43, 0x50, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, + 0x74, 0x73, 0x20, 0x64, 0x72, 0x6f, 0x70, 0x70, 0x65, 0x64, + 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74, + 0x73, 0x20, 0x72, 0x65, 0x63, 0x65, 0x69, 0x76, 0x65, 0x64, + 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74, + 0x73, 0x20, 0x73, 0x65, 0x6e, 0x74, 0xa, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x43, 0x68, 0x65, 0x63, 0x6b, 0x73, 0x75, 0x6d, 0x20, 0x65, + 0x72, 0x72, 0x6f, 0x72, 0x73, 0xa, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x44, + 0x61, 0x74, 0x61, 0x20, 0x70, 0x61, 0x63, 0x6b, 0x65, 0x74, + 0x73, 0x20, 0x77, 0x69, 0x74, 0x68, 0x6f, 0x75, 0x74, 0x20, + 0x41, 0x43, 0x4b, 0x73, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x52, 0x65, + 0x73, 0x65, 0x74, 0x73, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x52, 0x65, + 0x74, 0x72, 0x61, 0x6e, 0x73, 0x6d, 0x69, 0x73, 0x73, 0x69, + 0x6f, 0x6e, 0x73, 0xa, 0x9, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x4e, 0x6f, 0x20, 0x63, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, + 0x69, 0x6f, 0x6e, 0x20, 0x61, 0x76, 0x61, 0x6c, 0x69, 0x61, + 0x62, 0x6c, 0x65, 0xa, 0x9, 0x20, 0x20, 0x20, 0x20, 0x20, + 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, + 0x20, 0x61, 0x74, 0x74, 0x65, 0x6d, 0x70, 0x74, 0x73, 0x20, + 0x74, 0x6f, 0x20, 0x63, 0x6c, 0x6f, 0x73, 0x65, 0x64, 0x20, + 0x70, 0x6f, 0x72, 0x74, 0x73, 0xa, 0x3c, 0x2f, 0x70, 0x72, + 0x65, 0x3e, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0x3c, + 0x2f, 0x74, 0x64, 0x3e, 0x3c, 0x74, 0x64, 0x3e, 0x3c, 0x70, + 0x72, 0x65, 0x3e, 0x25, 0x21, 0x20, 0x6e, 0x65, 0x74, 0x2d, + 0x73, 0x74, 0x61, 0x74, 0x73, 0xa, 0x3c, 0x2f, 0x70, 0x72, + 0x65, 0x3e, 0x3c, 0x2f, 0x74, 0x61, 0x62, 0x6c, 0x65, 0x3e, + 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, 0x3c, + 0x2f, 0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68, + 0x74, 0x6d, 0x6c, 0x3e, 0xa, 0}; + +static const char data_tcp_shtml[] = { + /* /tcp.shtml */ + 0x2f, 0x74, 0x63, 0x70, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0, + 0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20, + 0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49, + 0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f, + 0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20, + 0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73, + 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45, + 0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, + 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72, + 0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34, + 0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64, + 0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, + 0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20, + 0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, + 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, + 0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42, + 0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65, + 0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, + 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e, + 0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x3e, 0xa, + 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61, 0x63, 0x65, + 0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c, 0x22, 0x3e, 0xa, + 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, + 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, + 0x22, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x53, 0x74, 0x61, + 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, + 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, + 0x72, 0x65, 0x66, 0x3d, 0x22, 0x72, 0x75, 0x6e, 0x74, 0x69, + 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, + 0x52, 0x75, 0x6e, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x20, 0x53, + 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, + 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, + 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x73, 0x74, 0x61, + 0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, + 0x54, 0x43, 0x50, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, + 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, + 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, + 0x3d, 0x22, 0x74, 0x63, 0x70, 0x2e, 0x73, 0x68, 0x74, 0x6d, + 0x6c, 0x22, 0x3e, 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, + 0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, + 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, + 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x68, 0x74, 0x74, + 0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x66, 0x72, + 0x65, 0x65, 0x72, 0x74, 0x6f, 0x73, 0x2e, 0x6f, 0x72, 0x67, + 0x2f, 0x22, 0x3e, 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, + 0x53, 0x2e, 0x6f, 0x72, 0x67, 0x20, 0x48, 0x6f, 0x6d, 0x65, + 0x70, 0x61, 0x67, 0x65, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, + 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, + 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, 0x6f, 0x2e, + 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x49, 0x4f, 0x3c, + 0x2f, 0x61, 0x3e, 0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, + 0x3e, 0xa, 0x3c, 0x68, 0x72, 0x3e, 0xa, 0x3c, 0x62, 0x72, + 0x3e, 0xa, 0x3c, 0x68, 0x32, 0x3e, 0x4e, 0x65, 0x74, 0x77, + 0x6f, 0x72, 0x6b, 0x20, 0x63, 0x6f, 0x6e, 0x6e, 0x65, 0x63, + 0x74, 0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x68, 0x32, 0x3e, + 0xa, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x74, 0x61, 0x62, 0x6c, + 0x65, 0x3e, 0xa, 0x3c, 0x74, 0x72, 0x3e, 0x3c, 0x74, 0x68, + 0x3e, 0x4c, 0x6f, 0x63, 0x61, 0x6c, 0x3c, 0x2f, 0x74, 0x68, + 0x3e, 0x3c, 0x74, 0x68, 0x3e, 0x52, 0x65, 0x6d, 0x6f, 0x74, + 0x65, 0x3c, 0x2f, 0x74, 0x68, 0x3e, 0x3c, 0x74, 0x68, 0x3e, + 0x53, 0x74, 0x61, 0x74, 0x65, 0x3c, 0x2f, 0x74, 0x68, 0x3e, + 0x3c, 0x74, 0x68, 0x3e, 0x52, 0x65, 0x74, 0x72, 0x61, 0x6e, + 0x73, 0x6d, 0x69, 0x73, 0x73, 0x69, 0x6f, 0x6e, 0x73, 0x3c, + 0x2f, 0x74, 0x68, 0x3e, 0x3c, 0x74, 0x68, 0x3e, 0x54, 0x69, + 0x6d, 0x65, 0x72, 0x3c, 0x2f, 0x74, 0x68, 0x3e, 0x3c, 0x74, + 0x68, 0x3e, 0x46, 0x6c, 0x61, 0x67, 0x73, 0x3c, 0x2f, 0x74, + 0x68, 0x3e, 0x3c, 0x2f, 0x74, 0x72, 0x3e, 0xa, 0x25, 0x21, + 0x20, 0x74, 0x63, 0x70, 0x2d, 0x63, 0x6f, 0x6e, 0x6e, 0x65, + 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x73, 0xa, 0x3c, 0x2f, 0x70, + 0x72, 0x65, 0x3e, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, + 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, 0x3c, + 0x2f, 0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68, + 0x74, 0x6d, 0x6c, 0x3e, 0xa, 0xa, 0}; + +const struct httpd_fsdata_file file_404_html[] = {{NULL, data_404_html, data_404_html + 10, sizeof(data_404_html) - 10, 0}}; + +const struct httpd_fsdata_file file_index_html[] = {{file_404_html, data_index_html, data_index_html + 12, sizeof(data_index_html) - 12, 0}}; + +const struct httpd_fsdata_file file_index_shtml[] = {{file_index_html, data_index_shtml, data_index_shtml + 13, sizeof(data_index_shtml) - 13, 0}}; + +const struct httpd_fsdata_file file_io_shtml[] = {{file_index_shtml, data_io_shtml, data_io_shtml + 10, sizeof(data_io_shtml) - 10, 0}}; + +const struct httpd_fsdata_file file_runtime_shtml[] = {{file_io_shtml, data_runtime_shtml, data_runtime_shtml + 15, sizeof(data_runtime_shtml) - 15, 0}}; + +const struct httpd_fsdata_file file_stats_shtml[] = {{file_runtime_shtml, data_stats_shtml, data_stats_shtml + 13, sizeof(data_stats_shtml) - 13, 0}}; + +const struct httpd_fsdata_file file_tcp_shtml[] = {{file_stats_shtml, data_tcp_shtml, data_tcp_shtml + 11, sizeof(data_tcp_shtml) - 11, 0}}; + +#define HTTPD_FS_ROOT file_tcp_shtml + +#define HTTPD_FS_NUMFILES 7 diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fsdata.h b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fsdata.h new file mode 100644 index 000000000..52d35c265 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd-fsdata.h @@ -0,0 +1,64 @@ +/* + * Copyright (c) 2001, Swedish Institute of Computer Science. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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. + * + * This file is part of the lwIP TCP/IP stack. + * + * Author: Adam Dunkels + * + * $Id: httpd-fsdata.h,v 1.1 2006/06/07 09:13:08 adam Exp $ + */ +#ifndef __HTTPD_FSDATA_H__ +#define __HTTPD_FSDATA_H__ + +#include "uip.h" + +struct httpd_fsdata_file { + const struct httpd_fsdata_file *next; + const char *name; + const char *data; + const int len; +#ifdef HTTPD_FS_STATISTICS +#if HTTPD_FS_STATISTICS == 1 + u16_t count; +#endif /* HTTPD_FS_STATISTICS */ +#endif /* HTTPD_FS_STATISTICS */ +}; + +struct httpd_fsdata_file_noconst { + struct httpd_fsdata_file *next; + char *name; + char *data; + int len; +#ifdef HTTPD_FS_STATISTICS +#if HTTPD_FS_STATISTICS == 1 + u16_t count; +#endif /* HTTPD_FS_STATISTICS */ +#endif /* HTTPD_FS_STATISTICS */ +}; + +#endif /* __HTTPD_FSDATA_H__ */ diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd.c b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd.c new file mode 100644 index 000000000..c416cc1c8 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd.c @@ -0,0 +1,346 @@ +/** + * \addtogroup apps + * @{ + */ + +/** + * \defgroup httpd Web server + * @{ + * The uIP web server is a very simplistic implementation of an HTTP + * server. It can serve web pages and files from a read-only ROM + * filesystem, and provides a very small scripting language. + + */ + +/** + * \file + * Web server + * \author + * Adam Dunkels + */ + + +/* + * Copyright (c) 2004, Adam Dunkels. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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. + * + * This file is part of the uIP TCP/IP stack. + * + * Author: Adam Dunkels + * + * $Id: httpd.c,v 1.2 2006/06/11 21:46:38 adam Exp $ + */ + +#include "uip.h" +#include "httpd.h" +#include "httpd-fs.h" +#include "httpd-cgi.h" +#include "http-strings.h" + +#include + +#define STATE_WAITING 0 +#define STATE_OUTPUT 1 + +#define ISO_nl 0x0a +#define ISO_space 0x20 +#define ISO_bang 0x21 +#define ISO_percent 0x25 +#define ISO_period 0x2e +#define ISO_slash 0x2f +#define ISO_colon 0x3a + + +/*---------------------------------------------------------------------------*/ +static unsigned short +generate_part_of_file(void *state) +{ + struct httpd_state *s = (struct httpd_state *)state; + + if(s->file.len > uip_mss()) { + s->len = uip_mss(); + } else { + s->len = s->file.len; + } + memcpy(uip_appdata, s->file.data, s->len); + + return s->len; +} +/*---------------------------------------------------------------------------*/ +static +PT_THREAD(send_file(struct httpd_state *s)) +{ + PSOCK_BEGIN(&s->sout); + + do { + PSOCK_GENERATOR_SEND(&s->sout, generate_part_of_file, s); + s->file.len -= s->len; + s->file.data += s->len; + } while(s->file.len > 0); + + PSOCK_END(&s->sout); +} +/*---------------------------------------------------------------------------*/ +static +PT_THREAD(send_part_of_file(struct httpd_state *s)) +{ + PSOCK_BEGIN(&s->sout); + + PSOCK_SEND(&s->sout, s->file.data, s->len); + + PSOCK_END(&s->sout); +} +/*---------------------------------------------------------------------------*/ +static void +next_scriptstate(struct httpd_state *s) +{ + char *p; + p = strchr(s->scriptptr, ISO_nl) + 1; + s->scriptlen -= (unsigned short)(p - s->scriptptr); + s->scriptptr = p; +} +/*---------------------------------------------------------------------------*/ +static +PT_THREAD(handle_script(struct httpd_state *s)) +{ + char *ptr; + + PT_BEGIN(&s->scriptpt); + + + while(s->file.len > 0) { + + /* Check if we should start executing a script. */ + if(*s->file.data == ISO_percent && + *(s->file.data + 1) == ISO_bang) { + s->scriptptr = s->file.data + 3; + s->scriptlen = s->file.len - 3; + if(*(s->scriptptr - 1) == ISO_colon) { + httpd_fs_open(s->scriptptr + 1, &s->file); + PT_WAIT_THREAD(&s->scriptpt, send_file(s)); + } else { + PT_WAIT_THREAD(&s->scriptpt, + httpd_cgi(s->scriptptr)(s, s->scriptptr)); + } + next_scriptstate(s); + + /* The script is over, so we reset the pointers and continue + sending the rest of the file. */ + s->file.data = s->scriptptr; + s->file.len = s->scriptlen; + } else { + /* See if we find the start of script marker in the block of HTML + to be sent. */ + + if(s->file.len > uip_mss()) { + s->len = uip_mss(); + } else { + s->len = s->file.len; + } + + if(*s->file.data == ISO_percent) { + ptr = strchr(s->file.data + 1, ISO_percent); + } else { + ptr = strchr(s->file.data, ISO_percent); + } + if(ptr != NULL && + ptr != s->file.data) { + s->len = (int)(ptr - s->file.data); + if(s->len >= uip_mss()) { + s->len = uip_mss(); + } + } + PT_WAIT_THREAD(&s->scriptpt, send_part_of_file(s)); + s->file.data += s->len; + s->file.len -= s->len; + + } + } + + PT_END(&s->scriptpt); +} +/*---------------------------------------------------------------------------*/ +static +PT_THREAD(send_headers(struct httpd_state *s, const char *statushdr)) +{ + char *ptr; + + PSOCK_BEGIN(&s->sout); + + PSOCK_SEND_STR(&s->sout, statushdr); + + ptr = strrchr(s->filename, ISO_period); + if(ptr == NULL) { + PSOCK_SEND_STR(&s->sout, http_content_type_binary); + } else if(strncmp(http_html, ptr, 5) == 0 || + strncmp(http_shtml, ptr, 6) == 0) { + PSOCK_SEND_STR(&s->sout, http_content_type_html); + } else if(strncmp(http_css, ptr, 4) == 0) { + PSOCK_SEND_STR(&s->sout, http_content_type_css); + } else if(strncmp(http_png, ptr, 4) == 0) { + PSOCK_SEND_STR(&s->sout, http_content_type_png); + } else if(strncmp(http_gif, ptr, 4) == 0) { + PSOCK_SEND_STR(&s->sout, http_content_type_gif); + } else if(strncmp(http_jpg, ptr, 4) == 0) { + PSOCK_SEND_STR(&s->sout, http_content_type_jpg); + } else { + PSOCK_SEND_STR(&s->sout, http_content_type_plain); + } + PSOCK_END(&s->sout); +} +/*---------------------------------------------------------------------------*/ +static +PT_THREAD(handle_output(struct httpd_state *s)) +{ + char *ptr; + + PT_BEGIN(&s->outputpt); + + if(!httpd_fs_open(s->filename, &s->file)) { + httpd_fs_open(http_404_html, &s->file); + strcpy(s->filename, http_404_html); + PT_WAIT_THREAD(&s->outputpt, + send_headers(s, + http_header_404)); + PT_WAIT_THREAD(&s->outputpt, + send_file(s)); + } else { + PT_WAIT_THREAD(&s->outputpt, + send_headers(s, + http_header_200)); + ptr = strchr(s->filename, ISO_period); + if(ptr != NULL && strncmp(ptr, http_shtml, 6) == 0) { + PT_INIT(&s->scriptpt); + PT_WAIT_THREAD(&s->outputpt, handle_script(s)); + } else { + PT_WAIT_THREAD(&s->outputpt, + send_file(s)); + } + } + PSOCK_CLOSE(&s->sout); + PT_END(&s->outputpt); +} +/*---------------------------------------------------------------------------*/ +static +PT_THREAD(handle_input(struct httpd_state *s)) +{ + PSOCK_BEGIN(&s->sin); + + PSOCK_READTO(&s->sin, ISO_space); + + + if(strncmp(s->inputbuf, http_get, 4) != 0) { + PSOCK_CLOSE_EXIT(&s->sin); + } + PSOCK_READTO(&s->sin, ISO_space); + + if(s->inputbuf[0] != ISO_slash) { + PSOCK_CLOSE_EXIT(&s->sin); + } + + if(s->inputbuf[1] == ISO_space) { + strncpy(s->filename, http_index_html, sizeof(s->filename)); + } else { + + s->inputbuf[PSOCK_DATALEN(&s->sin) - 1] = 0; + + /* Process any form input being sent to the server. */ + { + extern void vApplicationProcessFormInput( char *pcInputString ); + vApplicationProcessFormInput( s->inputbuf ); + } + + strncpy(s->filename, &s->inputbuf[0], sizeof(s->filename)); + } + + /* httpd_log_file(uip_conn->ripaddr, s->filename);*/ + + s->state = STATE_OUTPUT; + + while(1) { + PSOCK_READTO(&s->sin, ISO_nl); + + if(strncmp(s->inputbuf, http_referer, 8) == 0) { + s->inputbuf[PSOCK_DATALEN(&s->sin) - 2] = 0; + /* httpd_log(&s->inputbuf[9]);*/ + } + } + + PSOCK_END(&s->sin); +} +/*---------------------------------------------------------------------------*/ +static void +handle_connection(struct httpd_state *s) +{ + handle_input(s); + if(s->state == STATE_OUTPUT) { + handle_output(s); + } +} +/*---------------------------------------------------------------------------*/ +void +httpd_appcall(void) +{ + struct httpd_state *s = (struct httpd_state *)&(uip_conn->appstate); + + if(uip_closed() || uip_aborted() || uip_timedout()) { + } else if(uip_connected()) { + PSOCK_INIT(&s->sin, s->inputbuf, sizeof(s->inputbuf) - 1); + PSOCK_INIT(&s->sout, s->inputbuf, sizeof(s->inputbuf) - 1); + PT_INIT(&s->outputpt); + s->state = STATE_WAITING; + /* timer_set(&s->timer, CLOCK_SECOND * 100);*/ + s->timer = 0; + handle_connection(s); + } else if(s != NULL) { + if(uip_poll()) { + ++s->timer; + if(s->timer >= 20) { + uip_abort(); + } + } else { + s->timer = 0; + } + handle_connection(s); + } else { + uip_abort(); + } +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Initialize the web server + * + * This function initializes the web server and should be + * called at system boot-up. + */ +void +httpd_init(void) +{ + uip_listen(HTONS(80)); +} +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd.h b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd.h new file mode 100644 index 000000000..7f7a6666e --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/httpd.h @@ -0,0 +1,62 @@ +/* + * Copyright (c) 2001-2005, Adam Dunkels. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. The name of the author may not be used to endorse or promote + * products derived from this software without specific prior + * written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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. + * + * This file is part of the uIP TCP/IP stack. + * + * $Id: httpd.h,v 1.2 2006/06/11 21:46:38 adam Exp $ + * + */ + +#ifndef __HTTPD_H__ +#define __HTTPD_H__ + +#include "psock.h" +#include "httpd-fs.h" + +struct httpd_state { + unsigned char timer; + struct psock sin, sout; + struct pt outputpt, scriptpt; + char inputbuf[50]; + char filename[20]; + char state; + struct httpd_fs_file file; + int len; + char *scriptptr; + int scriptlen; + + unsigned short count; +}; + +void httpd_init(void); +void httpd_appcall(void); + +void httpd_log(char *msg); +void httpd_log_file(u16_t *requester, char *file); + +#endif /* __HTTPD_H__ */ diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/makefsdata b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/makefsdata new file mode 100644 index 000000000..8d2715a8a --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/makefsdata @@ -0,0 +1,78 @@ +#!/usr/bin/perl + +open(OUTPUT, "> httpd-fsdata.c"); + +chdir("httpd-fs"); + +opendir(DIR, "."); +@files = grep { !/^\./ && !/(CVS|~)/ } readdir(DIR); +closedir(DIR); + +foreach $file (@files) { + + if(-d $file && $file !~ /^\./) { + print "Processing directory $file\n"; + opendir(DIR, $file); + @newfiles = grep { !/^\./ && !/(CVS|~)/ } readdir(DIR); + closedir(DIR); + printf "Adding files @newfiles\n"; + @files = (@files, map { $_ = "$file/$_" } @newfiles); + next; + } +} + +foreach $file (@files) { + if(-f $file) { + + print "Adding file $file\n"; + + open(FILE, $file) || die "Could not open file $file\n"; + + $file =~ s-^-/-; + $fvar = $file; + $fvar =~ s-/-_-g; + $fvar =~ s-\.-_-g; + # for AVR, add PROGMEM here + print(OUTPUT "static const unsigned char data".$fvar."[] = {\n"); + print(OUTPUT "\t/* $file */\n\t"); + for($j = 0; $j < length($file); $j++) { + printf(OUTPUT "%#02x, ", unpack("C", substr($file, $j, 1))); + } + printf(OUTPUT "0,\n"); + + + $i = 0; + while(read(FILE, $data, 1)) { + if($i == 0) { + print(OUTPUT "\t"); + } + printf(OUTPUT "%#02x, ", unpack("C", $data)); + $i++; + if($i == 10) { + print(OUTPUT "\n"); + $i = 0; + } + } + print(OUTPUT "0};\n\n"); + close(FILE); + push(@fvars, $fvar); + push(@pfiles, $file); + } +} + +for($i = 0; $i < @fvars; $i++) { + $file = $pfiles[$i]; + $fvar = $fvars[$i]; + + if($i == 0) { + $prevfile = "NULL"; + } else { + $prevfile = "file" . $fvars[$i - 1]; + } + print(OUTPUT "const struct httpd_fsdata_file file".$fvar."[] = {{$prevfile, data$fvar, "); + print(OUTPUT "data$fvar + ". (length($file) + 1) .", "); + print(OUTPUT "sizeof(data$fvar) - ". (length($file) + 1) ."}};\n\n"); +} + +print(OUTPUT "#define HTTPD_FS_ROOT file$fvars[$i - 1]\n\n"); +print(OUTPUT "#define HTTPD_FS_NUMFILES $i\n"); diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/makestrings b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/makestrings new file mode 100644 index 000000000..8a13c6d29 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/makestrings @@ -0,0 +1,40 @@ +#!/usr/bin/perl + + +sub stringify { + my $name = shift(@_); + open(OUTPUTC, "> $name.c"); + open(OUTPUTH, "> $name.h"); + + open(FILE, "$name"); + + while() { + if(/(.+) "(.+)"/) { + $var = $1; + $data = $2; + + $datan = $data; + $datan =~ s/\\r/\r/g; + $datan =~ s/\\n/\n/g; + $datan =~ s/\\01/\01/g; + $datan =~ s/\\0/\0/g; + + printf(OUTPUTC "const char $var\[%d] = \n", length($datan) + 1); + printf(OUTPUTC "/* \"$data\" */\n"); + printf(OUTPUTC "{"); + for($j = 0; $j < length($datan); $j++) { + printf(OUTPUTC "%#02x, ", unpack("C", substr($datan, $j, 1))); + } + printf(OUTPUTC "};\n"); + + printf(OUTPUTH "extern const char $var\[%d];\n", length($datan) + 1); + + } + } + close(OUTPUTC); + close(OUTPUTH); +} +stringify("http-strings"); + +exit 0; + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/uIP_Task.c b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/uIP_Task.c new file mode 100644 index 000000000..da81da5ce --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/uIP_Task.c @@ -0,0 +1,327 @@ +/* + FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry. + + This file is part of the FreeRTOS.org distribution. + + FreeRTOS.org is free software; you can redistribute it and/or modify it + under the terms of the GNU General Public License (version 2) as published + by the Free Software Foundation and modified by the FreeRTOS exception. + **NOTE** The exception to the GPL is included to allow you to distribute a + combined work that includes FreeRTOS.org without being obliged to provide + the source code for any proprietary components. Alternative commercial + license and support terms are also available upon request. See the + licensing section of http://www.FreeRTOS.org for full details. + + FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. + + You should have received a copy of the GNU General Public License along + with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 + Temple Place, Suite 330, Boston, MA 02111-1307 USA. + + + *************************************************************************** + * * + * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * + * * + * This is a concise, step by step, 'hands on' guide that describes both * + * general multitasking concepts and FreeRTOS specifics. It presents and * + * explains numerous examples that are written using the FreeRTOS API. * + * Full source code for all the examples is provided in an accompanying * + * .zip file. * + * * + *************************************************************************** + + 1 tab == 4 spaces! + + Please ensure to read the configuration and relevant port sections of the + online documentation. + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/* Standard includes. */ +#include + +/* Scheduler includes. */ +#include "FreeRTOS.h" +#include "task.h" +#include "semphr.h" + +/* uip includes. */ +#include "uip.h" +#include "uip_arp.h" +#include "httpd.h" +#include "timer.h" +#include "clock-arch.h" + +/* Demo includes. */ +#include "emac.h" +#include "LED.h" + +#include "LPC17xx.h" +#include "core_cm3.h" +/*-----------------------------------------------------------*/ + +/* How long to wait before attempting to connect the MAC again. */ +#define uipINIT_WAIT 100 + +/* Shortcut to the header within the Rx buffer. */ +#define xHeader ((struct uip_eth_hdr *) &uip_buf[ 0 ]) + +/* Standard constant. */ +#define uipTOTAL_FRAME_HEADER_SIZE 54 + + +/*-----------------------------------------------------------*/ + +/* + * Send the uIP buffer to the MAC. + */ +static void prvENET_Send(void); + +/* + * Setup the MAC address in the MAC itself, and in the uIP stack. + */ +static void prvSetMACAddress( void ); + +/* + * Port functions required by the uIP stack. + */ +void clock_init( void ); +clock_time_t clock_time( void ); + +/*-----------------------------------------------------------*/ + +/* The semaphore used by the ISR to wake the uIP task. */ +extern xSemaphoreHandle xEMACSemaphore; + +/*-----------------------------------------------------------*/ + +void clock_init(void) +{ + /* This is done when the scheduler starts. */ +} +/*-----------------------------------------------------------*/ + +clock_time_t clock_time( void ) +{ + return xTaskGetTickCount(); +} +/*-----------------------------------------------------------*/ + +void vuIP_Task( void *pvParameters ) +{ +portBASE_TYPE i; +uip_ipaddr_t xIPAddr; +struct timer periodic_timer, arp_timer; +extern void ( vEMAC_ISR_Wrapper )( void ); + + ( void ) pvParameters; + + /* Create the semaphore used by the ISR to wake this task. */ + vSemaphoreCreateBinary( xEMACSemaphore ); + + /* Initialise the uIP stack. */ + timer_set( &periodic_timer, configTICK_RATE_HZ / 2 ); + timer_set( &arp_timer, configTICK_RATE_HZ * 10 ); + uip_init(); + uip_ipaddr( xIPAddr, configIP_ADDR0, configIP_ADDR1, configIP_ADDR2, configIP_ADDR3 ); + uip_sethostaddr( xIPAddr ); + uip_ipaddr( xIPAddr, configNET_MASK0, configNET_MASK1, configNET_MASK2, configNET_MASK3 ); + uip_setnetmask( xIPAddr ); + httpd_init(); + + /* Initialise the MAC. */ + while( Init_EMAC() != pdPASS ) + { + vTaskDelay( uipINIT_WAIT ); + } + + portENTER_CRITICAL(); + { + ETH_INTENABLE = INT_RX_DONE; + /* set the interrupt priority */ + NVIC_SetPriority( ENET_IRQn, configMAX_SYSCALL_INTERRUPT_PRIORITY ); + /* enable the interrupt */ + NVIC_EnableIRQ( ENET_IRQn ); + prvSetMACAddress(); + } + portEXIT_CRITICAL(); + + + for( ;; ) + { + /* Is there received data ready to be processed? */ + uip_len = uiGetEMACRxData( uip_buf ); + + if( uip_len > 0 ) + { + /* Standard uIP loop taken from the uIP manual. */ + if( xHeader->type == htons( UIP_ETHTYPE_IP ) ) + { + uip_arp_ipin(); + uip_input(); + + /* If the above function invocation resulted in data that + should be sent out on the network, the global variable + uip_len is set to a value > 0. */ + if( uip_len > 0 ) + { + uip_arp_out(); + prvENET_Send(); + } + } + else if( xHeader->type == htons( UIP_ETHTYPE_ARP ) ) + { + uip_arp_arpin(); + + /* If the above function invocation resulted in data that + should be sent out on the network, the global variable + uip_len is set to a value > 0. */ + if( uip_len > 0 ) + { + prvENET_Send(); + } + } + } + else + { + if( timer_expired( &periodic_timer ) ) + { + timer_reset( &periodic_timer ); + for( i = 0; i < UIP_CONNS; i++ ) + { + uip_periodic( i ); + + /* If the above function invocation resulted in data that + should be sent out on the network, the global variable + uip_len is set to a value > 0. */ + if( uip_len > 0 ) + { + uip_arp_out(); + prvENET_Send(); + } + } + + /* Call the ARP timer function every 10 seconds. */ + if( timer_expired( &arp_timer ) ) + { + timer_reset( &arp_timer ); + uip_arp_timer(); + } + } + else + { + /* We did not receive a packet, and there was no periodic + processing to perform. Block for a fixed period. If a packet + is received during this period we will be woken by the ISR + giving us the Semaphore. */ + xSemaphoreTake( xEMACSemaphore, configTICK_RATE_HZ / 2 ); + } + } + } +} +/*-----------------------------------------------------------*/ + +static void prvENET_Send(void) +{ + RequestSend(); + + /* Copy the header into the Tx buffer. */ + CopyToFrame_EMAC( uip_buf, uipTOTAL_FRAME_HEADER_SIZE ); + if( uip_len > uipTOTAL_FRAME_HEADER_SIZE ) + { + CopyToFrame_EMAC( uip_appdata, ( uip_len - uipTOTAL_FRAME_HEADER_SIZE ) ); + } + + DoSend_EMAC( uip_len ); + + RequestSend(); + + /* Copy the header into the Tx buffer. */ + CopyToFrame_EMAC( uip_buf, uipTOTAL_FRAME_HEADER_SIZE ); + if( uip_len > uipTOTAL_FRAME_HEADER_SIZE ) + { + CopyToFrame_EMAC( uip_appdata, ( uip_len - uipTOTAL_FRAME_HEADER_SIZE ) ); + } + + DoSend_EMAC( uip_len ); +} +/*-----------------------------------------------------------*/ + +static void prvSetMACAddress( void ) +{ +struct uip_eth_addr xAddr; + + /* Configure the MAC address in the uIP stack. */ + xAddr.addr[ 0 ] = configMAC_ADDR0; + xAddr.addr[ 1 ] = configMAC_ADDR1; + xAddr.addr[ 2 ] = configMAC_ADDR2; + xAddr.addr[ 3 ] = configMAC_ADDR3; + xAddr.addr[ 4 ] = configMAC_ADDR4; + xAddr.addr[ 5 ] = configMAC_ADDR5; + uip_setethaddr( xAddr ); +} +/*-----------------------------------------------------------*/ + +void vApplicationProcessFormInput( portCHAR *pcInputString ) +{ +char *c, *pcText; +static portCHAR cMessageForDisplay[ 32 ]; +extern xQueueHandle xLCDQueue; +xLCDMessage xLCDMessage; + + /* Process the form input sent by the IO page of the served HTML. */ + + c = strstr( pcInputString, "?" ); + if( c ) + { + /* Turn LED's on or off in accordance with the check box status. */ + if( strstr( c, "LED0=1" ) != NULL ) + { + /* Set LED7. */ + vParTestSetLED( 1 << 7, 1 ); + } + else + { + /* Clear LED7. */ + vParTestSetLED( 1 << 7, 0 ); + } + + /* Find the start of the text to be displayed on the LCD. */ + pcText = strstr( c, "LCD=" ); + pcText += strlen( "LCD=" ); + + /* Terminate the file name for further processing within uIP. */ + *c = 0x00; + + /* Terminate the LCD string. */ + c = strstr( pcText, " " ); + if( c != NULL ) + { + *c = 0x00; + } + + /* Add required spaces. */ + while( ( c = strstr( pcText, "+" ) ) != NULL ) + { + *c = ' '; + } + + /* Write the message to the LCD. */ + strcpy( cMessageForDisplay, pcText ); + xLCDMessage.pcMessage = cMessageForDisplay; + xQueueSend( xLCDQueue, &xLCDMessage, portMAX_DELAY ); + } +} + diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/uip-conf.h b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/uip-conf.h new file mode 100644 index 000000000..3e6f7f381 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/uip-conf.h @@ -0,0 +1,157 @@ +/** + * \addtogroup uipopt + * @{ + */ + +/** + * \name Project-specific configuration options + * @{ + * + * uIP has a number of configuration options that can be overridden + * for each project. These are kept in a project-specific uip-conf.h + * file and all configuration names have the prefix UIP_CONF. + */ + +/* + * Copyright (c) 2006, Swedish Institute of Computer Science. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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. + * + * This file is part of the uIP TCP/IP stack + * + * $Id: uip-conf.h,v 1.6 2006/06/12 08:00:31 adam Exp $ + */ + +/** + * \file + * An example uIP configuration file + * \author + * Adam Dunkels + */ + +#ifndef __UIP_CONF_H__ +#define __UIP_CONF_H__ + +#include + +/** + * 8 bit datatype + * + * This typedef defines the 8-bit type used throughout uIP. + * + * \hideinitializer + */ +typedef uint8_t u8_t; + +/** + * 16 bit datatype + * + * This typedef defines the 16-bit type used throughout uIP. + * + * \hideinitializer + */ +typedef uint16_t u16_t; + +/** + * Statistics datatype + * + * This typedef defines the dataype used for keeping statistics in + * uIP. + * + * \hideinitializer + */ +typedef unsigned short uip_stats_t; + +/** + * Maximum number of TCP connections. + * + * \hideinitializer + */ +#define UIP_CONF_MAX_CONNECTIONS 40 + +/** + * Maximum number of listening TCP ports. + * + * \hideinitializer + */ +#define UIP_CONF_MAX_LISTENPORTS 40 + +/** + * uIP buffer size. + * + * \hideinitializer + */ +#define UIP_CONF_BUFFER_SIZE 1480 + +/** + * CPU byte order. + * + * \hideinitializer + */ +#define UIP_CONF_BYTE_ORDER LITTLE_ENDIAN + +/** + * Logging on or off + * + * \hideinitializer + */ +#define UIP_CONF_LOGGING 0 + +/** + * UDP support on or off + * + * \hideinitializer + */ +#define UIP_CONF_UDP 0 + +/** + * UDP checksums on or off + * + * \hideinitializer + */ +#define UIP_CONF_UDP_CHECKSUMS 1 + +/** + * uIP statistics on or off + * + * \hideinitializer + */ +#define UIP_CONF_STATISTICS 1 + +/* Here we include the header file for the application(s) we use in + our project. */ +/*#include "smtp.h"*/ +/*#include "hello-world.h"*/ +/*#include "telnetd.h"*/ +#include "webserver.h" +/*#include "dhcpc.h"*/ +/*#include "resolv.h"*/ +/*#include "webclient.h"*/ + +#endif /* __UIP_CONF_H__ */ + +/** @} */ +/** @} */ diff --git a/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/webserver.h b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/webserver.h new file mode 100644 index 000000000..1acb290b8 --- /dev/null +++ b/Demo/CORTEX_LPC1768_GCC_Rowley/webserver/webserver.h @@ -0,0 +1,49 @@ +/* + * Copyright (c) 2002, Adam Dunkels. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. The name of the author may not be used to endorse or promote + * products derived from this software without specific prior + * written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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. + * + * This file is part of the uIP TCP/IP stack + * + * $Id: webserver.h,v 1.2 2006/06/11 21:46:38 adam Exp $ + * + */ +#ifndef __WEBSERVER_H__ +#define __WEBSERVER_H__ + +#include "httpd.h" + +typedef struct httpd_state uip_tcp_appstate_t; +/* UIP_APPCALL: the name of the application function. This function + must return void and take no arguments (i.e., C type "void + appfunc(void)"). */ +#ifndef UIP_APPCALL +#define UIP_APPCALL httpd_appcall +#endif + + +#endif /* __WEBSERVER_H__ */
LocalRemoteStateRetransmissionsTimerFlags