--- /dev/null
+/******************************************************************************/\r
+/* CortexM3.H: Header file for Cortex-M3 */\r
+/******************************************************************************/\r
+/* This file is part of the uVision/ARM development tools. */\r
+/* Copyright (c) 2008 Keil Software. All rights reserved. */\r
+/******************************************************************************/\r
+\r
+#ifndef __CortexM3_H\r
+#define __CortexM3_H\r
+\r
+\r
+#define REG8(x) (*((volatile unsigned char *)(x)))\r
+#define REG16(x) (*((volatile unsigned short *)(x)))\r
+#define REG32(x) (*((volatile unsigned long *)(x)))\r
+\r
+\r
+/* NVIC Registers */\r
+#define NVIC_INT_TYPE REG32(0xE000E004)\r
+#define NVIC_ST_CTRL REG32(0xE000E010)\r
+#define NVIC_ST_RELOAD REG32(0xE000E014)\r
+#define NVIC_ST_CURRENT REG32(0xE000E018)\r
+#define NVIC_ST_CALIB REG32(0xE000E01C)\r
+#define NVIC_ENABLE0 REG32(0xE000E100)\r
+#define NVIC_ENABLE1 REG32(0xE000E104)\r
+#define NVIC_ENABLE2 REG32(0xE000E108)\r
+#define NVIC_ENABLE3 REG32(0xE000E10C)\r
+#define NVIC_ENABLE4 REG32(0xE000E110)\r
+#define NVIC_ENABLE5 REG32(0xE000E114)\r
+#define NVIC_ENABLE6 REG32(0xE000E118)\r
+#define NVIC_ENABLE7 REG32(0xE000E11C)\r
+#define NVIC_DISABLE0 REG32(0xE000E180)\r
+#define NVIC_DISABLE1 REG32(0xE000E184)\r
+#define NVIC_DISABLE2 REG32(0xE000E188)\r
+#define NVIC_DISABLE3 REG32(0xE000E18C)\r
+#define NVIC_DISABLE4 REG32(0xE000E190)\r
+#define NVIC_DISABLE5 REG32(0xE000E194)\r
+#define NVIC_DISABLE6 REG32(0xE000E198)\r
+#define NVIC_DISABLE7 REG32(0xE000E19C)\r
+#define NVIC_PEND0 REG32(0xE000E200)\r
+#define NVIC_PEND1 REG32(0xE000E204)\r
+#define NVIC_PEND2 REG32(0xE000E208)\r
+#define NVIC_PEND3 REG32(0xE000E20C)\r
+#define NVIC_PEND4 REG32(0xE000E210)\r
+#define NVIC_PEND5 REG32(0xE000E214)\r
+#define NVIC_PEND6 REG32(0xE000E218)\r
+#define NVIC_PEND7 REG32(0xE000E21C)\r
+#define NVIC_UNPEND0 REG32(0xE000E280)\r
+#define NVIC_UNPEND1 REG32(0xE000E284)\r
+#define NVIC_UNPEND2 REG32(0xE000E288)\r
+#define NVIC_UNPEND3 REG32(0xE000E28C)\r
+#define NVIC_UNPEND4 REG32(0xE000E290)\r
+#define NVIC_UNPEND5 REG32(0xE000E294)\r
+#define NVIC_UNPEND6 REG32(0xE000E298)\r
+#define NVIC_UNPEND7 REG32(0xE000E29C)\r
+#define NVIC_ACTIVE0 REG32(0xE000E300)\r
+#define NVIC_ACTIVE1 REG32(0xE000E304)\r
+#define NVIC_ACTIVE2 REG32(0xE000E308)\r
+#define NVIC_ACTIVE3 REG32(0xE000E30C)\r
+#define NVIC_ACTIVE4 REG32(0xE000E310)\r
+#define NVIC_ACTIVE5 REG32(0xE000E314)\r
+#define NVIC_ACTIVE6 REG32(0xE000E318)\r
+#define NVIC_ACTIVE7 REG32(0xE000E31C)\r
+#define NVIC_PRI0 REG32(0xE000E400)\r
+#define NVIC_PRI1 REG32(0xE000E404)\r
+#define NVIC_PRI2 REG32(0xE000E408)\r
+#define NVIC_PRI3 REG32(0xE000E40C)\r
+#define NVIC_PRI4 REG32(0xE000E410)\r
+#define NVIC_PRI5 REG32(0xE000E414)\r
+#define NVIC_PRI6 REG32(0xE000E418)\r
+#define NVIC_PRI7 REG32(0xE000E41C)\r
+#define NVIC_PRI8 REG32(0xE000E420)\r
+#define NVIC_PRI9 REG32(0xE000E424)\r
+#define NVIC_PRI10 REG32(0xE000E428)\r
+#define NVIC_PRI11 REG32(0xE000E42C)\r
+#define NVIC_PRI12 REG32(0xE000E430)\r
+#define NVIC_PRI13 REG32(0xE000E434)\r
+#define NVIC_PRI14 REG32(0xE000E438)\r
+#define NVIC_PRI15 REG32(0xE000E43C)\r
+#define NVIC_PRI16 REG32(0xE000E440)\r
+#define NVIC_PRI17 REG32(0xE000E444)\r
+#define NVIC_PRI18 REG32(0xE000E448)\r
+#define NVIC_PRI19 REG32(0xE000E44C)\r
+#define NVIC_PRI20 REG32(0xE000E450)\r
+#define NVIC_PRI21 REG32(0xE000E454)\r
+#define NVIC_PRI22 REG32(0xE000E458)\r
+#define NVIC_PRI23 REG32(0xE000E45C)\r
+#define NVIC_PRI24 REG32(0xE000E460)\r
+#define NVIC_PRI25 REG32(0xE000E464)\r
+#define NVIC_PRI26 REG32(0xE000E468)\r
+#define NVIC_PRI27 REG32(0xE000E46C)\r
+#define NVIC_PRI28 REG32(0xE000E470)\r
+#define NVIC_PRI29 REG32(0xE000E474)\r
+#define NVIC_PRI30 REG32(0xE000E478)\r
+#define NVIC_PRI31 REG32(0xE000E47C)\r
+#define NVIC_PRI32 REG32(0xE000E480)\r
+#define NVIC_PRI33 REG32(0xE000E484)\r
+#define NVIC_PRI34 REG32(0xE000E488)\r
+#define NVIC_PRI35 REG32(0xE000E48C)\r
+#define NVIC_PRI36 REG32(0xE000E490)\r
+#define NVIC_PRI37 REG32(0xE000E494)\r
+#define NVIC_PRI38 REG32(0xE000E498)\r
+#define NVIC_PRI39 REG32(0xE000E49C)\r
+#define NVIC_PRI40 REG32(0xE000E4A0)\r
+#define NVIC_PRI41 REG32(0xE000E4A4)\r
+#define NVIC_PRI42 REG32(0xE000E4A8)\r
+#define NVIC_PRI43 REG32(0xE000E4AC)\r
+#define NVIC_PRI44 REG32(0xE000E4B0)\r
+#define NVIC_PRI45 REG32(0xE000E4B4)\r
+#define NVIC_PRI46 REG32(0xE000E4B8)\r
+#define NVIC_PRI47 REG32(0xE000E4BC)\r
+#define NVIC_PRI48 REG32(0xE000E4C0)\r
+#define NVIC_PRI49 REG32(0xE000E4C4)\r
+#define NVIC_PRI50 REG32(0xE000E4C8)\r
+#define NVIC_PRI51 REG32(0xE000E4CC)\r
+#define NVIC_PRI52 REG32(0xE000E4D0)\r
+#define NVIC_PRI53 REG32(0xE000E4D4)\r
+#define NVIC_PRI54 REG32(0xE000E4D8)\r
+#define NVIC_PRI55 REG32(0xE000E4DC)\r
+#define NVIC_PRI56 REG32(0xE000E4E0)\r
+#define NVIC_PRI57 REG32(0xE000E4E4)\r
+#define NVIC_PRI58 REG32(0xE000E4E8)\r
+#define NVIC_PRI59 REG32(0xE000E4EC)\r
+#define NVIC_CPUID REG32(0xE000ED00)\r
+#define NVIC_INT_CTRL REG32(0xE000ED04)\r
+#define NVIC_VECT_TABLE REG32(0xE000ED08)\r
+#define NVIC_AP_INT_RST REG32(0xE000ED0C)\r
+#define NVIC_SYS_CTRL REG32(0xE000ED10)\r
+#define NVIC_CFG_CTRL REG32(0xE000ED14)\r
+#define NVIC_SYS_H_PRI1 REG32(0xE000ED18)\r
+#define NVIC_SYS_H_PRI2 REG32(0xE000ED1C)\r
+#define NVIC_SYS_H_PRI3 REG32(0xE000ED20)\r
+#define NVIC_SYS_H_CTRL REG32(0xE000ED24)\r
+#define NVIC_FAULT_STA REG32(0xE000ED28)\r
+#define NVIC_HARD_F_STA REG32(0xE000ED2C)\r
+#define NVIC_DBG_F_STA REG32(0xE000ED30)\r
+#define NVIC_MM_F_ADR REG32(0xE000ED34)\r
+#define NVIC_BUS_F_ADR REG32(0xE000ED38)\r
+#define NVIC_SW_TRIG REG32(0xE000EF00)\r
+\r
+\r
+/* MPU Registers */\r
+#define MPU_TYPE REG32(0xE000ED90)\r
+#define MPU_CTRL REG32(0xE000ED94)\r
+#define MPU_RG_NUM REG32(0xE000ED98)\r
+#define MPU_RG_ADDR REG32(0xE000ED9C)\r
+#define MPU_RG_AT_SZ REG32(0xE000EDA0)\r
+\r
+\r
+#endif // __CortexM3_H\r
--- /dev/null
+/*\r
+ FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry.\r
+\r
+ This file is part of the FreeRTOS.org distribution.\r
+\r
+ FreeRTOS.org is free software; you can redistribute it and/or modify it\r
+ under the terms of the GNU General Public License (version 2) as published\r
+ by the Free Software Foundation and modified by the FreeRTOS exception.\r
+ **NOTE** The exception to the GPL is included to allow you to distribute a\r
+ combined work that includes FreeRTOS.org without being obliged to provide\r
+ the source code for any proprietary components. Alternative commercial\r
+ license and support terms are also available upon request. See the\r
+ licensing section of http://www.FreeRTOS.org for full details.\r
+\r
+ FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT\r
+ ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or\r
+ FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for\r
+ more details.\r
+\r
+ You should have received a copy of the GNU General Public License along\r
+ with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59\r
+ Temple Place, Suite 330, Boston, MA 02111-1307 USA.\r
+\r
+\r
+ ***************************************************************************\r
+ * *\r
+ * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation *\r
+ * *\r
+ * This is a concise, step by step, 'hands on' guide that describes both *\r
+ * general multitasking concepts and FreeRTOS specifics. It presents and *\r
+ * explains numerous examples that are written using the FreeRTOS API. *\r
+ * Full source code for all the examples is provided in an accompanying *\r
+ * .zip file. *\r
+ * *\r
+ ***************************************************************************\r
+\r
+ 1 tab == 4 spaces!\r
+\r
+ Please ensure to read the configuration and relevant port sections of the\r
+ online documentation.\r
+\r
+ http://www.FreeRTOS.org - Documentation, latest information, license and\r
+ contact details.\r
+\r
+ http://www.SafeRTOS.com - A version that is certified for use in safety\r
+ critical systems.\r
+\r
+ http://www.OpenRTOS.com - Commercial support, development, porting,\r
+ licensing and training services.\r
+*/\r
+\r
+#ifndef FREERTOS_CONFIG_H\r
+#define FREERTOS_CONFIG_H\r
+\r
+#include "LPC17xx.h"\r
+#include "LPC17xx_defs.h"\r
+\r
+/*-----------------------------------------------------------\r
+ * Application specific definitions.\r
+ *\r
+ * These definitions should be adjusted for your particular hardware and\r
+ * application requirements.\r
+ *\r
+ * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE\r
+ * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.\r
+ *----------------------------------------------------------*/\r
+\r
+#define configUSE_PREEMPTION 1\r
+#define configUSE_IDLE_HOOK 0\r
+#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 )\r
+#define configUSE_TICK_HOOK 1\r
+#define configCPU_CLOCK_HZ ( ( unsigned portLONG ) 64000000 )\r
+#define configTICK_RATE_HZ ( ( portTickType ) 1000 )\r
+#define configMINIMAL_STACK_SIZE ( ( unsigned portSHORT ) 80 )\r
+#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 19 * 1024 ) )\r
+#define configMAX_TASK_NAME_LEN ( 12 )\r
+#define configUSE_TRACE_FACILITY 1\r
+#define configUSE_16_BIT_TICKS 0\r
+#define configIDLE_SHOULD_YIELD 0\r
+#define configUSE_CO_ROUTINES 0\r
+#define configUSE_MUTEXES 1\r
+\r
+#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )\r
+\r
+#define configUSE_COUNTING_SEMAPHORES 0\r
+#define configUSE_ALTERNATIVE_API 0\r
+#define configCHECK_FOR_STACK_OVERFLOW 2\r
+#define configUSE_RECURSIVE_MUTEXES 1\r
+#define configQUEUE_REGISTRY_SIZE 10\r
+#define configGENERATE_RUN_TIME_STATS 1\r
+\r
+/* Set the following definitions to 1 to include the API function, or zero\r
+to exclude the API function. */\r
+\r
+#define INCLUDE_vTaskPrioritySet 1\r
+#define INCLUDE_uxTaskPriorityGet 1\r
+#define INCLUDE_vTaskDelete 1\r
+#define INCLUDE_vTaskCleanUpResources 0\r
+#define INCLUDE_vTaskSuspend 1\r
+#define INCLUDE_vTaskDelayUntil 1\r
+#define INCLUDE_vTaskDelay 1\r
+#define INCLUDE_uxTaskGetStackHighWaterMark 1\r
+\r
+/*-----------------------------------------------------------\r
+ * Ethernet configuration.\r
+ *-----------------------------------------------------------*/\r
+\r
+/* MAC address configuration. */\r
+#define configMAC_ADDR0 0x00\r
+#define configMAC_ADDR1 0x12\r
+#define configMAC_ADDR2 0x13\r
+#define configMAC_ADDR3 0x10\r
+#define configMAC_ADDR4 0x15\r
+#define configMAC_ADDR5 0x11\r
+\r
+/* IP address configuration. */\r
+#define configIP_ADDR0 192\r
+#define configIP_ADDR1 168\r
+#define configIP_ADDR2 0\r
+#define configIP_ADDR3 201\r
+\r
+/* Netmask configuration. */\r
+#define configNET_MASK0 255\r
+#define configNET_MASK1 255\r
+#define configNET_MASK2 255\r
+#define configNET_MASK3 0\r
+\r
+/* Use the system definition, if there is one */\r
+#ifdef __NVIC_PRIO_BITS\r
+ #define configPRIO_BITS __NVIC_PRIO_BITS\r
+#else\r
+ #define configPRIO_BITS 5 /* 32 priority levels */\r
+#endif\r
+\r
+/* The lowest priority. */\r
+#define configKERNEL_INTERRUPT_PRIORITY ( 31 << (8 - configPRIO_BITS) )\r
+/* Priority 5, or 160 as only the top three bits are implemented. */\r
+#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( 5 << (8 - configPRIO_BITS) )\r
+\r
+\r
+\r
+\r
+\r
+/*-----------------------------------------------------------\r
+ * Macros required to setup the timer for the run time stats.\r
+ *-----------------------------------------------------------*/\r
+extern void vConfigureTimerForRunTimeStats( void );\r
+#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() vConfigureTimerForRunTimeStats()\r
+#define portGET_RUN_TIME_COUNTER_VALUE() T0TC\r
+\r
+\r
+/* The structure that is passed on the xLCDQueue. Put here for convenience. */\r
+typedef struct\r
+{\r
+ char *pcMessage;\r
+} xLCDMessage;\r
+\r
+#endif /* FREERTOS_CONFIG_H */\r
--- /dev/null
+/*\r
+ FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry.\r
+\r
+ This file is part of the FreeRTOS.org distribution.\r
+\r
+ FreeRTOS.org is free software; you can redistribute it and/or modify it\r
+ under the terms of the GNU General Public License (version 2) as published\r
+ by the Free Software Foundation and modified by the FreeRTOS exception.\r
+ **NOTE** The exception to the GPL is included to allow you to distribute a\r
+ combined work that includes FreeRTOS.org without being obliged to provide\r
+ the source code for any proprietary components. Alternative commercial\r
+ license and support terms are also available upon request. See the \r
+ licensing section of http://www.FreeRTOS.org for full details.\r
+\r
+ FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT\r
+ ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or\r
+ FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for\r
+ more details.\r
+\r
+ You should have received a copy of the GNU General Public License along\r
+ with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59\r
+ Temple Place, Suite 330, Boston, MA 02111-1307 USA.\r
+\r
+\r
+ ***************************************************************************\r
+ * *\r
+ * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation *\r
+ * *\r
+ * This is a concise, step by step, 'hands on' guide that describes both *\r
+ * general multitasking concepts and FreeRTOS specifics. It presents and *\r
+ * explains numerous examples that are written using the FreeRTOS API. *\r
+ * Full source code for all the examples is provided in an accompanying *\r
+ * .zip file. *\r
+ * *\r
+ ***************************************************************************\r
+\r
+ 1 tab == 4 spaces!\r
+\r
+ Please ensure to read the configuration and relevant port sections of the\r
+ online documentation.\r
+\r
+ http://www.FreeRTOS.org - Documentation, latest information, license and\r
+ contact details.\r
+\r
+ http://www.SafeRTOS.com - A version that is certified for use in safety\r
+ critical systems.\r
+\r
+ http://www.OpenRTOS.com - Commercial support, development, porting,\r
+ licensing and training services.\r
+*/\r
+\r
+#ifndef LED_HH\r
+#define LED_HH\r
+\r
+void vToggleLED( unsigned long ulLED );\r
+void vSetLEDState( unsigned long ulLED, long lState );\r
+long lGetLEDState( unsigned long ulLED );\r
+\r
+#endif\r
--- /dev/null
+/*****************************************************************************
+ * 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 <LPC1000.h>
+
+#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 */
+
--- /dev/null
+#ifndef __LPC17xx_H\r
+#define __LPC17xx_H\r
+\r
+#include "CortexM3.h"\r
+\r
+\r
+/* System Control Block (SCB) includes:\r
+ Flash Accelerator Module, Clocking and Power Control, External Interrupts,\r
+ Reset, System Control and Status\r
+*/\r
+#define SCB_BASE_ADDR 0x400FC000\r
+\r
+/* Flash Accelerator Module */\r
+#define FLASHCTRL (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x000))\r
+#define FLASHTIM (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x004))\r
+\r
+/* Phase Locked Loop (Main PLL0) */\r
+#define PLL0CON (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x080))\r
+#define PLL0CFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x084))\r
+#define PLL0STAT (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x088))\r
+#define PLL0FEED (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x08C))\r
+\r
+/* Phase Locked Loop (USB PLL1) */\r
+#define PLL1CON (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0A0))\r
+#define PLL1CFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0A4))\r
+#define PLL1STAT (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0A8))\r
+#define PLL1FEED (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0AC))\r
+\r
+/* Power Control */\r
+#define PCON (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0C0))\r
+#define PCONP (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0C4))\r
+\r
+/* Clock Selection and Dividers */\r
+#define CCLKCFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x104))\r
+#define USBCLKCFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x108))\r
+#define CLKSRCSEL (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x10C))\r
+#define IRCTRIM (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1A4))\r
+#define PCLKSEL0 (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1A8))\r
+#define PCLKSEL1 (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1AC))\r
+ \r
+/* External Interrupts */\r
+#define EXTINT (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x140))\r
+#define EXTMODE (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x148))\r
+#define EXTPOLAR (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x14C))\r
+\r
+/* Reset */\r
+#define RSIR (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x180))\r
+\r
+/* System Controls and Status */\r
+#define SCS (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1A0)) \r
+\r
+\r
+/* Pin Connect Block */\r
+#define PINCON_BASE_ADDR 0x4002C000\r
+#define PINSEL0 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x00))\r
+#define PINSEL1 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x04))\r
+#define PINSEL2 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x08))\r
+#define PINSEL3 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x0C))\r
+#define PINSEL4 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x10))\r
+#define PINSEL5 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x14))\r
+#define PINSEL6 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x18))\r
+#define PINSEL7 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x1C))\r
+#define PINSEL8 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x20))\r
+#define PINSEL9 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x24))\r
+#define PINSEL10 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x28))\r
+\r
+#define PINMODE0 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x40))\r
+#define PINMODE1 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x44))\r
+#define PINMODE2 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x48))\r
+#define PINMODE3 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x4C))\r
+#define PINMODE4 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x50))\r
+#define PINMODE5 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x54))\r
+#define PINMODE6 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x58))\r
+#define PINMODE7 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x5C))\r
+#define PINMODE8 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x60))\r
+#define PINMODE9 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x64))\r
+#define PINMODE_OD0 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x68))\r
+#define PINMODE_OD1 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x6C))\r
+#define PINMODE_OD2 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x70))\r
+#define PINMODE_OD3 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x74))\r
+#define PINMODE_OD4 (*(volatile unsigned long *)(PINCON_BASE_ADDR + 0x78))\r
+\r
+\r
+/* General Purpose Input/Output (GPIO) - Fast GPIO */\r
+// #define GPIO_BASE_ADDR 0x50014000 /* For the first silicon v0.00 */\r
+#define GPIO_BASE_ADDR 0x2009C000 /* For silicon v0.01 or newer */\r
+#define FIO0DIR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x00)) \r
+#define FIO0MASK (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x10))\r
+#define FIO0PIN (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x14))\r
+#define FIO0SET (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x18))\r
+#define FIO0CLR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x1C))\r
+\r
+#define FIO1DIR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x20)) \r
+#define FIO1MASK (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x30))\r
+#define FIO1PIN (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x34))\r
+#define FIO1SET (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x38))\r
+#define FIO1CLR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x3C))\r
+\r
+#define FIO2DIR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x40)) \r
+#define FIO2MASK (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x50))\r
+#define FIO2PIN (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x54))\r
+#define FIO2SET (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x58))\r
+#define FIO2CLR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x5C))\r
+\r
+#define FIO3DIR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x60)) \r
+#define FIO3MASK (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x70))\r
+#define FIO3PIN (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x74))\r
+#define FIO3SET (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x78))\r
+#define FIO3CLR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x7C))\r
+\r
+#define FIO4DIR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x80)) \r
+#define FIO4MASK (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x90))\r
+#define FIO4PIN (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x94))\r
+#define FIO4SET (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x98))\r
+#define FIO4CLR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x9C))\r
+\r
+/* FIOs can be accessed through WORD, HALF-WORD or BYTE. */\r
+#define FIO0DIR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x00)) \r
+#define FIO1DIR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x20)) \r
+#define FIO2DIR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x40)) \r
+#define FIO3DIR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x60)) \r
+#define FIO4DIR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x80)) \r
+\r
+#define FIO0DIR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x01)) \r
+#define FIO1DIR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x21)) \r
+#define FIO2DIR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x41)) \r
+#define FIO3DIR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x61)) \r
+#define FIO4DIR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x81)) \r
+\r
+#define FIO0DIR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x02)) \r
+#define FIO1DIR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x22)) \r
+#define FIO2DIR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x42)) \r
+#define FIO3DIR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x62)) \r
+#define FIO4DIR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x82)) \r
+\r
+#define FIO0DIR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x03)) \r
+#define FIO1DIR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x23)) \r
+#define FIO2DIR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x43)) \r
+#define FIO3DIR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x63)) \r
+#define FIO4DIR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x83)) \r
+\r
+#define FIO0DIRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x00)) \r
+#define FIO1DIRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x20)) \r
+#define FIO2DIRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x40)) \r
+#define FIO3DIRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x60)) \r
+#define FIO4DIRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x80)) \r
+\r
+#define FIO0DIRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x02)) \r
+#define FIO1DIRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x22)) \r
+#define FIO2DIRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x42)) \r
+#define FIO3DIRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x62)) \r
+#define FIO4DIRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x82)) \r
+\r
+#define FIO0MASK0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x10)) \r
+#define FIO1MASK0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x30)) \r
+#define FIO2MASK0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x40)) \r
+#define FIO3MASK0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x50)) \r
+#define FIO4MASK0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x90)) \r
+\r
+#define FIO0MASK1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x11)) \r
+#define FIO1MASK1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x31)) \r
+#define FIO2MASK1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x41)) \r
+#define FIO3MASK1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x51)) \r
+#define FIO4MASK1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x91)) \r
+\r
+#define FIO0MASK2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x12)) \r
+#define FIO1MASK2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x32)) \r
+#define FIO2MASK2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x42)) \r
+#define FIO3MASK2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x52)) \r
+#define FIO4MASK2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x92)) \r
+\r
+#define FIO0MASK3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x13)) \r
+#define FIO1MASK3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x33)) \r
+#define FIO2MASK3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x43)) \r
+#define FIO3MASK3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x53)) \r
+#define FIO4MASK3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x93)) \r
+\r
+#define FIO0MASKL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x10)) \r
+#define FIO1MASKL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x30)) \r
+#define FIO2MASKL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x40)) \r
+#define FIO3MASKL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x50)) \r
+#define FIO4MASKL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x90)) \r
+\r
+#define FIO0MASKU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x12)) \r
+#define FIO1MASKU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x32)) \r
+#define FIO2MASKU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x42)) \r
+#define FIO3MASKU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x52)) \r
+#define FIO4MASKU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x92)) \r
+\r
+#define FIO0PIN0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x14)) \r
+#define FIO1PIN0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x34)) \r
+#define FIO2PIN0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x44)) \r
+#define FIO3PIN0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x54)) \r
+#define FIO4PIN0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x94)) \r
+\r
+#define FIO0PIN1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x15)) \r
+#define FIO1PIN1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x35)) \r
+#define FIO2PIN1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x45)) \r
+#define FIO3PIN1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x55)) \r
+#define FIO4PIN1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x95)) \r
+\r
+#define FIO0PIN2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x16)) \r
+#define FIO1PIN2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x36)) \r
+#define FIO2PIN2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x46)) \r
+#define FIO3PIN2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x56)) \r
+#define FIO4PIN2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x96)) \r
+\r
+#define FIO0PIN3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x17)) \r
+#define FIO1PIN3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x37)) \r
+#define FIO2PIN3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x47)) \r
+#define FIO3PIN3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x57)) \r
+#define FIO4PIN3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x97)) \r
+\r
+#define FIO0PINL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x14)) \r
+#define FIO1PINL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x34)) \r
+#define FIO2PINL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x44)) \r
+#define FIO3PINL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x54)) \r
+#define FIO4PINL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x94)) \r
+\r
+#define FIO0PINU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x16)) \r
+#define FIO1PINU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x36)) \r
+#define FIO2PINU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x46)) \r
+#define FIO3PINU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x56)) \r
+#define FIO4PINU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x96)) \r
+\r
+#define FIO0SET0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x18)) \r
+#define FIO1SET0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x38)) \r
+#define FIO2SET0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x48)) \r
+#define FIO3SET0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x58)) \r
+#define FIO4SET0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x98)) \r
+\r
+#define FIO0SET1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x19)) \r
+#define FIO1SET1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x39)) \r
+#define FIO2SET1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x49)) \r
+#define FIO3SET1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x59)) \r
+#define FIO4SET1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x99)) \r
+\r
+#define FIO0SET2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x1A)) \r
+#define FIO1SET2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x3A)) \r
+#define FIO2SET2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x4A)) \r
+#define FIO3SET2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x5A)) \r
+#define FIO4SET2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x9A)) \r
+\r
+#define FIO0SET3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x1B)) \r
+#define FIO1SET3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x3B)) \r
+#define FIO2SET3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x4B)) \r
+#define FIO3SET3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x5B)) \r
+#define FIO4SET3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x9B)) \r
+\r
+#define FIO0SETL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x18)) \r
+#define FIO1SETL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x38)) \r
+#define FIO2SETL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x48)) \r
+#define FIO3SETL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x58)) \r
+#define FIO4SETL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x98)) \r
+\r
+#define FIO0SETU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x1A)) \r
+#define FIO1SETU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x3A)) \r
+#define FIO2SETU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x4A)) \r
+#define FIO3SETU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x5A)) \r
+#define FIO4SETU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x9A)) \r
+\r
+#define FIO0CLR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x1C)) \r
+#define FIO1CLR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x3C)) \r
+#define FIO2CLR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x4C)) \r
+#define FIO3CLR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x5C)) \r
+#define FIO4CLR0 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x9C)) \r
+\r
+#define FIO0CLR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x1D)) \r
+#define FIO1CLR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x3D)) \r
+#define FIO2CLR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x4D)) \r
+#define FIO3CLR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x5D)) \r
+#define FIO4CLR1 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x9D)) \r
+\r
+#define FIO0CLR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x1E)) \r
+#define FIO1CLR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x3E)) \r
+#define FIO2CLR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x4E)) \r
+#define FIO3CLR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x5E)) \r
+#define FIO4CLR2 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x9E)) \r
+\r
+#define FIO0CLR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x1F)) \r
+#define FIO1CLR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x3F)) \r
+#define FIO2CLR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x4F)) \r
+#define FIO3CLR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x5F)) \r
+#define FIO4CLR3 (*(volatile unsigned char *)(GPIO_BASE_ADDR + 0x9F)) \r
+\r
+#define FIO0CLRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x1C)) \r
+#define FIO1CLRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x3C)) \r
+#define FIO2CLRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x4C)) \r
+#define FIO3CLRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x5C)) \r
+#define FIO4CLRL (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x9C)) \r
+\r
+#define FIO0CLRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x1E)) \r
+#define FIO1CLRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x3E)) \r
+#define FIO2CLRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x4E)) \r
+#define FIO3CLRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x5E)) \r
+#define FIO4CLRU (*(volatile unsigned short *)(GPIO_BASE_ADDR + 0x9E)) \r
+\r
+/* GPIO Interrupt Registers */\r
+#define GPIO_INT_BASE_ADDR 0x40028000\r
+#define IO0IntEnR (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0x90)) \r
+#define IO0IntEnF (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0x94))\r
+#define IO0IntStatR (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0x84))\r
+#define IO0IntStatF (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0x88))\r
+#define IO0IntClr (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0x8C))\r
+\r
+#define IO2IntEnR (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0xB0)) \r
+#define IO2IntEnF (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0xB4))\r
+#define IO2IntStatR (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0xA4))\r
+#define IO2IntStatF (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0xA8))\r
+#define IO2IntClr (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0xAC))\r
+\r
+#define IOIntStatus (*(volatile unsigned long *)(GPIO_INT_BASE_ADDR + 0x80))\r
+\r
+\r
+/* Timer 0 */\r
+#define TMR0_BASE_ADDR 0x40004000\r
+#define T0IR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x00))\r
+#define T0TCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x04))\r
+#define T0TC (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x08))\r
+#define T0PR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x0C))\r
+#define T0PC (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x10))\r
+#define T0MCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x14))\r
+#define T0MR0 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x18))\r
+#define T0MR1 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x1C))\r
+#define T0MR2 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x20))\r
+#define T0MR3 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x24))\r
+#define T0CCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x28))\r
+#define T0CR0 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x2C))\r
+#define T0CR1 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x30))\r
+#define T0CR2 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x34))\r
+#define T0CR3 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x38))\r
+#define T0EMR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x3C))\r
+#define T0CTCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x70))\r
+\r
+/* Timer 1 */\r
+#define TMR1_BASE_ADDR 0x40008000\r
+#define T1IR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x00))\r
+#define T1TCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x04))\r
+#define T1TC (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x08))\r
+#define T1PR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x0C))\r
+#define T1PC (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x10))\r
+#define T1MCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x14))\r
+#define T1MR0 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x18))\r
+#define T1MR1 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x1C))\r
+#define T1MR2 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x20))\r
+#define T1MR3 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x24))\r
+#define T1CCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x28))\r
+#define T1CR0 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x2C))\r
+#define T1CR1 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x30))\r
+#define T1CR2 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x34))\r
+#define T1CR3 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x38))\r
+#define T1EMR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x3C))\r
+#define T1CTCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x70))\r
+\r
+/* Timer 2 */\r
+#define TMR2_BASE_ADDR 0x40090000\r
+#define T2IR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x00))\r
+#define T2TCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x04))\r
+#define T2TC (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x08))\r
+#define T2PR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x0C))\r
+#define T2PC (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x10))\r
+#define T2MCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x14))\r
+#define T2MR0 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x18))\r
+#define T2MR1 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x1C))\r
+#define T2MR2 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x20))\r
+#define T2MR3 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x24))\r
+#define T2CCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x28))\r
+#define T2CR0 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x2C))\r
+#define T2CR1 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x30))\r
+#define T2CR2 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x34))\r
+#define T2CR3 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x38))\r
+#define T2EMR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x3C))\r
+#define T2CTCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x70))\r
+\r
+/* Timer 3 */\r
+#define TMR3_BASE_ADDR 0x40094000\r
+#define T3IR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x00))\r
+#define T3TCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x04))\r
+#define T3TC (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x08))\r
+#define T3PR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x0C))\r
+#define T3PC (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x10))\r
+#define T3MCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x14))\r
+#define T3MR0 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x18))\r
+#define T3MR1 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x1C))\r
+#define T3MR2 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x20))\r
+#define T3MR3 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x24))\r
+#define T3CCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x28))\r
+#define T3CR0 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x2C))\r
+#define T3CR1 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x30))\r
+#define T3CR2 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x34))\r
+#define T3CR3 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x38))\r
+#define T3EMR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x3C))\r
+#define T3CTCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x70))\r
+\r
+\r
+/* Pulse Width Modulator (PWM) */\r
+#define PWM1_BASE_ADDR 0x40018000\r
+#define PWM1IR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x00))\r
+#define PWM1TCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x04))\r
+#define PWM1TC (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x08))\r
+#define PWM1PR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x0C))\r
+#define PWM1PC (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x10))\r
+#define PWM1MCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x14))\r
+#define PWM1MR0 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x18))\r
+#define PWM1MR1 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x1C))\r
+#define PWM1MR2 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x20))\r
+#define PWM1MR3 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x24))\r
+#define PWM1CCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x28))\r
+#define PWM1CR0 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x2C))\r
+#define PWM1CR1 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x30))\r
+#define PWM1CR2 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x34))\r
+#define PWM1CR3 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x38))\r
+#define PWM1MR4 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x40))\r
+#define PWM1MR5 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x44))\r
+#define PWM1MR6 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x48))\r
+#define PWM1PCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x4C))\r
+#define PWM1LER (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x50))\r
+#define PWM1CTCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x70))\r
+\r
+\r
+/* Universal Asynchronous Receiver Transmitter 0 (UART0) */\r
+#define UART0_BASE_ADDR 0x4000C000\r
+#define U0RBR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x00))\r
+#define U0THR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x00))\r
+#define U0DLL (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x00))\r
+#define U0DLM (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x04))\r
+#define U0IER (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x04))\r
+#define U0IIR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x08))\r
+#define U0FCR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x08))\r
+#define U0LCR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x0C))\r
+#define U0LSR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x14))\r
+#define U0SCR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x1C))\r
+#define U0ACR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x20))\r
+#define U0FDR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x28))\r
+#define U0TER (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x30))\r
+#define U0RS485CTRL (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x4C))\r
+#define U0ADRMATCH (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x50))\r
+\r
+/* Universal Asynchronous Receiver Transmitter 1 (UART1) */\r
+#define UART1_BASE_ADDR 0x40010000\r
+#define U1RBR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x00))\r
+#define U1THR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x00))\r
+#define U1DLL (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x00))\r
+#define U1DLM (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x04))\r
+#define U1IER (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x04))\r
+#define U1IIR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x08))\r
+#define U1FCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x08))\r
+#define U1LCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x0C))\r
+#define U1MCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x10))\r
+#define U1LSR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x14))\r
+#define U1MSR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x18))\r
+#define U1SCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x1C))\r
+#define U1ACR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x20))\r
+#define U1FDR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x28))\r
+#define U1TER (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x30))\r
+#define U1RS485CTRL (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x4C))\r
+#define U1ADRMATCH (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x50))\r
+#define U1RS485DLY (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x54))\r
+\r
+/* Universal Asynchronous Receiver Transmitter 2 (UART2) */\r
+#define UART2_BASE_ADDR 0x40098000\r
+#define U2RBR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x00))\r
+#define U2THR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x00))\r
+#define U2DLL (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x00))\r
+#define U2DLM (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x04))\r
+#define U2IER (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x04))\r
+#define U2IIR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x08))\r
+#define U2FCR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x08))\r
+#define U2LCR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x0C))\r
+#define U2LSR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x14))\r
+#define U2SCR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x1C))\r
+#define U2ACR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x20))\r
+#define U2FDR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x28))\r
+#define U2TER (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x30))\r
+#define U2RS485CTRL (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x4C))\r
+#define U2ADRMATCH (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x50))\r
+\r
+/* Universal Asynchronous Receiver Transmitter 3 (UART3) */\r
+#define UART3_BASE_ADDR 0x4009C000\r
+#define U3RBR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x00))\r
+#define U3THR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x00))\r
+#define U3DLL (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x00))\r
+#define U3DLM (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x04))\r
+#define U3IER (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x04))\r
+#define U3IIR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x08))\r
+#define U3FCR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x08))\r
+#define U3LCR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x0C))\r
+#define U3LSR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x14))\r
+#define U3SCR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x1C))\r
+#define U3ACR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x20))\r
+#define U3ICR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x24))\r
+#define U3FDR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x28))\r
+#define U3TER (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x30))\r
+#define U3RS485CTRL (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x4C))\r
+#define U3ADRMATCH (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x50))\r
+\r
+\r
+/* SPI0 (Serial Peripheral Interface 0) */\r
+#define SPI0_BASE_ADDR 0x40020000\r
+#define S0SPCR (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x00))\r
+#define S0SPSR (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x04))\r
+#define S0SPDR (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x08))\r
+#define S0SPCCR (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x0C))\r
+#define S0SPINT (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x1C))\r
+\r
+/* SSP0 Controller */\r
+#define SSP0_BASE_ADDR 0x40088000\r
+#define SSP0CR0 (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x00))\r
+#define SSP0CR1 (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x04))\r
+#define SSP0DR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x08))\r
+#define SSP0SR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x0C))\r
+#define SSP0CPSR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x10))\r
+#define SSP0IMSC (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x14))\r
+#define SSP0RIS (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x18))\r
+#define SSP0MIS (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x1C))\r
+#define SSP0ICR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x20))\r
+#define SSP0DMACR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x24))\r
+\r
+/* SSP1 Controller */\r
+#define SSP1_BASE_ADDR 0x40030000\r
+#define SSP1CR0 (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x00))\r
+#define SSP1CR1 (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x04))\r
+#define SSP1DR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x08))\r
+#define SSP1SR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x0C))\r
+#define SSP1CPSR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x10))\r
+#define SSP1IMSC (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x14))\r
+#define SSP1RIS (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x18))\r
+#define SSP1MIS (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x1C))\r
+#define SSP1ICR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x20))\r
+#define SSP1DMACR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x24))\r
+\r
+\r
+/* I2C Interface 0 */\r
+#define I2C0_BASE_ADDR 0x4001C000\r
+#define I2C0CONSET (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x00))\r
+#define I2C0STAT (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x04))\r
+#define I2C0DAT (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x08))\r
+#define I2C0ADR0 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x0C))\r
+#define I2C0SCLH (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x10))\r
+#define I2C0SCLL (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x14))\r
+#define I2C0CONCLR (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x18))\r
+#define I2C0MMCLR (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x1C))\r
+#define I2C0ADR1 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x20))\r
+#define I2C0ADR2 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x24))\r
+#define I2C0ADR3 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x28))\r
+#define I2C0DATBUFFER (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x2C))\r
+#define I2C0MASK0 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x30))\r
+#define I2C0MASK1 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x34))\r
+#define I2C0MASK2 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x38))\r
+#define I2C0MASK3 (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x3C))\r
+\r
+/* I2C Interface 1 */\r
+#define I2C1_BASE_ADDR 0x4005C000\r
+#define I2C1CONSET (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x00))\r
+#define I2C1STAT (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x04))\r
+#define I2C1DAT (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x08))\r
+#define I2C1ADR0 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x0C))\r
+#define I2C1SCLH (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x10))\r
+#define I2C1SCLL (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x14))\r
+#define I2C1CONCLR (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x18))\r
+#define I2C1MMCLR (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x1C))\r
+#define I2C1ADR1 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x20))\r
+#define I2C1ADR2 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x24))\r
+#define I2C1ADR3 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x28))\r
+#define I2C1DATBUFFER (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x2C))\r
+#define I2C1MASK0 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x30))\r
+#define I2C1MASK1 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x34))\r
+#define I2C1MASK2 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x38))\r
+#define I2C1MASK3 (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x3C))\r
+\r
+/* I2C Interface 2 */\r
+#define I2C2_BASE_ADDR 0x400A0000\r
+#define I2C2CONSET (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x00))\r
+#define I2C2STAT (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x04))\r
+#define I2C2DAT (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x08))\r
+#define I2C2ADR0 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x0C))\r
+#define I2C2SCLH (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x10))\r
+#define I2C2SCLL (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x14))\r
+#define I2C2CONCLR (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x18))\r
+#define I2C2MMCLR (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x1C))\r
+#define I2C2ADR1 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x20))\r
+#define I2C2ADR2 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x24))\r
+#define I2C2ADR3 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x28))\r
+#define I2C2DATBUFFER (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x2C))\r
+#define I2C2MASK0 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x30))\r
+#define I2C2MASK1 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x34))\r
+#define I2C2MASK2 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x38))\r
+#define I2C2MASK3 (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x3C))\r
+\r
+\r
+/* I2S Interface Controller (I2S) */\r
+#define I2S_BASE_ADDR 0x400A8000\r
+#define I2SDAO (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x00))\r
+#define I2SDAI (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x04))\r
+#define I2STXFIFO (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x08))\r
+#define I2SRXFIFO (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x0C))\r
+#define I2SSTATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x10))\r
+#define I2SDMA1 (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x14))\r
+#define I2SDMA2 (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x18))\r
+#define I2SIRQ (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x1C))\r
+#define I2STXRATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x20))\r
+#define I2SRXRATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x24))\r
+#define I2STXBITRATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x28))\r
+#define I2SRXBITRATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x2C))\r
+#define I2STXMODE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x30))\r
+#define I2SRXMODE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x34))\r
+\r
+\r
+/* Repetitive Interrupt Timer (RIT) */\r
+#define RIT_BASE_ADDR 0x400B4000\r
+#define RICOMPVAL (*(volatile unsigned long *)(RIT_BASE_ADDR + 0x00))\r
+#define RIMASK (*(volatile unsigned long *)(RIT_BASE_ADDR + 0x04))\r
+#define RICTRL (*(volatile unsigned long *)(RIT_BASE_ADDR + 0x08))\r
+#define RICOUNTER (*(volatile unsigned long *)(RIT_BASE_ADDR + 0x0C))\r
+\r
+\r
+/* Real Time Clock (RTC) */\r
+#define RTC_BASE_ADDR 0x40024000\r
+#define RTC_ILR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x00))\r
+#define RTC_CCR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x08))\r
+#define RTC_CIIR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x0C))\r
+#define RTC_AMR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x10))\r
+#define RTC_CTIME0 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x14))\r
+#define RTC_CTIME1 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x18))\r
+#define RTC_CTIME2 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x1C))\r
+#define RTC_SEC (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x20))\r
+#define RTC_MIN (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x24))\r
+#define RTC_HOUR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x28))\r
+#define RTC_DOM (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x2C))\r
+#define RTC_DOW (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x30))\r
+#define RTC_DOY (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x34))\r
+#define RTC_MONTH (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x38))\r
+#define RTC_YEAR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x3C))\r
+#define RTC_CALIBRATION (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x40))\r
+#define RTC_GPREG0 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x44))\r
+#define RTC_GPREG1 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x48))\r
+#define RTC_GPREG2 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x4C))\r
+#define RTC_GPREG3 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x50))\r
+#define RTC_GPREG4 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x54))\r
+#define RTC_WAKEUPDIS (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x58))\r
+#define RTC_PWRCTRL (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x5c))\r
+#define RTC_ALSEC (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x60))\r
+#define RTC_ALMIN (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x64))\r
+#define RTC_ALHOUR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x68))\r
+#define RTC_ALDOM (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x6C))\r
+#define RTC_ALDOW (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x70))\r
+#define RTC_ALDOY (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x74))\r
+#define RTC_ALMON (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x78))\r
+#define RTC_ALYEAR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x7C))\r
+\r
+\r
+/* Watchdog Timer (WDT) */\r
+#define WDT_BASE_ADDR 0x40000000\r
+#define WDMOD (*(volatile unsigned long *)(WDT_BASE_ADDR + 0x00))\r
+#define WDTC (*(volatile unsigned long *)(WDT_BASE_ADDR + 0x04))\r
+#define WDFEED (*(volatile unsigned long *)(WDT_BASE_ADDR + 0x08))\r
+#define WDTV (*(volatile unsigned long *)(WDT_BASE_ADDR + 0x0C))\r
+#define WDCLKSEL (*(volatile unsigned long *)(WDT_BASE_ADDR + 0x10))\r
+\r
+\r
+/* A/D Converter 0 (ADC0) */\r
+#define AD0_BASE_ADDR 0x40034000\r
+#define AD0CR (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x00))\r
+#define AD0GDR (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x04))\r
+#define AD0INTEN (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x0C))\r
+#define AD0DR0 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x10))\r
+#define AD0DR1 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x14))\r
+#define AD0DR2 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x18))\r
+#define AD0DR3 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x1C))\r
+#define AD0DR4 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x20))\r
+#define AD0DR5 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x24))\r
+#define AD0DR6 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x28))\r
+#define AD0DR7 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x2C))\r
+#define AD0STAT (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x30))\r
+#define ADTRIM (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x34))\r
+\r
+\r
+/* D/A Converter (DAC) */\r
+#define DAC_BASE_ADDR 0x4008C000\r
+#define DACR (*(volatile unsigned long *)(DAC_BASE_ADDR + 0x00))\r
+#define DACCTRL (*(volatile unsigned long *)(DAC_BASE_ADDR + 0x04))\r
+#define DACCNTVAL (*(volatile unsigned long *)(DAC_BASE_ADDR + 0x08))\r
+\r
+\r
+/* Motor Control PWM */\r
+#define MCPWM_BASE_ADDR 0x400B8000\r
+#define MCCON (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x00))\r
+#define MCCON_SET (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x04))\r
+#define MCCON_CLR (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x08))\r
+#define MCCAPCON (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x0C))\r
+#define MCCAPCON_SET (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x10))\r
+#define MCCAPCON_CLR (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x14))\r
+#define MCTIM0 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x18))\r
+#define MCTIM1 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x1C))\r
+#define MCTIM2 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x20))\r
+#define MCPER0 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x24))\r
+#define MCPER1 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x28))\r
+#define MCPER2 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x2C))\r
+#define MCPW0 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x30))\r
+#define MCPW1 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x34))\r
+#define MCPW2 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x38))\r
+#define MCDEADTIME (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x3C))\r
+#define MCCCP (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x40))\r
+#define MCCR0 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x44))\r
+#define MCCR1 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x48))\r
+#define MCCR2 (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x4C))\r
+#define MCINTEN (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x50))\r
+#define MCINTEN_SET (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x54))\r
+#define MCINTEN_CLR (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x58))\r
+#define MCCNTCON (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x5C))\r
+#define MCCNTCON_SET (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x60))\r
+#define MCCNTCON_CLR (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x64))\r
+#define MCINTFLAG (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x68))\r
+#define MCINTFLAG_SET (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x6C))\r
+#define MCINTFLAG_CLR (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x70))\r
+#define MCCAP_CLR (*(volatile unsigned long *)(MCPWM_BASE_ADDR + 0x74))\r
+\r
+\r
+/* Quadrature Encoder Interface (QEI) */\r
+#define QEI_BASE_ADDR 0x400BC000\r
+\r
+/* QEI Control Registers */\r
+#define QEICON (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x000))\r
+#define QEISTAT (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x004))\r
+#define QEICONF (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x008))\r
+\r
+/* QEI Position, Index, and Timer Registers */\r
+#define QEIPOS (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x00C))\r
+#define QEIMAXPSOS (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x010))\r
+#define CMPOS0 (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x014))\r
+#define CMPOS1 (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x018))\r
+#define CMPOS2 (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x01C))\r
+#define INXCNT (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x020))\r
+#define INXCMP (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x024))\r
+#define QEILOAD (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x028))\r
+#define QEITIME (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x02C))\r
+#define QEIVEL (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x030))\r
+#define QEICAP (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x034))\r
+#define VELCOMP (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x038))\r
+#define FILTER (*(volatile unsigned long *)(QEI_BASE_ADDR + 0x03C))\r
+\r
+/* QEI Interrupt registers */\r
+#define QEIIES (*(volatile unsigned long *)(QEI_BASE_ADDR + 0xFDC))\r
+#define QEIIEC (*(volatile unsigned long *)(QEI_BASE_ADDR + 0xFD8))\r
+#define QEIINTSTAT (*(volatile unsigned long *)(QEI_BASE_ADDR + 0xFE0))\r
+#define QEIIE (*(volatile unsigned long *)(QEI_BASE_ADDR + 0xFE4))\r
+#define QEICLR (*(volatile unsigned long *)(QEI_BASE_ADDR + 0xFE8))\r
+#define QEISET (*(volatile unsigned long *)(QEI_BASE_ADDR + 0xFEC))\r
+\r
+\r
+/* CAN Controllers and Acceptance Filter */\r
+\r
+/* CAN Acceptance Filter */\r
+#define CAN_AF_BASE_ADDR 0x4003C000\r
+#define AFMR (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x00)) \r
+#define SFF_sa (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x04)) \r
+#define SFF_GRP_sa (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x08))\r
+#define EFF_sa (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x0C))\r
+#define EFF_GRP_sa (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x10)) \r
+#define ENDofTable (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x14))\r
+#define LUTerrAd (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x18)) \r
+#define LUTerr (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x1C))\r
+#define FCANIE (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x20))\r
+#define FCANIC0 (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x24))\r
+#define FCANIC1 (*(volatile unsigned long *)(CAN_AF_BASE_ADDR + 0x28))\r
+\r
+/* CAN Centralized Registers */\r
+#define CAN_BASE_ADDR 0x40040000 \r
+#define CANTxSR (*(volatile unsigned long *)(CAN_BASE_ADDR + 0x00)) \r
+#define CANRxSR (*(volatile unsigned long *)(CAN_BASE_ADDR + 0x04)) \r
+#define CANMSR (*(volatile unsigned long *)(CAN_BASE_ADDR + 0x08))\r
+\r
+/* CAN1 Controller */\r
+#define CAN1_BASE_ADDR 0x40044000\r
+#define CAN1MOD (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x00)) \r
+#define CAN1CMR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x04)) \r
+#define CAN1GSR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x08)) \r
+#define CAN1ICR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x0C)) \r
+#define CAN1IER (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x10))\r
+#define CAN1BTR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x14)) \r
+#define CAN1EWL (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x18)) \r
+#define CAN1SR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x1C)) \r
+#define CAN1RFS (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x20)) \r
+#define CAN1RID (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x24))\r
+#define CAN1RDA (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x28)) \r
+#define CAN1RDB (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x2C)) \r
+#define CAN1TFI1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x30)) \r
+#define CAN1TID1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x34)) \r
+#define CAN1TDA1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x38))\r
+#define CAN1TDB1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x3C)) \r
+#define CAN1TFI2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x40)) \r
+#define CAN1TID2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x44)) \r
+#define CAN1TDA2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x48)) \r
+#define CAN1TDB2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x4C))\r
+#define CAN1TFI3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x50)) \r
+#define CAN1TID3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x54)) \r
+#define CAN1TDA3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x58)) \r
+#define CAN1TDB3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x5C))\r
+\r
+/* CAN2 Controller */\r
+#define CAN2_BASE_ADDR 0x40048000\r
+#define CAN2MOD (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x00)) \r
+#define CAN2CMR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x04)) \r
+#define CAN2GSR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x08)) \r
+#define CAN2ICR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x0C)) \r
+#define CAN2IER (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x10))\r
+#define CAN2BTR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x14)) \r
+#define CAN2EWL (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x18)) \r
+#define CAN2SR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x1C)) \r
+#define CAN2RFS (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x20)) \r
+#define CAN2RID (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x24))\r
+#define CAN2RDA (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x28)) \r
+#define CAN2RDB (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x2C)) \r
+#define CAN2TFI1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x30)) \r
+#define CAN2TID1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x34)) \r
+#define CAN2TDA1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x38))\r
+#define CAN2TDB1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x3C)) \r
+#define CAN2TFI2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x40)) \r
+#define CAN2TID2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x44)) \r
+#define CAN2TDA2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x48)) \r
+#define CAN2TDB2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x4C))\r
+#define CAN2TFI3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x50)) \r
+#define CAN2TID3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x54)) \r
+#define CAN2TDA3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x58)) \r
+#define CAN2TDB3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x5C))\r
+\r
+\r
+/* General Purpose DMA Controller (GPDMA) */\r
+#define DMA_BASE_ADDR 0x50004000\r
+#define DMACIntStat (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x000))\r
+#define DMACIntTCStat (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x004))\r
+#define DMACIntTCClear (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x008))\r
+#define DMACIntErrStat (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x00C))\r
+#define DMACIntErrClr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x010))\r
+#define DMACRawIntTCStat (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x014))\r
+#define DMACRawIntErrStat (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x018))\r
+#define DMACEnbldChns (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x01C))\r
+#define DMACSoftBReq (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x020))\r
+#define DMACSoftSReq (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x024))\r
+#define DMACSoftLBReq (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x028))\r
+#define DMACSoftLSReq (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x02C))\r
+#define DMACConfig (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x030))\r
+#define DMACSync (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x034))\r
+\r
+/* DMA Channel 0 Registers */\r
+#define DMACC0SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x100))\r
+#define DMACC0DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x104))\r
+#define DMACC0LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x108))\r
+#define DMACC0Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x10C))\r
+#define DMACC0Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x110))\r
+\r
+/* DMA Channel 1 Registers */\r
+#define DMACC1SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x120))\r
+#define DMACC1DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x124))\r
+#define DMACC1LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x128))\r
+#define DMACC1Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x12C))\r
+#define DMACC1Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x130))\r
+\r
+/* DMA Channel 2 Registers */\r
+#define DMACC2SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x140))\r
+#define DMACC2DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x144))\r
+#define DMACC2LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x148))\r
+#define DMACC2Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x14C))\r
+#define DMACC2Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x150))\r
+\r
+/* DMA Channel 3 Registers */\r
+#define DMACC3SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x160))\r
+#define DMACC3DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x164))\r
+#define DMACC3LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x168))\r
+#define DMACC3Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x16C))\r
+#define DMACC3Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x170))\r
+\r
+/* DMA Channel 4 Registers */\r
+#define DMACC4SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x180))\r
+#define DMACC4DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x184))\r
+#define DMACC4LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x188))\r
+#define DMACC4Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x18C))\r
+#define DMACC4Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x190))\r
+\r
+/* DMA Channel 5 Registers */\r
+#define DMACC5SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1A0))\r
+#define DMACC5DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1A4))\r
+#define DMACC5LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1A8))\r
+#define DMACC5Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1AC))\r
+#define DMACC5Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1B0))\r
+\r
+/* DMA Channel 6 Registers */\r
+#define DMACC6SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1C0))\r
+#define DMACC6DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1C4))\r
+#define DMACC6LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1C8))\r
+#define DMACC6Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1CC))\r
+#define DMACC6Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1D0))\r
+\r
+/* DMA Channel 7 Registers */\r
+#define DMACC7SrcAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1E0))\r
+#define DMACC7DestAddr (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1E4))\r
+#define DMACC7LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1E8))\r
+#define DMACC7Control (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1EC))\r
+#define DMACC7Config (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x1F0))\r
+\r
+\r
+/* USB Controller */\r
+#define USB_BASE_ADDR 0x5000C000\r
+\r
+#define USBIntSt (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1C0))\r
+\r
+\r
+/* USB Device Controller */\r
+\r
+/* USB Device Clock Control Registers */\r
+#define USBClkCtrl (*(volatile unsigned long *)(USB_BASE_ADDR + 0xFF4))\r
+#define USBClkSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0xFF8))\r
+\r
+/* USB Device Interrupt Registers */\r
+#define USBDevIntSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x200))\r
+#define USBDevIntEn (*(volatile unsigned long *)(USB_BASE_ADDR + 0x204))\r
+#define USBDevIntClr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x208))\r
+#define USBDevIntSet (*(volatile unsigned long *)(USB_BASE_ADDR + 0x20C))\r
+#define USBDevIntPri (*(volatile unsigned long *)(USB_BASE_ADDR + 0x22C))\r
+\r
+/* USB Device Endpoint Interrupt Registers */\r
+#define USBEpIntSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x230))\r
+#define USBEpIntEn (*(volatile unsigned long *)(USB_BASE_ADDR + 0x234))\r
+#define USBEpIntClr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x238))\r
+#define USBEpIntSet (*(volatile unsigned long *)(USB_BASE_ADDR + 0x23C))\r
+#define USBEpIntPri (*(volatile unsigned long *)(USB_BASE_ADDR + 0x240))\r
+\r
+/* USB Device Endpoint Realization Registers */\r
+#define USBReEp (*(volatile unsigned long *)(USB_BASE_ADDR + 0x244))\r
+#define USBEpInd (*(volatile unsigned long *)(USB_BASE_ADDR + 0x248))\r
+#define USBMaxPSize (*(volatile unsigned long *)(USB_BASE_ADDR + 0x24C))\r
+\r
+/* USB Device SIE Command Reagisters */\r
+#define USBCmdCode (*(volatile unsigned long *)(USB_BASE_ADDR + 0x210))\r
+#define USBCmdData (*(volatile unsigned long *)(USB_BASE_ADDR + 0x214))\r
+\r
+/* USB Device Data Transfer Registers */\r
+#define USBRxData (*(volatile unsigned long *)(USB_BASE_ADDR + 0x218))\r
+#define USBTxData (*(volatile unsigned long *)(USB_BASE_ADDR + 0x21C))\r
+#define USBRxPLen (*(volatile unsigned long *)(USB_BASE_ADDR + 0x220))\r
+#define USBTxPLen (*(volatile unsigned long *)(USB_BASE_ADDR + 0x224))\r
+#define USBCtrl (*(volatile unsigned long *)(USB_BASE_ADDR + 0x228))\r
+\r
+/* USB Device DMA Registers */\r
+#define USBDMARSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x250))\r
+#define USBDMARClr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x254))\r
+#define USBDMARSet (*(volatile unsigned long *)(USB_BASE_ADDR + 0x258))\r
+#define USBUDCAH (*(volatile unsigned long *)(USB_BASE_ADDR + 0x280))\r
+#define USBEpDMASt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x284))\r
+#define USBEpDMAEn (*(volatile unsigned long *)(USB_BASE_ADDR + 0x288))\r
+#define USBEpDMADis (*(volatile unsigned long *)(USB_BASE_ADDR + 0x28C))\r
+#define USBDMAIntSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x290))\r
+#define USBDMAIntEn (*(volatile unsigned long *)(USB_BASE_ADDR + 0x294))\r
+#define USBEoTIntSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2A0))\r
+#define USBEoTIntClr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2A4))\r
+#define USBEoTIntSet (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2A8))\r
+#define USBNDDRIntSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2AC))\r
+#define USBNDDRIntClr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2B0))\r
+#define USBNDDRIntSet (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2B4))\r
+#define USBSysErrIntSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2B8))\r
+#define USBSysErrIntClr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2BC))\r
+#define USBSysErrIntSet (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2C0))\r
+\r
+\r
+/* USB Host Controller */\r
+#define HcRevision (*(volatile unsigned long *)(USB_BASE_ADDR + 0x000))\r
+#define HcControl (*(volatile unsigned long *)(USB_BASE_ADDR + 0x004))\r
+#define HcCommandStatus (*(volatile unsigned long *)(USB_BASE_ADDR + 0x008))\r
+#define HcInterruptStatus (*(volatile unsigned long *)(USB_BASE_ADDR + 0x00C))\r
+#define HcInterruptEnable (*(volatile unsigned long *)(USB_BASE_ADDR + 0x010))\r
+#define HcInterruptDisable (*(volatile unsigned long *)(USB_BASE_ADDR + 0x014))\r
+#define HcHCCA (*(volatile unsigned long *)(USB_BASE_ADDR + 0x018))\r
+#define HcPeriodCurrentED (*(volatile unsigned long *)(USB_BASE_ADDR + 0x01C))\r
+#define HcControlHeadED (*(volatile unsigned long *)(USB_BASE_ADDR + 0x020))\r
+#define HcControlCurrentED (*(volatile unsigned long *)(USB_BASE_ADDR + 0x024))\r
+#define HcBulkHeadED (*(volatile unsigned long *)(USB_BASE_ADDR + 0x028))\r
+#define HcBulkCurrentED (*(volatile unsigned long *)(USB_BASE_ADDR + 0x02C))\r
+#define HcDoneHead (*(volatile unsigned long *)(USB_BASE_ADDR + 0x030))\r
+#define HcFmInterval (*(volatile unsigned long *)(USB_BASE_ADDR + 0x034))\r
+#define HcFmRemaining (*(volatile unsigned long *)(USB_BASE_ADDR + 0x038))\r
+#define HcFmNumber (*(volatile unsigned long *)(USB_BASE_ADDR + 0x03C))\r
+#define HcPeriodStart (*(volatile unsigned long *)(USB_BASE_ADDR + 0x040))\r
+#define HcLSThreshold (*(volatile unsigned long *)(USB_BASE_ADDR + 0x044))\r
+#define HcRhDescriptorA (*(volatile unsigned long *)(USB_BASE_ADDR + 0x048))\r
+#define HcRhDescriptorB (*(volatile unsigned long *)(USB_BASE_ADDR + 0x04C))\r
+#define HcRhStatus (*(volatile unsigned long *)(USB_BASE_ADDR + 0x050))\r
+#define HcRhPortStatus1 (*(volatile unsigned long *)(USB_BASE_ADDR + 0x054))\r
+#define HcRhPortStatus2 (*(volatile unsigned long *)(USB_BASE_ADDR + 0x058))\r
+\r
+\r
+/* USB OTG Controller */\r
+\r
+/* USB OTG Registers */\r
+#define OTGIntSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0x100))\r
+#define OTGIntEn (*(volatile unsigned long *)(USB_BASE_ADDR + 0x104))\r
+#define OTGIntSet (*(volatile unsigned long *)(USB_BASE_ADDR + 0x108))\r
+#define OTGIntClr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x10C))\r
+#define OTGIntCtrl (*(volatile unsigned long *)(USB_BASE_ADDR + 0x110))\r
+#define OTGTmr (*(volatile unsigned long *)(USB_BASE_ADDR + 0x114))\r
+\r
+/* USB OTG I2C Registers */\r
+#define I2C_RX (*(volatile unsigned long *)(USB_BASE_ADDR + 0x300))\r
+#define I2C_TX (*(volatile unsigned long *)(USB_BASE_ADDR + 0x300))\r
+#define I2C_STS (*(volatile unsigned long *)(USB_BASE_ADDR + 0x304))\r
+#define I2C_CTL (*(volatile unsigned long *)(USB_BASE_ADDR + 0x308))\r
+#define I2C_CLKHI (*(volatile unsigned long *)(USB_BASE_ADDR + 0x30C))\r
+#define I2C_CLKLO (*(volatile unsigned long *)(USB_BASE_ADDR + 0x310))\r
+\r
+/* USB OTG Clock Control Registers */\r
+#define OTGClkCtrl (*(volatile unsigned long *)(USB_BASE_ADDR + 0xFF4))\r
+#define OTGClkSt (*(volatile unsigned long *)(USB_BASE_ADDR + 0xFF8))\r
+\r
+\r
+/* Ethernet MAC */\r
+#define MAC_BASE_ADDR 0x50000000\r
+\r
+/* MAC Registers */\r
+#define ETH_MAC1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x000))\r
+#define ETH_MAC2 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x004))\r
+#define ETH_IPGT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x008))\r
+#define ETH_IPGR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x00C))\r
+#define ETH_CLRT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x010))\r
+#define ETH_MAXF (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x014))\r
+#define ETH_PHYSUPP (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x018))\r
+#define ETH_TEST (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x01C))\r
+#define ETH_MIICFG (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x020))\r
+#define ETH_MIICMD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x024))\r
+#define ETH_MIIADR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x028))\r
+#define ETH_MIIWTD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x02C))\r
+#define ETH_MIIRDD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x030))\r
+#define ETH_MIIIND (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x034))\r
+#define ETH_SA0 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x040))\r
+#define ETH_SA1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x044))\r
+#define ETH_SA2 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x048))\r
+\r
+/* MAC Control Registers */\r
+#define ETH_COMMAND (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x100))\r
+#define ETH_STATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x104))\r
+#define ETH_RXDESC (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x108))\r
+#define ETH_RXSTAT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x10C))\r
+#define ETH_RXDESCRNO (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x110))\r
+#define ETH_RXPRODIX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x114))\r
+#define ETH_RXCONSIX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x118))\r
+#define ETH_TXDESC (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x11C))\r
+#define ETH_TXSTAT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x120))\r
+#define ETH_TXDESCRNO (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x124))\r
+#define ETH_TXPRODIX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x128))\r
+#define ETH_TXCONSIX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x12C))\r
+#define ETH_TSV0 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x158))\r
+#define ETH_TSV1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x15C))\r
+#define ETH_RSV (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x160))\r
+#define ETH_FLOWCNTCOUNT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x170))\r
+#define ETH_FLOWCNTSTAT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x174))\r
+\r
+/* MAX Rx Filter Registers */\r
+#define ETH_RXFILTERCTL (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x200))\r
+#define ETH_RXFILTERWOLSTAT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x204))\r
+#define ETH_RXFILTERWOLCLR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x208))\r
+#define ETH_HASHFILTERL (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x210))\r
+#define ETH_HASHFILTERH (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x214))\r
+\r
+/* MAC Module Control Registers */\r
+#define ETH_INSTSTAT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE0))\r
+#define ETH_INTENABLE (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE4))\r
+#define ETH_INTCLEAR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE8))\r
+#define ETH_INTSET (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFEC))\r
+#define ETH_POWERDOWN (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFF4))\r
+\r
+#define MAC_Module_ID (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFFC))\r
+\r
+/* Ethernet MAC (32 bit data bus) -- all registers are RW unless indicated in parentheses */\r
+#define MAC_BASE_ADDR 0x50000000\r
+#define MAC_MAC1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x000)) /* MAC config reg 1 */\r
+#define MAC_MAC2 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x004)) /* MAC config reg 2 */\r
+#define MAC_IPGT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x008)) /* b2b InterPacketGap reg */\r
+#define MAC_IPGR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x00C)) /* non b2b InterPacketGap reg */\r
+#define MAC_CLRT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x010)) /* CoLlision window/ReTry reg */\r
+#define MAC_MAXF (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x014)) /* MAXimum Frame reg */\r
+#define MAC_SUPP (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x018)) /* PHY SUPPort reg */\r
+#define MAC_TEST (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x01C)) /* TEST reg */\r
+#define MAC_MCFG (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x020)) /* MII Mgmt ConFiG reg */\r
+#define MAC_MCMD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x024)) /* MII Mgmt CoMmanD reg */\r
+#define MAC_MADR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x028)) /* MII Mgmt ADdRess reg */\r
+#define MAC_MWTD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x02C)) /* MII Mgmt WriTe Data reg (WO) */\r
+#define MAC_MRDD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x030)) /* MII Mgmt ReaD Data reg (RO) */\r
+#define MAC_MIND (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x034)) /* MII Mgmt INDicators reg (RO) */\r
+\r
+#define MAC_SA0 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x040)) /* Station Address 0 reg */\r
+#define MAC_SA1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x044)) /* Station Address 1 reg */\r
+#define MAC_SA2 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x048)) /* Station Address 2 reg */\r
+\r
+#define MAC_COMMAND (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x100)) /* Command reg */\r
+#define MAC_STATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x104)) /* Status reg (RO) */\r
+#define MAC_RXDESCRIPTOR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x108)) /* Rx descriptor base address reg */\r
+#define MAC_RXSTATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x10C)) /* Rx status base address reg */\r
+#define MAC_RXDESCRIPTORNUM (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x110)) /* Rx number of descriptors reg */\r
+#define MAC_RXPRODUCEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x114)) /* Rx produce index reg (RO) */\r
+#define MAC_RXCONSUMEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x118)) /* Rx consume index reg */\r
+#define MAC_TXDESCRIPTOR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x11C)) /* Tx descriptor base address reg */\r
+#define MAC_TXSTATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x120)) /* Tx status base address reg */\r
+#define MAC_TXDESCRIPTORNUM (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x124)) /* Tx number of descriptors reg */\r
+#define MAC_TXPRODUCEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x128)) /* Tx produce index reg */\r
+#define MAC_TXCONSUMEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x12C)) /* Tx consume index reg (RO) */\r
+\r
+#define MAC_TSV0 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x158)) /* Tx status vector 0 reg (RO) */\r
+#define MAC_TSV1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x15C)) /* Tx status vector 1 reg (RO) */\r
+#define MAC_RSV (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x160)) /* Rx status vector reg (RO) */\r
+\r
+#define MAC_FLOWCONTROLCNT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x170)) /* Flow control counter reg */\r
+#define MAC_FLOWCONTROLSTS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x174)) /* Flow control status reg */\r
+\r
+#define MAC_RXFILTERCTRL (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x200)) /* Rx filter ctrl reg */\r
+#define MAC_RXFILTERWOLSTS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x204)) /* Rx filter WoL status reg (RO) */\r
+#define MAC_RXFILTERWOLCLR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x208)) /* Rx filter WoL clear reg (WO) */\r
+\r
+#define MAC_HASHFILTERL (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x210)) /* Hash filter LSBs reg */\r
+#define MAC_HASHFILTERH (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x214)) /* Hash filter MSBs reg */\r
+\r
+#define MAC_INTSTATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE0)) /* Interrupt status reg (RO) */\r
+#define MAC_INTENABLE (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE4)) /* Interrupt enable reg */\r
+#define MAC_INTCLEAR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE8)) /* Interrupt clear reg (WO) */\r
+#define MAC_INTSET (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFEC)) /* Interrupt set reg (WO) */\r
+\r
+#define MAC_POWERDOWN (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFF4)) /* Power-down reg */\r
+#define MAC_MODULEID (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFFC)) /* Module ID reg (RO) */\r
+\r
+#define PCONP_PCTIM0 0x00000002\r
+#define PCONP_PCTIM1 0x00000004\r
+#define PCONP_PCUART0 0x00000008\r
+#define PCONP_PCUART1 0x00000010\r
+#define PCONP_PCPWM1 0x00000040\r
+#define PCONP_PCI2C0 0x00000080\r
+#define PCONP_PCSPI 0x00000100\r
+#define PCONP_PCRTC 0x00000200\r
+#define PCONP_PCSSP1 0x00000400\r
+#define PCONP_PCAD 0x00001000\r
+#define PCONP_PCCAN1 0x00002000\r
+#define PCONP_PCCAN2 0x00004000\r
+#define PCONP_PCGPIO 0x00008000\r
+#define PCONP_PCRIT 0x00010000\r
+#define PCONP_PCMCPWM 0x00020000\r
+#define PCONP_PCQEI 0x00040000\r
+#define PCONP_PCI2C1 0x00080000\r
+#define PCONP_PCSSP0 0x00200000\r
+#define PCONP_PCTIM2 0x00400000\r
+#define PCONP_PCTIM3 0x00800000\r
+#define PCONP_PCUART2 0x01000000\r
+#define PCONP_PCUART3 0x02000000\r
+#define PCONP_PCI2C2 0x04000000\r
+#define PCONP_PCI2S 0x08000000\r
+#define PCONP_PCGPDMA 0x20000000\r
+#define PCONP_PCENET 0x40000000\r
+#define PCONP_PCUSB 0x80000000\r
+\r
+#define PLLCON_PLLE 0x00000001\r
+#define PLLCON_PLLC 0x00000002\r
+#define PLLCON_MASK 0x00000003\r
+\r
+#define PLLCFG_MUL1 0x00000000\r
+#define PLLCFG_MUL2 0x00000001\r
+#define PLLCFG_MUL3 0x00000002\r
+#define PLLCFG_MUL4 0x00000003\r
+#define PLLCFG_MUL5 0x00000004\r
+#define PLLCFG_MUL6 0x00000005\r
+#define PLLCFG_MUL7 0x00000006\r
+#define PLLCFG_MUL8 0x00000007\r
+#define PLLCFG_MUL9 0x00000008\r
+#define PLLCFG_MUL10 0x00000009\r
+#define PLLCFG_MUL11 0x0000000A\r
+#define PLLCFG_MUL12 0x0000000B\r
+#define PLLCFG_MUL13 0x0000000C\r
+#define PLLCFG_MUL14 0x0000000D\r
+#define PLLCFG_MUL15 0x0000000E\r
+#define PLLCFG_MUL16 0x0000000F\r
+#define PLLCFG_MUL17 0x00000010\r
+#define PLLCFG_MUL18 0x00000011\r
+#define PLLCFG_MUL19 0x00000012\r
+#define PLLCFG_MUL20 0x00000013\r
+#define PLLCFG_MUL21 0x00000014\r
+#define PLLCFG_MUL22 0x00000015\r
+#define PLLCFG_MUL23 0x00000016\r
+#define PLLCFG_MUL24 0x00000017\r
+#define PLLCFG_MUL25 0x00000018\r
+#define PLLCFG_MUL26 0x00000019\r
+#define PLLCFG_MUL27 0x0000001A\r
+#define PLLCFG_MUL28 0x0000001B\r
+#define PLLCFG_MUL29 0x0000001C\r
+#define PLLCFG_MUL30 0x0000001D\r
+#define PLLCFG_MUL31 0x0000001E\r
+#define PLLCFG_MUL32 0x0000001F\r
+#define PLLCFG_MUL33 0x00000020\r
+#define PLLCFG_MUL34 0x00000021\r
+#define PLLCFG_MUL35 0x00000022\r
+#define PLLCFG_MUL36 0x00000023\r
+\r
+#define PLLCFG_DIV1 0x00000000\r
+#define PLLCFG_DIV2 0x00010000\r
+#define PLLCFG_DIV3 0x00020000\r
+#define PLLCFG_DIV4 0x00030000\r
+#define PLLCFG_DIV5 0x00040000\r
+#define PLLCFG_DIV6 0x00050000\r
+#define PLLCFG_DIV7 0x00060000\r
+#define PLLCFG_DIV8 0x00070000\r
+#define PLLCFG_DIV9 0x00080000\r
+#define PLLCFG_DIV10 0x00090000\r
+#define PLLCFG_MASK 0x00FF7FFF\r
+\r
+#define PLLSTAT_MSEL_MASK 0x00007FFF\r
+#define PLLSTAT_NSEL_MASK 0x00FF0000\r
+\r
+#define PLLSTAT_PLLE (1 << 24)\r
+#define PLLSTAT_PLLC (1 << 25)\r
+#define PLLSTAT_PLOCK (1 << 26)\r
+\r
+#define PLLFEED_FEED1 0x000000AA\r
+#define PLLFEED_FEED2 0x00000055\r
+\r
+#define NVIC_IRQ_WDT 0u // IRQ0, exception number 16\r
+#define NVIC_IRQ_TIMER0 1u // IRQ1, exception number 17\r
+#define NVIC_IRQ_TIMER1 2u // IRQ2, exception number 18\r
+#define NVIC_IRQ_TIMER2 3u // IRQ3, exception number 19\r
+#define NVIC_IRQ_TIMER3 4u // IRQ4, exception number 20\r
+#define NVIC_IRQ_UART0 5u // IRQ5, exception number 21\r
+#define NVIC_IRQ_UART1 6u // IRQ6, exception number 22\r
+#define NVIC_IRQ_UART2 7u // IRQ7, exception number 23\r
+#define NVIC_IRQ_UART3 8u // IRQ8, exception number 24\r
+#define NVIC_IRQ_PWM1 9u // IRQ9, exception number 25\r
+#define NVIC_IRQ_I2C0 10u // IRQ10, exception number 26\r
+#define NVIC_IRQ_I2C1 11u // IRQ11, exception number 27\r
+#define NVIC_IRQ_I2C2 12u // IRQ12, exception number 28\r
+#define NVIC_IRQ_SPI 13u // IRQ13, exception number 29\r
+#define NVIC_IRQ_SSP0 14u // IRQ14, exception number 30\r
+#define NVIC_IRQ_SSP1 15u // IRQ15, exception number 31\r
+#define NVIC_IRQ_PLL0 16u // IRQ16, exception number 32\r
+#define NVIC_IRQ_RTC 17u // IRQ17, exception number 33\r
+#define NVIC_IRQ_EINT0 18u // IRQ18, exception number 34\r
+#define NVIC_IRQ_EINT1 19u // IRQ19, exception number 35\r
+#define NVIC_IRQ_EINT2 20u // IRQ20, exception number 36\r
+#define NVIC_IRQ_EINT3 21u // IRQ21, exception number 37\r
+#define NVIC_IRQ_ADC 22u // IRQ22, exception number 38\r
+#define NVIC_IRQ_BOD 23u // IRQ23, exception number 39\r
+#define NVIC_IRQ_USB 24u // IRQ24, exception number 40\r
+#define NVIC_IRQ_CAN 25u // IRQ25, exception number 41\r
+#define NVIC_IRQ_GPDMA 26u // IRQ26, exception number 42\r
+#define NVIC_IRQ_I2S 27u // IRQ27, exception number 43\r
+#define NVIC_IRQ_ETHERNET 28u // IRQ28, exception number 44\r
+#define NVIC_IRQ_RIT 29u // IRQ29, exception number 45\r
+#define NVIC_IRQ_MCPWM 30u // IRQ30, exception number 46\r
+#define NVIC_IRQ_QE 31u // IRQ31, exception number 47\r
+#define NVIC_IRQ_PLL1 32u // IRQ32, exception number 48\r
+#define NVIC_IRQ_USB_ACT 33u // IRQ33, exception number 49\r
+#define NVIC_IRQ_CAN_ACT 34u // IRQ34, exception number 50\r
+\r
+typedef enum IRQn\r
+{\r
+/****** Cortex-M3 Processor Exceptions Numbers ***************************************************/\r
+ NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */\r
+ MemoryManagement_IRQn = -12, /*!< 4 Cortex-M3 Memory Management Interrupt */\r
+ BusFault_IRQn = -11, /*!< 5 Cortex-M3 Bus Fault Interrupt */\r
+ UsageFault_IRQn = -10, /*!< 6 Cortex-M3 Usage Fault Interrupt */\r
+ SVCall_IRQn = -5, /*!< 11 Cortex-M3 SV Call Interrupt */\r
+ DebugMonitor_IRQn = -4, /*!< 12 Cortex-M3 Debug Monitor Interrupt */\r
+ PendSV_IRQn = -2, /*!< 14 Cortex-M3 Pend SV Interrupt */\r
+ SysTick_IRQn = -1, /*!< 15 Cortex-M3 System Tick Interrupt */\r
+\r
+/****** LPC17xx Specific Interrupt Numbers *******************************************************/\r
+ WDT_IRQn = 0, /*!< Watchdog Timer Interrupt */\r
+ TIMER0_IRQn = 1, /*!< Timer0 Interrupt */\r
+ TIMER1_IRQn = 2, /*!< Timer1 Interrupt */\r
+ TIMER2_IRQn = 3, /*!< Timer2 Interrupt */\r
+ TIMER3_IRQn = 4, /*!< Timer3 Interrupt */\r
+ UART0_IRQn = 5, /*!< UART0 Interrupt */\r
+ UART1_IRQn = 6, /*!< UART1 Interrupt */\r
+ UART2_IRQn = 7, /*!< UART2 Interrupt */\r
+ UART3_IRQn = 8, /*!< UART3 Interrupt */\r
+ PWM1_IRQn = 9, /*!< PWM1 Interrupt */\r
+ I2C0_IRQn = 10, /*!< I2C0 Interrupt */\r
+ I2C1_IRQn = 11, /*!< I2C1 Interrupt */\r
+ I2C2_IRQn = 12, /*!< I2C2 Interrupt */\r
+ SPI_IRQn = 13, /*!< SPI Interrupt */\r
+ SSP0_IRQn = 14, /*!< SSP0 Interrupt */\r
+ SSP1_IRQn = 15, /*!< SSP1 Interrupt */\r
+ PLL0_IRQn = 16, /*!< PLL0 Lock (Main PLL) Interrupt */\r
+ RTC_IRQn = 17, /*!< Real Time Clock Interrupt */\r
+ EINT0_IRQn = 18, /*!< External Interrupt 0 Interrupt */\r
+ EINT1_IRQn = 19, /*!< External Interrupt 1 Interrupt */\r
+ EINT2_IRQn = 20, /*!< External Interrupt 2 Interrupt */\r
+ EINT3_IRQn = 21, /*!< External Interrupt 3 Interrupt */\r
+ ADC_IRQn = 22, /*!< A/D Converter Interrupt */\r
+ BOD_IRQn = 23, /*!< Brown-Out Detect Interrupt */\r
+ USB_IRQn = 24, /*!< USB Interrupt */\r
+ CAN_IRQn = 25, /*!< CAN Interrupt */\r
+ DMA_IRQn = 26, /*!< General Purpose DMA Interrupt */\r
+ I2S_IRQn = 27, /*!< I2S Interrupt */\r
+ ENET_IRQn = 28, /*!< Ethernet Interrupt */\r
+ RIT_IRQn = 29, /*!< Repetitive Interrupt Timer Interrupt */\r
+ MCPWM_IRQn = 30, /*!< Motor Control PWM Interrupt */\r
+ QEI_IRQn = 31, /*!< Quadrature Encoder Interface Interrupt */\r
+ PLL1_IRQn = 32, /*!< PLL1 Lock (USB PLL) Interrupt */\r
+} IRQn_Type;\r
+\r
+#endif // __LPC17xx_H\r
--- /dev/null
+/******************************************************************************\r
+ * LPC17xx.h: Header file for NXP LPC17xx Cortex-M3 Family Microprocessors\r
+ * The header file is the super set of all hardware definitions of the \r
+ * peripherals for the LPC17xx/24xx microprocessor.\r
+ *\r
+ * Copyright(C) 2006-2008, NXP Semiconductor\r
+ * All rights reserved.\r
+ *\r
+ * History\r
+ *\r
+******************************************************************************/\r
+\r
+#ifndef __LPC17xx_H\r
+#define __LPC17xx_H\r
+\r
+//#include "sysdefs.h"\r
+\r
+#define SRAM_BASE_LOCAL ((unsigned long)0x10000000) // 32 Kb\r
+#define SRAM_BASE_AHB ((unsigned long)0x20000000) // 32 Kb\r
+\r
+/* System Control Space memory map */\r
+#ifndef SCS_BASE\r
+ #define SCS_BASE ((unsigned long)0xE000E000)\r
+#endif\r
+\r
+#define SysTick_BASE (SCS_BASE + 0x0010)\r
+#define NVIC_BASE (SCS_BASE + 0x0100)\r
+#define CM3_PERIPH_BASE_ADDR (SCS_BASE + 0x0D00)\r
+\r
+typedef struct\r
+{\r
+ unsigned long CPUID;\r
+ unsigned long IRQControlState;\r
+ unsigned long ExceptionTableOffset;\r
+ unsigned long AIRC;\r
+ unsigned long SysCtrl;\r
+ unsigned long ConfigCtrl;\r
+ unsigned long SystemPriority[3];\r
+ unsigned long SysHandlerCtrl;\r
+ unsigned long ConfigFaultStatus;\r
+ unsigned long HardFaultStatus;\r
+ unsigned long DebugFaultStatus;\r
+ unsigned long MemoryManageFaultAddr;\r
+ unsigned long BusFaultAddr;\r
+} CM3_t;\r
+\r
+/* Vector Table Base Address */\r
+#define NVIC_VectorTable_RAM SRAM_BASE_AHB\r
+#define NVIC_VectorTable_FLASH ((unsigned long)0x00000000)\r
+\r
+#define IS_NVIC_VECTORTBL(TABLE_BASE) ((TABLE_BASE == NVIC_VectorTable_RAM) || \\r
+ (TABLE_BASE == NVIC_VectorTable_FLASH))\r
+ \r
+/* Pin Connect Block */\r
+#define PINSEL_BASE_ADDR 0x4002C000\r
+#define PINSEL0 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x00))\r
+#define PINSEL1 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x04))\r
+#define PINSEL2 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x08))\r
+#define PINSEL3 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x0C))\r
+#define PINSEL4 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x10))\r
+#define PINSEL5 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x14))\r
+#define PINSEL6 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x18))\r
+#define PINSEL7 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x1C))\r
+#define PINSEL8 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x20))\r
+#define PINSEL9 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x24))\r
+#define PINSEL10 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x28))\r
+\r
+#define PINMODE0 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x40))\r
+#define PINMODE1 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x44))\r
+#define PINMODE2 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x48))\r
+#define PINMODE3 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x4C))\r
+#define PINMODE4 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x50))\r
+#define PINMODE5 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x54))\r
+#define PINMODE6 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x58))\r
+#define PINMODE7 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x5C))\r
+#define PINMODE8 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x60))\r
+#define PINMODE9 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x64))\r
+\r
+/* Open drain mode control */\r
+#define PINMODE_OD0 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x68))\r
+#define PINMODE_OD1 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x6C))\r
+#define PINMODE_OD2 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x70))\r
+#define PINMODE_OD3 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x74))\r
+#define PINMODE_OD4 (*(volatile unsigned long *)(PINSEL_BASE_ADDR + 0x78))\r
+
+#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)
+\r
+/* General Purpose Input/Output (GPIO) */\r
+/* Fast I/O setup */\r
+\r
+#define FIO_BASE_ADDR 0x50014000\r
+\r
+#define FIO0DIR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x00)) \r
+#define FIO0MASK (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x10))\r
+#define FIO0PIN (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x14))\r
+#define FIO0SET (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x18))\r
+#define FIO0CLR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x1C))\r
+\r
+#ifdef LPC1766_UM_DEFS\r
+/* Fast GPIO Register Access */\r
+#define FIO0SET0 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x38))\r
+#define FIO0SET1 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x39))\r
+#define FIO0SET2 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x3A))\r
+#define FIO0SET3 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x3B))\r
+#define FIO0SETL (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x38))\r
+#define FIO0SETU (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x3A))\r
+#endif\r
+\r
+#define FIO1DIR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x20)) \r
+#define FIO1MASK (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x30))\r
+#define FIO1PIN (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x34))\r
+#define FIO1SET (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x38))\r
+#define FIO1CLR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x3C))\r
+\r
+#ifdef LPC1766_UM_DEFS\r
+/* Fast GPIO Register Access */\r
+#define FIO1SET0 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x78))\r
+#define FIO1SET1 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x79))\r
+#define FIO1SET2 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x7A))\r
+#define FIO1SET3 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x7B))\r
+#define FIO1SETL (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x78))\r
+#define FIO1SETU (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x7A))\r
+#endif\r
+\r
+#define FIO2DIR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x40)) \r
+#define FIO2MASK (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x50))\r
+#define FIO2PIN (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x54))\r
+#define FIO2SET (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x58))\r
+#define FIO2CLR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x5C))\r
+\r
+#ifdef LPC1766_UM_DEFS\r
+/* Fast GPIO Register Access */\r
+#define FIO2SET0 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xB8))\r
+#define FIO2SET1 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xB9))\r
+#define FIO2SET2 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xBA))\r
+#define FIO2SET3 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xBB))\r
+#define FIO2SETL (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xB8))\r
+#define FIO2SETU (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xBA))\r
+#endif\r
+\r
+#define FIO3DIR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x60)) \r
+#define FIO3MASK (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x70))\r
+#define FIO3PIN (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x74))\r
+#define FIO3SET (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x78))\r
+#define FIO3CLR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x7C))\r
+\r
+#ifdef LPC1766_UM_DEFS\r
+/* Fast GPIO Register Access */\r
+#define FIO3SET0 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xF8))\r
+#define FIO3SET1 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xF9))\r
+#define FIO3SET2 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xFA))\r
+#define FIO3SET3 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xFB))\r
+#define FIO3SETL (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xF8))\r
+#define FIO3SETU (*(volatile unsigned long *)(FIO_BASE_ADDR + 0xFA))\r
+#endif\r
+\r
+#define FIO4DIR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x80)) \r
+#define FIO4MASK (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x90))\r
+#define FIO4PIN (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x94))\r
+#define FIO4SET (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x98))\r
+#define FIO4CLR (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x9C))\r
+\r
+#ifdef LPC1766_UM_DEFS\r
+/* Fast GPIO Register Access */\r
+#define FIO4SET0 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x138))\r
+#define FIO4SET1 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x139))\r
+#define FIO4SET2 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x13A))\r
+#define FIO0SET3 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x3B))\r
+#define FIO4SET3 (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x13B))\r
+#define FIO4SETL (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x138))\r
+#define FIO4SETU (*(volatile unsigned long *)(FIO_BASE_ADDR + 0x13A))\r
+#endif\r
+\r
+/* General Purpose Input/Output (GPIO) */\r
+#define GPIO_BASE_ADDR 0x40028000\r
+#define IOPIN0 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x00))\r
+#define IOSET0 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x04))\r
+#define IODIR0 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x08))\r
+#define IOCLR0 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x0C))\r
+#define IOPIN1 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x10))\r
+#define IOSET1 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x14))\r
+#define IODIR1 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x18))\r
+#define IOCLR1 (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x1C))\r
+
+#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)\r
+\r
+/* GPIO Interrupt Registers */\r
+#define IO0_INT_EN_R (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x90)) \r
+#define IO0_INT_EN_F (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x94))\r
+#define IO0_INT_STAT_R (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x84))\r
+#define IO0_INT_STAT_F (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x88))\r
+#define IO0_INT_CLR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x8C))\r
+\r
+#define IO2_INT_EN_R (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0xB0)) \r
+#define IO2_INT_EN_F (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0xB4))\r
+#define IO2_INT_STAT_R (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0xA4))\r
+#define IO2_INT_STAT_F (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0xA8))\r
+#define IO2_INT_CLR (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0xAC))\r
+\r
+#define IO_INT_STAT (*(volatile unsigned long *)(GPIO_BASE_ADDR + 0x80))\r
+\r
+#define PARTCFG_BASE_ADDR 0x3FFF8000\r
+#define PARTCFG (*(volatile unsigned long *)(PARTCFG_BASE_ADDR + 0x00)) \r
+\r
+/* System Control Block(SCB) modules include Memory Accelerator Module,\r
+Phase Locked Loop, VPB divider, Power Control, External Interrupt, \r
+Reset, and Code Security/Debugging */\r
+#define SCB_BASE_ADDR 0x400FC000\r
+\r
+/* Memory Accelerator Module */\r
+\r
+/* Phase Locked Loop (PLL0) */\r
+#define PLL0CON (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x080))\r
+#define PLL0CFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x084))\r
+#define PLL0STAT (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x088))\r
+#define PLL0FEED (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x08C))\r
+\r
+/* Phase Locked Loop (PLL1) */\r
+#define PLL1CON (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0A0))\r
+#define PLL1CFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0A4))\r
+#define PLL1STAT (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0A8))\r
+#define PLL1FEED (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0AC))\r
+
+#define PLLCON_PLLE 0x00000001
+#define PLLCON_PLLC 0x00000002
+#define PLLCON_MASK 0x00000003\r
+\r
+#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\r
+#define PLLCFG_MUL33 0x00000020\r
+#define PLLCFG_MUL34 0x00000021\r
+#define PLLCFG_MUL35 0x00000022\r
+#define PLLCFG_MUL36 0x00000023\r
+
+#define PLLCFG_DIV1 0x00000000
+#define PLLCFG_DIV2 0x00010000\r
+#define PLLCFG_DIV3 0x00020000
+#define PLLCFG_DIV4 0x00030000\r
+#define PLLCFG_DIV5 0x00040000\r
+#define PLLCFG_DIV6 0x00050000\r
+#define PLLCFG_DIV7 0x00060000
+#define PLLCFG_DIV8 0x00070000\r
+#define PLLCFG_DIV9 0x00080000\r
+#define PLLCFG_DIV10 0x00090000
+#define PLLCFG_MASK 0x00FF7FFF\r
+\r
+#define PLLSTAT_MSEL_MASK 0x00007FFF\r
+#define PLLSTAT_NSEL_MASK 0x00FF0000\r
+
+#define PLLSTAT_PLLE (1 << 24)
+#define PLLSTAT_PLLC (1 << 25)
+#define PLLSTAT_PLOCK (1 << 26)\r
+
+#define PLLFEED_FEED1 0x000000AA
+#define PLLFEED_FEED2 0x00000055\r
+\r
+/* Power Control */\r
+#define PCON (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0C0))\r
+#define PCONP (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x0C4))\r
+
+#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\r
+#define PCONP_PCAD 0x00001000\r
+#define PCONP_PCCAN1 0x00002000\r
+#define PCONP_PCCAN2 0x00004000\r
+#define PCONP_PCGPIO 0x00008000\r
+#define PCONP_PCRIT 0x00010000\r
+#define PCONP_PCMCPWM 0x00020000\r
+#define PCONP_PCQEI 0x00040000
+#define PCONP_PCI2C1 0x00080000\r
+#define PCONP_PCSSP0 0x00200000\r
+#define PCONP_PCTIM2 0x00400000\r
+#define PCONP_PCTIM3 0x00800000\r
+#define PCONP_PCUART2 0x01000000\r
+#define PCONP_PCUART3 0x02000000\r
+#define PCONP_PCI2C2 0x04000000\r
+#define PCONP_PCI2S 0x08000000\r
+#define PCONP_PCGPDMA 0x20000000\r
+#define PCONP_PCENET 0x40000000\r
+#define PCONP_PCUSB 0x80000000\r
+#define PCONP_MASK 0x801817BE
+\r
+// 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\r
+\r
+/* Clock Divider */\r
+// #define APBDIV (*(volatile unsigned long *)(BASE_ADDR + 0x100))\r
+#define CCLKCFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x104))\r
+#define USBCLKCFG (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x108))\r
+#define CLKSRCSEL (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x10C))\r
+#define PCLKSEL0 (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1A8))\r
+#define PCLKSEL1 (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1AC))\r
+ \r
+/* External Interrupts */\r
+#define EXTINT (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x140))\r
+#define INTWAKE (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x144))\r
+#define EXTMODE (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x148))\r
+#define EXTPOLAR (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x14C))\r
+\r
+/* Reset, reset source identification */\r
+#define RSIR (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x180))\r
+\r
+/* RSID, code security protection */\r
+#define CSPR (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x184))\r
+\r
+/* AHB configuration */\r
+#define AHBCFG1 (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x188))\r
+#define AHBCFG2 (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x18C))\r
+\r
+/* System Controls and Status */\r
+#define SCS (*(volatile unsigned long *)(SCB_BASE_ADDR + 0x1A0)) \r
+\r
+/* MPMC(EMC) registers, note: all the external memory controller(EMC) registers \r
+are for LPC24xx only. */\r
+#define STATIC_MEM0_BASE 0x80000000\r
+#define STATIC_MEM1_BASE 0x81000000\r
+#define STATIC_MEM2_BASE 0x82000000\r
+#define STATIC_MEM3_BASE 0x83000000\r
+\r
+#define DYNAMIC_MEM0_BASE 0xA0000000\r
+#define DYNAMIC_MEM1_BASE 0xB0000000\r
+#define DYNAMIC_MEM2_BASE 0xC0000000\r
+#define DYNAMIC_MEM3_BASE 0xD0000000\r
+\r
+/* External Memory Controller (EMC) */\r
+#define EMC_BASE_ADDR 0xFFE08000\r
+#define EMC_CTRL (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x000))\r
+#define EMC_STAT (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x004))\r
+#define EMC_CONFIG (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x008))\r
+\r
+/* Dynamic RAM access registers */\r
+#define EMC_DYN_CTRL (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x020))\r
+#define EMC_DYN_RFSH (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x024))\r
+#define EMC_DYN_RD_CFG (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x028))\r
+#define EMC_DYN_RP (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x030))\r
+#define EMC_DYN_RAS (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x034))\r
+#define EMC_DYN_SREX (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x038))\r
+#define EMC_DYN_APR (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x03C))\r
+#define EMC_DYN_DAL (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x040))\r
+#define EMC_DYN_WR (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x044))\r
+#define EMC_DYN_RC (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x048))\r
+#define EMC_DYN_RFC (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x04C))\r
+#define EMC_DYN_XSR (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x050))\r
+#define EMC_DYN_RRD (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x054))\r
+#define EMC_DYN_MRD (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x058))\r
+\r
+#define EMC_DYN_CFG0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x100))\r
+#define EMC_DYN_RASCAS0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x104))\r
+#define EMC_DYN_CFG1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x120))\r
+#define EMC_DYN_RASCAS1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x124))\r
+#define EMC_DYN_CFG2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x140))\r
+#define EMC_DYN_RASCAS2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x144))\r
+#define EMC_DYN_CFG3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x160))\r
+#define EMC_DYN_RASCAS3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x164))\r
+\r
+/* static RAM access registers */\r
+#define EMC_STA_CFG0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x200))\r
+#define EMC_STA_WAITWEN0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x204))\r
+#define EMC_STA_WAITOEN0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x208))\r
+#define EMC_STA_WAITRD0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x20C))\r
+#define EMC_STA_WAITPAGE0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x210))\r
+#define EMC_STA_WAITWR0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x214))\r
+#define EMC_STA_WAITTURN0 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x218))\r
+\r
+#define EMC_STA_CFG1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x220))\r
+#define EMC_STA_WAITWEN1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x224))\r
+#define EMC_STA_WAITOEN1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x228))\r
+#define EMC_STA_WAITRD1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x22C))\r
+#define EMC_STA_WAITPAGE1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x230))\r
+#define EMC_STA_WAITWR1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x234))\r
+#define EMC_STA_WAITTURN1 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x238))\r
+\r
+#define EMC_STA_CFG2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x240))\r
+#define EMC_STA_WAITWEN2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x244))\r
+#define EMC_STA_WAITOEN2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x248))\r
+#define EMC_STA_WAITRD2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x24C))\r
+#define EMC_STA_WAITPAGE2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x250))\r
+#define EMC_STA_WAITWR2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x254))\r
+#define EMC_STA_WAITTURN2 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x258))\r
+\r
+#define EMC_STA_CFG3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x260))\r
+#define EMC_STA_WAITWEN3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x264))\r
+#define EMC_STA_WAITOEN3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x268))\r
+#define EMC_STA_WAITRD3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x26C))\r
+#define EMC_STA_WAITPAGE3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x270))\r
+#define EMC_STA_WAITWR3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x274))\r
+#define EMC_STA_WAITTURN3 (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x278))\r
+\r
+#define EMC_STA_EXT_WAIT (*(volatile unsigned long *)(EMC_BASE_ADDR + 0x880))\r
+\r
+/* Timer 0 */\r
+#define TMR0_BASE_ADDR 0x40004000\r
+#define T0IR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x00))\r
+#define T0TCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x04))\r
+#define T0TC (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x08))\r
+#define T0PR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x0C))\r
+#define T0PC (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x10))\r
+#define T0MCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x14))\r
+#define T0MR0 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x18))\r
+#define T0MR1 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x1C))\r
+#define T0MR2 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x20))\r
+#define T0MR3 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x24))\r
+#define T0CCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x28))\r
+#define T0CR0 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x2C))\r
+#define T0CR1 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x30))\r
+#define T0CR2 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x34))\r
+#define T0CR3 (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x38))\r
+#define T0EMR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x3C))\r
+#define T0CTCR (*(volatile unsigned long *)(TMR0_BASE_ADDR + 0x70))\r
+\r
+/* Timer 1 */\r
+#define TMR1_BASE_ADDR 0x40008000\r
+#define T1IR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x00))\r
+#define T1TCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x04))\r
+#define T1TC (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x08))\r
+#define T1PR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x0C))\r
+#define T1PC (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x10))\r
+#define T1MCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x14))\r
+#define T1MR0 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x18))\r
+#define T1MR1 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x1C))\r
+#define T1MR2 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x20))\r
+#define T1MR3 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x24))\r
+#define T1CCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x28))\r
+#define T1CR0 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x2C))\r
+#define T1CR1 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x30))\r
+#define T1CR2 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x34))\r
+#define T1CR3 (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x38))\r
+#define T1EMR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x3C))\r
+#define T1CTCR (*(volatile unsigned long *)(TMR1_BASE_ADDR + 0x70))\r
+\r
+/* Timer 2 */\r
+#define TMR2_BASE_ADDR 0x40090000\r
+#define T2IR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x00))\r
+#define T2TCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x04))\r
+#define T2TC (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x08))\r
+#define T2PR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x0C))\r
+#define T2PC (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x10))\r
+#define T2MCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x14))\r
+#define T2MR0 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x18))\r
+#define T2MR1 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x1C))\r
+#define T2MR2 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x20))\r
+#define T2MR3 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x24))\r
+#define T2CCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x28))\r
+#define T2CR0 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x2C))\r
+#define T2CR1 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x30))\r
+#define T2CR2 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x34))\r
+#define T2CR3 (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x38))\r
+#define T2EMR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x3C))\r
+#define T2CTCR (*(volatile unsigned long *)(TMR2_BASE_ADDR + 0x70))\r
+\r
+/* Timer 3 */\r
+#define TMR3_BASE_ADDR 0x40094000\r
+#define T3IR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x00))\r
+#define T3TCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x04))\r
+#define T3TC (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x08))\r
+#define T3PR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x0C))\r
+#define T3PC (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x10))\r
+#define T3MCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x14))\r
+#define T3MR0 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x18))\r
+#define T3MR1 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x1C))\r
+#define T3MR2 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x20))\r
+#define T3MR3 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x24))\r
+#define T3CCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x28))\r
+#define T3CR0 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x2C))\r
+#define T3CR1 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x30))\r
+#define T3CR2 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x34))\r
+#define T3CR3 (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x38))\r
+#define T3EMR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x3C))\r
+#define T3CTCR (*(volatile unsigned long *)(TMR3_BASE_ADDR + 0x70))\r
+
+#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
+\r
+/* Pulse Width Modulator (PWM1) */\r
+#define PWM1_BASE_ADDR 0x40018000\r
+#define PWM1IR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x00))\r
+#define PWM1TCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x04))\r
+#define PWM1TC (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x08))\r
+#define PWM1PR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x0C))\r
+#define PWM1PC (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x10))\r
+#define PWM1MCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x14))\r
+#define PWM1MR0 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x18))\r
+#define PWM1MR1 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x1C))\r
+#define PWM1MR2 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x20))\r
+#define PWM1MR3 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x24))\r
+#define PWM1CCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x28))\r
+#define PWM1CR0 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x2C))\r
+#define PWM1CR1 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x30))\r
+#define PWM1CR2 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x34))\r
+#define PWM1CR3 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x38))\r
+#define PWM1EMR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x3C))\r
+#define PWM1MR4 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x40))\r
+#define PWM1MR5 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x44))\r
+#define PWM1MR6 (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x48))\r
+#define PWM1PCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x4C))\r
+#define PWM1LER (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x50))\r
+#define PWM1CTCR (*(volatile unsigned long *)(PWM1_BASE_ADDR + 0x70))\r
+\r
+/* Universal Asynchronous Receiver Transmitter 0 (UART0) */\r
+#define UART0_BASE_ADDR 0x4000C000\r
+#define U0RBR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x00))\r
+#define U0THR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x00))\r
+#define U0DLL (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x00))\r
+#define U0DLM (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x04))\r
+#define U0IER (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x04))\r
+#define U0IIR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x08))\r
+#define U0FCR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x08))\r
+#define U0LCR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x0C))\r
+#define U0LSR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x14))\r
+#define U0SCR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x1C))\r
+#define U0ACR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x20))\r
+#define U0ICR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x24))\r
+#define U0FDR (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x28))\r
+#define U0TER (*(volatile unsigned long *)(UART0_BASE_ADDR + 0x30))\r
+
+#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\r
+\r
+/* Universal Asynchronous Receiver Transmitter 1 (UART1) */\r
+#define UART1_BASE_ADDR 0x40010000\r
+#define U1RBR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x00))\r
+#define U1THR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x00))\r
+#define U1DLL (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x00))\r
+#define U1DLM (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x04))\r
+#define U1IER (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x04))\r
+#define U1IIR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x08))\r
+#define U1FCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x08))\r
+#define U1LCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x0C))\r
+#define U1MCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x10))\r
+#define U1LSR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x14))\r
+#define U1MSR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x18))\r
+#define U1SCR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x1C))\r
+#define U1ACR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x20))\r
+#define U1FDR (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x28))\r
+#define U1TER (*(volatile unsigned long *)(UART1_BASE_ADDR + 0x30))\r
+
+#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\r
+\r
+/* Universal Asynchronous Receiver Transmitter 2 (UART2) */\r
+#define UART2_BASE_ADDR 0x40098000\r
+#define U2RBR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x00))\r
+#define U2THR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x00))\r
+#define U2DLL (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x00))\r
+#define U2DLM (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x04))\r
+#define U2IER (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x04))\r
+#define U2IIR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x08))\r
+#define U2FCR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x08))\r
+#define U2LCR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x0C))\r
+#define U2LSR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x14))\r
+#define U2SCR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x1C))\r
+#define U2ACR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x20))\r
+#define U2ICR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x24))\r
+#define U2FDR (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x28))\r
+#define U2TER (*(volatile unsigned long *)(UART2_BASE_ADDR + 0x30))\r
+\r
+/* Universal Asynchronous Receiver Transmitter 3 (UART3) */\r
+#define UART3_BASE_ADDR 0x4009C000\r
+#define U3RBR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x00))\r
+#define U3THR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x00))\r
+#define U3DLL (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x00))\r
+#define U3DLM (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x04))\r
+#define U3IER (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x04))\r
+#define U3IIR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x08))\r
+#define U3FCR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x08))\r
+#define U3LCR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x0C))\r
+#define U3LSR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x14))\r
+#define U3SCR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x1C))\r
+#define U3ACR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x20))\r
+#define U3ICR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x24))\r
+#define U3FDR (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x28))\r
+#define U3TER (*(volatile unsigned long *)(UART3_BASE_ADDR + 0x30))\r
+
+#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\r
+\r
+/* I2C Interface 0 */\r
+#define I2C0_BASE_ADDR 0x4001C000\r
+#define I20CONSET (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x00))\r
+#define I20STAT (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x04))\r
+#define I20DAT (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x08))\r
+#define I20ADR (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x0C))\r
+#define I20SCLH (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x10))\r
+#define I20SCLL (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x14))\r
+#define I20CONCLR (*(volatile unsigned long *)(I2C0_BASE_ADDR + 0x18))\r
+\r
+/* I2C Interface 1 */\r
+#define I2C1_BASE_ADDR 0x4005C000\r
+#define I21CONSET (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x00))\r
+#define I21STAT (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x04))\r
+#define I21DAT (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x08))\r
+#define I21ADR (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x0C))\r
+#define I21SCLH (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x10))\r
+#define I21SCLL (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x14))\r
+#define I21CONCLR (*(volatile unsigned long *)(I2C1_BASE_ADDR + 0x18))\r
+\r
+/* I2C Interface 2 */\r
+#define I2C2_BASE_ADDR 0x400A000\r
+#define I22CONSET (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x00))\r
+#define I22STAT (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x04))\r
+#define I22DAT (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x08))\r
+#define I22ADR (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x0C))\r
+#define I22SCLH (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x10))\r
+#define I22SCLL (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x14))\r
+#define I22CONCLR (*(volatile unsigned long *)(I2C2_BASE_ADDR + 0x18))\r
+\r
+/* SPI0 (Serial Peripheral Interface 0) */\r
+#define SPI0_BASE_ADDR 0x40020000\r
+#define S0SPCR (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x00))\r
+#define S0SPSR (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x04))\r
+#define S0SPDR (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x08))\r
+#define S0SPCCR (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x0C))\r
+#define S0SPINT (*(volatile unsigned long *)(SPI0_BASE_ADDR + 0x1C))\r
+\r
+/* SSP0 Controller */\r
+#define SSP0_BASE_ADDR 0x40088000\r
+#define SSP0CR0 (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x00))\r
+#define SSP0CR1 (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x04))\r
+#define SSP0DR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x08))\r
+#define SSP0SR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x0C))\r
+#define SSP0CPSR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x10))\r
+#define SSP0IMSC (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x14))\r
+#define SSP0RIS (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x18))\r
+#define SSP0MIS (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x1C))\r
+#define SSP0ICR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x20))\r
+#define SSP0DMACR (*(volatile unsigned long *)(SSP0_BASE_ADDR + 0x24))\r
+\r
+/* SSP1 Controller */\r
+#define SSP1_BASE_ADDR 0x40030000\r
+#define SSP1CR0 (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x00))\r
+#define SSP1CR1 (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x04))\r
+#define SSP1DR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x08))\r
+#define SSP1SR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x0C))\r
+#define SSP1CPSR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x10))\r
+#define SSP1IMSC (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x14))\r
+#define SSP1RIS (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x18))\r
+#define SSP1MIS (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x1C))\r
+#define SSP1ICR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x20))\r
+#define SSP1DMACR (*(volatile unsigned long *)(SSP1_BASE_ADDR + 0x24))\r
+\r
+/* Real Time Clock */\r
+#define RTC_BASE_ADDR 0x40024000\r
+#define RTC_ILR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x00))\r
+#define RTC_CTC (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x04))\r
+#define RTC_CCR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x08))\r
+#define RTC_CIIR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x0C))\r
+#define RTC_AMR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x10))\r
+#define RTC_CTIME0 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x14))\r
+#define RTC_CTIME1 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x18))\r
+#define RTC_CTIME2 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x1C))\r
+\r
+#define RTC_SEC (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x20))\r
+#define RTC_MIN (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x24))\r
+#define RTC_HOUR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x28))\r
+#define RTC_DOM (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x2C))\r
+#define RTC_DOW (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x30))\r
+#define RTC_DOY (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x34))\r
+#define RTC_MONTH (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x38))\r
+#define RTC_YEAR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x3C))\r
+\r
+#define RTC_CISS (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x40))\r
+#define RTC_GPREG0 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x44))\r
+#define RTC_GPREG1 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x48))\r
+#define RTC_GPREG2 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x4C))\r
+#define RTC_GPREG3 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x50))\r
+#define RTC_GPREG4 (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x54))\r
+#define RTC_WAKEUPDIS (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x58))\r
+#define RTC_PWRCTRL (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x5C))\r
+\r
+#define RTC_ALSEC (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x60))\r
+#define RTC_ALMIN (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x64))\r
+#define RTC_ALHOUR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x68))\r
+#define RTC_ALDOM (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x6C))\r
+#define RTC_ALDOW (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x70))\r
+#define RTC_ALDOY (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x74))\r
+#define RTC_ALMON (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x78))\r
+#define RTC_ALYEAR (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x7C))\r
+#define RTC_PREINT (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x80))\r
+#define RTC_PREFRAC (*(volatile unsigned long *)(RTC_BASE_ADDR + 0x84))\r
+\r
+#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;
+\r
+/* A/D Converter 0 (AD0) */\r
+#define AD0_BASE_ADDR 0x40034000\r
+#define AD0CR (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x00))\r
+#define AD0GDR (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x04))\r
+#define AD0INTEN (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x0C))\r
+#define AD0DR0 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x10))\r
+#define AD0DR1 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x14))\r
+#define AD0DR2 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x18))\r
+#define AD0DR3 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x1C))\r
+#define AD0DR4 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x20))\r
+#define AD0DR5 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x24))\r
+#define AD0DR6 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x28))\r
+#define AD0DR7 (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x2C))\r
+#define AD0STAT (*(volatile unsigned long *)(AD0_BASE_ADDR + 0x30))\r
+\r
+/* D/A Converter */\r
+#define DAC_BASE_ADDR 0x4008C000\r
+#define DACR (*(volatile unsigned long *)(DAC_BASE_ADDR + 0x00))\r
+\r
+/* Watchdog */\r
+#define WDG_BASE_ADDR 0x40000000\r
+#define WDMOD (*(volatile unsigned long *)(WDG_BASE_ADDR + 0x00))\r
+#define WDTC (*(volatile unsigned long *)(WDG_BASE_ADDR + 0x04))\r
+#define WDFEED (*(volatile unsigned long *)(WDG_BASE_ADDR + 0x08))\r
+#define WDTV (*(volatile unsigned long *)(WDG_BASE_ADDR + 0x0C))\r
+#define WDCLKSEL (*(volatile unsigned long *)(WDG_BASE_ADDR + 0x10))\r
+\r
+/* CAN CONTROLLERS AND ACCEPTANCE FILTER */\r
+#define CAN_ACCEPT_BASE_ADDR 0x4003C000\r
+#define CAN_AFMR (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x00)) \r
+#define CAN_SFF_SA (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x04)) \r
+#define CAN_SFF_GRP_SA (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x08))\r
+#define CAN_EFF_SA (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x0C))\r
+#define CAN_EFF_GRP_SA (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x10)) \r
+#define CAN_EOT (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x14))\r
+#define CAN_LUT_ERR_ADR (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x18)) \r
+#define CAN_LUT_ERR (*(volatile unsigned long *)(CAN_ACCEPT_BASE_ADDR + 0x1C))\r
+\r
+#define CAN_CENTRAL_BASE_ADDR 0xE0040000 \r
+#define CAN_TX_SR (*(volatile unsigned long *)(CAN_CENTRAL_BASE_ADDR + 0x00)) \r
+#define CAN_RX_SR (*(volatile unsigned long *)(CAN_CENTRAL_BASE_ADDR + 0x04)) \r
+#define CAN_MSR (*(volatile unsigned long *)(CAN_CENTRAL_BASE_ADDR + 0x08))\r
+\r
+#define CAN1_BASE_ADDR 0x40044000\r
+#define CAN1MOD (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x00)) \r
+#define CAN1CMR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x04)) \r
+#define CAN1GSR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x08)) \r
+#define CAN1ICR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x0C)) \r
+#define CAN1IER (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x10))\r
+#define CAN1BTR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x14)) \r
+#define CAN1EWL (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x18)) \r
+#define CAN1SR (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x1C)) \r
+#define CAN1RFS (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x20)) \r
+#define CAN1RID (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x24))\r
+#define CAN1RDA (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x28)) \r
+#define CAN1RDB (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x2C))\r
+ \r
+#define CAN1TFI1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x30)) \r
+#define CAN1TID1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x34)) \r
+#define CAN1TDA1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x38))\r
+#define CAN1TDB1 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x3C)) \r
+#define CAN1TFI2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x40)) \r
+#define CAN1TID2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x44)) \r
+#define CAN1TDA2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x48)) \r
+#define CAN1TDB2 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x4C))\r
+#define CAN1TFI3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x50)) \r
+#define CAN1TID3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x54)) \r
+#define CAN1TDA3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x58)) \r
+#define CAN1TDB3 (*(volatile unsigned long *)(CAN1_BASE_ADDR + 0x5C))\r
+\r
+#define CAN2_BASE_ADDR 0x40048000\r
+#define CAN2MOD (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x00)) \r
+#define CAN2CMR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x04)) \r
+#define CAN2GSR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x08)) \r
+#define CAN2ICR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x0C)) \r
+#define CAN2IER (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x10))\r
+#define CAN2BTR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x14)) \r
+#define CAN2EWL (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x18)) \r
+#define CAN2SR (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x1C)) \r
+#define CAN2RFS (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x20)) \r
+#define CAN2RID (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x24))\r
+#define CAN2RDA (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x28)) \r
+#define CAN2RDB (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x2C))\r
+ \r
+#define CAN2TFI1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x30)) \r
+#define CAN2TID1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x34)) \r
+#define CAN2TDA1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x38))\r
+#define CAN2TDB1 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x3C)) \r
+#define CAN2TFI2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x40)) \r
+#define CAN2TID2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x44)) \r
+#define CAN2TDA2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x48)) \r
+#define CAN2TDB2 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x4C))\r
+#define CAN2TFI3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x50)) \r
+#define CAN2TID3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x54)) \r
+#define CAN2TDA3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x58)) \r
+#define CAN2TDB3 (*(volatile unsigned long *)(CAN2_BASE_ADDR + 0x5C))\r
+\r
+/* I2S Interface Controller (I2S) */\r
+#define I2S_BASE_ADDR 0x400A8000\r
+#define I2S_DAO (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x00))\r
+#define I2S_DAI (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x04))\r
+#define I2S_TX_FIFO (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x08))\r
+#define I2S_RX_FIFO (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x0C))\r
+#define I2S_STATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x10))\r
+#define I2S_DMA1 (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x14))\r
+#define I2S_DMA2 (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x18))\r
+#define I2S_IRQ (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x1C))\r
+#define I2S_TXRATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x20))\r
+#define I2S_RXRATE (*(volatile unsigned long *)(I2S_BASE_ADDR + 0x24))\r
+\r
+/* General-purpose DMA Controller */\r
+#define DMA_BASE_ADDR 0x50004000\r
+#define GPDMA_INT_STAT (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x000))\r
+#define GPDMA_INT_TCSTAT (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x004))\r
+#define GPDMA_INT_TCCLR (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x008))\r
+#define GPDMA_INT_ERR_STAT (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x00C))\r
+#define GPDMA_INT_ERR_CLR (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x010))\r
+#define GPDMA_RAW_INT_TCSTAT (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x014))\r
+#define GPDMA_RAW_INT_ERR_STAT (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x018))\r
+#define GPDMA_ENABLED_CHNS (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x01C))\r
+#define GPDMA_SOFT_BREQ (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x020))\r
+#define GPDMA_SOFT_SREQ (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x024))\r
+#define GPDMA_SOFT_LBREQ (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x028))\r
+#define GPDMA_SOFT_LSREQ (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x02C))\r
+#define GPDMA_CONFIG (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x030))\r
+#define GPDMA_SYNC (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x034))\r
+\r
+/* DMA channel 0 registers */\r
+#define GPDMA_CH0_SRC (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x100))\r
+#define GPDMA_CH0_DEST (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x104))\r
+#define GPDMA_CH0_LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x108))\r
+#define GPDMA_CH0_CTRL (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x10C))\r
+#define GPDMA_CH0_CFG (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x110))\r
+\r
+/* DMA channel 1 registers */\r
+#define GPDMA_CH1_SRC (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x120))\r
+#define GPDMA_CH1_DEST (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x124))\r
+#define GPDMA_CH1_LLI (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x128))\r
+#define GPDMA_CH1_CTRL (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x12C))\r
+#define GPDMA_CH1_CFG (*(volatile unsigned long *)(DMA_BASE_ADDR + 0x130))\r
+\r
+\r
+/* USB Controller */\r
+#define USB_INT_BASE_ADDR 0x400FC1C0\r
+#define USB_BASE_ADDR 0x5000C200 /* USB Base Address */\r
+\r
+#define USB_INT_STAT (*(volatile unsigned long *)(USB_INT_BASE_ADDR + 0x00))\r
+\r
+/* USB Device Interrupt Registers */\r
+#define DEV_INT_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0x00))\r
+#define DEV_INT_EN (*(volatile unsigned long *)(USB_BASE_ADDR + 0x04))\r
+#define DEV_INT_CLR (*(volatile unsigned long *)(USB_BASE_ADDR + 0x08))\r
+#define DEV_INT_SET (*(volatile unsigned long *)(USB_BASE_ADDR + 0x0C))\r
+#define DEV_INT_PRIO (*(volatile unsigned long *)(USB_BASE_ADDR + 0x2C))\r
+\r
+/* USB Device Endpoint Interrupt Registers */\r
+#define EP_INT_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0x30))\r
+#define EP_INT_EN (*(volatile unsigned long *)(USB_BASE_ADDR + 0x34))\r
+#define EP_INT_CLR (*(volatile unsigned long *)(USB_BASE_ADDR + 0x38))\r
+#define EP_INT_SET (*(volatile unsigned long *)(USB_BASE_ADDR + 0x3C))\r
+#define EP_INT_PRIO (*(volatile unsigned long *)(USB_BASE_ADDR + 0x40))\r
+\r
+/* USB Device Endpoint Realization Registers */\r
+#define REALIZE_EP (*(volatile unsigned long *)(USB_BASE_ADDR + 0x44))\r
+#define EP_INDEX (*(volatile unsigned long *)(USB_BASE_ADDR + 0x48))\r
+#define MAXPACKET_SIZE (*(volatile unsigned long *)(USB_BASE_ADDR + 0x4C))\r
+\r
+/* USB Device Command Reagisters */\r
+#define CMD_CODE (*(volatile unsigned long *)(USB_BASE_ADDR + 0x10))\r
+#define CMD_DATA (*(volatile unsigned long *)(USB_BASE_ADDR + 0x14))\r
+\r
+/* USB Device Data Transfer Registers */\r
+#define RX_DATA (*(volatile unsigned long *)(USB_BASE_ADDR + 0x18))\r
+#define TX_DATA (*(volatile unsigned long *)(USB_BASE_ADDR + 0x1C))\r
+#define RX_PLENGTH (*(volatile unsigned long *)(USB_BASE_ADDR + 0x20))\r
+#define TX_PLENGTH (*(volatile unsigned long *)(USB_BASE_ADDR + 0x24))\r
+#define USB_CTRL (*(volatile unsigned long *)(USB_BASE_ADDR + 0x28))\r
+\r
+/* USB Device DMA Registers */\r
+#define DMA_REQ_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0x50))\r
+#define DMA_REQ_CLR (*(volatile unsigned long *)(USB_BASE_ADDR + 0x54))\r
+#define DMA_REQ_SET (*(volatile unsigned long *)(USB_BASE_ADDR + 0x58))\r
+#define UDCA_HEAD (*(volatile unsigned long *)(USB_BASE_ADDR + 0x80))\r
+#define EP_DMA_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0x84))\r
+#define EP_DMA_EN (*(volatile unsigned long *)(USB_BASE_ADDR + 0x88))\r
+#define EP_DMA_DIS (*(volatile unsigned long *)(USB_BASE_ADDR + 0x8C))\r
+#define DMA_INT_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0x90))\r
+#define DMA_INT_EN (*(volatile unsigned long *)(USB_BASE_ADDR + 0x94))\r
+#define EOT_INT_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0xA0))\r
+#define EOT_INT_CLR (*(volatile unsigned long *)(USB_BASE_ADDR + 0xA4))\r
+#define EOT_INT_SET (*(volatile unsigned long *)(USB_BASE_ADDR + 0xA8))\r
+#define NDD_REQ_INT_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0xAC))\r
+#define NDD_REQ_INT_CLR (*(volatile unsigned long *)(USB_BASE_ADDR + 0xB0))\r
+#define NDD_REQ_INT_SET (*(volatile unsigned long *)(USB_BASE_ADDR + 0xB4))\r
+#define SYS_ERR_INT_STAT (*(volatile unsigned long *)(USB_BASE_ADDR + 0xB8))\r
+#define SYS_ERR_INT_CLR (*(volatile unsigned long *)(USB_BASE_ADDR + 0xBC))\r
+#define SYS_ERR_INT_SET (*(volatile unsigned long *)(USB_BASE_ADDR + 0xC0))\r
+\r
+/* USB Host and OTG registers are for LPC24xx only */\r
+/* USB Host Controller */\r
+#define USBHC_BASE_ADDR 0x5000C000\r
+#define HC_REVISION (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x00))\r
+#define HC_CONTROL (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x04))\r
+#define HC_CMD_STAT (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x08))\r
+#define HC_INT_STAT (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x0C))\r
+#define HC_INT_EN (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x10))\r
+#define HC_INT_DIS (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x14))\r
+#define HC_HCCA (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x18))\r
+#define HC_PERIOD_CUR_ED (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x1C))\r
+#define HC_CTRL_HEAD_ED (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x20))\r
+#define HC_CTRL_CUR_ED (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x24))\r
+#define HC_BULK_HEAD_ED (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x28))\r
+#define HC_BULK_CUR_ED (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x2C))\r
+#define HC_DONE_HEAD (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x30))\r
+#define HC_FM_INTERVAL (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x34))\r
+#define HC_FM_REMAINING (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x38))\r
+#define HC_FM_NUMBER (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x3C))\r
+#define HC_PERIOD_START (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x40))\r
+#define HC_LS_THRHLD (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x44))\r
+#define HC_RH_DESCA (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x48))\r
+#define HC_RH_DESCB (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x4C))\r
+#define HC_RH_STAT (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x50))\r
+#define HC_RH_PORT_STAT1 (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x54))\r
+#define HC_RH_PORT_STAT2 (*(volatile unsigned long *)(USBHC_BASE_ADDR + 0x58))\r
+\r
+/* USB OTG Controller */\r
+#define USBOTG_BASE_ADDR 0x5000C100\r
+#define OTG_INT_STAT (*(volatile unsigned long *)(USBOTG_BASE_ADDR + 0x00))\r
+#define OTG_INT_EN (*(volatile unsigned long *)(USBOTG_BASE_ADDR + 0x04))\r
+#define OTG_INT_SET (*(volatile unsigned long *)(USBOTG_BASE_ADDR + 0x08))\r
+#define OTG_INT_CLR (*(volatile unsigned long *)(USBOTG_BASE_ADDR + 0x0C))\r
+/* On LPC17xx, the name is USBPortSel */ \r
+#define OTG_STAT_CTRL (*(volatile unsigned long *)(USBOTG_BASE_ADDR + 0x10))\r
+#define OTG_TIMER (*(volatile unsigned long *)(USBOTG_BASE_ADDR + 0x14))\r
+\r
+#define USBOTG_I2C_BASE_ADDR 0x5000C300\r
+#define OTG_I2C_RX (*(volatile unsigned long *)(USBOTG_I2C_BASE_ADDR + 0x00))\r
+#define OTG_I2C_TX (*(volatile unsigned long *)(USBOTG_I2C_BASE_ADDR + 0x00))\r
+#define OTG_I2C_STS (*(volatile unsigned long *)(USBOTG_I2C_BASE_ADDR + 0x04))\r
+#define OTG_I2C_CTL (*(volatile unsigned long *)(USBOTG_I2C_BASE_ADDR + 0x08))\r
+#define OTG_I2C_CLKHI (*(volatile unsigned long *)(USBOTG_I2C_BASE_ADDR + 0x0C))\r
+#define OTG_I2C_CLKLO (*(volatile unsigned long *)(USBOTG_I2C_BASE_ADDR + 0x10))\r
+\r
+/* On LPC17xx, the names are USBClkCtrl and USBClkSt */\r
+#define USBOTG_CLK_BASE_ADDR 0x5000CFF0\r
+#define OTG_CLK_CTRL (*(volatile unsigned long *)(USBOTG_CLK_BASE_ADDR + 0x04))\r
+#define OTG_CLK_STAT (*(volatile unsigned long *)(USBOTG_CLK_BASE_ADDR + 0x08))\r
+\r
+/* Note: below three register name convention is for LPC17xx USB device only, match\r
+with the spec. update in USB Device Section. */ \r
+#define USBPortSel (*(volatile unsigned long *)(USBOTG_BASE_ADDR + 0x10))\r
+#define USBClkCtrl (*(volatile unsigned long *)(USBOTG_CLK_BASE_ADDR + 0x04))\r
+#define USBClkSt (*(volatile unsigned long *)(USBOTG_CLK_BASE_ADDR + 0x08))\r
+\r
+/* Ethernet MAC (32 bit data bus) -- all registers are RW unless indicated in parentheses */\r
+#define MAC_BASE_ADDR 0x50000000\r
+#define MAC_MAC1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x000)) /* MAC config reg 1 */\r
+#define MAC_MAC2 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x004)) /* MAC config reg 2 */\r
+#define MAC_IPGT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x008)) /* b2b InterPacketGap reg */\r
+#define MAC_IPGR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x00C)) /* non b2b InterPacketGap reg */\r
+#define MAC_CLRT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x010)) /* CoLlision window/ReTry reg */\r
+#define MAC_MAXF (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x014)) /* MAXimum Frame reg */\r
+#define MAC_SUPP (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x018)) /* PHY SUPPort reg */\r
+#define MAC_TEST (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x01C)) /* TEST reg */\r
+#define MAC_MCFG (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x020)) /* MII Mgmt ConFiG reg */\r
+#define MAC_MCMD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x024)) /* MII Mgmt CoMmanD reg */\r
+#define MAC_MADR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x028)) /* MII Mgmt ADdRess reg */\r
+#define MAC_MWTD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x02C)) /* MII Mgmt WriTe Data reg (WO) */\r
+#define MAC_MRDD (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x030)) /* MII Mgmt ReaD Data reg (RO) */\r
+#define MAC_MIND (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x034)) /* MII Mgmt INDicators reg (RO) */\r
+\r
+#define MAC_SA0 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x040)) /* Station Address 0 reg */\r
+#define MAC_SA1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x044)) /* Station Address 1 reg */\r
+#define MAC_SA2 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x048)) /* Station Address 2 reg */\r
+\r
+#define MAC_COMMAND (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x100)) /* Command reg */\r
+#define MAC_STATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x104)) /* Status reg (RO) */\r
+#define MAC_RXDESCRIPTOR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x108)) /* Rx descriptor base address reg */\r
+#define MAC_RXSTATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x10C)) /* Rx status base address reg */\r
+#define MAC_RXDESCRIPTORNUM (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x110)) /* Rx number of descriptors reg */\r
+#define MAC_RXPRODUCEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x114)) /* Rx produce index reg (RO) */\r
+#define MAC_RXCONSUMEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x118)) /* Rx consume index reg */\r
+#define MAC_TXDESCRIPTOR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x11C)) /* Tx descriptor base address reg */\r
+#define MAC_TXSTATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x120)) /* Tx status base address reg */\r
+#define MAC_TXDESCRIPTORNUM (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x124)) /* Tx number of descriptors reg */\r
+#define MAC_TXPRODUCEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x128)) /* Tx produce index reg */\r
+#define MAC_TXCONSUMEINDEX (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x12C)) /* Tx consume index reg (RO) */\r
+\r
+#define MAC_TSV0 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x158)) /* Tx status vector 0 reg (RO) */\r
+#define MAC_TSV1 (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x15C)) /* Tx status vector 1 reg (RO) */\r
+#define MAC_RSV (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x160)) /* Rx status vector reg (RO) */\r
+\r
+#define MAC_FLOWCONTROLCNT (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x170)) /* Flow control counter reg */\r
+#define MAC_FLOWCONTROLSTS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x174)) /* Flow control status reg */\r
+\r
+#define MAC_RXFILTERCTRL (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x200)) /* Rx filter ctrl reg */\r
+#define MAC_RXFILTERWOLSTS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x204)) /* Rx filter WoL status reg (RO) */\r
+#define MAC_RXFILTERWOLCLR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x208)) /* Rx filter WoL clear reg (WO) */\r
+\r
+#define MAC_HASHFILTERL (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x210)) /* Hash filter LSBs reg */\r
+#define MAC_HASHFILTERH (*(volatile unsigned long *)(MAC_BASE_ADDR + 0x214)) /* Hash filter MSBs reg */\r
+\r
+#define MAC_INTSTATUS (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE0)) /* Interrupt status reg (RO) */\r
+#define MAC_INTENABLE (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE4)) /* Interrupt enable reg */\r
+#define MAC_INTCLEAR (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFE8)) /* Interrupt clear reg (WO) */\r
+#define MAC_INTSET (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFEC)) /* Interrupt set reg (WO) */\r
+\r
+#define MAC_POWERDOWN (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFF4)) /* Power-down reg */\r
+#define MAC_MODULEID (*(volatile unsigned long *)(MAC_BASE_ADDR + 0xFFC)) /* Module ID reg (RO) */\r
+\r
+\r
+#define FLASHCFG (*(volatile unsigned long * ) (0x400F C000))\r
+\r
+#endif // __LPC17xx_H\r
+\r
--- /dev/null
+/*\r
+ FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry.\r
+\r
+ This file is part of the FreeRTOS.org distribution.\r
+\r
+ FreeRTOS.org is free software; you can redistribute it and/or modify it\r
+ under the terms of the GNU General Public License (version 2) as published\r
+ by the Free Software Foundation and modified by the FreeRTOS exception.\r
+ **NOTE** The exception to the GPL is included to allow you to distribute a\r
+ combined work that includes FreeRTOS.org without being obliged to provide\r
+ the source code for any proprietary components. Alternative commercial\r
+ license and support terms are also available upon request. See the\r
+ licensing section of http://www.FreeRTOS.org for full details.\r
+\r
+ FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT\r
+ ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or\r
+ FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for\r
+ more details.\r
+\r
+ You should have received a copy of the GNU General Public License along\r
+ with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59\r
+ Temple Place, Suite 330, Boston, MA 02111-1307 USA.\r
+\r
+\r
+ ***************************************************************************\r
+ * *\r
+ * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation *\r
+ * *\r
+ * This is a concise, step by step, 'hands on' guide that describes both *\r
+ * general multitasking concepts and FreeRTOS specifics. It presents and *\r
+ * explains numerous examples that are written using the FreeRTOS API. *\r
+ * Full source code for all the examples is provided in an accompanying *\r
+ * .zip file. *\r
+ * *\r
+ ***************************************************************************\r
+\r
+ 1 tab == 4 spaces!\r
+\r
+ Please ensure to read the configuration and relevant port sections of the\r
+ online documentation.\r
+\r
+ http://www.FreeRTOS.org - Documentation, latest information, license and\r
+ contact details.\r
+\r
+ http://www.SafeRTOS.com - A version that is certified for use in safety\r
+ critical systems.\r
+\r
+ http://www.OpenRTOS.com - Commercial support, development, porting,\r
+ licensing and training services.\r
+*/\r
+\r
+/* FreeRTOS.org includes. */\r
+#include "FreeRTOS.h"\r
+\r
+/* Demo application includes. */\r
+#include "partest.h"\r
+\r
+#define partstFIRST_IO ( ( unsigned portLONG ) 0x04 )\r
+#define partstNUM_LEDS ( 5 )\r
+#define partstALL_OUTPUTS_OFF ( ( unsigned portLONG ) 0xff )\r
+\r
+/*-----------------------------------------------------------\r
+ * Simple parallel port IO routines.\r
+ *-----------------------------------------------------------*/\r
+\r
+void vParTestInitialise( void )\r
+{\r
+ PINSEL10 = 0;\r
+ FIO2DIR = 0x000000FF;\r
+ FIO2MASK = 0x00000000;\r
+ FIO2CLR = 0xFF;\r
+ SCS |= (1<<0); //fast mode for port 0 and 1\r
+\r
+ FIO2CLR = partstALL_OUTPUTS_OFF;\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+void vParTestSetLED( unsigned portBASE_TYPE uxLED, signed portBASE_TYPE xValue )\r
+{\r
+unsigned portLONG ulLED = partstFIRST_IO;\r
+\r
+ if( uxLED < partstNUM_LEDS )\r
+ {\r
+ /* Rotate to the wanted bit of port */\r
+ ulLED <<= ( unsigned portLONG ) uxLED;\r
+\r
+ /* Set of clear the output. */\r
+ if( xValue )\r
+ {\r
+ FIO2CLR = ulLED;\r
+ }\r
+ else\r
+ {\r
+ FIO2SET = ulLED;\r
+ }\r
+ }\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+void vParTestToggleLED( unsigned portBASE_TYPE uxLED )\r
+{\r
+unsigned portLONG ulLED = partstFIRST_IO, ulCurrentState;\r
+\r
+ if( uxLED < partstNUM_LEDS )\r
+ {\r
+ /* Rotate to the wanted bit of port 0. Only P10 to P13 have an LED\r
+ attached. */\r
+ ulLED <<= ( unsigned portLONG ) uxLED;\r
+\r
+ /* If this bit is already set, clear it, and visa versa. */\r
+ ulCurrentState = FIO2PIN;\r
+ if( ulCurrentState & ulLED )\r
+ {\r
+ FIO2CLR = ulLED;\r
+ }\r
+ else\r
+ {\r
+ FIO2SET = ulLED;\r
+ }\r
+ }\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+unsigned portBASE_TYPE uxParTextGetLED( unsigned portBASE_TYPE uxLED )\r
+{\r
+unsigned portLONG ulLED = partstFIRST_IO;\r
+\r
+ ulLED <<= ( unsigned portLONG ) uxLED;\r
+\r
+ return ( FIO2PIN & ulLED );\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+long lParTestGetLEDState( unsigned portBASE_TYPE uxLED )\r
+{\r
+ return 0;\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+int __putchar( int x )\r
+{\r
+ /* Not used. */\r
+}\r
+\r
+\r
+\r
+\r
--- /dev/null
+<!DOCTYPE CrossStudio_Project_File>
+<solution Name="RTOSDemo" version="2">
+ <project Name="RTOSDemo">
+ <configuration Name="Common" Target="LPC1768" arm_architecture="v7M" arm_core_type="Cortex-M3" arm_linker_heap_size="128" arm_linker_process_stack_size="0" arm_linker_stack_size="128" arm_simulator_memory_simulation_filename="$(TargetsDir)/LPC1000/LPC1000SimulatorMemory.dll" arm_simulator_memory_simulation_parameter="0x80000;0x8000;0x8000" arm_target_debug_interface_type="ADIv5" arm_target_loader_parameter="12000000" c_preprocessor_definitions="PACK_STRUCT_END=__attribute((packed));ALIGN_STRUCT_END=__attribute((aligned(4)))" c_user_include_directories="$(TargetsDir)/LPC1000/include;../../Source/include;../Common/include;../../Source/portable/GCC/ARM_CM3;../Common/ethernet/uIP/uip-1.0/uip;.;./webserver" link_include_startup_code="No" linker_additional_files="$(TargetsDir)/LPC1000/lib/liblpc1000$(LibExt)$(LIB);$(TargetsDir)/LPC1000/lib/cmsis$(LibExt)$(LIB)" linker_memory_map_file="$(TargetsDir)/LPC1000/LPC1768_MemoryMap.xml" linker_printf_fmt_level="int" linker_printf_width_precision_supported="No" oscillator_frequency="12MHz" project_directory="" project_type="Executable" property_groups_file_path="$(TargetsDir)/LPC1000/propertyGroups.xml"/>
+ <configuration Name="RAM" Placement="RAM" linker_section_placement_file="$(StudioDir)/targets/Cortex_M/ram_placement.xml" target_reset_script="SRAMReset()"/>
+ <configuration Name="Flash" Placement="Flash" arm_target_flash_loader_file_path="$(TargetsDir)/LPC1000/Release/Loader_rpc.elf" arm_target_flash_loader_type="LIBMEM RPC Loader" linker_patch_build_command="$(StudioDir)/bin/crossscript "load(\"$(TargetsDir)/LPC1000/LPC1000_LinkPatch.js\");patch(\"$(TargetPath)\");"" linker_section_placement_file="$(StudioDir)/targets/Cortex_M/flash_placement.xml" target_reset_script="FLASHReset()"/>
+ <folder Name="Source Files">
+ <configuration Name="Common" filter="c;cpp;cxx;cc;h;s;asm;inc"/>
+ <folder Name="FreeRTOS">
+ <file file_name="../../Source/tasks.c"/>
+ <file file_name="../../Source/list.c"/>
+ <file file_name="../../Source/queue.c"/>
+ <file file_name="../../Source/portable/GCC/ARM_CM3/port.c"/>
+ <file file_name="../../Source/portable/MemMang/heap_2.c"/>
+ </folder>
+ <folder Name="Common Demo Tasks">
+ <file file_name="../Common/Minimal/recmutex.c"/>
+ <file file_name="../Common/Minimal/semtest.c"/>
+ <file file_name="../Common/Minimal/BlockQ.c"/>
+ <file file_name="../Common/Minimal/blocktim.c"/>
+ <file file_name="../Common/Minimal/flash.c"/>
+ <file file_name="../Common/Minimal/GenQTest.c"/>
+ <file file_name="../Common/Minimal/integer.c"/>
+ <file file_name="../Common/Minimal/QPeek.c"/>
+ <file file_name="../Common/Minimal/PollQ.c"/>
+ </folder>
+ <file file_name="main.c"/>
+ <folder Name="WEB Server">
+ <file file_name="../Common/ethernet/uIP/uip-1.0/uip/uip.c"/>
+ <file file_name="../Common/ethernet/uIP/uip-1.0/uip/uip_arp.c"/>
+ <file file_name="../Common/ethernet/uIP/uip-1.0/uip/psock.c"/>
+ <file file_name="../Common/ethernet/uIP/uip-1.0/uip/timer.c"/>
+ <file file_name="webserver/uIP_Task.c"/>
+ <file file_name="webserver/emac.c"/>
+ <file file_name="webserver/httpd.c"/>
+ <file file_name="webserver/httpd-cgi.c"/>
+ <file file_name="webserver/httpd-fs.c"/>
+ <file file_name="webserver/http-strings.c"/>
+ </folder>
+ <file file_name="ParTest.c"/>
+ <file file_name="printf-stdarg.c"/>
+ </folder>
+ <folder Name="System Files">
+ <file file_name="$(StudioDir)/source/thumb_crt0.s"/>
+ <file file_name="$(TargetsDir)/LPC1000/LPC1700_Target.js">
+ <configuration Name="Common" file_type="Reset Script"/>
+ </file>
+ <file file_name="LPC1700_Startup.s"/>
+ </folder>
+ </project>
+ <configuration Name="THUMB Flash Debug" inherited_configurations="THUMB;Flash;Debug"/>
+ <configuration Name="THUMB" Platform="ARM" arm_instruction_set="THUMB" arm_library_instruction_set="THUMB" c_preprocessor_definitions="__THUMB" hidden="Yes"/>
+ <configuration Name="Flash" c_preprocessor_definitions="__FLASH_BUILD" hidden="Yes"/>
+ <configuration Name="Debug" build_debug_information="Yes" c_preprocessor_definitions="DEBUG" gcc_optimization_level="None" hidden="Yes" link_include_startup_code="No"/>
+ <configuration Name="THUMB Flash Release" inherited_configurations="THUMB;Flash;Release"/>
+ <configuration Name="Release" build_debug_information="No" c_additional_options="-g1" c_preprocessor_definitions="NDEBUG" gcc_optimization_level="Level 1" hidden="Yes" link_include_startup_code="No"/>
+</solution>
--- /dev/null
+<!DOCTYPE CrossStudio_for_ARM_Session_File>
+<session>
+ <Bookmarks/>
+ <Breakpoints/>
+ <ExecutionCountWindow/>
+ <Memory1>
+ <MemoryWindow autoEvaluate="0" addressText="0x10003c24" numColumns="8" sizeText="100" dataSize="1" radix="16" addressSpace="" />
+ </Memory1>
+ <Memory2>
+ <MemoryWindow autoEvaluate="0" addressText="" numColumns="8" sizeText="" dataSize="1" radix="16" addressSpace="" />
+ </Memory2>
+ <Memory3>
+ <MemoryWindow autoEvaluate="0" addressText="" numColumns="8" sizeText="" dataSize="1" radix="16" addressSpace="" />
+ </Memory3>
+ <Memory4>
+ <MemoryWindow autoEvaluate="0" addressText="" numColumns="8" sizeText="" dataSize="1" radix="16" addressSpace="" />
+ </Memory4>
+ <Project>
+ <ProjectSessionItem path="RTOSDemo" name="unnamed" />
+ <ProjectSessionItem path="RTOSDemo;RTOSDemo" name="unnamed" />
+ <ProjectSessionItem path="RTOSDemo;RTOSDemo;Source Files" name="unnamed" />
+ </Project>
+ <Register1>
+ <RegisterWindow openNodes="CPU;CPU/xPSR;CPU/CFBP;CPU/CFBP/CONTROL[0];CPU/CFBP/CONTROL[1]" binaryNodes="" unsignedNodes="" visibleGroups="CPU" decimalNodes="" octalNodes="" asciiNodes="" />
+ </Register1>
+ <Register2>
+ <RegisterWindow openNodes="" binaryNodes="" unsignedNodes="" visibleGroups="" decimalNodes="" octalNodes="" asciiNodes="" />
+ </Register2>
+ <Register3>
+ <RegisterWindow openNodes="" binaryNodes="" unsignedNodes="" visibleGroups="" decimalNodes="" octalNodes="" asciiNodes="" />
+ </Register3>
+ <Register4>
+ <RegisterWindow openNodes="" binaryNodes="" unsignedNodes="" visibleGroups="" decimalNodes="" octalNodes="" asciiNodes="" />
+ </Register4>
+ <TargetWindow programAction="" uploadFileType="" programLoadAddress="" programSize="" uploadFileName="" uploadMemoryInterface="" programFileName="" uploadStartAddress="" programFileType="" uploadSize="" programMemoryInterface="" />
+ <TraceWindow>
+ <Trace enabled="Yes" />
+ </TraceWindow>
+ <Watch1>
+ <Watches active="1" update="Never" />
+ </Watch1>
+ <Watch2>
+ <Watches active="0" update="Never" />
+ </Watch2>
+ <Watch3>
+ <Watches active="0" update="Never" />
+ </Watch3>
+ <Watch4>
+ <Watches active="0" update="Never" />
+ </Watch4>
+ <Files>
+ <SessionOpenFile useTextEdit="1" useBinaryEdit="0" codecName="Latin1" x="0" debugPath="C:\E\Dev\FreeRTOS\WorkingCopy3\Demo\CORTEX_LPC1768_GCC_Rowley\main.c" y="172" path="C:\E\Dev\FreeRTOS\WorkingCopy3\Demo\CORTEX_LPC1768_GCC_Rowley\main.c" left="0" selected="1" name="unnamed" top="150" />
+ </Files>
+ <ARMCrossStudioWindow activeProject="RTOSDemo" autoConnectTarget="Amontec JTAGkey" debugSearchFileMap="" fileDialogInitialDirectory="C:\E\Dev\FreeRTOS\WorkingCopy3\Demo\CORTEX_LPC1768_GCC_Rowley" fileDialogDefaultFilter="*.*" autoConnectCapabilities="388991" debugSearchPath="" buildConfiguration="THUMB Flash Debug" />
+</session>
--- /dev/null
+/******************************************************************************\r
+ * @file: core_cm3.h\r
+ * @purpose: CMSIS Cortex-M3 Core Peripheral Access Layer Header File\r
+ * @version: V1.20\r
+ * @date: 22. May 2009\r
+ *----------------------------------------------------------------------------\r
+ *\r
+ * Copyright (C) 2009 ARM Limited. All rights reserved.\r
+ *\r
+ * ARM Limited (ARM) is supplying this software for use with Cortex-Mx \r
+ * processor based microcontrollers. This file can be freely distributed \r
+ * within development tools that are supporting such ARM based processors. \r
+ *\r
+ * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED\r
+ * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF\r
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.\r
+ * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR\r
+ * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.\r
+ *\r
+ ******************************************************************************/\r
+\r
+#ifndef __CM3_CORE_H__\r
+#define __CM3_CORE_H__\r
+\r
+#ifdef __cplusplus\r
+ extern "C" {\r
+#endif \r
+\r
+#define __CM3_CMSIS_VERSION_MAIN (0x01) /*!< [31:16] CMSIS HAL main version */\r
+#define __CM3_CMSIS_VERSION_SUB (0x20) /*!< [15:0] CMSIS HAL sub version */\r
+#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16) | __CM3_CMSIS_VERSION_SUB) /*!< CMSIS HAL version number */\r
+\r
+#define __CORTEX_M (0x03) /*!< Cortex core */\r
+\r
+/**\r
+ * Lint configuration \n\r
+ * ----------------------- \n\r
+ *\r
+ * The following Lint messages will be suppressed and not shown: \n\r
+ * \n\r
+ * --- Error 10: --- \n\r
+ * register uint32_t __regBasePri __asm("basepri"); \n\r
+ * Error 10: Expecting ';' \n\r
+ * \n\r
+ * --- Error 530: --- \n\r
+ * return(__regBasePri); \n\r
+ * Warning 530: Symbol '__regBasePri' (line 264) not initialized \n\r
+ * \n\r
+ * --- Error 550: --- \n\r
+ * __regBasePri = (basePri & 0x1ff); \n\r
+ * } \n\r
+ * Warning 550: Symbol '__regBasePri' (line 271) not accessed \n\r
+ * \n\r
+ * --- Error 754: --- \n\r
+ * uint32_t RESERVED0[24]; \n\r
+ * Info 754: local structure member '<some, not used in the HAL>' (line 109, file ./cm3_core.h) not referenced \n\r
+ * \n\r
+ * --- Error 750: --- \n\r
+ * #define __CM3_CORE_H__ \n\r
+ * Info 750: local macro '__CM3_CORE_H__' (line 43, file./cm3_core.h) not referenced \n\r
+ * \n\r
+ * --- Error 528: --- \n\r
+ * static __INLINE void NVIC_DisableIRQ(uint32_t IRQn) \n\r
+ * Warning 528: Symbol 'NVIC_DisableIRQ(unsigned int)' (line 419, file ./cm3_core.h) not referenced \n\r
+ * \n\r
+ * --- Error 751: --- \n\r
+ * } InterruptType_Type; \n\r
+ * Info 751: local typedef 'InterruptType_Type' (line 170, file ./cm3_core.h) not referenced \n\r
+ * \n\r
+ * \n\r
+ * Note: To re-enable a Message, insert a space before 'lint' * \n\r
+ *\r
+ */\r
+\r
+/*lint -save */\r
+/*lint -e10 */\r
+/*lint -e530 */\r
+/*lint -e550 */\r
+/*lint -e754 */\r
+/*lint -e750 */\r
+/*lint -e528 */\r
+/*lint -e751 */\r
+\r
+\r
+#include <stdint.h> /* Include standard types */\r
+\r
+#if defined (__ICCARM__)\r
+ #include <intrinsics.h> /* IAR Intrinsics */\r
+#endif\r
+\r
+\r
+#ifndef __NVIC_PRIO_BITS\r
+ #define __NVIC_PRIO_BITS 4 /*!< standard definition for NVIC Priority Bits */\r
+#endif\r
+\r
+\r
+\r
+\r
+/**\r
+ * IO definitions\r
+ *\r
+ * define access restrictions to peripheral registers\r
+ */\r
+\r
+#ifdef __cplusplus\r
+#define __I volatile /*!< defines 'read only' permissions */\r
+#else\r
+#define __I volatile const /*!< defines 'read only' permissions */\r
+#endif\r
+#define __O volatile /*!< defines 'write only' permissions */\r
+#define __IO volatile /*!< defines 'read / write' permissions */\r
+\r
+\r
+\r
+/*******************************************************************************\r
+ * Register Abstraction\r
+ ******************************************************************************/\r
+\r
+\r
+/* System Reset */\r
+#define NVIC_VECTRESET 0 /*!< Vector Reset Bit */\r
+#define NVIC_SYSRESETREQ 2 /*!< System Reset Request */\r
+#define NVIC_AIRCR_VECTKEY (0x5FA << 16) /*!< AIRCR Key for write access */\r
+#define NVIC_AIRCR_ENDIANESS 15 /*!< Endianess */\r
+\r
+/* Core Debug */\r
+#define CoreDebug_DEMCR_TRCENA (1 << 24) /*!< DEMCR TRCENA enable */\r
+#define ITM_TCR_ITMENA 1 /*!< ITM enable */\r
+\r
+\r
+\r
+\r
+/* memory mapping struct for Nested Vectored Interrupt Controller (NVIC) */\r
+typedef struct\r
+{\r
+ __IO uint32_t ISER[8]; /*!< Interrupt Set Enable Register */\r
+ uint32_t RESERVED0[24];\r
+ __IO uint32_t ICER[8]; /*!< Interrupt Clear Enable Register */\r
+ uint32_t RSERVED1[24];\r
+ __IO uint32_t ISPR[8]; /*!< Interrupt Set Pending Register */\r
+ uint32_t RESERVED2[24];\r
+ __IO uint32_t ICPR[8]; /*!< Interrupt Clear Pending Register */\r
+ uint32_t RESERVED3[24];\r
+ __IO uint32_t IABR[8]; /*!< Interrupt Active bit Register */\r
+ uint32_t RESERVED4[56];\r
+ __IO uint8_t IP[240]; /*!< Interrupt Priority Register, 8Bit wide */\r
+ uint32_t RESERVED5[644];\r
+ __O uint32_t STIR; /*!< Software Trigger Interrupt Register */\r
+} NVIC_Type;\r
+\r
+\r
+/* memory mapping struct for System Control Block */\r
+typedef struct\r
+{\r
+ __I uint32_t CPUID; /*!< CPU ID Base Register */\r
+ __IO uint32_t ICSR; /*!< Interrupt Control State Register */\r
+ __IO uint32_t VTOR; /*!< Vector Table Offset Register */\r
+ __IO uint32_t AIRCR; /*!< Application Interrupt / Reset Control Register */\r
+ __IO uint32_t SCR; /*!< System Control Register */\r
+ __IO uint32_t CCR; /*!< Configuration Control Register */\r
+ __IO uint8_t SHP[12]; /*!< System Handlers Priority Registers (4-7, 8-11, 12-15) */\r
+ __IO uint32_t SHCSR; /*!< System Handler Control and State Register */\r
+ __IO uint32_t CFSR; /*!< Configurable Fault Status Register */\r
+ __IO uint32_t HFSR; /*!< Hard Fault Status Register */\r
+ __IO uint32_t DFSR; /*!< Debug Fault Status Register */\r
+ __IO uint32_t MMFAR; /*!< Mem Manage Address Register */\r
+ __IO uint32_t BFAR; /*!< Bus Fault Address Register */\r
+ __IO uint32_t AFSR; /*!< Auxiliary Fault Status Register */\r
+ __I uint32_t PFR[2]; /*!< Processor Feature Register */\r
+ __I uint32_t DFR; /*!< Debug Feature Register */\r
+ __I uint32_t ADR; /*!< Auxiliary Feature Register */\r
+ __I uint32_t MMFR[4]; /*!< Memory Model Feature Register */\r
+ __I uint32_t ISAR[5]; /*!< ISA Feature Register */\r
+} SCB_Type;\r
+\r
+\r
+/* memory mapping struct for SysTick */\r
+typedef struct\r
+{\r
+ __IO uint32_t CTRL; /*!< SysTick Control and Status Register */\r
+ __IO uint32_t LOAD; /*!< SysTick Reload Value Register */\r
+ __IO uint32_t VAL; /*!< SysTick Current Value Register */\r
+ __I uint32_t CALIB; /*!< SysTick Calibration Register */\r
+} SysTick_Type;\r
+\r
+\r
+/* memory mapping structur for ITM */\r
+typedef struct\r
+{\r
+ __O union \r
+ {\r
+ __O uint8_t u8; /*!< ITM Stimulus Port 8-bit */\r
+ __O uint16_t u16; /*!< ITM Stimulus Port 16-bit */\r
+ __O uint32_t u32; /*!< ITM Stimulus Port 32-bit */\r
+ } PORT [32]; /*!< ITM Stimulus Port Registers */\r
+ uint32_t RESERVED0[864];\r
+ __IO uint32_t TER; /*!< ITM Trace Enable Register */\r
+ uint32_t RESERVED1[15];\r
+ __IO uint32_t TPR; /*!< ITM Trace Privilege Register */\r
+ uint32_t RESERVED2[15];\r
+ __IO uint32_t TCR; /*!< ITM Trace Control Register */\r
+ uint32_t RESERVED3[29];\r
+ __IO uint32_t IWR; /*!< ITM Integration Write Register */\r
+ __IO uint32_t IRR; /*!< ITM Integration Read Register */\r
+ __IO uint32_t IMCR; /*!< ITM Integration Mode Control Register */\r
+ uint32_t RESERVED4[43];\r
+ __IO uint32_t LAR; /*!< ITM Lock Access Register */\r
+ __IO uint32_t LSR; /*!< ITM Lock Status Register */\r
+ uint32_t RESERVED5[6];\r
+ __I uint32_t PID4; /*!< ITM Product ID Registers */\r
+ __I uint32_t PID5;\r
+ __I uint32_t PID6;\r
+ __I uint32_t PID7;\r
+ __I uint32_t PID0;\r
+ __I uint32_t PID1;\r
+ __I uint32_t PID2;\r
+ __I uint32_t PID3;\r
+ __I uint32_t CID0;\r
+ __I uint32_t CID1;\r
+ __I uint32_t CID2;\r
+ __I uint32_t CID3;\r
+} ITM_Type;\r
+\r
+\r
+/* memory mapped struct for Interrupt Type */\r
+typedef struct\r
+{\r
+ uint32_t RESERVED0;\r
+ __I uint32_t ICTR; /*!< Interrupt Control Type Register */\r
+#if ((defined __CM3_REV) && (__CM3_REV >= 0x200))\r
+ __IO uint32_t ACTLR; /*!< Auxiliary Control Register */\r
+#else\r
+ uint32_t RESERVED1;\r
+#endif\r
+} InterruptType_Type;\r
+\r
+\r
+/* Memory Protection Unit */\r
+#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1)\r
+typedef struct\r
+{\r
+ __I uint32_t TYPE; /*!< MPU Type Register */\r
+ __IO uint32_t CTRL; /*!< MPU Control Register */\r
+ __IO uint32_t RNR; /*!< MPU Region RNRber Register */\r
+ __IO uint32_t RBAR; /*!< MPU Region Base Address Register */\r
+ __IO uint32_t RASR; /*!< MPU Region Attribute and Size Register */\r
+ __IO uint32_t RBAR_A1; /*!< MPU Alias 1 Region Base Address Register */\r
+ __IO uint32_t RASR_A1; /*!< MPU Alias 1 Region Attribute and Size Register */\r
+ __IO uint32_t RBAR_A2; /*!< MPU Alias 2 Region Base Address Register */\r
+ __IO uint32_t RASR_A2; /*!< MPU Alias 2 Region Attribute and Size Register */\r
+ __IO uint32_t RBAR_A3; /*!< MPU Alias 3 Region Base Address Register */\r
+ __IO uint32_t RASR_A3; /*!< MPU Alias 3 Region Attribute and Size Register */\r
+} MPU_Type;\r
+#endif\r
+\r
+\r
+/* Core Debug Register */\r
+typedef struct\r
+{\r
+ __IO uint32_t DHCSR; /*!< Debug Halting Control and Status Register */\r
+ __O uint32_t DCRSR; /*!< Debug Core Register Selector Register */\r
+ __IO uint32_t DCRDR; /*!< Debug Core Register Data Register */\r
+ __IO uint32_t DEMCR; /*!< Debug Exception and Monitor Control Register */\r
+} CoreDebug_Type;\r
+\r
+\r
+/* Memory mapping of Cortex-M3 Hardware */\r
+#define SCS_BASE (0xE000E000) /*!< System Control Space Base Address */\r
+#define ITM_BASE (0xE0000000) /*!< ITM Base Address */\r
+#define CoreDebug_BASE (0xE000EDF0) /*!< Core Debug Base Address */\r
+#define SysTick_BASE (SCS_BASE + 0x0010) /*!< SysTick Base Address */\r
+#define NVIC_BASE (SCS_BASE + 0x0100) /*!< NVIC Base Address */\r
+#define SCB_BASE (SCS_BASE + 0x0D00) /*!< System Control Block Base Address */\r
+\r
+#define InterruptType ((InterruptType_Type *) SCS_BASE) /*!< Interrupt Type Register */\r
+#define SCB ((SCB_Type *) SCB_BASE) /*!< SCB configuration struct */\r
+#define SysTick ((SysTick_Type *) SysTick_BASE) /*!< SysTick configuration struct */\r
+#define NVIC ((NVIC_Type *) NVIC_BASE) /*!< NVIC configuration struct */\r
+#define ITM ((ITM_Type *) ITM_BASE) /*!< ITM configuration struct */\r
+#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */\r
+\r
+#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1)\r
+ #define MPU_BASE (SCS_BASE + 0x0D90) /*!< Memory Protection Unit */\r
+ #define MPU ((MPU_Type*) MPU_BASE) /*!< Memory Protection Unit */\r
+#endif\r
+\r
+\r
+\r
+/*******************************************************************************\r
+ * Hardware Abstraction Layer\r
+ ******************************************************************************/\r
+\r
+\r
+#if defined ( __CC_ARM )\r
+ #define __ASM __asm /*!< asm keyword for ARM Compiler */\r
+ #define __INLINE __inline /*!< inline keyword for ARM Compiler */\r
+\r
+#elif defined ( __ICCARM__ )\r
+ #define __ASM __asm /*!< asm keyword for IAR Compiler */\r
+ #define __INLINE inline /*!< inline keyword for IAR Compiler. Only avaiable in High optimization mode! */\r
+\r
+#elif defined ( __GNUC__ )\r
+ #define __ASM __asm /*!< asm keyword for GNU Compiler */\r
+ #define __INLINE inline /*!< inline keyword for GNU Compiler */\r
+\r
+#elif defined ( __TASKING__ )\r
+ #define __ASM __asm /*!< asm keyword for TASKING Compiler */\r
+ #define __INLINE inline /*!< inline keyword for TASKING Compiler */\r
+\r
+#endif\r
+\r
+\r
+/* ################### Compiler specific Intrinsics ########################### */\r
+\r
+#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/\r
+/* ARM armcc specific functions */\r
+\r
+#define __enable_fault_irq __enable_fiq\r
+#define __disable_fault_irq __disable_fiq\r
+\r
+#define __NOP __nop\r
+#define __WFI __wfi\r
+#define __WFE __wfe\r
+#define __SEV __sev\r
+#define __ISB() __isb(0)\r
+#define __DSB() __dsb(0)\r
+#define __DMB() __dmb(0)\r
+#define __REV __rev\r
+#define __RBIT __rbit\r
+#define __LDREXB(ptr) ((unsigned char ) __ldrex(ptr))\r
+#define __LDREXH(ptr) ((unsigned short) __ldrex(ptr))\r
+#define __LDREXW(ptr) ((unsigned int ) __ldrex(ptr))\r
+#define __STREXB(value, ptr) __strex(value, ptr)\r
+#define __STREXH(value, ptr) __strex(value, ptr)\r
+#define __STREXW(value, ptr) __strex(value, ptr)\r
+\r
+\r
+/* intrinsic unsigned long long __ldrexd(volatile void *ptr) */\r
+/* intrinsic int __strexd(unsigned long long val, volatile void *ptr) */\r
+/* intrinsic void __enable_irq(); */\r
+/* intrinsic void __disable_irq(); */\r
+\r
+\r
+/**\r
+ * @brief Return the Process Stack Pointer\r
+ *\r
+ * @param none\r
+ * @return uint32_t ProcessStackPointer\r
+ *\r
+ * Return the actual process stack pointer\r
+ */\r
+extern uint32_t __get_PSP(void);\r
+\r
+/**\r
+ * @brief Set the Process Stack Pointer\r
+ *\r
+ * @param uint32_t Process Stack Pointer\r
+ * @return none\r
+ *\r
+ * Assign the value ProcessStackPointer to the MSP \r
+ * (process stack pointer) Cortex processor register\r
+ */\r
+extern void __set_PSP(uint32_t topOfProcStack);\r
+\r
+/**\r
+ * @brief Return the Main Stack Pointer\r
+ *\r
+ * @param none\r
+ * @return uint32_t Main Stack Pointer\r
+ *\r
+ * Return the current value of the MSP (main stack pointer)\r
+ * Cortex processor register\r
+ */\r
+extern uint32_t __get_MSP(void);\r
+\r
+/**\r
+ * @brief Set the Main Stack Pointer\r
+ *\r
+ * @param uint32_t Main Stack Pointer\r
+ * @return none\r
+ *\r
+ * Assign the value mainStackPointer to the MSP \r
+ * (main stack pointer) Cortex processor register\r
+ */\r
+extern void __set_MSP(uint32_t topOfMainStack);\r
+\r
+/**\r
+ * @brief Reverse byte order in unsigned short value\r
+ *\r
+ * @param uint16_t value to reverse\r
+ * @return uint32_t reversed value\r
+ *\r
+ * Reverse byte order in unsigned short value\r
+ */\r
+extern uint32_t __REV16(uint16_t value);\r
+\r
+/*\r
+ * @brief Reverse byte order in signed short value with sign extension to integer\r
+ *\r
+ * @param int16_t value to reverse\r
+ * @return int32_t reversed value\r
+ *\r
+ * Reverse byte order in signed short value with sign extension to integer\r
+ */\r
+extern int32_t __REVSH(int16_t value);\r
+\r
+\r
+#if (__ARMCC_VERSION < 400000)\r
+\r
+/**\r
+ * @brief Remove the exclusive lock created by ldrex\r
+ *\r
+ * @param none\r
+ * @return none\r
+ *\r
+ * Removes the exclusive lock which is created by ldrex.\r
+ */\r
+extern void __CLREX(void);\r
+\r
+/**\r
+ * @brief Return the Base Priority value\r
+ *\r
+ * @param none\r
+ * @return uint32_t BasePriority\r
+ *\r
+ * Return the content of the base priority register\r
+ */\r
+extern uint32_t __get_BASEPRI(void);\r
+\r
+/**\r
+ * @brief Set the Base Priority value\r
+ *\r
+ * @param uint32_t BasePriority\r
+ * @return none\r
+ *\r
+ * Set the base priority register\r
+ */\r
+extern void __set_BASEPRI(uint32_t basePri);\r
+\r
+/**\r
+ * @brief Return the Priority Mask value\r
+ *\r
+ * @param none\r
+ * @return uint32_t PriMask\r
+ *\r
+ * Return the state of the priority mask bit from the priority mask\r
+ * register\r
+ */\r
+extern uint32_t __get_PRIMASK(void);\r
+\r
+/**\r
+ * @brief Set the Priority Mask value\r
+ *\r
+ * @param uint32_t PriMask\r
+ * @return none\r
+ *\r
+ * Set the priority mask bit in the priority mask register\r
+ */\r
+extern void __set_PRIMASK(uint32_t priMask);\r
+\r
+/**\r
+ * @brief Return the Fault Mask value\r
+ *\r
+ * @param none\r
+ * @return uint32_t FaultMask\r
+ *\r
+ * Return the content of the fault mask register\r
+ */\r
+extern uint32_t __get_FAULTMASK(void);\r
+\r
+/**\r
+ * @brief Set the Fault Mask value\r
+ *\r
+ * @param uint32_t faultMask value\r
+ * @return none\r
+ *\r
+ * Set the fault mask register\r
+ */\r
+extern void __set_FAULTMASK(uint32_t faultMask);\r
+\r
+/**\r
+ * @brief Return the Control Register value\r
+ * \r
+ * @param none\r
+ * @return uint32_t Control value\r
+ *\r
+ * Return the content of the control register\r
+ */\r
+extern uint32_t __get_CONTROL(void);\r
+\r
+/**\r
+ * @brief Set the Control Register value\r
+ *\r
+ * @param uint32_t Control value\r
+ * @return none\r
+ *\r
+ * Set the control register\r
+ */\r
+extern void __set_CONTROL(uint32_t control);\r
+\r
+#else /* (__ARMCC_VERSION >= 400000) */\r
+\r
+\r
+/**\r
+ * @brief Remove the exclusive lock created by ldrex\r
+ *\r
+ * @param none\r
+ * @return none\r
+ *\r
+ * Removes the exclusive lock which is created by ldrex.\r
+ */\r
+#define __CLREX __clrex\r
+\r
+/**\r
+ * @brief Return the Base Priority value\r
+ *\r
+ * @param none\r
+ * @return uint32_t BasePriority\r
+ *\r
+ * Return the content of the base priority register\r
+ */\r
+static __INLINE uint32_t __get_BASEPRI(void)\r
+{\r
+ register uint32_t __regBasePri __ASM("basepri");\r
+ return(__regBasePri);\r
+}\r
+\r
+/**\r
+ * @brief Set the Base Priority value\r
+ *\r
+ * @param uint32_t BasePriority\r
+ * @return none\r
+ *\r
+ * Set the base priority register\r
+ */\r
+static __INLINE void __set_BASEPRI(uint32_t basePri)\r
+{\r
+ register uint32_t __regBasePri __ASM("basepri");\r
+ __regBasePri = (basePri & 0x1ff);\r
+}\r
+\r
+/**\r
+ * @brief Return the Priority Mask value\r
+ *\r
+ * @param none\r
+ * @return uint32_t PriMask\r
+ *\r
+ * Return the state of the priority mask bit from the priority mask\r
+ * register\r
+ */\r
+static __INLINE uint32_t __get_PRIMASK(void)\r
+{\r
+ register uint32_t __regPriMask __ASM("primask");\r
+ return(__regPriMask);\r
+}\r
+\r
+/**\r
+ * @brief Set the Priority Mask value\r
+ *\r
+ * @param uint32_t PriMask\r
+ * @return none\r
+ *\r
+ * Set the priority mask bit in the priority mask register\r
+ */\r
+static __INLINE void __set_PRIMASK(uint32_t priMask)\r
+{\r
+ register uint32_t __regPriMask __ASM("primask");\r
+ __regPriMask = (priMask);\r
+}\r
+\r
+/**\r
+ * @brief Return the Fault Mask value\r
+ *\r
+ * @param none\r
+ * @return uint32_t FaultMask\r
+ *\r
+ * Return the content of the fault mask register\r
+ */\r
+static __INLINE uint32_t __get_FAULTMASK(void)\r
+{\r
+ register uint32_t __regFaultMask __ASM("faultmask");\r
+ return(__regFaultMask);\r
+}\r
+\r
+/**\r
+ * @brief Set the Fault Mask value\r
+ *\r
+ * @param uint32_t faultMask value\r
+ * @return none\r
+ *\r
+ * Set the fault mask register\r
+ */\r
+static __INLINE void __set_FAULTMASK(uint32_t faultMask)\r
+{\r
+ register uint32_t __regFaultMask __ASM("faultmask");\r
+ __regFaultMask = (faultMask & 1);\r
+}\r
+\r
+/**\r
+ * @brief Return the Control Register value\r
+ * \r
+ * @param none\r
+ * @return uint32_t Control value\r
+ *\r
+ * Return the content of the control register\r
+ */\r
+static __INLINE uint32_t __get_CONTROL(void)\r
+{\r
+ register uint32_t __regControl __ASM("control");\r
+ return(__regControl);\r
+}\r
+\r
+/**\r
+ * @brief Set the Control Register value\r
+ *\r
+ * @param uint32_t Control value\r
+ * @return none\r
+ *\r
+ * Set the control register\r
+ */\r
+static __INLINE void __set_CONTROL(uint32_t control)\r
+{\r
+ register uint32_t __regControl __ASM("control");\r
+ __regControl = control;\r
+}\r
+\r
+#endif /* __ARMCC_VERSION */ \r
+\r
+\r
+\r
+#elif (defined (__ICCARM__)) /*------------------ ICC Compiler -------------------*/\r
+/* IAR iccarm specific functions */\r
+\r
+#define __enable_irq __enable_interrupt /*!< global Interrupt enable */\r
+#define __disable_irq __disable_interrupt /*!< global Interrupt disable */\r
+\r
+static __INLINE void __enable_fault_irq() { __ASM ("cpsie f"); }\r
+static __INLINE void __disable_fault_irq() { __ASM ("cpsid f"); }\r
+\r
+#define __NOP __no_operation() /*!< no operation intrinsic in IAR Compiler */ \r
+static __INLINE void __WFI() { __ASM ("wfi"); }\r
+static __INLINE void __WFE() { __ASM ("wfe"); }\r
+static __INLINE void __SEV() { __ASM ("sev"); }\r
+static __INLINE void __CLREX() { __ASM ("clrex"); }\r
+\r
+/* intrinsic void __ISB(void) */\r
+/* intrinsic void __DSB(void) */\r
+/* intrinsic void __DMB(void) */\r
+/* intrinsic void __set_PRIMASK(); */\r
+/* intrinsic void __get_PRIMASK(); */\r
+/* intrinsic void __set_FAULTMASK(); */\r
+/* intrinsic void __get_FAULTMASK(); */\r
+/* intrinsic uint32_t __REV(uint32_t value); */\r
+/* intrinsic uint32_t __REVSH(uint32_t value); */\r
+/* intrinsic unsigned long __STREX(unsigned long, unsigned long); */\r
+/* intrinsic unsigned long __LDREX(unsigned long *); */\r
+\r
+\r
+/**\r
+ * @brief Return the Process Stack Pointer\r
+ *\r
+ * @param none\r
+ * @return uint32_t ProcessStackPointer\r
+ *\r
+ * Return the actual process stack pointer\r
+ */\r
+extern uint32_t __get_PSP(void);\r
+\r
+/**\r
+ * @brief Set the Process Stack Pointer\r
+ *\r
+ * @param uint32_t Process Stack Pointer\r
+ * @return none\r
+ *\r
+ * Assign the value ProcessStackPointer to the MSP \r
+ * (process stack pointer) Cortex processor register\r
+ */\r
+extern void __set_PSP(uint32_t topOfProcStack);\r
+\r
+/**\r
+ * @brief Return the Main Stack Pointer\r
+ *\r
+ * @param none\r
+ * @return uint32_t Main Stack Pointer\r
+ *\r
+ * Return the current value of the MSP (main stack pointer)\r
+ * Cortex processor register\r
+ */\r
+extern uint32_t __get_MSP(void);\r
+\r
+/**\r
+ * @brief Set the Main Stack Pointer\r
+ *\r
+ * @param uint32_t Main Stack Pointer\r
+ * @return none\r
+ *\r
+ * Assign the value mainStackPointer to the MSP \r
+ * (main stack pointer) Cortex processor register\r
+ */\r
+extern void __set_MSP(uint32_t topOfMainStack);\r
+\r
+/**\r
+ * @brief Reverse byte order in unsigned short value\r
+ *\r
+ * @param uint16_t value to reverse\r
+ * @return uint32_t reversed value\r
+ *\r
+ * Reverse byte order in unsigned short value\r
+ */\r
+extern uint32_t __REV16(uint16_t value);\r
+\r
+/**\r
+ * @brief Reverse bit order of value\r
+ *\r
+ * @param uint32_t value to reverse\r
+ * @return uint32_t reversed value\r
+ *\r
+ * Reverse bit order of value\r
+ */\r
+extern uint32_t __RBIT(uint32_t value);\r
+\r
+/**\r
+ * @brief LDR Exclusive\r
+ *\r
+ * @param uint8_t* address\r
+ * @return uint8_t value of (*address)\r
+ *\r
+ * Exclusive LDR command\r
+ */\r
+extern uint8_t __LDREXB(uint8_t *addr);\r
+\r
+/**\r
+ * @brief LDR Exclusive\r
+ *\r
+ * @param uint16_t* address\r
+ * @return uint16_t value of (*address)\r
+ *\r
+ * Exclusive LDR command\r
+ */\r
+extern uint16_t __LDREXH(uint16_t *addr);\r
+\r
+/**\r
+ * @brief LDR Exclusive\r
+ *\r
+ * @param uint32_t* address\r
+ * @return uint32_t value of (*address)\r
+ *\r
+ * Exclusive LDR command\r
+ */\r
+extern uint32_t __LDREXW(uint32_t *addr);\r
+\r
+/**\r
+ * @brief STR Exclusive\r
+ *\r
+ * @param uint8_t *address\r
+ * @param uint8_t value to store\r
+ * @return uint32_t successful / failed\r
+ *\r
+ * Exclusive STR command\r
+ */\r
+extern uint32_t __STREXB(uint8_t value, uint8_t *addr);\r
+\r
+/**\r
+ * @brief STR Exclusive\r
+ *\r
+ * @param uint16_t *address\r
+ * @param uint16_t value to store\r
+ * @return uint32_t successful / failed\r
+ *\r
+ * Exclusive STR command\r
+ */\r
+extern uint32_t __STREXH(uint16_t value, uint16_t *addr);\r
+\r
+/**\r
+ * @brief STR Exclusive\r
+ *\r
+ * @param uint32_t *address\r
+ * @param uint32_t value to store\r
+ * @return uint32_t successful / failed\r
+ *\r
+ * Exclusive STR command\r
+ */\r
+extern uint32_t __STREXW(uint32_t value, uint32_t *addr);\r
+\r
+\r
+\r
+#elif (defined (__GNUC__)) /*------------------ GNU Compiler ---------------------*/\r
+/* GNU gcc specific functions */\r
+\r
+static __INLINE void __enable_irq() { __ASM volatile ("cpsie i"); }\r
+static __INLINE void __disable_irq() { __ASM volatile ("cpsid i"); }\r
+\r
+static __INLINE void __enable_fault_irq() { __ASM volatile ("cpsie f"); }\r
+static __INLINE void __disable_fault_irq() { __ASM volatile ("cpsid f"); }\r
+\r
+static __INLINE void __NOP() { __ASM volatile ("nop"); }\r
+static __INLINE void __WFI() { __ASM volatile ("wfi"); }\r
+static __INLINE void __WFE() { __ASM volatile ("wfe"); }\r
+static __INLINE void __SEV() { __ASM volatile ("sev"); }\r
+static __INLINE void __ISB() { __ASM volatile ("isb"); }\r
+static __INLINE void __DSB() { __ASM volatile ("dsb"); }\r
+static __INLINE void __DMB() { __ASM volatile ("dmb"); }\r
+static __INLINE void __CLREX() { __ASM volatile ("clrex"); }\r
+\r
+\r
+/**\r
+ * @brief Return the Process Stack Pointer\r
+ *\r
+ * @param none\r
+ * @return uint32_t ProcessStackPointer\r
+ *\r
+ * Return the actual process stack pointer\r
+ */\r
+extern uint32_t __get_PSP(void);\r
+\r
+/**\r
+ * @brief Set the Process Stack Pointer\r
+ *\r
+ * @param uint32_t Process Stack Pointer\r
+ * @return none\r
+ *\r
+ * Assign the value ProcessStackPointer to the MSP \r
+ * (process stack pointer) Cortex processor register\r
+ */\r
+extern void __set_PSP(uint32_t topOfProcStack);\r
+\r
+/**\r
+ * @brief Return the Main Stack Pointer\r
+ *\r
+ * @param none\r
+ * @return uint32_t Main Stack Pointer\r
+ *\r
+ * Return the current value of the MSP (main stack pointer)\r
+ * Cortex processor register\r
+ */\r
+extern uint32_t __get_MSP(void);\r
+\r
+/**\r
+ * @brief Set the Main Stack Pointer\r
+ *\r
+ * @param uint32_t Main Stack Pointer\r
+ * @return none\r
+ *\r
+ * Assign the value mainStackPointer to the MSP \r
+ * (main stack pointer) Cortex processor register\r
+ */\r
+extern void __set_MSP(uint32_t topOfMainStack);\r
+\r
+/**\r
+ * @brief Return the Base Priority value\r
+ *\r
+ * @param none\r
+ * @return uint32_t BasePriority\r
+ *\r
+ * Return the content of the base priority register\r
+ */\r
+extern uint32_t __get_BASEPRI(void);\r
+\r
+/**\r
+ * @brief Set the Base Priority value\r
+ *\r
+ * @param uint32_t BasePriority\r
+ * @return none\r
+ *\r
+ * Set the base priority register\r
+ */\r
+extern void __set_BASEPRI(uint32_t basePri);\r
+\r
+/**\r
+ * @brief Return the Priority Mask value\r
+ *\r
+ * @param none\r
+ * @return uint32_t PriMask\r
+ *\r
+ * Return the state of the priority mask bit from the priority mask\r
+ * register\r
+ */\r
+extern uint32_t __get_PRIMASK(void);\r
+\r
+/**\r
+ * @brief Set the Priority Mask value\r
+ *\r
+ * @param uint32_t PriMask\r
+ * @return none\r
+ *\r
+ * Set the priority mask bit in the priority mask register\r
+ */\r
+extern void __set_PRIMASK(uint32_t priMask);\r
+\r
+/**\r
+ * @brief Return the Fault Mask value\r
+ *\r
+ * @param none\r
+ * @return uint32_t FaultMask\r
+ *\r
+ * Return the content of the fault mask register\r
+ */\r
+extern uint32_t __get_FAULTMASK(void);\r
+\r
+/**\r
+ * @brief Set the Fault Mask value\r
+ *\r
+ * @param uint32_t faultMask value\r
+ * @return none\r
+ *\r
+ * Set the fault mask register\r
+ */\r
+extern void __set_FAULTMASK(uint32_t faultMask);\r
+\r
+/**\r
+ * @brief Return the Control Register value\r
+* \r
+* @param none\r
+* @return uint32_t Control value\r
+ *\r
+ * Return the content of the control register\r
+ */\r
+extern uint32_t __get_CONTROL(void);\r
+\r
+/**\r
+ * @brief Set the Control Register value\r
+ *\r
+ * @param uint32_t Control value\r
+ * @return none\r
+ *\r
+ * Set the control register\r
+ */\r
+extern void __set_CONTROL(uint32_t control);\r
+\r
+/**\r
+ * @brief Reverse byte order in integer value\r
+ *\r
+ * @param uint32_t value to reverse\r
+ * @return uint32_t reversed value\r
+ *\r
+ * Reverse byte order in integer value\r
+ */\r
+extern uint32_t __REV(uint32_t value);\r
+\r
+/**\r
+ * @brief Reverse byte order in unsigned short value\r
+ *\r
+ * @param uint16_t value to reverse\r
+ * @return uint32_t reversed value\r
+ *\r
+ * Reverse byte order in unsigned short value\r
+ */\r
+extern uint32_t __REV16(uint16_t value);\r
+\r
+/*\r
+ * Reverse byte order in signed short value with sign extension to integer\r
+ *\r
+ * @param int16_t value to reverse\r
+ * @return int32_t reversed value\r
+ *\r
+ * @brief Reverse byte order in signed short value with sign extension to integer\r
+ */\r
+extern int32_t __REVSH(int16_t value);\r
+\r
+/**\r
+ * @brief Reverse bit order of value\r
+ *\r
+ * @param uint32_t value to reverse\r
+ * @return uint32_t reversed value\r
+ *\r
+ * Reverse bit order of value\r
+ */\r
+extern uint32_t __RBIT(uint32_t value);\r
+\r
+/**\r
+ * @brief LDR Exclusive\r
+ *\r
+ * @param uint8_t* address\r
+ * @return uint8_t value of (*address)\r
+ *\r
+ * Exclusive LDR command\r
+ */\r
+extern uint8_t __LDREXB(uint8_t *addr);\r
+\r
+/**\r
+ * @brief LDR Exclusive\r
+ *\r
+ * @param uint16_t* address\r
+ * @return uint16_t value of (*address)\r
+ *\r
+ * Exclusive LDR command\r
+ */\r
+extern uint16_t __LDREXH(uint16_t *addr);\r
+\r
+/**\r
+ * @brief LDR Exclusive\r
+ *\r
+ * @param uint32_t* address\r
+ * @return uint32_t value of (*address)\r
+ *\r
+ * Exclusive LDR command\r
+ */\r
+extern uint32_t __LDREXW(uint32_t *addr);\r
+\r
+/**\r
+ * @brief STR Exclusive\r
+ *\r
+ * @param uint8_t *address\r
+ * @param uint8_t value to store\r
+ * @return uint32_t successful / failed\r
+ *\r
+ * Exclusive STR command\r
+ */\r
+extern uint32_t __STREXB(uint8_t value, uint8_t *addr);\r
+\r
+/**\r
+ * @brief STR Exclusive\r
+ *\r
+ * @param uint16_t *address\r
+ * @param uint16_t value to store\r
+ * @return uint32_t successful / failed\r
+ *\r
+ * Exclusive STR command\r
+ */\r
+extern uint32_t __STREXH(uint16_t value, uint16_t *addr);\r
+\r
+/**\r
+ * @brief STR Exclusive\r
+ *\r
+ * @param uint32_t *address\r
+ * @param uint32_t value to store\r
+ * @return uint32_t successful / failed\r
+ *\r
+ * Exclusive STR command\r
+ */\r
+extern uint32_t __STREXW(uint32_t value, uint32_t *addr);\r
+\r
+\r
+#elif (defined (__TASKING__)) /*------------------ TASKING Compiler ---------------------*/\r
+/* TASKING carm specific functions */\r
+\r
+/*\r
+ * The CMSIS functions have been implemented as intrinsics in the compiler.\r
+ * Please use "carm -?i" to get an up to date list of all instrinsics,\r
+ * Including the CMSIS ones.\r
+ */\r
+\r
+#endif\r
+\r
+\r
+\r
+/* ########################## NVIC functions #################################### */\r
+\r
+\r
+/**\r
+ * @brief Set the Priority Grouping in NVIC Interrupt Controller\r
+ *\r
+ * @param uint32_t priority_grouping is priority grouping field\r
+ * @return none \r
+ *\r
+ * Set the priority grouping field using the required unlock sequence.\r
+ * The parameter priority_grouping is assigned to the field \r
+ * SCB->AIRCR [10:8] PRIGROUP field. Only values from 0..7 are used.\r
+ * In case of a conflict between priority grouping and available\r
+ * priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set.\r
+ */\r
+static __INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup)\r
+{\r
+ uint32_t reg_value;\r
+ uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */\r
+ \r
+ reg_value = SCB->AIRCR; /* read old register configuration */\r
+ reg_value &= ~((0xFFFFU << 16) | (0x0F << 8)); /* clear bits to change */\r
+ reg_value = ((reg_value | NVIC_AIRCR_VECTKEY | (PriorityGroupTmp << 8))); /* Insert write key and priorty group */\r
+ SCB->AIRCR = reg_value;\r
+}\r
+\r
+/**\r
+ * @brief Get the Priority Grouping from NVIC Interrupt Controller\r
+ *\r
+ * @param none\r
+ * @return uint32_t priority grouping field \r
+ *\r
+ * Get the priority grouping from NVIC Interrupt Controller.\r
+ * priority grouping is SCB->AIRCR [10:8] PRIGROUP field.\r
+ */\r
+static __INLINE uint32_t NVIC_GetPriorityGrouping(void)\r
+{\r
+ return ((SCB->AIRCR >> 8) & 0x07); /* read priority grouping field */\r
+}\r
+\r
+/**\r
+ * @brief Enable Interrupt in NVIC Interrupt Controller\r
+ *\r
+ * @param IRQn_Type IRQn specifies the interrupt number\r
+ * @return none \r
+ *\r
+ * Enable a device specific interupt in the NVIC interrupt controller.\r
+ * The interrupt number cannot be a negative value.\r
+ */\r
+static __INLINE void NVIC_EnableIRQ(IRQn_Type IRQn)\r
+{\r
+ NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* enable interrupt */\r
+}\r
+\r
+/**\r
+ * @brief Disable the interrupt line for external interrupt specified\r
+ * \r
+ * @param IRQn_Type IRQn is the positive number of the external interrupt\r
+ * @return none\r
+ * \r
+ * Disable a device specific interupt in the NVIC interrupt controller.\r
+ * The interrupt number cannot be a negative value.\r
+ */\r
+static __INLINE void NVIC_DisableIRQ(IRQn_Type IRQn)\r
+{\r
+ NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */\r
+}\r
+\r
+/**\r
+ * @brief Read the interrupt pending bit for a device specific interrupt source\r
+ * \r
+ * @param IRQn_Type IRQn is the number of the device specifc interrupt\r
+ * @return uint32_t 1 if pending interrupt else 0\r
+ *\r
+ * Read the pending register in NVIC and return 1 if its status is pending, \r
+ * otherwise it returns 0\r
+ */\r
+static __INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn)\r
+{\r
+ return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */\r
+}\r
+\r
+/**\r
+ * @brief Set the pending bit for an external interrupt\r
+ * \r
+ * @param IRQn_Type IRQn is the Number of the interrupt\r
+ * @return none\r
+ *\r
+ * Set the pending bit for the specified interrupt.\r
+ * The interrupt number cannot be a negative value.\r
+ */\r
+static __INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn)\r
+{\r
+ NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */\r
+}\r
+\r
+/**\r
+ * @brief Clear the pending bit for an external interrupt\r
+ *\r
+ * @param IRQn_Type IRQn is the Number of the interrupt\r
+ * @return none\r
+ *\r
+ * Clear the pending bit for the specified interrupt. \r
+ * The interrupt number cannot be a negative value.\r
+ */\r
+static __INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn)\r
+{\r
+ NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */\r
+}\r
+\r
+/**\r
+ * @brief Read the active bit for an external interrupt\r
+ *\r
+ * @param IRQn_Type IRQn is the Number of the interrupt\r
+ * @return uint32_t 1 if active else 0\r
+ *\r
+ * Read the active register in NVIC and returns 1 if its status is active, \r
+ * otherwise it returns 0.\r
+ */\r
+static __INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn)\r
+{\r
+ return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */\r
+}\r
+\r
+/**\r
+ * @brief Set the priority for an interrupt\r
+ *\r
+ * @param IRQn_Type IRQn is the Number of the interrupt\r
+ * @param priority is the priority for the interrupt\r
+ * @return none\r
+ *\r
+ * Set the priority for the specified interrupt. The interrupt \r
+ * number can be positive to specify an external (device specific) \r
+ * interrupt, or negative to specify an internal (core) interrupt. \n\r
+ *\r
+ * Note: The priority cannot be set for every core interrupt.\r
+ */\r
+static __INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority)\r
+{\r
+ if(IRQn < 0) {\r
+ SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M3 System Interrupts */\r
+ else {\r
+ NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */\r
+}\r
+\r
+/**\r
+ * @brief Read the priority for an interrupt\r
+ *\r
+ * @param IRQn_Type IRQn is the Number of the interrupt\r
+ * @return uint32_t priority is the priority for the interrupt\r
+ *\r
+ * Read the priority for the specified interrupt. The interrupt \r
+ * number can be positive to specify an external (device specific) \r
+ * interrupt, or negative to specify an internal (core) interrupt.\r
+ *\r
+ * The returned priority value is automatically aligned to the implemented\r
+ * priority bits of the microcontroller.\r
+ *\r
+ * Note: The priority cannot be set for every core interrupt.\r
+ */\r
+static __INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn)\r
+{\r
+\r
+ if(IRQn < 0) {\r
+ return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M3 system interrupts */\r
+ else {\r
+ return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */\r
+}\r
+\r
+\r
+/**\r
+ * @brief Encode the priority for an interrupt\r
+ *\r
+ * @param uint32_t PriorityGroup is the used priority group\r
+ * @param uint32_t PreemptPriority is the preemptive priority value (starting from 0)\r
+ * @param uint32_t SubPriority is the sub priority value (starting from 0)\r
+ * @return uint32_t the priority for the interrupt\r
+ *\r
+ * Encode the priority for an interrupt with the given priority group,\r
+ * preemptive priority value and sub priority value.\r
+ * In case of a conflict between priority grouping and available\r
+ * priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set.\r
+ *\r
+ * The returned priority value can be used for NVIC_SetPriority(...) function\r
+ */\r
+static __INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority)\r
+{\r
+ uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */\r
+ uint32_t PreemptPriorityBits;\r
+ uint32_t SubPriorityBits;\r
+\r
+ PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp;\r
+ SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS;\r
+ \r
+ return (\r
+ ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) |\r
+ ((SubPriority & ((1 << (SubPriorityBits )) - 1)))\r
+ );\r
+}\r
+\r
+\r
+/**\r
+ * @brief Decode the priority of an interrupt\r
+ *\r
+ * @param uint32_t Priority the priority for the interrupt\r
+ * @param uint32_t PrioGroup is the used priority group\r
+ * @param uint32_t* pPreemptPrio is the preemptive priority value (starting from 0)\r
+ * @param uint32_t* pSubPrio is the sub priority value (starting from 0)\r
+ * @return none\r
+ *\r
+ * Decode an interrupt priority value with the given priority group to \r
+ * preemptive priority value and sub priority value.\r
+ * In case of a conflict between priority grouping and available\r
+ * priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set.\r
+ *\r
+ * The priority value can be retrieved with NVIC_GetPriority(...) function\r
+ */\r
+static __INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority)\r
+{\r
+ uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */\r
+ uint32_t PreemptPriorityBits;\r
+ uint32_t SubPriorityBits;\r
+\r
+ PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp;\r
+ SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS;\r
+ \r
+ *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1);\r
+ *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1);\r
+}\r
+\r
+\r
+\r
+/* ################################## SysTick function ############################################ */\r
+\r
+#if (!defined (__Vendor_SysTickConfig)) || (__Vendor_SysTickConfig == 0)\r
+\r
+/* SysTick constants */\r
+#define SYSTICK_ENABLE 0 /* Config-Bit to start or stop the SysTick Timer */\r
+#define SYSTICK_TICKINT 1 /* Config-Bit to enable or disable the SysTick interrupt */\r
+#define SYSTICK_CLKSOURCE 2 /* Clocksource has the offset 2 in SysTick Control and Status Register */\r
+#define SYSTICK_MAXCOUNT ((1<<24) -1) /* SysTick MaxCount */\r
+\r
+/**\r
+ * @brief Initialize and start the SysTick counter and its interrupt.\r
+ *\r
+ * @param uint32_t ticks is the number of ticks between two interrupts\r
+ * @return none\r
+ *\r
+ * Initialise the system tick timer and its interrupt and start the\r
+ * system tick timer / counter in free running mode to generate \r
+ * periodical interrupts.\r
+ */\r
+static __INLINE uint32_t SysTick_Config(uint32_t ticks)\r
+{ \r
+ if (ticks > SYSTICK_MAXCOUNT) return (1); /* Reload value impossible */\r
+\r
+ SysTick->LOAD = (ticks & SYSTICK_MAXCOUNT) - 1; /* set reload register */\r
+ NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Cortex-M0 System Interrupts */\r
+ SysTick->VAL = (0x00); /* Load the SysTick Counter Value */\r
+ SysTick->CTRL = (1 << SYSTICK_CLKSOURCE) | (1<<SYSTICK_ENABLE) | (1<<SYSTICK_TICKINT); /* Enable SysTick IRQ and SysTick Timer */\r
+ return (0); /* Function successful */\r
+}\r
+\r
+#endif\r
+\r
+\r
+\r
+\r
+\r
+/* ################################## Reset function ############################################ */\r
+\r
+/**\r
+ * @brief Initiate a system reset request.\r
+ *\r
+ * @param none\r
+ * @return none\r
+ *\r
+ * Initialize a system reset request to reset the MCU\r
+ */\r
+static __INLINE void NVIC_SystemReset(void)\r
+{\r
+ SCB->AIRCR = (NVIC_AIRCR_VECTKEY | (SCB->AIRCR & (0x700)) | (1<<NVIC_SYSRESETREQ)); /* Keep priority group unchanged */\r
+ __DSB(); /* Ensure completion of memory access */ \r
+ while(1); /* wait until reset */\r
+}\r
+\r
+\r
+/* ################################## Debug Output function ############################################ */\r
+\r
+\r
+/**\r
+ * @brief Outputs a character via the ITM channel 0\r
+ *\r
+ * @param uint32_t character to output\r
+ * @return uint32_t input character\r
+ *\r
+ * The function outputs a character via the ITM channel 0. \r
+ * The function returns when no debugger is connected that has booked the output. \r
+ * It is blocking when a debugger is connected, but the previous character send is not transmitted. \r
+ */\r
+static __INLINE uint32_t ITM_SendChar (uint32_t ch)\r
+{\r
+ if (ch == '\n') ITM_SendChar('\r');\r
+ \r
+ if ((CoreDebug->DEMCR & CoreDebug_DEMCR_TRCENA) &&\r
+ (ITM->TCR & ITM_TCR_ITMENA) &&\r
+ (ITM->TER & (1UL << 0)) ) \r
+ {\r
+ while (ITM->PORT[0].u32 == 0);\r
+ ITM->PORT[0].u8 = (uint8_t) ch;\r
+ } \r
+ return (ch);\r
+}\r
+\r
+#ifdef __cplusplus\r
+}\r
+#endif\r
+\r
+#endif /* __CM3_CORE_H__ */\r
+\r
+/*lint -restore */\r
--- /dev/null
+/*\r
+ FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry.\r
+\r
+ This file is part of the FreeRTOS.org distribution.\r
+\r
+ FreeRTOS.org is free software; you can redistribute it and/or modify it\r
+ under the terms of the GNU General Public License (version 2) as published\r
+ by the Free Software Foundation and modified by the FreeRTOS exception.\r
+ **NOTE** The exception to the GPL is included to allow you to distribute a\r
+ combined work that includes FreeRTOS.org without being obliged to provide\r
+ the source code for any proprietary components. Alternative commercial\r
+ license and support terms are also available upon request. See the\r
+ licensing section of http://www.FreeRTOS.org for full details.\r
+\r
+ FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT\r
+ ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or\r
+ FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for\r
+ more details.\r
+\r
+ You should have received a copy of the GNU General Public License along\r
+ with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59\r
+ Temple Place, Suite 330, Boston, MA 02111-1307 USA.\r
+\r
+\r
+ ***************************************************************************\r
+ * *\r
+ * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation *\r
+ * *\r
+ * This is a concise, step by step, 'hands on' guide that describes both *\r
+ * general multitasking concepts and FreeRTOS specifics. It presents and *\r
+ * explains numerous examples that are written using the FreeRTOS API. *\r
+ * Full source code for all the examples is provided in an accompanying *\r
+ * .zip file. *\r
+ * *\r
+ ***************************************************************************\r
+\r
+ 1 tab == 4 spaces!\r
+\r
+ Please ensure to read the configuration and relevant port sections of the\r
+ online documentation.\r
+\r
+ http://www.FreeRTOS.org - Documentation, latest information, license and\r
+ contact details.\r
+\r
+ http://www.SafeRTOS.com - A version that is certified for use in safety\r
+ critical systems.\r
+\r
+ http://www.OpenRTOS.com - Commercial support, development, porting,\r
+ licensing and training services.\r
+*/\r
+\r
+\r
+/*\r
+ * Creates all the demo application tasks, then starts the scheduler. The WEB\r
+ * documentation provides more details of the standard demo application tasks\r
+ * (which just exist to test the kernel port and provide an example of how to use\r
+ * each FreeRTOS API function).\r
+ *\r
+ * In addition to the standard demo tasks, the following tasks and tests are\r
+ * defined and/or created within this file:\r
+ *\r
+ * "LCD" task - the LCD task is a 'gatekeeper' task. It is the only task that\r
+ * is permitted to access the display directly. Other tasks wishing to write a\r
+ * message to the LCD send the message on a queue to the LCD task instead of\r
+ * accessing the LCD themselves. The LCD task just blocks on the queue waiting\r
+ * for messages - waking and displaying the messages as they arrive. The use\r
+ * of a gatekeeper in this manner permits both tasks and interrupts to write to\r
+ * the LCD without worrying about mutual exclusion. This is demonstrated by the\r
+ * check hook (see below) which sends messages to the display even though it\r
+ * executes from an interrupt context.\r
+ *\r
+ * "Check" hook - This only executes fully every five seconds from the tick\r
+ * hook. Its main function is to check that all the standard demo tasks are\r
+ * still operational. Should any unexpected behaviour be discovered within a\r
+ * demo task then the tick hook will write an error to the LCD (via the LCD task).\r
+ * If all the demo tasks are executing with their expected behaviour then the\r
+ * check hook writes PASS to the LCD (again via the LCD task), as described above.\r
+ * The check hook also toggles LED 4 each time it executes.\r
+ *\r
+ * LED tasks - These just demonstrate how multiple instances of a single task\r
+ * definition can be created. Each LED task simply toggles an LED. The task\r
+ * parameter is used to pass the number of the LED to be toggled into the task.\r
+ *\r
+ * "uIP" task - This is the task that handles the uIP stack. All TCP/IP\r
+ * processing is performed in this task.\r
+ */\r
+\r
+/* Standard includes. */\r
+#include <stdio.h>\r
+\r
+/* Scheduler includes. */\r
+#include "FreeRTOS.h"\r
+#include "task.h"\r
+#include "queue.h"\r
+#include "semphr.h"\r
+\r
+/* Hardware library includes. */\r
+#include "LPC17xx_defs.h"\r
+\r
+/* Demo app includes. */\r
+#include "BlockQ.h"\r
+#include "integer.h"\r
+#include "blocktim.h"\r
+#include "flash.h"\r
+#include "partest.h"\r
+#include "semtest.h"\r
+#include "PollQ.h"\r
+#include "GenQTest.h"\r
+#include "QPeek.h"\r
+#include "recmutex.h"\r
+\r
+/*-----------------------------------------------------------*/\r
+\r
+/* The number of LED tasks that will be created. */\r
+#define mainNUM_LED_TASKS ( 6 )\r
+\r
+/* The time between cycles of the 'check' functionality (defined within the\r
+tick hook. */\r
+#define mainCHECK_DELAY ( ( portTickType ) 5000 / portTICK_RATE_MS )\r
+\r
+/* Task priorities. */\r
+#define mainQUEUE_POLL_PRIORITY ( tskIDLE_PRIORITY + 2 )\r
+#define mainSEM_TEST_PRIORITY ( tskIDLE_PRIORITY + 1 )\r
+#define mainBLOCK_Q_PRIORITY ( tskIDLE_PRIORITY + 2 )\r
+#define mainUIP_TASK_PRIORITY ( tskIDLE_PRIORITY + 3 )\r
+#define mainLCD_TASK_PRIORITY ( tskIDLE_PRIORITY + 2 )\r
+#define mainINTEGER_TASK_PRIORITY ( tskIDLE_PRIORITY )\r
+#define mainGEN_QUEUE_TASK_PRIORITY ( tskIDLE_PRIORITY )\r
+#define mainFLASH_TASK_PRIORITY ( tskIDLE_PRIORITY + 2 )\r
+\r
+/* The WEB server has a larger stack as it utilises stack hungry string\r
+handling library calls. */\r
+#define mainBASIC_WEB_STACK_SIZE ( configMINIMAL_STACK_SIZE * 4 )\r
+\r
+/* The length of the queue used to send messages to the LCD task. */\r
+#define mainQUEUE_SIZE ( 3 )\r
+\r
+/* The task that is toggled by the check task. */\r
+#define mainCHECK_TASK_LED ( 4 )\r
+/*-----------------------------------------------------------*/\r
+\r
+/*\r
+ * Configure the hardware for the demo.\r
+ */\r
+static void prvSetupHardware( void );\r
+\r
+/*\r
+ * Very simple task that toggles an LED.\r
+ */\r
+static void vLEDTask( void *pvParameters );\r
+\r
+/*\r
+ * The task that handles the uIP stack. All TCP/IP processing is performed in\r
+ * this task.\r
+ */\r
+extern void vuIP_Task( void *pvParameters );\r
+\r
+/*\r
+ * The LCD gatekeeper task as described in the comments at the top of this file.\r
+ * */\r
+static void vLCDTask( void *pvParameters );\r
+\r
+/*-----------------------------------------------------------*/\r
+\r
+/* The queue used to send messages to the LCD task. */\r
+xQueueHandle xLCDQueue;\r
+\r
+\r
+\r
+/*-----------------------------------------------------------*/\r
+\r
+int main( void )\r
+{\r
+long l;\r
+\r
+ /* Configure the hardware for use by this demo. */\r
+ prvSetupHardware();\r
+\r
+ /* Start the standard demo tasks. These are just here to exercise the\r
+ kernel port and provide examples of how the FreeRTOS API can be used. */\r
+ vStartBlockingQueueTasks( mainBLOCK_Q_PRIORITY );\r
+ vCreateBlockTimeTasks();\r
+ vStartSemaphoreTasks( mainSEM_TEST_PRIORITY );\r
+ vStartPolledQueueTasks( mainQUEUE_POLL_PRIORITY );\r
+ vStartIntegerMathTasks( mainINTEGER_TASK_PRIORITY );\r
+ vStartGenericQueueTasks( mainGEN_QUEUE_TASK_PRIORITY );\r
+ vStartQueuePeekTasks();\r
+ vStartRecursiveMutexTasks();\r
+\r
+ vStartLEDFlashTasks( mainFLASH_TASK_PRIORITY );\r
+\r
+ /* Create the uIP task. The WEB server runs in this task. */\r
+ xTaskCreate( vuIP_Task, ( signed char * ) "uIP", mainBASIC_WEB_STACK_SIZE, ( void * ) NULL, mainUIP_TASK_PRIORITY, NULL );\r
+\r
+ /* Create the queue used by the LCD task. Messages for display on the LCD\r
+ are received via this queue. */\r
+ xLCDQueue = xQueueCreate( mainQUEUE_SIZE, sizeof( xLCDMessage ) );\r
+\r
+ /* Start the LCD gatekeeper task - as described in the comments at the top\r
+ of this file. */\r
+ xTaskCreate( vLCDTask, ( signed portCHAR * ) "LCD", configMINIMAL_STACK_SIZE * 2, NULL, mainLCD_TASK_PRIORITY, NULL );\r
+\r
+ /* Start the scheduler. */\r
+ vTaskStartScheduler();\r
+\r
+ /* Will only get here if there was insufficient memory to create the idle\r
+ task. The idle task is created within vTaskStartScheduler(). */\r
+ for( ;; );\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+void vLCDTask( void *pvParameters )\r
+{\r
+xLCDMessage xMessage;\r
+unsigned long ulRow = 0;\r
+char cIPAddr[ 17 ]; /* To fit max IP address length of xxx.xxx.xxx.xxx\0 */\r
+\r
+ ( void ) pvParameters;\r
+\r
+ /* The LCD gatekeeper task as described in the comments at the top of this\r
+ file. */\r
+\r
+ /* Initialise the LCD and display a startup message that includes the\r
+ configured IP address. */\r
+ sprintf( cIPAddr, "%d.%d.%d.%d", configIP_ADDR0, configIP_ADDR1, configIP_ADDR2, configIP_ADDR3 );\r
+\r
+ for( ;; )\r
+ {\r
+ /* Wait for a message to arrive to be displayed. */\r
+ while( xQueueReceive( xLCDQueue, &xMessage, portMAX_DELAY ) != pdPASS );\r
+\r
+ }\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+void vApplicationTickHook( void )\r
+{\r
+static xLCDMessage xMessage = { "PASS" };\r
+static unsigned portLONG ulTicksSinceLastDisplay = 0;\r
+portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;\r
+\r
+ /* Called from every tick interrupt as described in the comments at the top\r
+ of this file.\r
+\r
+ Have enough ticks passed to make it time to perform our health status\r
+ check again? */\r
+ ulTicksSinceLastDisplay++;\r
+ if( ulTicksSinceLastDisplay >= mainCHECK_DELAY )\r
+ {\r
+ /* Reset the counter so these checks run again in mainCHECK_DELAY\r
+ ticks time. */\r
+ ulTicksSinceLastDisplay = 0;\r
+\r
+ /* Has an error been found in any task? */\r
+ if( xAreGenericQueueTasksStillRunning() != pdTRUE )\r
+ {\r
+ xMessage.pcMessage = "ERROR: GEN Q";\r
+ }\r
+ else if( xAreQueuePeekTasksStillRunning() != pdTRUE )\r
+ {\r
+ xMessage.pcMessage = "ERROR: PEEK Q";\r
+ }\r
+ else if( xAreBlockingQueuesStillRunning() != pdTRUE )\r
+ {\r
+ xMessage.pcMessage = "ERROR: BLOCK Q";\r
+ }\r
+ else if( xAreBlockTimeTestTasksStillRunning() != pdTRUE )\r
+ {\r
+ xMessage.pcMessage = "ERROR: BLOCK TIME";\r
+ }\r
+ else if( xAreSemaphoreTasksStillRunning() != pdTRUE )\r
+ {\r
+ xMessage.pcMessage = "ERROR: SEMAPHR";\r
+ }\r
+ else if( xArePollingQueuesStillRunning() != pdTRUE )\r
+ {\r
+ xMessage.pcMessage = "ERROR: POLL Q";\r
+ }\r
+ else if( xAreIntegerMathsTaskStillRunning() != pdTRUE )\r
+ {\r
+ xMessage.pcMessage = "ERROR: INT MATH";\r
+ }\r
+ else if( xAreRecursiveMutexTasksStillRunning() != pdTRUE )\r
+ {\r
+ xMessage.pcMessage = "ERROR: REC MUTEX";\r
+ }\r
+\r
+ /* Send the message to the OLED gatekeeper for display. The\r
+ xHigherPriorityTaskWoken parameter is not actually used here\r
+ as this function is running in the tick interrupt anyway - but\r
+ it must still be supplied. */\r
+ xHigherPriorityTaskWoken = pdFALSE;\r
+ xQueueSendFromISR( xLCDQueue, &xMessage, &xHigherPriorityTaskWoken );\r
+\r
+ /* Also toggle and LED. This can be done from here because in this port\r
+ the LED toggling functions don't use critical sections. */\r
+ vParTestToggleLED( mainCHECK_TASK_LED );\r
+ }\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+void prvSetupHardware( void )\r
+{\r
+ /* Disable peripherals power. */\r
+ PCONP = 0;\r
+\r
+ /* Enable GPIO power. */\r
+ PCONP = PCONP_PCGPIO;\r
+\r
+ /* Disable TPIU. */\r
+ PINSEL10 = 0;\r
+\r
+ /* Disconnect the main PLL. */\r
+ PLL0CON &= ~PLLCON_PLLC;\r
+ PLL0FEED = PLLFEED_FEED1;\r
+ PLL0FEED = PLLFEED_FEED2;\r
+ while ((PLL0STAT & PLLSTAT_PLLC) != 0);\r
+\r
+ /* Turn off the main PLL. */\r
+ PLL0CON &= ~PLLCON_PLLE;\r
+ PLL0FEED = PLLFEED_FEED1;\r
+ PLL0FEED = PLLFEED_FEED2;\r
+ while ((PLL0STAT & PLLSTAT_PLLE) != 0);\r
+\r
+ /* No CPU clock divider. */\r
+ CCLKCFG = 0;\r
+\r
+ /* OSCEN. */\r
+ SCS = 0x20;\r
+ while ((SCS & 0x40) == 0);\r
+\r
+ /* Use main oscillator. */\r
+ CLKSRCSEL = 1;\r
+ PLL0CFG = (PLLCFG_MUL16 | PLLCFG_DIV1);\r
+\r
+ PLL0FEED = PLLFEED_FEED1;\r
+ PLL0FEED = PLLFEED_FEED2;\r
+\r
+ /* Activate the PLL by turning it on then feeding the correct\r
+ sequence of bytes. */\r
+ PLL0CON = PLLCON_PLLE;\r
+ PLL0FEED = PLLFEED_FEED1;\r
+ PLL0FEED = PLLFEED_FEED2;\r
+\r
+ /* 6x CPU clock divider (64 MHz) */\r
+ CCLKCFG = 5;\r
+\r
+ /* Wait for the PLL to lock. */\r
+ while ((PLL0STAT & PLLSTAT_PLOCK) == 0);\r
+\r
+ /* Connect the PLL. */\r
+ PLL0CON = PLLCON_PLLC | PLLCON_PLLE;\r
+ PLL0FEED = PLLFEED_FEED1;\r
+ PLL0FEED = PLLFEED_FEED2;\r
+\r
+ /* Setup the peripheral bus to be the same as the PLL output (64 MHz). */\r
+ PCLKSEL0 = 0x05555555;\r
+\r
+ /* Configure LED GPIOs as outputs. */\r
+ FIO2DIR = 0xff;\r
+ FIO2CLR = 0xff;\r
+ FIO2MASK = 0;\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed portCHAR *pcTaskName )\r
+{\r
+ /* This function will get called if a task overflows its stack. */\r
+\r
+ ( void ) pxTask;\r
+ ( void ) pcTaskName;\r
+\r
+ for( ;; );\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+void vConfigureTimerForRunTimeStats( void )\r
+{\r
+const unsigned long TCR_COUNT_RESET = 2, CTCR_CTM_TIMER = 0x00, TCR_COUNT_ENABLE = 0x01;\r
+\r
+ /* This function configures a timer that is used as the time base when\r
+ collecting run time statistical information - basically the percentage\r
+ of CPU time that each task is utilising. It is called automatically when\r
+ the scheduler is started (assuming configGENERATE_RUN_TIME_STATS is set\r
+ to 1. */\r
+\r
+ /* Power up and feed the timer. */\r
+ PCONP |= 0x02UL;\r
+ PCLKSEL0 = (PCLKSEL0 & (~(0x3<<2))) | (0x01 << 2);\r
+\r
+ /* Reset Timer 0 */\r
+ T0TCR = TCR_COUNT_RESET;\r
+\r
+ /* Just count up. */\r
+ T0CTCR = CTCR_CTM_TIMER;\r
+\r
+ /* Prescale to a frequency that is good enough to get a decent resolution,\r
+ but not too fast so as to overflow all the time. */\r
+ T0PR = ( configCPU_CLOCK_HZ / 10000UL ) - 1UL;\r
+\r
+ /* Start the counter. */\r
+ T0TCR = TCR_COUNT_ENABLE;\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
--- /dev/null
+/*\r
+ Copyright 2001, 2002 Georges Menie (www.menie.org)\r
+ stdarg version contributed by Christian Ettinger\r
+\r
+ This program is free software; you can redistribute it and/or modify\r
+ it under the terms of the GNU Lesser General Public License as published by\r
+ the Free Software Foundation; either version 2 of the License, or\r
+ (at your option) any later version.\r
+\r
+ This program is distributed in the hope that it will be useful,\r
+ but WITHOUT ANY WARRANTY; without even the implied warranty of\r
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the\r
+ GNU Lesser General Public License for more details.\r
+\r
+ You should have received a copy of the GNU Lesser General Public License\r
+ along with this program; if not, write to the Free Software\r
+ Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA\r
+*/\r
+\r
+/*\r
+ putchar is the only external dependency for this file,\r
+ if you have a working putchar, leave it commented out.\r
+ If not, uncomment the define below and\r
+ replace outbyte(c) by your own function call.\r
+\r
+*/\r
+\r
+#define putchar(c) c\r
+\r
+#include <stdarg.h>\r
+\r
+static void printchar(char **str, int c)\r
+{\r
+ //extern int putchar(int c);\r
+ \r
+ if (str) {\r
+ **str = (char)c;\r
+ ++(*str);\r
+ }\r
+ else\r
+ { \r
+ (void)putchar(c);\r
+ }\r
+}\r
+\r
+#define PAD_RIGHT 1\r
+#define PAD_ZERO 2\r
+\r
+static int prints(char **out, const char *string, int width, int pad)\r
+{\r
+ register int pc = 0, padchar = ' ';\r
+\r
+ if (width > 0) {\r
+ register int len = 0;\r
+ register const char *ptr;\r
+ for (ptr = string; *ptr; ++ptr) ++len;\r
+ if (len >= width) width = 0;\r
+ else width -= len;\r
+ if (pad & PAD_ZERO) padchar = '0';\r
+ }\r
+ if (!(pad & PAD_RIGHT)) {\r
+ for ( ; width > 0; --width) {\r
+ printchar (out, padchar);\r
+ ++pc;\r
+ }\r
+ }\r
+ for ( ; *string ; ++string) {\r
+ printchar (out, *string);\r
+ ++pc;\r
+ }\r
+ for ( ; width > 0; --width) {\r
+ printchar (out, padchar);\r
+ ++pc;\r
+ }\r
+\r
+ return pc;\r
+}\r
+\r
+/* the following should be enough for 32 bit int */\r
+#define PRINT_BUF_LEN 12\r
+\r
+static int printi(char **out, int i, int b, int sg, int width, int pad, int letbase)\r
+{\r
+ char print_buf[PRINT_BUF_LEN];\r
+ register char *s;\r
+ register int t, neg = 0, pc = 0;\r
+ register unsigned int u = (unsigned int)i;\r
+\r
+ if (i == 0) {\r
+ print_buf[0] = '0';\r
+ print_buf[1] = '\0';\r
+ return prints (out, print_buf, width, pad);\r
+ }\r
+\r
+ if (sg && b == 10 && i < 0) {\r
+ neg = 1;\r
+ u = (unsigned int)-i;\r
+ }\r
+\r
+ s = print_buf + PRINT_BUF_LEN-1;\r
+ *s = '\0';\r
+\r
+ while (u) {\r
+ t = (unsigned int)u % b;\r
+ if( t >= 10 )\r
+ t += letbase - '0' - 10;\r
+ *--s = (char)(t + '0');\r
+ u /= b;\r
+ }\r
+\r
+ if (neg) {\r
+ if( width && (pad & PAD_ZERO) ) {\r
+ printchar (out, '-');\r
+ ++pc;\r
+ --width;\r
+ }\r
+ else {\r
+ *--s = '-';\r
+ }\r
+ }\r
+\r
+ return pc + prints (out, s, width, pad);\r
+}\r
+\r
+static int print( char **out, const char *format, va_list args )\r
+{\r
+ register int width, pad;\r
+ register int pc = 0;\r
+ char scr[2];\r
+\r
+ for (; *format != 0; ++format) {\r
+ if (*format == '%') {\r
+ ++format;\r
+ width = pad = 0;\r
+ if (*format == '\0') break;\r
+ if (*format == '%') goto out;\r
+ if (*format == '-') {\r
+ ++format;\r
+ pad = PAD_RIGHT;\r
+ }\r
+ while (*format == '0') {\r
+ ++format;\r
+ pad |= PAD_ZERO;\r
+ }\r
+ for ( ; *format >= '0' && *format <= '9'; ++format) {\r
+ width *= 10;\r
+ width += *format - '0';\r
+ }\r
+ if( *format == 's' ) {\r
+ register char *s = (char *)va_arg( args, int );\r
+ pc += prints (out, s?s:"(null)", width, pad);\r
+ continue;\r
+ }\r
+ if( *format == 'd' ) {\r
+ pc += printi (out, va_arg( args, int ), 10, 1, width, pad, 'a');\r
+ continue;\r
+ }\r
+ if( *format == 'x' ) {\r
+ pc += printi (out, va_arg( args, int ), 16, 0, width, pad, 'a');\r
+ continue;\r
+ }\r
+ if( *format == 'X' ) {\r
+ pc += printi (out, va_arg( args, int ), 16, 0, width, pad, 'A');\r
+ continue;\r
+ }\r
+ if( *format == 'u' ) {\r
+ pc += printi (out, va_arg( args, int ), 10, 0, width, pad, 'a');\r
+ continue;\r
+ }\r
+ if( *format == 'c' ) {\r
+ /* char are converted to int then pushed on the stack */\r
+ scr[0] = (char)va_arg( args, int );\r
+ scr[1] = '\0';\r
+ pc += prints (out, scr, width, pad);\r
+ continue;\r
+ }\r
+ }\r
+ else {\r
+ out:\r
+ printchar (out, *format);\r
+ ++pc;\r
+ }\r
+ }\r
+ if (out) **out = '\0';\r
+ va_end( args );\r
+ return pc;\r
+}\r
+\r
+int printf(const char *format, ...)\r
+{\r
+ va_list args;\r
+ \r
+ va_start( args, format );\r
+ return print( 0, format, args );\r
+}\r
+\r
+int sprintf(char *out, const char *format, ...)\r
+{\r
+ va_list args;\r
+ \r
+ va_start( args, format );\r
+ return print( &out, format, args );\r
+}\r
+\r
+\r
+int snprintf( char *buf, unsigned int count, const char *format, ... )\r
+{\r
+ va_list args;\r
+ \r
+ ( void ) count;\r
+ \r
+ va_start( args, format );\r
+ return print( &buf, format, args );\r
+}\r
+\r
+\r
+#ifdef TEST_PRINTF\r
+int main(void)\r
+{\r
+ char *ptr = "Hello world!";\r
+ char *np = 0;\r
+ int i = 5;\r
+ unsigned int bs = sizeof(int)*8;\r
+ int mi;\r
+ char buf[80];\r
+\r
+ mi = (1 << (bs-1)) + 1;\r
+ printf("%s\n", ptr);\r
+ printf("printf test\n");\r
+ printf("%s is null pointer\n", np);\r
+ printf("%d = 5\n", i);\r
+ printf("%d = - max int\n", mi);\r
+ printf("char %c = 'a'\n", 'a');\r
+ printf("hex %x = ff\n", 0xff);\r
+ printf("hex %02x = 00\n", 0);\r
+ printf("signed %d = unsigned %u = hex %x\n", -3, -3, -3);\r
+ printf("%d %s(s)%", 0, "message");\r
+ printf("\n");\r
+ printf("%d %s(s) with %%\n", 0, "message");\r
+ sprintf(buf, "justif: \"%-10s\"\n", "left"); printf("%s", buf);\r
+ sprintf(buf, "justif: \"%10s\"\n", "right"); printf("%s", buf);\r
+ sprintf(buf, " 3: %04d zero padded\n", 3); printf("%s", buf);\r
+ sprintf(buf, " 3: %-4d left justif.\n", 3); printf("%s", buf);\r
+ sprintf(buf, " 3: %4d right justif.\n", 3); printf("%s", buf);\r
+ sprintf(buf, "-3: %04d zero padded\n", -3); printf("%s", buf);\r
+ sprintf(buf, "-3: %-4d left justif.\n", -3); printf("%s", buf);\r
+ sprintf(buf, "-3: %4d right justif.\n", -3); printf("%s", buf);\r
+\r
+ return 0;\r
+}\r
+\r
+/*\r
+ * if you compile this file with\r
+ * gcc -Wall $(YOUR_C_OPTIONS) -DTEST_PRINTF -c printf.c\r
+ * you will get a normal warning:\r
+ * printf.c:214: warning: spurious trailing `%' in format\r
+ * this line is testing an invalid % at the end of the format string.\r
+ *\r
+ * this should display (on 32bit int machine) :\r
+ *\r
+ * Hello world!\r
+ * printf test\r
+ * (null) is null pointer\r
+ * 5 = 5\r
+ * -2147483647 = - max int\r
+ * char a = 'a'\r
+ * hex ff = ff\r
+ * hex 00 = 00\r
+ * signed -3 = unsigned 4294967293 = hex fffffffd\r
+ * 0 message(s)\r
+ * 0 message(s) with %\r
+ * justif: "left "\r
+ * justif: " right"\r
+ * 3: 0003 zero padded\r
+ * 3: 3 left justif.\r
+ * 3: 3 right justif.\r
+ * -3: -003 zero padded\r
+ * -3: -3 left justif.\r
+ * -3: -3 right justif.\r
+ */\r
+\r
+#endif\r
+\r
+\r
+/* To keep linker happy. */\r
+int write( int i, char* c, int n)\r
+{\r
+ (void)i;\r
+ (void)n;\r
+ (void)c;\r
+ return 0;\r
+}\r
+\r
--- /dev/null
+/******************************************************************************\r
+ * @file: system_LPC17xx.h\r
+ * @purpose: CMSIS Cortex-M3 Device Peripheral Access Layer Header File\r
+ * for the NXP LPC17xx Device Series \r
+ * @version: V1.0\r
+ * @date: 25. Nov. 2008\r
+ *----------------------------------------------------------------------------\r
+ *\r
+ * Copyright (C) 2008 ARM Limited. All rights reserved.\r
+ *\r
+ * ARM Limited (ARM) is supplying this software for use with Cortex-M3 \r
+ * processor based microcontrollers. This file can be freely distributed \r
+ * within development tools that are supporting such ARM based processors. \r
+ *\r
+ * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED\r
+ * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF\r
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.\r
+ * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR\r
+ * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.\r
+ *\r
+ ******************************************************************************/\r
+\r
+\r
+#ifndef __SYSTEM_LPC17xx_H\r
+#define __SYSTEM_LPC17xx_H\r
+\r
+extern uint32_t SystemFrequency; /*!< System Clock Frequency (Core Clock) */\r
+\r
+\r
+/**\r
+ * Initialize the system\r
+ *\r
+ * @param none\r
+ * @return none\r
+ *\r
+ * @brief Setup the microcontroller system.\r
+ * Initialize the System and update the SystemFrequency variable.\r
+ */\r
+extern void SystemInit (void);\r
+#endif\r
--- /dev/null
+/*\r
+ * Copyright (c) 2006, Swedish Institute of Computer Science.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without\r
+ * modification, are permitted provided that the following conditions\r
+ * are met:\r
+ * 1. Redistributions of source code must retain the above copyright\r
+ * notice, this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright\r
+ * notice, this list of conditions and the following disclaimer in the\r
+ * documentation and/or other materials provided with the distribution.\r
+ * 3. Neither the name of the Institute nor the names of its contributors\r
+ * may be used to endorse or promote products derived from this software\r
+ * without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND\r
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\r
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\r
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE\r
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\r
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS\r
+ * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)\r
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\r
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY\r
+ * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF\r
+ * SUCH DAMAGE.\r
+ *\r
+ * This file is part of the uIP TCP/IP stack\r
+ *\r
+ * $Id: clock-arch.h,v 1.2 2006/06/12 08:00:31 adam Exp $\r
+ */\r
+\r
+#ifndef __CLOCK_ARCH_H__\r
+#define __CLOCK_ARCH_H__\r
+\r
+#include "FreeRTOS.h"\r
+\r
+typedef unsigned long clock_time_t;\r
+#define CLOCK_CONF_SECOND configTICK_RATE_HZ\r
+\r
+#endif /* __CLOCK_ARCH_H__ */\r
--- /dev/null
+/******************************************************************\r
+ ***** *****\r
+ ***** Ver.: 1.0 *****\r
+ ***** Date: 07/05/2001 *****\r
+ ***** Auth: Andreas Dannenberg *****\r
+ ***** HTWK Leipzig *****\r
+ ***** university of applied sciences *****\r
+ ***** Germany *****\r
+ ***** Func: ethernet packet-driver for use with LAN- *****\r
+ ***** controller CS8900 from Crystal/Cirrus Logic *****\r
+ ***** *****\r
+ ***** Keil: Module modified for use with Philips *****\r
+ ***** LPC2378 EMAC Ethernet controller *****\r
+ ***** *****\r
+ ******************************************************************/\r
+\r
+/* Adapted from file originally written by Andreas Dannenberg. Supplied with permission. */\r
+#include "FreeRTOS.h"\r
+#include "semphr.h"\r
+#include "task.h"\r
+#include "emac.h"\r
+#include "LPC17xx_defs.h"\r
+\r
+#define configPINSEL2_VALUE 0x50150105\r
+\r
+/* The semaphore used to wake the uIP task when data arives. */\r
+xSemaphoreHandle xEMACSemaphore = NULL;\r
+\r
+static unsigned short *rptr;\r
+static unsigned short *tptr;\r
+\r
+static unsigned short SwapBytes( unsigned short Data )\r
+{\r
+ return( Data >> 8 ) | ( Data << 8 );\r
+}\r
+\r
+// Keil: function added to write PHY\r
+int write_PHY( int PhyReg, int Value )\r
+{\r
+ unsigned int tout;\r
+ const unsigned int uiMaxTime = 10;\r
+\r
+ MAC_MADR = DP83848C_DEF_ADR | PhyReg;\r
+ MAC_MWTD = Value;\r
+\r
+ /* Wait utill operation completed */\r
+ tout = 0;\r
+ for( tout = 0; tout < uiMaxTime; tout++ )\r
+ {\r
+ if( (MAC_MIND & MIND_BUSY) == 0 )\r
+ {\r
+ break;\r
+ }\r
+\r
+ vTaskDelay( 2 );\r
+ }\r
+\r
+ if( tout < uiMaxTime )\r
+ {\r
+ return pdPASS;\r
+ }\r
+ else\r
+ {\r
+ return pdFAIL;\r
+ }\r
+}\r
+\r
+// Keil: function added to read PHY\r
+unsigned short read_PHY( unsigned char PhyReg, portBASE_TYPE *pxStatus )\r
+{\r
+ unsigned int tout;\r
+ const unsigned int uiMaxTime = 10;\r
+\r
+ MAC_MADR = DP83848C_DEF_ADR | PhyReg;\r
+ MAC_MCMD = MCMD_READ;\r
+\r
+ /* Wait until operation completed */\r
+ tout = 0;\r
+ for( tout = 0; tout < uiMaxTime; tout++ )\r
+ {\r
+ if( (MAC_MIND & MIND_BUSY) == 0 )\r
+ {\r
+ break;\r
+ }\r
+\r
+ vTaskDelay( 2 );\r
+ }\r
+\r
+ MAC_MCMD = 0;\r
+\r
+ if( tout >= uiMaxTime )\r
+ {\r
+ *pxStatus = pdFAIL;\r
+ }\r
+\r
+ return( MAC_MRDD );\r
+}\r
+\r
+// Keil: function added to initialize Rx Descriptors\r
+void rx_descr_init( void )\r
+{\r
+ unsigned int i;\r
+\r
+ for( i = 0; i < NUM_RX_FRAG; i++ )\r
+ {\r
+ RX_DESC_PACKET( i ) = RX_BUF( i );\r
+ RX_DESC_CTRL( i ) = RCTRL_INT | ( ETH_FRAG_SIZE - 1 );\r
+ RX_STAT_INFO( i ) = 0;\r
+ RX_STAT_HASHCRC( i ) = 0;\r
+ }\r
+\r
+ /* Set EMAC Receive Descriptor Registers. */\r
+ MAC_RXDESCRIPTOR = RX_DESC_BASE;\r
+ MAC_RXSTATUS = RX_STAT_BASE;\r
+ MAC_RXDESCRIPTORNUM = NUM_RX_FRAG - 1;\r
+\r
+ /* Rx Descriptors Point to 0 */\r
+ MAC_RXCONSUMEINDEX = 0;\r
+}\r
+\r
+// Keil: function added to initialize Tx Descriptors\r
+void tx_descr_init( void )\r
+{\r
+ unsigned int i;\r
+\r
+ for( i = 0; i < NUM_TX_FRAG; i++ )\r
+ {\r
+ TX_DESC_PACKET( i ) = TX_BUF( i );\r
+ TX_DESC_CTRL( i ) = 0;\r
+ TX_STAT_INFO( i ) = 0;\r
+ }\r
+\r
+ /* Set EMAC Transmit Descriptor Registers. */\r
+ MAC_TXDESCRIPTOR = TX_DESC_BASE;\r
+ MAC_TXSTATUS = TX_STAT_BASE;\r
+ MAC_TXDESCRIPTORNUM = NUM_TX_FRAG - 1;\r
+\r
+ /* Tx Descriptors Point to 0 */\r
+ MAC_TXPRODUCEINDEX = 0;\r
+}\r
+\r
+// configure port-pins for use with LAN-controller,\r
+// reset it and send the configuration-sequence\r
+portBASE_TYPE Init_EMAC( void )\r
+{\r
+ portBASE_TYPE xReturn = pdPASS;\r
+\r
+ // Keil: function modified to access the EMAC\r
+ // Initializes the EMAC ethernet controller\r
+ volatile unsigned int regv, tout, id1, id2;\r
+\r
+ /* Enable P1 Ethernet Pins. */\r
+ PINSEL2 = configPINSEL2_VALUE;\r
+ PINSEL3 = ( PINSEL3 &~0x0000000F ) | 0x00000005;\r
+\r
+ /* Power Up the EMAC controller. */\r
+ PCONP |= PCONP_PCENET;\r
+ vTaskDelay( 2 );\r
+\r
+ /* Reset all EMAC internal modules. */\r
+ MAC_MAC1 = MAC1_RES_TX | MAC1_RES_MCS_TX | MAC1_RES_RX | MAC1_RES_MCS_RX | MAC1_SIM_RES | MAC1_SOFT_RES;\r
+ MAC_COMMAND = CR_REG_RES | CR_TX_RES | CR_RX_RES | CR_PASS_RUNT_FRM;\r
+\r
+ /* A short delay after reset. */\r
+ vTaskDelay( 2 );\r
+\r
+ /* Initialize MAC control registers. */\r
+ MAC_MAC1 = MAC1_PASS_ALL;\r
+ MAC_MAC2 = MAC2_CRC_EN | MAC2_PAD_EN;\r
+ MAC_MAXF = ETH_MAX_FLEN;\r
+ MAC_CLRT = CLRT_DEF;\r
+ MAC_IPGR = IPGR_DEF;\r
+\r
+ /* Enable Reduced MII interface. */\r
+ MAC_COMMAND = CR_RMII | CR_PASS_RUNT_FRM;\r
+\r
+ /* Reset Reduced MII Logic. */\r
+ MAC_SUPP = SUPP_RES_RMII;\r
+ vTaskDelay( 2 );\r
+ MAC_SUPP = 0;\r
+\r
+ /* Put the PHY in reset mode */\r
+ write_PHY( PHY_REG_BMCR, 0x8000 );\r
+ xReturn = write_PHY( PHY_REG_BMCR, 0x8000 );\r
+\r
+ /* Wait for hardware reset to end. */\r
+ for( tout = 0; tout < 100; tout++ )\r
+ {\r
+ vTaskDelay( 10 );\r
+ regv = read_PHY( PHY_REG_BMCR, &xReturn );\r
+ if( !(regv & 0x8000) )\r
+ {\r
+ /* Reset complete */\r
+ break;\r
+ }\r
+ }\r
+\r
+ /* Check if this is a DP83848C PHY. */\r
+ id1 = read_PHY( PHY_REG_IDR1, &xReturn );\r
+ id2 = read_PHY( PHY_REG_IDR2, &xReturn );\r
+ if( ((id1 << 16) | (id2 & 0xFFF0)) == DP83848C_ID )\r
+ {\r
+ /* Set the Ethernet MAC Address registers */\r
+ MAC_SA0 = ( emacETHADDR0 << 8 ) | emacETHADDR1;\r
+ MAC_SA1 = ( emacETHADDR2 << 8 ) | emacETHADDR3;\r
+ MAC_SA2 = ( emacETHADDR4 << 8 ) | emacETHADDR5;\r
+\r
+ /* Initialize Tx and Rx DMA Descriptors */\r
+ rx_descr_init();\r
+ tx_descr_init();\r
+\r
+ /* Receive Broadcast and Perfect Match Packets */\r
+ MAC_RXFILTERCTRL = RFC_UCAST_EN | RFC_BCAST_EN | RFC_PERFECT_EN;\r
+\r
+ /* Create the semaphore used ot wake the uIP task. */\r
+ vSemaphoreCreateBinary( xEMACSemaphore );\r
+\r
+ /* Configure the PHY device */\r
+\r
+ /* Use autonegotiation about the link speed. */\r
+ if( write_PHY(PHY_REG_BMCR, PHY_AUTO_NEG) )\r
+ {\r
+ /* Wait to complete Auto_Negotiation. */\r
+ for( tout = 0; tout < 10; tout++ )\r
+ {\r
+ vTaskDelay( 100 );\r
+ regv = read_PHY( PHY_REG_BMSR, &xReturn );\r
+ if( regv & 0x0020 )\r
+ {\r
+ /* Autonegotiation Complete. */\r
+ break;\r
+ }\r
+ }\r
+ }\r
+ }\r
+ else\r
+ {\r
+ xReturn = pdFAIL;\r
+ }\r
+\r
+ /* Check the link status. */\r
+ if( xReturn == pdPASS )\r
+ {\r
+ xReturn = pdFAIL;\r
+ for( tout = 0; tout < 10; tout++ )\r
+ {\r
+ vTaskDelay( 100 );\r
+ regv = read_PHY( PHY_REG_STS, &xReturn );\r
+ if( regv & 0x0001 )\r
+ {\r
+ /* Link is on. */\r
+ xReturn = pdPASS;\r
+ break;\r
+ }\r
+ }\r
+ }\r
+\r
+ if( xReturn == pdPASS )\r
+ {\r
+ /* Configure Full/Half Duplex mode. */\r
+ if( regv & 0x0004 )\r
+ {\r
+ /* Full duplex is enabled. */\r
+ MAC_MAC2 |= MAC2_FULL_DUP;\r
+ MAC_COMMAND |= CR_FULL_DUP;\r
+ MAC_IPGT = IPGT_FULL_DUP;\r
+ }\r
+ else\r
+ {\r
+ /* Half duplex mode. */\r
+ MAC_IPGT = IPGT_HALF_DUP;\r
+ }\r
+\r
+ /* Configure 100MBit/10MBit mode. */\r
+ if( regv & 0x0002 )\r
+ {\r
+ /* 10MBit mode. */\r
+ MAC_SUPP = 0;\r
+ }\r
+ else\r
+ {\r
+ /* 100MBit mode. */\r
+ MAC_SUPP = SUPP_SPEED;\r
+ }\r
+\r
+ /* Reset all interrupts */\r
+ MAC_INTCLEAR = 0xFFFF;\r
+\r
+ /* Enable receive and transmit mode of MAC Ethernet core */\r
+ MAC_COMMAND |= ( CR_RX_EN | CR_TX_EN );\r
+ MAC_MAC1 |= MAC1_REC_EN;\r
+ }\r
+\r
+ return xReturn;\r
+}\r
+\r
+// reads a word in little-endian byte order from RX_BUFFER\r
+unsigned short ReadFrame_EMAC( void )\r
+{\r
+ return( *rptr++ );\r
+}\r
+\r
+// reads a word in big-endian byte order from RX_FRAME_PORT\r
+// (useful to avoid permanent byte-swapping while reading\r
+// TCP/IP-data)\r
+unsigned short ReadFrameBE_EMAC( void )\r
+{\r
+ unsigned short ReturnValue;\r
+\r
+ ReturnValue = SwapBytes( *rptr++ );\r
+ return( ReturnValue );\r
+}\r
+\r
+// copies bytes from frame port to MCU-memory\r
+// NOTES: * an odd number of byte may only be transfered\r
+// if the frame is read to the end!\r
+// * MCU-memory MUST start at word-boundary\r
+void CopyFromFrame_EMAC( void *Dest, unsigned short Size )\r
+{\r
+ unsigned short *piDest; // Keil: Pointer added to correct expression\r
+ piDest = Dest; // Keil: Line added\r
+ while( Size > 1 )\r
+ {\r
+ *piDest++ = ReadFrame_EMAC();\r
+ Size -= 2;\r
+ }\r
+\r
+ if( Size )\r
+ { // check for leftover byte...\r
+ *( unsigned char * ) piDest = ( char ) ReadFrame_EMAC(); // the LAN-Controller will return 0\r
+ } // for the highbyte\r
+}\r
+\r
+// does a dummy read on frame-I/O-port\r
+// NOTE: only an even number of bytes is read!\r
+void DummyReadFrame_EMAC( unsigned short Size ) // discards an EVEN number of bytes\r
+{ // from RX-fifo\r
+ while( Size > 1 )\r
+ {\r
+ ReadFrame_EMAC();\r
+ Size -= 2;\r
+ }\r
+}\r
+\r
+// Reads the length of the received ethernet frame and checks if the\r
+// destination address is a broadcast message or not\r
+// returns the frame length\r
+unsigned short StartReadFrame( void )\r
+{\r
+ unsigned short RxLen;\r
+ unsigned int idx;\r
+\r
+ idx = MAC_RXCONSUMEINDEX;\r
+ RxLen = ( RX_STAT_INFO(idx) & RINFO_SIZE ) - 3;\r
+ rptr = ( unsigned short * ) RX_DESC_PACKET( idx );\r
+ return( RxLen );\r
+}\r
+\r
+void EndReadFrame( void )\r
+{\r
+ unsigned int idx;\r
+\r
+ /* DMA free packet. */\r
+ idx = MAC_RXCONSUMEINDEX;\r
+\r
+ if( ++idx == NUM_RX_FRAG )\r
+ {\r
+ idx = 0;\r
+ }\r
+\r
+ MAC_RXCONSUMEINDEX = idx;\r
+}\r
+\r
+unsigned int CheckFrameReceived( void )\r
+{ \r
+ // Packet received ?\r
+ if( MAC_RXPRODUCEINDEX != MAC_RXCONSUMEINDEX )\r
+ { // more packets received ?\r
+ return( 1 );\r
+ }\r
+ else\r
+ {\r
+ return( 0 );\r
+ }\r
+}\r
+\r
+unsigned int uiGetEMACRxData( unsigned char *ucBuffer )\r
+{\r
+ unsigned int uiLen = 0;\r
+\r
+ if( MAC_RXPRODUCEINDEX != MAC_RXCONSUMEINDEX )\r
+ {\r
+ uiLen = StartReadFrame();\r
+ CopyFromFrame_EMAC( ucBuffer, uiLen );\r
+ EndReadFrame();\r
+ }\r
+\r
+ return uiLen;\r
+}\r
+\r
+// requests space in EMAC memory for storing an outgoing frame\r
+void RequestSend( void )\r
+{\r
+ unsigned int idx;\r
+\r
+ idx = MAC_TXPRODUCEINDEX;\r
+ tptr = ( unsigned short * ) TX_DESC_PACKET( idx );\r
+}\r
+\r
+// check if ethernet controller is ready to accept the\r
+// frame we want to send\r
+unsigned int Rdy4Tx( void )\r
+{\r
+ return( 1 ); // the ethernet controller transmits much faster\r
+} // than the CPU can load its buffers\r
+\r
+// writes a word in little-endian byte order to TX_BUFFER\r
+void WriteFrame_EMAC( unsigned short Data )\r
+{\r
+ *tptr++ = Data;\r
+}\r
+\r
+// copies bytes from MCU-memory to frame port\r
+// NOTES: * an odd number of byte may only be transfered\r
+// if the frame is written to the end!\r
+// * MCU-memory MUST start at word-boundary\r
+void CopyToFrame_EMAC( void *Source, unsigned int Size )\r
+{\r
+ unsigned short *piSource;\r
+\r
+ piSource = Source;\r
+ Size = ( Size + 1 ) & 0xFFFE; // round Size up to next even number\r
+ while( Size > 0 )\r
+ {\r
+ WriteFrame_EMAC( *piSource++ );\r
+ Size -= 2;\r
+ }\r
+}\r
+\r
+void DoSend_EMAC( unsigned short FrameSize )\r
+{\r
+ unsigned int idx;\r
+\r
+ idx = MAC_TXPRODUCEINDEX;\r
+ TX_DESC_CTRL( idx ) = FrameSize | TCTRL_LAST;\r
+ if( ++idx == NUM_TX_FRAG )\r
+ {\r
+ idx = 0;\r
+ }\r
+\r
+ MAC_TXPRODUCEINDEX = idx;\r
+}\r
+\r
+void vEMAC_ISR( void )\r
+{\r
+ portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;\r
+\r
+ /* Clear the interrupt. */\r
+ MAC_INTCLEAR = 0xffff;\r
+\r
+ /* Ensure the uIP task is not blocked as data has arrived. */\r
+ xSemaphoreGiveFromISR( xEMACSemaphore, &xHigherPriorityTaskWoken );\r
+\r
+ portEND_SWITCHING_ISR( xHigherPriorityTaskWoken );\r
+}\r
--- /dev/null
+/*----------------------------------------------------------------------------\r
+ * LPC2378 Ethernet Definitions\r
+ *----------------------------------------------------------------------------\r
+ * Name: EMAC.H\r
+ * Purpose: Philips LPC2378 EMAC hardware definitions\r
+ *----------------------------------------------------------------------------\r
+ * Copyright (c) 2006 KEIL - An ARM Company. All rights reserved.\r
+ *---------------------------------------------------------------------------*/\r
+#ifndef __EMAC_H\r
+#define __EMAC_H\r
+\r
+/* MAC address definition. The MAC address must be unique on the network. */\r
+#define emacETHADDR0 0\r
+#define emacETHADDR1 0xbd\r
+#define emacETHADDR2 0x33\r
+#define emacETHADDR3 0x02\r
+#define emacETHADDR4 0x64\r
+#define emacETHADDR5 0x24\r
+\r
+\r
+/* EMAC Memory Buffer configuration for 16K Ethernet RAM. */\r
+#define NUM_RX_FRAG 4 /* Num.of RX Fragments 4*1536= 6.0kB */\r
+#define NUM_TX_FRAG 2 /* Num.of TX Fragments 2*1536= 3.0kB */\r
+#define ETH_FRAG_SIZE 1536 /* Packet Fragment size 1536 Bytes */\r
+\r
+#define ETH_MAX_FLEN 1536 /* Max. Ethernet Frame Size */\r
+\r
+/* EMAC variables located in 16K Ethernet SRAM */\r
+//extern unsigned char xEthDescriptors[];\r
+#define RX_DESC_BASE (0x2007c000UL)\r
+#define RX_STAT_BASE (RX_DESC_BASE + NUM_RX_FRAG*8)\r
+#define TX_DESC_BASE (RX_STAT_BASE + NUM_RX_FRAG*8)\r
+#define TX_STAT_BASE (TX_DESC_BASE + NUM_TX_FRAG*8)\r
+#define RX_BUF_BASE (TX_STAT_BASE + NUM_TX_FRAG*4)\r
+#define TX_BUF_BASE (RX_BUF_BASE + NUM_RX_FRAG*ETH_FRAG_SIZE)\r
+#define TX_BUF_END (TX_BUF_BASE + NUM_TX_FRAG*ETH_FRAG_SIZE)\r
+\r
+/* RX and TX descriptor and status definitions. */\r
+#define RX_DESC_PACKET(i) (*(unsigned int *)(RX_DESC_BASE + 8*i))\r
+#define RX_DESC_CTRL(i) (*(unsigned int *)(RX_DESC_BASE+4 + 8*i))\r
+#define RX_STAT_INFO(i) (*(unsigned int *)(RX_STAT_BASE + 8*i))\r
+#define RX_STAT_HASHCRC(i) (*(unsigned int *)(RX_STAT_BASE+4 + 8*i))\r
+#define TX_DESC_PACKET(i) (*(unsigned int *)(TX_DESC_BASE + 8*i))\r
+#define TX_DESC_CTRL(i) (*(unsigned int *)(TX_DESC_BASE+4 + 8*i))\r
+#define TX_STAT_INFO(i) (*(unsigned int *)(TX_STAT_BASE + 4*i))\r
+#define RX_BUF(i) (RX_BUF_BASE + ETH_FRAG_SIZE*i)\r
+#define TX_BUF(i) (TX_BUF_BASE + ETH_FRAG_SIZE*i)\r
+\r
+/* MAC Configuration Register 1 */\r
+#define MAC1_REC_EN 0x00000001 /* Receive Enable */\r
+#define MAC1_PASS_ALL 0x00000002 /* Pass All Receive Frames */\r
+#define MAC1_RX_FLOWC 0x00000004 /* RX Flow Control */\r
+#define MAC1_TX_FLOWC 0x00000008 /* TX Flow Control */\r
+#define MAC1_LOOPB 0x00000010 /* Loop Back Mode */\r
+#define MAC1_RES_TX 0x00000100 /* Reset TX Logic */\r
+#define MAC1_RES_MCS_TX 0x00000200 /* Reset MAC TX Control Sublayer */\r
+#define MAC1_RES_RX 0x00000400 /* Reset RX Logic */\r
+#define MAC1_RES_MCS_RX 0x00000800 /* Reset MAC RX Control Sublayer */\r
+#define MAC1_SIM_RES 0x00004000 /* Simulation Reset */\r
+#define MAC1_SOFT_RES 0x00008000 /* Soft Reset MAC */\r
+\r
+/* MAC Configuration Register 2 */\r
+#define MAC2_FULL_DUP 0x00000001 /* Full Duplex Mode */\r
+#define MAC2_FRM_LEN_CHK 0x00000002 /* Frame Length Checking */\r
+#define MAC2_HUGE_FRM_EN 0x00000004 /* Huge Frame Enable */\r
+#define MAC2_DLY_CRC 0x00000008 /* Delayed CRC Mode */\r
+#define MAC2_CRC_EN 0x00000010 /* Append CRC to every Frame */\r
+#define MAC2_PAD_EN 0x00000020 /* Pad all Short Frames */\r
+#define MAC2_VLAN_PAD_EN 0x00000040 /* VLAN Pad Enable */\r
+#define MAC2_ADET_PAD_EN 0x00000080 /* Auto Detect Pad Enable */\r
+#define MAC2_PPREAM_ENF 0x00000100 /* Pure Preamble Enforcement */\r
+#define MAC2_LPREAM_ENF 0x00000200 /* Long Preamble Enforcement */\r
+#undef MAC2_NO_BACKOFF /* Remove compiler warning. */\r
+#define MAC2_NO_BACKOFF 0x00001000 /* No Backoff Algorithm */\r
+#define MAC2_BACK_PRESSURE 0x00002000 /* Backoff Presurre / No Backoff */\r
+#define MAC2_EXCESS_DEF 0x00004000 /* Excess Defer */\r
+\r
+/* Back-to-Back Inter-Packet-Gap Register */\r
+#define IPGT_FULL_DUP 0x00000015 /* Recommended value for Full Duplex */\r
+#define IPGT_HALF_DUP 0x00000012 /* Recommended value for Half Duplex */\r
+\r
+/* Non Back-to-Back Inter-Packet-Gap Register */\r
+#define IPGR_DEF 0x00000012 /* Recommended value */\r
+\r
+/* Collision Window/Retry Register */\r
+#define CLRT_DEF 0x0000370F /* Default value */\r
+\r
+/* PHY Support Register */\r
+#undef SUPP_SPEED /* Remove compiler warning. */\r
+#define SUPP_SPEED 0x00000100 /* Reduced MII Logic Current Speed */\r
+#define SUPP_RES_RMII 0x00000800 /* Reset Reduced MII Logic */\r
+\r
+/* Test Register */\r
+#define TEST_SHCUT_PQUANTA 0x00000001 /* Shortcut Pause Quanta */\r
+#define TEST_TST_PAUSE 0x00000002 /* Test Pause */\r
+#define TEST_TST_BACKP 0x00000004 /* Test Back Pressure */\r
+\r
+/* MII Management Configuration Register */\r
+#define MCFG_SCAN_INC 0x00000001 /* Scan Increment PHY Address */\r
+#define MCFG_SUPP_PREAM 0x00000002 /* Suppress Preamble */\r
+#define MCFG_CLK_SEL 0x0000001C /* Clock Select Mask */\r
+#define MCFG_RES_MII 0x00008000 /* Reset MII Management Hardware */\r
+\r
+/* MII Management Command Register */\r
+#undef MCMD_READ /* Remove compiler warning. */\r
+#define MCMD_READ 0x00000001 /* MII Read */\r
+#undef MCMD_SCAN /* Remove compiler warning. */\r
+#define MCMD_SCAN 0x00000002 /* MII Scan continuously */\r
+\r
+#define MII_WR_TOUT 0x00050000 /* MII Write timeout count */\r
+#define MII_RD_TOUT 0x00050000 /* MII Read timeout count */\r
+\r
+/* MII Management Address Register */\r
+#define MADR_REG_ADR 0x0000001F /* MII Register Address Mask */\r
+#define MADR_PHY_ADR 0x00001F00 /* PHY Address Mask */\r
+\r
+/* MII Management Indicators Register */\r
+#undef MIND_BUSY /* Remove compiler warning. */\r
+#define MIND_BUSY 0x00000001 /* MII is Busy */\r
+#define MIND_SCAN 0x00000002 /* MII Scanning in Progress */\r
+#define MIND_NOT_VAL 0x00000004 /* MII Read Data not valid */\r
+#define MIND_MII_LINK_FAIL 0x00000008 /* MII Link Failed */\r
+\r
+/* Command Register */\r
+#define CR_RX_EN 0x00000001 /* Enable Receive */\r
+#define CR_TX_EN 0x00000002 /* Enable Transmit */\r
+#define CR_REG_RES 0x00000008 /* Reset Host Registers */\r
+#define CR_TX_RES 0x00000010 /* Reset Transmit Datapath */\r
+#define CR_RX_RES 0x00000020 /* Reset Receive Datapath */\r
+#define CR_PASS_RUNT_FRM 0x00000040 /* Pass Runt Frames */\r
+#define CR_PASS_RX_FILT 0x00000080 /* Pass RX Filter */\r
+#define CR_TX_FLOW_CTRL 0x00000100 /* TX Flow Control */\r
+#define CR_RMII 0x00000200 /* Reduced MII Interface */\r
+#define CR_FULL_DUP 0x00000400 /* Full Duplex */\r
+\r
+/* Status Register */\r
+#define SR_RX_EN 0x00000001 /* Enable Receive */\r
+#define SR_TX_EN 0x00000002 /* Enable Transmit */\r
+\r
+/* Transmit Status Vector 0 Register */\r
+#define TSV0_CRC_ERR 0x00000001 /* CRC error */\r
+#define TSV0_LEN_CHKERR 0x00000002 /* Length Check Error */\r
+#define TSV0_LEN_OUTRNG 0x00000004 /* Length Out of Range */\r
+#define TSV0_DONE 0x00000008 /* Tramsmission Completed */\r
+#define TSV0_MCAST 0x00000010 /* Multicast Destination */\r
+#define TSV0_BCAST 0x00000020 /* Broadcast Destination */\r
+#define TSV0_PKT_DEFER 0x00000040 /* Packet Deferred */\r
+#define TSV0_EXC_DEFER 0x00000080 /* Excessive Packet Deferral */\r
+#define TSV0_EXC_COLL 0x00000100 /* Excessive Collision */\r
+#define TSV0_LATE_COLL 0x00000200 /* Late Collision Occured */\r
+#define TSV0_GIANT 0x00000400 /* Giant Frame */\r
+#define TSV0_UNDERRUN 0x00000800 /* Buffer Underrun */\r
+#define TSV0_BYTES 0x0FFFF000 /* Total Bytes Transferred */\r
+#define TSV0_CTRL_FRAME 0x10000000 /* Control Frame */\r
+#define TSV0_PAUSE 0x20000000 /* Pause Frame */\r
+#define TSV0_BACK_PRESS 0x40000000 /* Backpressure Method Applied */\r
+#define TSV0_VLAN 0x80000000 /* VLAN Frame */\r
+\r
+/* Transmit Status Vector 1 Register */\r
+#define TSV1_BYTE_CNT 0x0000FFFF /* Transmit Byte Count */\r
+#define TSV1_COLL_CNT 0x000F0000 /* Transmit Collision Count */\r
+\r
+/* Receive Status Vector Register */\r
+#define RSV_BYTE_CNT 0x0000FFFF /* Receive Byte Count */\r
+#define RSV_PKT_IGNORED 0x00010000 /* Packet Previously Ignored */\r
+#define RSV_RXDV_SEEN 0x00020000 /* RXDV Event Previously Seen */\r
+#define RSV_CARR_SEEN 0x00040000 /* Carrier Event Previously Seen */\r
+#define RSV_REC_CODEV 0x00080000 /* Receive Code Violation */\r
+#define RSV_CRC_ERR 0x00100000 /* CRC Error */\r
+#define RSV_LEN_CHKERR 0x00200000 /* Length Check Error */\r
+#define RSV_LEN_OUTRNG 0x00400000 /* Length Out of Range */\r
+#define RSV_REC_OK 0x00800000 /* Frame Received OK */\r
+#define RSV_MCAST 0x01000000 /* Multicast Frame */\r
+#define RSV_BCAST 0x02000000 /* Broadcast Frame */\r
+#define RSV_DRIB_NIBB 0x04000000 /* Dribble Nibble */\r
+#define RSV_CTRL_FRAME 0x08000000 /* Control Frame */\r
+#define RSV_PAUSE 0x10000000 /* Pause Frame */\r
+#define RSV_UNSUPP_OPC 0x20000000 /* Unsupported Opcode */\r
+#define RSV_VLAN 0x40000000 /* VLAN Frame */\r
+\r
+/* Flow Control Counter Register */\r
+#define FCC_MIRR_CNT 0x0000FFFF /* Mirror Counter */\r
+#define FCC_PAUSE_TIM 0xFFFF0000 /* Pause Timer */\r
+\r
+/* Flow Control Status Register */\r
+#define FCS_MIRR_CNT 0x0000FFFF /* Mirror Counter Current */\r
+\r
+/* Receive Filter Control Register */\r
+#define RFC_UCAST_EN 0x00000001 /* Accept Unicast Frames Enable */\r
+#define RFC_BCAST_EN 0x00000002 /* Accept Broadcast Frames Enable */\r
+#define RFC_MCAST_EN 0x00000004 /* Accept Multicast Frames Enable */\r
+#define RFC_UCAST_HASH_EN 0x00000008 /* Accept Unicast Hash Filter Frames */\r
+#define RFC_MCAST_HASH_EN 0x00000010 /* Accept Multicast Hash Filter Fram.*/\r
+#define RFC_PERFECT_EN 0x00000020 /* Accept Perfect Match Enable */\r
+#define RFC_MAGP_WOL_EN 0x00001000 /* Magic Packet Filter WoL Enable */\r
+#define RFC_PFILT_WOL_EN 0x00002000 /* Perfect Filter WoL Enable */\r
+\r
+/* Receive Filter WoL Status/Clear Registers */\r
+#define WOL_UCAST 0x00000001 /* Unicast Frame caused WoL */\r
+#define WOL_BCAST 0x00000002 /* Broadcast Frame caused WoL */\r
+#define WOL_MCAST 0x00000004 /* Multicast Frame caused WoL */\r
+#define WOL_UCAST_HASH 0x00000008 /* Unicast Hash Filter Frame WoL */\r
+#define WOL_MCAST_HASH 0x00000010 /* Multicast Hash Filter Frame WoL */\r
+#define WOL_PERFECT 0x00000020 /* Perfect Filter WoL */\r
+#define WOL_RX_FILTER 0x00000080 /* RX Filter caused WoL */\r
+#define WOL_MAG_PACKET 0x00000100 /* Magic Packet Filter caused WoL */\r
+\r
+/* Interrupt Status/Enable/Clear/Set Registers */\r
+#define INT_RX_OVERRUN 0x00000001 /* Overrun Error in RX Queue */\r
+#define INT_RX_ERR 0x00000002 /* Receive Error */\r
+#define INT_RX_FIN 0x00000004 /* RX Finished Process Descriptors */\r
+#define INT_RX_DONE 0x00000008 /* Receive Done */\r
+#define INT_TX_UNDERRUN 0x00000010 /* Transmit Underrun */\r
+#define INT_TX_ERR 0x00000020 /* Transmit Error */\r
+#define INT_TX_FIN 0x00000040 /* TX Finished Process Descriptors */\r
+#define INT_TX_DONE 0x00000080 /* Transmit Done */\r
+#define INT_SOFT_INT 0x00001000 /* Software Triggered Interrupt */\r
+#define INT_WAKEUP 0x00002000 /* Wakeup Event Interrupt */\r
+\r
+/* Power Down Register */\r
+#define PD_POWER_DOWN 0x80000000 /* Power Down MAC */\r
+\r
+/* RX Descriptor Control Word */\r
+#define RCTRL_SIZE 0x000007FF /* Buffer size mask */\r
+#define RCTRL_INT 0x80000000 /* Generate RxDone Interrupt */\r
+\r
+/* RX Status Hash CRC Word */\r
+#define RHASH_SA 0x000001FF /* Hash CRC for Source Address */\r
+#define RHASH_DA 0x001FF000 /* Hash CRC for Destination Address */\r
+\r
+/* RX Status Information Word */\r
+#define RINFO_SIZE 0x000007FF /* Data size in bytes */\r
+#define RINFO_CTRL_FRAME 0x00040000 /* Control Frame */\r
+#define RINFO_VLAN 0x00080000 /* VLAN Frame */\r
+#define RINFO_FAIL_FILT 0x00100000 /* RX Filter Failed */\r
+#define RINFO_MCAST 0x00200000 /* Multicast Frame */\r
+#define RINFO_BCAST 0x00400000 /* Broadcast Frame */\r
+#define RINFO_CRC_ERR 0x00800000 /* CRC Error in Frame */\r
+#define RINFO_SYM_ERR 0x01000000 /* Symbol Error from PHY */\r
+#define RINFO_LEN_ERR 0x02000000 /* Length Error */\r
+#define RINFO_RANGE_ERR 0x04000000 /* Range Error (exceeded max. size) */\r
+#define RINFO_ALIGN_ERR 0x08000000 /* Alignment Error */\r
+#define RINFO_OVERRUN 0x10000000 /* Receive overrun */\r
+#define RINFO_NO_DESCR 0x20000000 /* No new Descriptor available */\r
+#define RINFO_LAST_FLAG 0x40000000 /* Last Fragment in Frame */\r
+#define RINFO_ERR 0x80000000 /* Error Occured (OR of all errors) */\r
+\r
+#define RINFO_ERR_MASK (RINFO_FAIL_FILT | RINFO_CRC_ERR | RINFO_SYM_ERR | \\r
+ RINFO_LEN_ERR | RINFO_ALIGN_ERR | RINFO_OVERRUN)\r
+\r
+/* TX Descriptor Control Word */\r
+#define TCTRL_SIZE 0x000007FF /* Size of data buffer in bytes */\r
+#define TCTRL_OVERRIDE 0x04000000 /* Override Default MAC Registers */\r
+#define TCTRL_HUGE 0x08000000 /* Enable Huge Frame */\r
+#define TCTRL_PAD 0x10000000 /* Pad short Frames to 64 bytes */\r
+#define TCTRL_CRC 0x20000000 /* Append a hardware CRC to Frame */\r
+#define TCTRL_LAST 0x40000000 /* Last Descriptor for TX Frame */\r
+#define TCTRL_INT 0x80000000 /* Generate TxDone Interrupt */\r
+\r
+/* TX Status Information Word */\r
+#define TINFO_COL_CNT 0x01E00000 /* Collision Count */\r
+#define TINFO_DEFER 0x02000000 /* Packet Deferred (not an error) */\r
+#define TINFO_EXCESS_DEF 0x04000000 /* Excessive Deferral */\r
+#define TINFO_EXCESS_COL 0x08000000 /* Excessive Collision */\r
+#define TINFO_LATE_COL 0x10000000 /* Late Collision Occured */\r
+#define TINFO_UNDERRUN 0x20000000 /* Transmit Underrun */\r
+#define TINFO_NO_DESCR 0x40000000 /* No new Descriptor available */\r
+#define TINFO_ERR 0x80000000 /* Error Occured (OR of all errors) */\r
+\r
+/* DP83848C PHY Registers */\r
+#define PHY_REG_BMCR 0x00 /* Basic Mode Control Register */\r
+#define PHY_REG_BMSR 0x01 /* Basic Mode Status Register */\r
+#define PHY_REG_IDR1 0x02 /* PHY Identifier 1 */\r
+#define PHY_REG_IDR2 0x03 /* PHY Identifier 2 */\r
+#define PHY_REG_ANAR 0x04 /* Auto-Negotiation Advertisement */\r
+#define PHY_REG_ANLPAR 0x05 /* Auto-Neg. Link Partner Abitily */\r
+#define PHY_REG_ANER 0x06 /* Auto-Neg. Expansion Register */\r
+#define PHY_REG_ANNPTR 0x07 /* Auto-Neg. Next Page TX */\r
+\r
+/* PHY Extended Registers */\r
+#define PHY_REG_STS 0x10 /* Status Register */\r
+#define PHY_REG_MICR 0x11 /* MII Interrupt Control Register */\r
+#define PHY_REG_MISR 0x12 /* MII Interrupt Status Register */\r
+#define PHY_REG_FCSCR 0x14 /* False Carrier Sense Counter */\r
+#define PHY_REG_RECR 0x15 /* Receive Error Counter */\r
+#define PHY_REG_PCSR 0x16 /* PCS Sublayer Config. and Status */\r
+#define PHY_REG_RBR 0x17 /* RMII and Bypass Register */\r
+#define PHY_REG_LEDCR 0x18 /* LED Direct Control Register */\r
+#define PHY_REG_PHYCR 0x19 /* PHY Control Register */\r
+#define PHY_REG_10BTSCR 0x1A /* 10Base-T Status/Control Register */\r
+#define PHY_REG_CDCTRL1 0x1B /* CD Test Control and BIST Extens. */\r
+#define PHY_REG_EDCR 0x1D /* Energy Detect Control Register */\r
+\r
+#define PHY_FULLD_100M 0x2100 /* Full Duplex 100Mbit */\r
+#define PHY_HALFD_100M 0x2000 /* Half Duplex 100Mbit */\r
+#define PHY_FULLD_10M 0x0100 /* Full Duplex 10Mbit */\r
+#define PHY_HALFD_10M 0x0000 /* Half Duplex 10MBit */\r
+#define PHY_AUTO_NEG 0x3000 /* Select Auto Negotiation */\r
+\r
+#define DP83848C_DEF_ADR 0x0100 /* Default PHY device address */\r
+#define DP83848C_ID 0x20005C90 /* PHY Identifier */\r
+\r
+// prototypes\r
+portBASE_TYPE Init_EMAC(void);\r
+unsigned short ReadFrameBE_EMAC(void);\r
+void CopyToFrame_EMAC(void *Source, unsigned int Size);\r
+void CopyFromFrame_EMAC(void *Dest, unsigned short Size);\r
+void DummyReadFrame_EMAC(unsigned short Size);\r
+unsigned short StartReadFrame(void);\r
+void EndReadFrame(void);\r
+unsigned int CheckFrameReceived(void);\r
+void RequestSend(void);\r
+unsigned int Rdy4Tx(void);\r
+void DoSend_EMAC(unsigned short FrameSize);\r
+void vEMACWaitForInput( void );\r
+unsigned int uiGetEMACRxData( unsigned char *ucBuffer );\r
+\r
+\r
+#endif\r
+\r
+/*----------------------------------------------------------------------------\r
+ * end of file\r
+ *---------------------------------------------------------------------------*/\r
+\r
--- /dev/null
+http_http "http://"\r
+http_200 "200 "\r
+http_301 "301 "\r
+http_302 "302 "\r
+http_get "GET "\r
+http_10 "HTTP/1.0"\r
+http_11 "HTTP/1.1"\r
+http_content_type "content-type: "\r
+http_texthtml "text/html"\r
+http_location "location: "\r
+http_host "host: "\r
+http_crnl "\r\n"\r
+http_index_html "/index.html"\r
+http_404_html "/404.html"\r
+http_referer "Referer:"\r
+http_header_200 "HTTP/1.0 200 OK\r\nServer: uIP/1.0 http://www.sics.se/~adam/uip/\r\nConnection: close\r\n"\r
+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"\r
+http_content_type_plain "Content-type: text/plain\r\n\r\n"\r
+http_content_type_html "Content-type: text/html\r\n\r\n"\r
+http_content_type_css "Content-type: text/css\r\n\r\n"\r
+http_content_type_text "Content-type: text/text\r\n\r\n"\r
+http_content_type_png "Content-type: image/png\r\n\r\n"\r
+http_content_type_gif "Content-type: image/gif\r\n\r\n"\r
+http_content_type_jpg "Content-type: image/jpeg\r\n\r\n"\r
+http_content_type_binary "Content-type: application/octet-stream\r\n\r\n"\r
+http_html ".html"\r
+http_shtml ".shtml"\r
+http_htm ".htm"\r
+http_css ".css"\r
+http_png ".png"\r
+http_gif ".gif"\r
+http_jpg ".jpg"\r
+http_text ".txt"\r
+http_txt ".txt"\r
+\r
--- /dev/null
+const char http_http[8] = \r
+/* "http://" */\r
+{0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, 0x2f, };\r
+const char http_200[5] = \r
+/* "200 " */\r
+{0x32, 0x30, 0x30, 0x20, };\r
+const char http_301[5] = \r
+/* "301 " */\r
+{0x33, 0x30, 0x31, 0x20, };\r
+const char http_302[5] = \r
+/* "302 " */\r
+{0x33, 0x30, 0x32, 0x20, };\r
+const char http_get[5] = \r
+/* "GET " */\r
+{0x47, 0x45, 0x54, 0x20, };\r
+const char http_10[9] = \r
+/* "HTTP/1.0" */\r
+{0x48, 0x54, 0x54, 0x50, 0x2f, 0x31, 0x2e, 0x30, };\r
+const char http_11[9] = \r
+/* "HTTP/1.1" */\r
+{0x48, 0x54, 0x54, 0x50, 0x2f, 0x31, 0x2e, 0x31, };\r
+const char http_content_type[15] = \r
+/* "content-type: " */\r
+{0x63, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, };\r
+const char http_texthtml[10] = \r
+/* "text/html" */\r
+{0x74, 0x65, 0x78, 0x74, 0x2f, 0x68, 0x74, 0x6d, 0x6c, };\r
+const char http_location[11] = \r
+/* "location: " */\r
+{0x6c, 0x6f, 0x63, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x3a, 0x20, };\r
+const char http_host[7] = \r
+/* "host: " */\r
+{0x68, 0x6f, 0x73, 0x74, 0x3a, 0x20, };\r
+const char http_crnl[3] = \r
+/* "\r\n" */\r
+{0xd, 0xa, };\r
+const char http_index_html[12] = \r
+/* "/index.html" */\r
+{0x2f, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x68, 0x74, 0x6d, 0x6c, };\r
+const char http_404_html[10] = \r
+/* "/404.html" */\r
+{0x2f, 0x34, 0x30, 0x34, 0x2e, 0x68, 0x74, 0x6d, 0x6c, };\r
+const char http_referer[9] = \r
+/* "Referer:" */\r
+{0x52, 0x65, 0x66, 0x65, 0x72, 0x65, 0x72, 0x3a, };\r
+const char http_header_200[84] = \r
+/* "HTTP/1.0 200 OK\r\nServer: uIP/1.0 http://www.sics.se/~adam/uip/\r\nConnection: close\r\n" */\r
+{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, };\r
+const char http_header_404[91] = \r
+/* "HTTP/1.0 404 Not found\r\nServer: uIP/1.0 http://www.sics.se/~adam/uip/\r\nConnection: close\r\n" */\r
+{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, };\r
+const char http_content_type_plain[29] = \r
+/* "Content-type: text/plain\r\n\r\n" */\r
+{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, };\r
+const char http_content_type_html[28] = \r
+/* "Content-type: text/html\r\n\r\n" */\r
+{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, };\r
+const char http_content_type_css [27] = \r
+/* "Content-type: text/css\r\n\r\n" */\r
+{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, };\r
+const char http_content_type_text[28] = \r
+/* "Content-type: text/text\r\n\r\n" */\r
+{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, };\r
+const char http_content_type_png [28] = \r
+/* "Content-type: image/png\r\n\r\n" */\r
+{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, };\r
+const char http_content_type_gif [28] = \r
+/* "Content-type: image/gif\r\n\r\n" */\r
+{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, };\r
+const char http_content_type_jpg [29] = \r
+/* "Content-type: image/jpeg\r\n\r\n" */\r
+{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, };\r
+const char http_content_type_binary[43] = \r
+/* "Content-type: application/octet-stream\r\n\r\n" */\r
+{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, };\r
+const char http_html[6] = \r
+/* ".html" */\r
+{0x2e, 0x68, 0x74, 0x6d, 0x6c, };\r
+const char http_shtml[7] = \r
+/* ".shtml" */\r
+{0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, };\r
+const char http_htm[5] = \r
+/* ".htm" */\r
+{0x2e, 0x68, 0x74, 0x6d, };\r
+const char http_css[5] = \r
+/* ".css" */\r
+{0x2e, 0x63, 0x73, 0x73, };\r
+const char http_png[5] = \r
+/* ".png" */\r
+{0x2e, 0x70, 0x6e, 0x67, };\r
+const char http_gif[5] = \r
+/* ".gif" */\r
+{0x2e, 0x67, 0x69, 0x66, };\r
+const char http_jpg[5] = \r
+/* ".jpg" */\r
+{0x2e, 0x6a, 0x70, 0x67, };\r
+const char http_text[5] = \r
+/* ".txt" */\r
+{0x2e, 0x74, 0x78, 0x74, };\r
+const char http_txt[5] = \r
+/* ".txt" */\r
+{0x2e, 0x74, 0x78, 0x74, };\r
--- /dev/null
+extern const char http_http[8];\r
+extern const char http_200[5];\r
+extern const char http_301[5];\r
+extern const char http_302[5];\r
+extern const char http_get[5];\r
+extern const char http_10[9];\r
+extern const char http_11[9];\r
+extern const char http_content_type[15];\r
+extern const char http_texthtml[10];\r
+extern const char http_location[11];\r
+extern const char http_host[7];\r
+extern const char http_crnl[3];\r
+extern const char http_index_html[12];\r
+extern const char http_404_html[10];\r
+extern const char http_referer[9];\r
+extern const char http_header_200[84];\r
+extern const char http_header_404[91];\r
+extern const char http_content_type_plain[29];\r
+extern const char http_content_type_html[28];\r
+extern const char http_content_type_css [27];\r
+extern const char http_content_type_text[28];\r
+extern const char http_content_type_png [28];\r
+extern const char http_content_type_gif [28];\r
+extern const char http_content_type_jpg [29];\r
+extern const char http_content_type_binary[43];\r
+extern const char http_html[6];\r
+extern const char http_shtml[7];\r
+extern const char http_htm[5];\r
+extern const char http_css[5];\r
+extern const char http_png[5];\r
+extern const char http_gif[5];\r
+extern const char http_jpg[5];\r
+extern const char http_text[5];\r
+extern const char http_txt[5];\r
--- /dev/null
+/**\r
+ * \addtogroup httpd\r
+ * @{\r
+ */\r
+\r
+/**\r
+ * \file\r
+ * Web server script interface\r
+ * \author\r
+ * Adam Dunkels <adam@sics.se>\r
+ *\r
+ */\r
+\r
+/*\r
+ * Copyright (c) 2001-2006, Adam Dunkels.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without\r
+ * modification, are permitted provided that the following conditions\r
+ * are met:\r
+ * 1. Redistributions of source code must retain the above copyright\r
+ * notice, this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright\r
+ * notice, this list of conditions and the following disclaimer in the\r
+ * documentation and/or other materials provided with the distribution.\r
+ * 3. The name of the author may not be used to endorse or promote\r
+ * products derived from this software without specific prior\r
+ * written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS\r
+ * OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\r
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\r
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY\r
+ * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\r
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE\r
+ * GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\r
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,\r
+ * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING\r
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\r
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\r
+ *\r
+ * This file is part of the uIP TCP/IP stack.\r
+ *\r
+ * $Id: httpd-cgi.c,v 1.2 2006/06/11 21:46:37 adam Exp $\r
+ *\r
+ */\r
+\r
+#include "uip.h"\r
+#include "psock.h"\r
+#include "httpd.h"\r
+#include "httpd-cgi.h"\r
+#include "httpd-fs.h"\r
+\r
+#include <stdio.h>\r
+#include <string.h>\r
+\r
+HTTPD_CGI_CALL(file, "file-stats", file_stats);\r
+HTTPD_CGI_CALL(tcp, "tcp-connections", tcp_stats);\r
+HTTPD_CGI_CALL(net, "net-stats", net_stats);\r
+HTTPD_CGI_CALL(rtos, "rtos-stats", rtos_stats );\r
+HTTPD_CGI_CALL(run, "run-time", run_time );\r
+HTTPD_CGI_CALL(io, "led-io", led_io );\r
+\r
+\r
+static const struct httpd_cgi_call *calls[] = { &file, &tcp, &net, &rtos, &run, &io, NULL };\r
+\r
+/*---------------------------------------------------------------------------*/\r
+static\r
+PT_THREAD(nullfunction(struct httpd_state *s, char *ptr))\r
+{\r
+ PSOCK_BEGIN(&s->sout);\r
+ ( void ) ptr;\r
+ PSOCK_END(&s->sout);\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+httpd_cgifunction\r
+httpd_cgi(char *name)\r
+{\r
+ const struct httpd_cgi_call **f;\r
+\r
+ /* Find the matching name in the table, return the function. */\r
+ for(f = calls; *f != NULL; ++f) {\r
+ if(strncmp((*f)->name, name, strlen((*f)->name)) == 0) {\r
+ return (*f)->function;\r
+ }\r
+ }\r
+ return nullfunction;\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+static unsigned short\r
+generate_file_stats(void *arg)\r
+{\r
+ char *f = (char *)arg;\r
+ return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE, "%5u", httpd_fs_count(f));\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+static\r
+PT_THREAD(file_stats(struct httpd_state *s, char *ptr))\r
+{\r
+ PSOCK_BEGIN(&s->sout);\r
+\r
+ PSOCK_GENERATOR_SEND(&s->sout, generate_file_stats, strchr(ptr, ' ') + 1);\r
+\r
+ PSOCK_END(&s->sout);\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+static const char closed[] = /* "CLOSED",*/\r
+{0x43, 0x4c, 0x4f, 0x53, 0x45, 0x44, 0};\r
+static const char syn_rcvd[] = /* "SYN-RCVD",*/\r
+{0x53, 0x59, 0x4e, 0x2d, 0x52, 0x43, 0x56,\r
+ 0x44, 0};\r
+static const char syn_sent[] = /* "SYN-SENT",*/\r
+{0x53, 0x59, 0x4e, 0x2d, 0x53, 0x45, 0x4e,\r
+ 0x54, 0};\r
+static const char established[] = /* "ESTABLISHED",*/\r
+{0x45, 0x53, 0x54, 0x41, 0x42, 0x4c, 0x49, 0x53, 0x48,\r
+ 0x45, 0x44, 0};\r
+static const char fin_wait_1[] = /* "FIN-WAIT-1",*/\r
+{0x46, 0x49, 0x4e, 0x2d, 0x57, 0x41, 0x49,\r
+ 0x54, 0x2d, 0x31, 0};\r
+static const char fin_wait_2[] = /* "FIN-WAIT-2",*/\r
+{0x46, 0x49, 0x4e, 0x2d, 0x57, 0x41, 0x49,\r
+ 0x54, 0x2d, 0x32, 0};\r
+static const char closing[] = /* "CLOSING",*/\r
+{0x43, 0x4c, 0x4f, 0x53, 0x49,\r
+ 0x4e, 0x47, 0};\r
+static const char time_wait[] = /* "TIME-WAIT,"*/\r
+{0x54, 0x49, 0x4d, 0x45, 0x2d, 0x57, 0x41,\r
+ 0x49, 0x54, 0};\r
+static const char last_ack[] = /* "LAST-ACK"*/\r
+{0x4c, 0x41, 0x53, 0x54, 0x2d, 0x41, 0x43,\r
+ 0x4b, 0};\r
+\r
+static const char *states[] = {\r
+ closed,\r
+ syn_rcvd,\r
+ syn_sent,\r
+ established,\r
+ fin_wait_1,\r
+ fin_wait_2,\r
+ closing,\r
+ time_wait,\r
+ last_ack};\r
+\r
+\r
+static unsigned short\r
+generate_tcp_stats(void *arg)\r
+{\r
+ struct uip_conn *conn;\r
+ struct httpd_state *s = (struct httpd_state *)arg;\r
+\r
+ conn = &uip_conns[s->count];\r
+ return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE,\r
+ "<tr><td>%d</td><td>%u.%u.%u.%u:%u</td><td>%s</td><td>%u</td><td>%u</td><td>%c %c</td></tr>\r\n",\r
+ htons(conn->lport),\r
+ htons(conn->ripaddr[0]) >> 8,\r
+ htons(conn->ripaddr[0]) & 0xff,\r
+ htons(conn->ripaddr[1]) >> 8,\r
+ htons(conn->ripaddr[1]) & 0xff,\r
+ htons(conn->rport),\r
+ states[conn->tcpstateflags & UIP_TS_MASK],\r
+ conn->nrtx,\r
+ conn->timer,\r
+ (uip_outstanding(conn))? '*':' ',\r
+ (uip_stopped(conn))? '!':' ');\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+static\r
+PT_THREAD(tcp_stats(struct httpd_state *s, char *ptr))\r
+{\r
+\r
+ PSOCK_BEGIN(&s->sout);\r
+ ( void ) ptr;\r
+ for(s->count = 0; s->count < UIP_CONNS; ++s->count) {\r
+ if((uip_conns[s->count].tcpstateflags & UIP_TS_MASK) != UIP_CLOSED) {\r
+ PSOCK_GENERATOR_SEND(&s->sout, generate_tcp_stats, s);\r
+ }\r
+ }\r
+\r
+ PSOCK_END(&s->sout);\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+static unsigned short\r
+generate_net_stats(void *arg)\r
+{\r
+ struct httpd_state *s = (struct httpd_state *)arg;\r
+ return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE,\r
+ "%5u\n", ((uip_stats_t *)&uip_stat)[s->count]);\r
+}\r
+\r
+static\r
+PT_THREAD(net_stats(struct httpd_state *s, char *ptr))\r
+{\r
+ PSOCK_BEGIN(&s->sout);\r
+\r
+ ( void ) ptr;\r
+#if UIP_STATISTICS\r
+\r
+ for(s->count = 0; s->count < sizeof(uip_stat) / sizeof(uip_stats_t);\r
+ ++s->count) {\r
+ PSOCK_GENERATOR_SEND(&s->sout, generate_net_stats, s);\r
+ }\r
+\r
+#endif /* UIP_STATISTICS */\r
+\r
+ PSOCK_END(&s->sout);\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+\r
+extern void vTaskList( signed char *pcWriteBuffer );\r
+static char cCountBuf[ 32 ];\r
+long lRefreshCount = 0;\r
+static unsigned short\r
+generate_rtos_stats(void *arg)\r
+{\r
+ ( void ) arg;\r
+ lRefreshCount++;\r
+ sprintf( cCountBuf, "<p><br>Refresh count = %d", (int)lRefreshCount );\r
+ vTaskList( uip_appdata );\r
+ strcat( uip_appdata, cCountBuf );\r
+\r
+ return strlen( uip_appdata );\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+\r
+\r
+static\r
+PT_THREAD(rtos_stats(struct httpd_state *s, char *ptr))\r
+{\r
+ PSOCK_BEGIN(&s->sout);\r
+ ( void ) ptr;\r
+ PSOCK_GENERATOR_SEND(&s->sout, generate_rtos_stats, NULL);\r
+ PSOCK_END(&s->sout);\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+\r
+char *pcStatus;\r
+unsigned long ulString;\r
+\r
+static unsigned short generate_io_state( void *arg )\r
+{\r
+extern long lParTestGetLEDState( unsigned long ulLED );\r
+\r
+ ( void ) arg;\r
+\r
+ if( lParTestGetLEDState( 1 << 7 ) == 0 )\r
+ {\r
+ pcStatus = "";\r
+ }\r
+ else\r
+ {\r
+ pcStatus = "checked";\r
+ }\r
+\r
+ sprintf( uip_appdata,\r
+ "<input type=\"checkbox\" name=\"LED0\" value=\"1\" %s>LED 7"\\r
+ "<p>"\\r
+ "<input type=\"text\" name=\"LCD\" value=\"Enter LCD text\" size=\"16\">",\r
+ pcStatus );\r
+\r
+ return strlen( uip_appdata );\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+\r
+extern void vTaskGetRunTimeStats( signed char *pcWriteBuffer );\r
+static unsigned short\r
+generate_runtime_stats(void *arg)\r
+{\r
+ ( void ) arg;\r
+ lRefreshCount++;\r
+ sprintf( cCountBuf, "<p><br>Refresh count = %d", (int)lRefreshCount );\r
+ vTaskGetRunTimeStats( uip_appdata );\r
+ strcat( uip_appdata, cCountBuf );\r
+\r
+ return strlen( uip_appdata );\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+\r
+\r
+static\r
+PT_THREAD(run_time(struct httpd_state *s, char *ptr))\r
+{\r
+ PSOCK_BEGIN(&s->sout);\r
+ ( void ) ptr;\r
+ PSOCK_GENERATOR_SEND(&s->sout, generate_runtime_stats, NULL);\r
+ PSOCK_END(&s->sout);\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+\r
+\r
+static PT_THREAD(led_io(struct httpd_state *s, char *ptr))\r
+{\r
+ PSOCK_BEGIN(&s->sout);\r
+ ( void ) ptr;\r
+ PSOCK_GENERATOR_SEND(&s->sout, generate_io_state, NULL);\r
+ PSOCK_END(&s->sout);\r
+}\r
+\r
+/** @} */\r
+\r
+\r
+\r
+\r
+\r
+\r
--- /dev/null
+/**\r
+ * \addtogroup httpd\r
+ * @{\r
+ */\r
+\r
+/**\r
+ * \file\r
+ * Web server script interface header file\r
+ * \author\r
+ * Adam Dunkels <adam@sics.se>\r
+ *\r
+ */\r
+\r
+\r
+\r
+/*\r
+ * Copyright (c) 2001, Adam Dunkels.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without\r
+ * modification, are permitted provided that the following conditions\r
+ * are met:\r
+ * 1. Redistributions of source code must retain the above copyright\r
+ * notice, this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright\r
+ * notice, this list of conditions and the following disclaimer in the\r
+ * documentation and/or other materials provided with the distribution.\r
+ * 3. The name of the author may not be used to endorse or promote\r
+ * products derived from this software without specific prior\r
+ * written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS\r
+ * OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\r
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\r
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY\r
+ * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\r
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE\r
+ * GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\r
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,\r
+ * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING\r
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\r
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\r
+ *\r
+ * This file is part of the uIP TCP/IP stack.\r
+ *\r
+ * $Id: httpd-cgi.h,v 1.2 2006/06/11 21:46:38 adam Exp $\r
+ *\r
+ */\r
+\r
+#ifndef __HTTPD_CGI_H__\r
+#define __HTTPD_CGI_H__\r
+\r
+#include "psock.h"\r
+#include "httpd.h"\r
+\r
+typedef PT_THREAD((* httpd_cgifunction)(struct httpd_state *, char *));\r
+\r
+httpd_cgifunction httpd_cgi(char *name);\r
+\r
+struct httpd_cgi_call {\r
+ const char *name;\r
+ const httpd_cgifunction function;\r
+};\r
+\r
+/**\r
+ * \brief HTTPD CGI function declaration\r
+ * \param name The C variable name of the function\r
+ * \param str The string name of the function, used in the script file\r
+ * \param function A pointer to the function that implements it\r
+ *\r
+ * This macro is used for declaring a HTTPD CGI\r
+ * function. This function is then added to the list of\r
+ * HTTPD CGI functions with the httpd_cgi_add() function.\r
+ *\r
+ * \hideinitializer\r
+ */\r
+#define HTTPD_CGI_CALL(name, str, function) \\r
+static PT_THREAD(function(struct httpd_state *, char *)); \\r
+static const struct httpd_cgi_call name = {str, function}\r
+\r
+void httpd_cgi_init(void);\r
+#endif /* __HTTPD_CGI_H__ */\r
+\r
+/** @} */\r
--- /dev/null
+/*\r
+ * Copyright (c) 2001, Swedish Institute of Computer Science.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without\r
+ * modification, are permitted provided that the following conditions\r
+ * are met:\r
+ * 1. Redistributions of source code must retain the above copyright\r
+ * notice, this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright\r
+ * notice, this list of conditions and the following disclaimer in the\r
+ * documentation and/or other materials provided with the distribution.\r
+ * 3. Neither the name of the Institute nor the names of its contributors\r
+ * may be used to endorse or promote products derived from this software\r
+ * without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND\r
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\r
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\r
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE\r
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\r
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS\r
+ * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)\r
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\r
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY\r
+ * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF\r
+ * SUCH DAMAGE.\r
+ *\r
+ * This file is part of the lwIP TCP/IP stack.\r
+ *\r
+ * Author: Adam Dunkels <adam@sics.se>\r
+ *\r
+ * $Id: httpd-fs.c,v 1.1 2006/06/07 09:13:08 adam Exp $\r
+ */\r
+\r
+#include "httpd.h"\r
+#include "httpd-fs.h"\r
+#include "httpd-fsdata.h"\r
+\r
+#ifndef NULL\r
+#define NULL 0\r
+#endif /* NULL */\r
+\r
+#include "httpd-fsdata.c"\r
+\r
+#if HTTPD_FS_STATISTICS\r
+static u16_t count[HTTPD_FS_NUMFILES];\r
+#endif /* HTTPD_FS_STATISTICS */\r
+\r
+/*-----------------------------------------------------------------------------------*/\r
+static u8_t\r
+httpd_fs_strcmp(const char *str1, const char *str2)\r
+{\r
+ u8_t i;\r
+ i = 0;\r
+ loop:\r
+\r
+ if(str2[i] == 0 ||\r
+ str1[i] == '\r' ||\r
+ str1[i] == '\n') {\r
+ return 0;\r
+ }\r
+\r
+ if(str1[i] != str2[i]) {\r
+ return 1;\r
+ }\r
+\r
+\r
+ ++i;\r
+ goto loop;\r
+}\r
+/*-----------------------------------------------------------------------------------*/\r
+int\r
+httpd_fs_open(const char *name, struct httpd_fs_file *file)\r
+{\r
+#if HTTPD_FS_STATISTICS\r
+ u16_t i = 0;\r
+#endif /* HTTPD_FS_STATISTICS */\r
+ struct httpd_fsdata_file_noconst *f;\r
+\r
+ for(f = (struct httpd_fsdata_file_noconst *)HTTPD_FS_ROOT;\r
+ f != NULL;\r
+ f = (struct httpd_fsdata_file_noconst *)f->next) {\r
+\r
+ if(httpd_fs_strcmp(name, f->name) == 0) {\r
+ file->data = f->data;\r
+ file->len = f->len;\r
+#if HTTPD_FS_STATISTICS\r
+ ++count[i];\r
+#endif /* HTTPD_FS_STATISTICS */\r
+ return 1;\r
+ }\r
+#if HTTPD_FS_STATISTICS\r
+ ++i;\r
+#endif /* HTTPD_FS_STATISTICS */\r
+\r
+ }\r
+ return 0;\r
+}\r
+/*-----------------------------------------------------------------------------------*/\r
+void\r
+httpd_fs_init(void)\r
+{\r
+#if HTTPD_FS_STATISTICS\r
+ u16_t i;\r
+ for(i = 0; i < HTTPD_FS_NUMFILES; i++) {\r
+ count[i] = 0;\r
+ }\r
+#endif /* HTTPD_FS_STATISTICS */\r
+}\r
+/*-----------------------------------------------------------------------------------*/\r
+#if HTTPD_FS_STATISTICS\r
+u16_t httpd_fs_count\r
+(char *name)\r
+{\r
+ struct httpd_fsdata_file_noconst *f;\r
+ u16_t i;\r
+\r
+ i = 0;\r
+ for(f = (struct httpd_fsdata_file_noconst *)HTTPD_FS_ROOT;\r
+ f != NULL;\r
+ f = (struct httpd_fsdata_file_noconst *)f->next) {\r
+\r
+ if(httpd_fs_strcmp(name, f->name) == 0) {\r
+ return count[i];\r
+ }\r
+ ++i;\r
+ }\r
+ return 0;\r
+}\r
+#endif /* HTTPD_FS_STATISTICS */\r
+/*-----------------------------------------------------------------------------------*/\r
--- /dev/null
+/*\r
+ * Copyright (c) 2001, Swedish Institute of Computer Science.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without\r
+ * modification, are permitted provided that the following conditions\r
+ * are met:\r
+ * 1. Redistributions of source code must retain the above copyright\r
+ * notice, this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright\r
+ * notice, this list of conditions and the following disclaimer in the\r
+ * documentation and/or other materials provided with the distribution.\r
+ * 3. Neither the name of the Institute nor the names of its contributors\r
+ * may be used to endorse or promote products derived from this software\r
+ * without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND\r
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\r
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\r
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE\r
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\r
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS\r
+ * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)\r
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\r
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY\r
+ * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF\r
+ * SUCH DAMAGE.\r
+ *\r
+ * This file is part of the lwIP TCP/IP stack.\r
+ *\r
+ * Author: Adam Dunkels <adam@sics.se>\r
+ *\r
+ * $Id: httpd-fs.h,v 1.1 2006/06/07 09:13:08 adam Exp $\r
+ */\r
+#ifndef __HTTPD_FS_H__\r
+#define __HTTPD_FS_H__\r
+\r
+#define HTTPD_FS_STATISTICS 1\r
+\r
+struct httpd_fs_file {\r
+ char *data;\r
+ int len;\r
+};\r
+\r
+/* file must be allocated by caller and will be filled in\r
+ by the function. */\r
+int httpd_fs_open(const char *name, struct httpd_fs_file *file);\r
+\r
+#ifdef HTTPD_FS_STATISTICS\r
+#if HTTPD_FS_STATISTICS == 1\r
+u16_t httpd_fs_count(char *name);\r
+#endif /* HTTPD_FS_STATISTICS */\r
+#endif /* HTTPD_FS_STATISTICS */\r
+\r
+void httpd_fs_init(void);\r
+\r
+#endif /* __HTTPD_FS_H__ */\r
--- /dev/null
+<html>\r
+ <body bgcolor="white">\r
+ <center>\r
+ <h1>404 - file not found</h1>\r
+ <h3>Go <a href="/">here</a> instead.</h3>\r
+ </center>\r
+ </body>\r
+</html>
\ No newline at end of file
--- /dev/null
+<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN" "http://www.w3.org/TR/html4/loose.dtd">\r
+<html>\r
+ <head>\r
+ <title>FreeRTOS.org uIP WEB server demo</title>\r
+ </head>\r
+ <BODY onLoad="window.setTimeout("location.href='index.shtml'",100)">\r
+<font face="arial">\r
+Loading index.shtml. Click <a href="index.shtml">here</a> if not automatically redirected.\r
+</font>\r
+</font>\r
+</body>\r
+</html>\r
+\r
--- /dev/null
+<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN" "http://www.w3.org/TR/html4/loose.dtd">\r
+<html>\r
+ <head>\r
+ <title>FreeRTOS.org uIP WEB server demo</title>\r
+ </head>\r
+ <BODY onLoad="window.setTimeout("location.href='index.shtml'",2000)">\r
+<font face="arial">\r
+<a href="index.shtml">Task Stats</a> <b>|</b> <a href="runtime.shtml">Run Time Stats</a> <b>|</b> <a href="stats.shtml">TCP Stats</a> <b>|</b> <a href="tcp.shtml">Connections</a> <b>|</b> <a href="http://www.freertos.org/">FreeRTOS.org Homepage</a> <b>|</b> <a href="io.shtml">IO</a>\r
+<br><p>\r
+<hr>\r
+<br><p>\r
+<h2>Task statistics</h2>\r
+Page will refresh every 2 seconds.<p>\r
+<font face="courier"><pre>Task State Priority Stack #<br>************************************************<br>\r
+%! rtos-stats\r
+</pre></font>\r
+</font>\r
+</body>\r
+</html>\r
+\r
--- /dev/null
+<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN" "http://www.w3.org/TR/html4/loose.dtd">\r
+<html>\r
+ <head>\r
+ <title>FreeRTOS.org uIP WEB server demo</title>\r
+ </head>\r
+ <BODY>\r
+<font face="arial">\r
+<a href="index.shtml">Task Stats</a> <b>|</b> <a href="runtime.shtml">Run Time Stats</a> <b>|</b> <a href="stats.shtml">TCP Stats</a> <b>|</b> <a href="tcp.shtml">Connections</a> <b>|</b> <a href="http://www.freertos.org/">FreeRTOS.org Homepage</a> <b>|</b> <a href="io.shtml">IO</a>\r
+<br><p>\r
+<hr>\r
+<b>LED and LCD IO</b><br>\r
+\r
+<p>\r
+\r
+Use the check box to turn on or off the LED, enter text to display on the OLED display, then click "Update IO".\r
+\r
+\r
+<p>\r
+<form name="aForm" action="/io.shtml" method="get">\r
+%! led-io\r
+<p>\r
+<input type="submit" value="Update IO">\r
+</form>\r
+<br><p>\r
+</font>\r
+</body>\r
+</html>\r
+\r
--- /dev/null
+<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN" "http://www.w3.org/TR/html4/loose.dtd">\r
+<html>\r
+ <head>\r
+ <title>FreeRTOS.org uIP WEB server demo</title>\r
+ </head>\r
+ <BODY onLoad="window.setTimeout("location.href='runtime.shtml'",2000)">\r
+<font face="arial">\r
+<a href="index.shtml">Task Stats</a> <b>|</b> <a href="runtime.shtml">Run Time Stats</a> <b>|</b> <a href="stats.shtml">TCP Stats</a> <b>|</b> <a href="tcp.shtml">Connections</a> <b>|</b> <a href="http://www.freertos.org/">FreeRTOS.org Homepage</a> <b>|</b> <a href="io.shtml">IO</a>\r
+<br><p>\r
+<hr>\r
+<br><p>\r
+<h2>Run-time statistics</h2>\r
+Page will refresh every 2 seconds.<p>\r
+<font face="courier"><pre>Task Abs Time % Time<br>****************************************<br>\r
+%! run-time\r
+</pre></font>\r
+</font>\r
+</body>\r
+</html>\r
+\r
--- /dev/null
+<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN" "http://www.w3.org/TR/html4/loose.dtd">\r
+<html>\r
+ <head>\r
+ <title>FreeRTOS.org uIP WEB server demo</title>\r
+ </head>\r
+ <BODY>\r
+<font face="arial">\r
+<a href="index.shtml">Task Stats</a> <b>|</b> <a href="runtime.shtml">Run Time Stats</a> <b>|</b> <a href="stats.shtml">TCP Stats</a> <b>|</b> <a href="tcp.shtml">Connections</a> <b>|</b> <a href="http://www.freertos.org/">FreeRTOS.org Homepage</a> <b>|</b> <a href="io.shtml">IO</a>\r
+<br><p>\r
+<hr>\r
+<br><p>\r
+<h2>Network statistics</h2>\r
+<table width="300" border="0">\r
+<tr><td align="left"><font face="courier"><pre>\r
+IP Packets dropped\r
+ Packets received\r
+ Packets sent\r
+IP errors IP version/header length\r
+ IP length, high byte\r
+ IP length, low byte\r
+ IP fragments\r
+ Header checksum\r
+ Wrong protocol\r
+ICMP Packets dropped\r
+ Packets received\r
+ Packets sent\r
+ Type errors\r
+TCP Packets dropped\r
+ Packets received\r
+ Packets sent\r
+ Checksum errors\r
+ Data packets without ACKs\r
+ Resets\r
+ Retransmissions\r
+ No connection avaliable\r
+ Connection attempts to closed ports\r
+</pre></font></td><td><pre>%! net-stats\r
+</pre></table>\r
+</font>\r
+</body>\r
+</html>\r
--- /dev/null
+<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN" "http://www.w3.org/TR/html4/loose.dtd">\r
+<html>\r
+ <head>\r
+ <title>FreeRTOS.org uIP WEB server demo</title>\r
+ </head>\r
+ <BODY>\r
+<font face="arial">\r
+<a href="index.shtml">Task Stats</a> <b>|</b> <a href="runtime.shtml">Run Time Stats</a> <b>|</b> <a href="stats.shtml">TCP Stats</a> <b>|</b> <a href="tcp.shtml">Connections</a> <b>|</b> <a href="http://www.freertos.org/">FreeRTOS.org Homepage</a> <b>|</b> <a href="io.shtml">IO</a>\r
+<br><p>\r
+<hr>\r
+<br>\r
+<h2>Network connections</h2>\r
+<p>\r
+<table>\r
+<tr><th>Local</th><th>Remote</th><th>State</th><th>Retransmissions</th><th>Timer</th><th>Flags</th></tr>\r
+%! tcp-connections\r
+</pre></font>\r
+</font>\r
+</body>\r
+</html>\r
+\r
--- /dev/null
+static const char data_404_html[] = {\r
+ /* /404.html */\r
+ 0x2f, 0x34, 0x30, 0x34, 0x2e, 0x68, 0x74, 0x6d, 0x6c, 0,\r
+ 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, 0x20, 0x20, 0x3c, \r
+ 0x62, 0x6f, 0x64, 0x79, 0x20, 0x62, 0x67, 0x63, 0x6f, 0x6c, \r
+ 0x6f, 0x72, 0x3d, 0x22, 0x77, 0x68, 0x69, 0x74, 0x65, 0x22, \r
+ 0x3e, 0xa, 0x20, 0x20, 0x20, 0x20, 0x3c, 0x63, 0x65, 0x6e, \r
+ 0x74, 0x65, 0x72, 0x3e, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x3c, 0x68, 0x31, 0x3e, 0x34, 0x30, 0x34, 0x20, 0x2d, \r
+ 0x20, 0x66, 0x69, 0x6c, 0x65, 0x20, 0x6e, 0x6f, 0x74, 0x20, \r
+ 0x66, 0x6f, 0x75, 0x6e, 0x64, 0x3c, 0x2f, 0x68, 0x31, 0x3e, \r
+ 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x3c, 0x68, 0x33, \r
+ 0x3e, 0x47, 0x6f, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, \r
+ 0x66, 0x3d, 0x22, 0x2f, 0x22, 0x3e, 0x68, 0x65, 0x72, 0x65, \r
+ 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x69, 0x6e, 0x73, 0x74, 0x65, \r
+ 0x61, 0x64, 0x2e, 0x3c, 0x2f, 0x68, 0x33, 0x3e, 0xa, 0x20, \r
+ 0x20, 0x20, 0x20, 0x3c, 0x2f, 0x63, 0x65, 0x6e, 0x74, 0x65, \r
+ 0x72, 0x3e, 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x62, 0x6f, 0x64, \r
+ 0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x3e, \r
+0};\r
+\r
+static const char data_index_html[] = {\r
+ /* /index.html */\r
+ 0x2f, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x68, 0x74, 0x6d, 0x6c, 0,\r
+ 0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20, \r
+ 0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49, \r
+ 0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f, \r
+ 0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20, \r
+ 0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73, \r
+ 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45, \r
+ 0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, \r
+ 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72, \r
+ 0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34, \r
+ 0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64, \r
+ 0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, \r
+ 0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20, \r
+ 0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, \r
+ 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, \r
+ 0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42, \r
+ 0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65, \r
+ 0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, \r
+ 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e, \r
+ 0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x20, 0x6f, \r
+ 0x6e, 0x4c, 0x6f, 0x61, 0x64, 0x3d, 0x22, 0x77, 0x69, 0x6e, \r
+ 0x64, 0x6f, 0x77, 0x2e, 0x73, 0x65, 0x74, 0x54, 0x69, 0x6d, \r
+ 0x65, 0x6f, 0x75, 0x74, 0x28, 0x26, 0x71, 0x75, 0x6f, 0x74, \r
+ 0x3b, 0x6c, 0x6f, 0x63, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x2e, \r
+ 0x68, 0x72, 0x65, 0x66, 0x3d, 0x27, 0x69, 0x6e, 0x64, 0x65, \r
+ 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x27, 0x26, 0x71, \r
+ 0x75, 0x6f, 0x74, 0x3b, 0x2c, 0x31, 0x30, 0x30, 0x29, 0x22, \r
+ 0x3e, 0xa, 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61, \r
+ 0x63, 0x65, 0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c, 0x22, \r
+ 0x3e, 0xa, 0x4c, 0x6f, 0x61, 0x64, 0x69, 0x6e, 0x67, 0x20, \r
+ 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, \r
+ 0x6c, 0x2e, 0x20, 0x20, 0x43, 0x6c, 0x69, 0x63, 0x6b, 0x20, \r
+ 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, \r
+ 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, \r
+ 0x22, 0x3e, 0x68, 0x65, 0x72, 0x65, 0x3c, 0x2f, 0x61, 0x3e, \r
+ 0x20, 0x69, 0x66, 0x20, 0x6e, 0x6f, 0x74, 0x20, 0x61, 0x75, \r
+ 0x74, 0x6f, 0x6d, 0x61, 0x74, 0x69, 0x63, 0x61, 0x6c, 0x6c, \r
+ 0x79, 0x20, 0x72, 0x65, 0x64, 0x69, 0x72, 0x65, 0x63, 0x74, \r
+ 0x65, 0x64, 0x2e, 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, \r
+ 0x3e, 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, \r
+ 0x3c, 0x2f, 0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f, \r
+ 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, 0xa, 0};\r
+\r
+static const char data_index_shtml[] = {\r
+ /* /index.shtml */\r
+ 0x2f, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0,\r
+ 0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20, \r
+ 0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49, \r
+ 0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f, \r
+ 0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20, \r
+ 0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73, \r
+ 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45, \r
+ 0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, \r
+ 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72, \r
+ 0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34, \r
+ 0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64, \r
+ 0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, \r
+ 0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20, \r
+ 0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, \r
+ 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, \r
+ 0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42, \r
+ 0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65, \r
+ 0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, \r
+ 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e, \r
+ 0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x20, 0x6f, \r
+ 0x6e, 0x4c, 0x6f, 0x61, 0x64, 0x3d, 0x22, 0x77, 0x69, 0x6e, \r
+ 0x64, 0x6f, 0x77, 0x2e, 0x73, 0x65, 0x74, 0x54, 0x69, 0x6d, \r
+ 0x65, 0x6f, 0x75, 0x74, 0x28, 0x26, 0x71, 0x75, 0x6f, 0x74, \r
+ 0x3b, 0x6c, 0x6f, 0x63, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x2e, \r
+ 0x68, 0x72, 0x65, 0x66, 0x3d, 0x27, 0x69, 0x6e, 0x64, 0x65, \r
+ 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x27, 0x26, 0x71, \r
+ 0x75, 0x6f, 0x74, 0x3b, 0x2c, 0x32, 0x30, 0x30, 0x30, 0x29, \r
+ 0x22, 0x3e, 0xa, 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, \r
+ 0x61, 0x63, 0x65, 0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c, \r
+ 0x22, 0x3e, 0xa, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, \r
+ 0x3d, 0x22, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, \r
+ 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, \r
+ 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, \r
+ 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, \r
+ 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x72, 0x75, \r
+ 0x6e, 0x74, 0x69, 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, \r
+ 0x6c, 0x22, 0x3e, 0x52, 0x75, 0x6e, 0x20, 0x54, 0x69, 0x6d, \r
+ 0x65, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, \r
+ 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, \r
+ 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, \r
+ 0x73, 0x74, 0x61, 0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d, \r
+ 0x6c, 0x22, 0x3e, 0x54, 0x43, 0x50, 0x20, 0x53, 0x74, 0x61, \r
+ 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, \r
+ 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, \r
+ 0x72, 0x65, 0x66, 0x3d, 0x22, 0x74, 0x63, 0x70, 0x2e, 0x73, \r
+ 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x43, 0x6f, 0x6e, 0x6e, \r
+ 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x61, \r
+ 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, \r
+ 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, \r
+ 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, \r
+ 0x2e, 0x66, 0x72, 0x65, 0x65, 0x72, 0x74, 0x6f, 0x73, 0x2e, \r
+ 0x6f, 0x72, 0x67, 0x2f, 0x22, 0x3e, 0x46, 0x72, 0x65, 0x65, \r
+ 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, 0x72, 0x67, 0x20, 0x48, \r
+ 0x6f, 0x6d, 0x65, 0x70, 0x61, 0x67, 0x65, 0x3c, 0x2f, 0x61, \r
+ 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, \r
+ 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, \r
+ 0x69, 0x6f, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, \r
+ 0x49, 0x4f, 0x3c, 0x2f, 0x61, 0x3e, 0xa, 0x3c, 0x62, 0x72, \r
+ 0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x68, 0x72, 0x3e, 0xa, \r
+ 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x68, \r
+ 0x32, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x73, 0x74, 0x61, \r
+ 0x74, 0x69, 0x73, 0x74, 0x69, 0x63, 0x73, 0x3c, 0x2f, 0x68, \r
+ 0x32, 0x3e, 0xa, 0x50, 0x61, 0x67, 0x65, 0x20, 0x77, 0x69, \r
+ 0x6c, 0x6c, 0x20, 0x72, 0x65, 0x66, 0x72, 0x65, 0x73, 0x68, \r
+ 0x20, 0x65, 0x76, 0x65, 0x72, 0x79, 0x20, 0x32, 0x20, 0x73, \r
+ 0x65, 0x63, 0x6f, 0x6e, 0x64, 0x73, 0x2e, 0x3c, 0x70, 0x3e, \r
+ 0xa, 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61, 0x63, \r
+ 0x65, 0x3d, 0x22, 0x63, 0x6f, 0x75, 0x72, 0x69, 0x65, 0x72, \r
+ 0x22, 0x3e, 0x3c, 0x70, 0x72, 0x65, 0x3e, 0x54, 0x61, 0x73, \r
+ 0x6b, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x53, 0x74, 0x61, 0x74, 0x65, 0x20, 0x20, 0x50, 0x72, \r
+ 0x69, 0x6f, 0x72, 0x69, 0x74, 0x79, 0x20, 0x20, 0x53, 0x74, \r
+ 0x61, 0x63, 0x6b, 0x9, 0x23, 0x3c, 0x62, 0x72, 0x3e, 0x2a, \r
+ 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, \r
+ 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, \r
+ 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, \r
+ 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, \r
+ 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x3c, 0x62, 0x72, \r
+ 0x3e, 0xa, 0x25, 0x21, 0x20, 0x72, 0x74, 0x6f, 0x73, 0x2d, \r
+ 0x73, 0x74, 0x61, 0x74, 0x73, 0xa, 0x3c, 0x2f, 0x70, 0x72, \r
+ 0x65, 0x3e, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, \r
+ 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, 0x3c, 0x2f, \r
+ 0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68, 0x74, \r
+ 0x6d, 0x6c, 0x3e, 0xa, 0xa, 0};\r
+\r
+static const char data_io_shtml[] = {\r
+ /* /io.shtml */\r
+ 0x2f, 0x69, 0x6f, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0,\r
+ 0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20, \r
+ 0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49, \r
+ 0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f, \r
+ 0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20, \r
+ 0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73, \r
+ 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45, \r
+ 0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, \r
+ 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72, \r
+ 0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34, \r
+ 0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64, \r
+ 0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, \r
+ 0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20, \r
+ 0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, \r
+ 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, \r
+ 0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42, \r
+ 0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65, \r
+ 0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, \r
+ 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e, \r
+ 0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x3e, 0xa, \r
+ 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61, 0x63, 0x65, \r
+ 0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c, 0x22, 0x3e, 0xa, \r
+ 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, \r
+ 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, \r
+ 0x22, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x53, 0x74, 0x61, \r
+ 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, \r
+ 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, \r
+ 0x72, 0x65, 0x66, 0x3d, 0x22, 0x72, 0x75, 0x6e, 0x74, 0x69, \r
+ 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, \r
+ 0x52, 0x75, 0x6e, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x20, 0x53, \r
+ 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, \r
+ 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, \r
+ 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x73, 0x74, 0x61, \r
+ 0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, \r
+ 0x54, 0x43, 0x50, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, \r
+ 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, \r
+ 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, \r
+ 0x3d, 0x22, 0x74, 0x63, 0x70, 0x2e, 0x73, 0x68, 0x74, 0x6d, \r
+ 0x6c, 0x22, 0x3e, 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, \r
+ 0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, \r
+ 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, \r
+ 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x68, 0x74, 0x74, \r
+ 0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x66, 0x72, \r
+ 0x65, 0x65, 0x72, 0x74, 0x6f, 0x73, 0x2e, 0x6f, 0x72, 0x67, \r
+ 0x2f, 0x22, 0x3e, 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, \r
+ 0x53, 0x2e, 0x6f, 0x72, 0x67, 0x20, 0x48, 0x6f, 0x6d, 0x65, \r
+ 0x70, 0x61, 0x67, 0x65, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, \r
+ 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, \r
+ 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, 0x6f, 0x2e, \r
+ 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x49, 0x4f, 0x3c, \r
+ 0x2f, 0x61, 0x3e, 0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, \r
+ 0x3e, 0xa, 0x3c, 0x68, 0x72, 0x3e, 0xa, 0x3c, 0x62, 0x3e, \r
+ 0x4c, 0x45, 0x44, 0x20, 0x61, 0x6e, 0x64, 0x20, 0x4c, 0x43, \r
+ 0x44, 0x20, 0x49, 0x4f, 0x3c, 0x2f, 0x62, 0x3e, 0x3c, 0x62, \r
+ 0x72, 0x3e, 0xa, 0xa, 0x3c, 0x70, 0x3e, 0xa, 0xa, 0x55, \r
+ 0x73, 0x65, 0x20, 0x74, 0x68, 0x65, 0x20, 0x63, 0x68, 0x65, \r
+ 0x63, 0x6b, 0x20, 0x62, 0x6f, 0x78, 0x20, 0x74, 0x6f, 0x20, \r
+ 0x74, 0x75, 0x72, 0x6e, 0x20, 0x6f, 0x6e, 0x20, 0x6f, 0x72, \r
+ 0x20, 0x6f, 0x66, 0x66, 0x20, 0x74, 0x68, 0x65, 0x20, 0x4c, \r
+ 0x45, 0x44, 0x2c, 0x20, 0x65, 0x6e, 0x74, 0x65, 0x72, 0x20, \r
+ 0x74, 0x65, 0x78, 0x74, 0x20, 0x74, 0x6f, 0x20, 0x64, 0x69, \r
+ 0x73, 0x70, 0x6c, 0x61, 0x79, 0x20, 0x6f, 0x6e, 0x20, 0x74, \r
+ 0x68, 0x65, 0x20, 0x4f, 0x4c, 0x45, 0x44, 0x20, 0x64, 0x69, \r
+ 0x73, 0x70, 0x6c, 0x61, 0x79, 0x2c, 0x20, 0x74, 0x68, 0x65, \r
+ 0x6e, 0x20, 0x63, 0x6c, 0x69, 0x63, 0x6b, 0x20, 0x22, 0x55, \r
+ 0x70, 0x64, 0x61, 0x74, 0x65, 0x20, 0x49, 0x4f, 0x22, 0x2e, \r
+ 0xa, 0xa, 0xa, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x66, 0x6f, \r
+ 0x72, 0x6d, 0x20, 0x6e, 0x61, 0x6d, 0x65, 0x3d, 0x22, 0x61, \r
+ 0x46, 0x6f, 0x72, 0x6d, 0x22, 0x20, 0x61, 0x63, 0x74, 0x69, \r
+ 0x6f, 0x6e, 0x3d, 0x22, 0x2f, 0x69, 0x6f, 0x2e, 0x73, 0x68, \r
+ 0x74, 0x6d, 0x6c, 0x22, 0x20, 0x6d, 0x65, 0x74, 0x68, 0x6f, \r
+ 0x64, 0x3d, 0x22, 0x67, 0x65, 0x74, 0x22, 0x3e, 0xa, 0x25, \r
+ 0x21, 0x20, 0x6c, 0x65, 0x64, 0x2d, 0x69, 0x6f, 0xa, 0x3c, \r
+ 0x70, 0x3e, 0xa, 0x3c, 0x69, 0x6e, 0x70, 0x75, 0x74, 0x20, \r
+ 0x74, 0x79, 0x70, 0x65, 0x3d, 0x22, 0x73, 0x75, 0x62, 0x6d, \r
+ 0x69, 0x74, 0x22, 0x20, 0x76, 0x61, 0x6c, 0x75, 0x65, 0x3d, \r
+ 0x22, 0x55, 0x70, 0x64, 0x61, 0x74, 0x65, 0x20, 0x49, 0x4f, \r
+ 0x22, 0x3e, 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x72, 0x6d, 0x3e, \r
+ 0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, \r
+ 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, 0x3c, 0x2f, 0x62, \r
+ 0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68, 0x74, 0x6d, \r
+ 0x6c, 0x3e, 0xa, 0xa, 0};\r
+\r
+static const char data_runtime_shtml[] = {\r
+ /* /runtime.shtml */\r
+ 0x2f, 0x72, 0x75, 0x6e, 0x74, 0x69, 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0,\r
+ 0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20, \r
+ 0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49, \r
+ 0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f, \r
+ 0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20, \r
+ 0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73, \r
+ 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45, \r
+ 0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, \r
+ 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72, \r
+ 0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34, \r
+ 0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64, \r
+ 0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, \r
+ 0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20, \r
+ 0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, \r
+ 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, \r
+ 0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42, \r
+ 0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65, \r
+ 0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, \r
+ 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e, \r
+ 0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x20, 0x6f, \r
+ 0x6e, 0x4c, 0x6f, 0x61, 0x64, 0x3d, 0x22, 0x77, 0x69, 0x6e, \r
+ 0x64, 0x6f, 0x77, 0x2e, 0x73, 0x65, 0x74, 0x54, 0x69, 0x6d, \r
+ 0x65, 0x6f, 0x75, 0x74, 0x28, 0x26, 0x71, 0x75, 0x6f, 0x74, \r
+ 0x3b, 0x6c, 0x6f, 0x63, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x2e, \r
+ 0x68, 0x72, 0x65, 0x66, 0x3d, 0x27, 0x72, 0x75, 0x6e, 0x74, \r
+ 0x69, 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x27, \r
+ 0x26, 0x71, 0x75, 0x6f, 0x74, 0x3b, 0x2c, 0x32, 0x30, 0x30, \r
+ 0x30, 0x29, 0x22, 0x3e, 0xa, 0x3c, 0x66, 0x6f, 0x6e, 0x74, \r
+ 0x20, 0x66, 0x61, 0x63, 0x65, 0x3d, 0x22, 0x61, 0x72, 0x69, \r
+ 0x61, 0x6c, 0x22, 0x3e, 0xa, 0x3c, 0x61, 0x20, 0x68, 0x72, \r
+ 0x65, 0x66, 0x3d, 0x22, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, \r
+ 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x54, 0x61, 0x73, \r
+ 0x6b, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, \r
+ 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, \r
+ 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, \r
+ 0x72, 0x75, 0x6e, 0x74, 0x69, 0x6d, 0x65, 0x2e, 0x73, 0x68, \r
+ 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x52, 0x75, 0x6e, 0x20, 0x54, \r
+ 0x69, 0x6d, 0x65, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, \r
+ 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, \r
+ 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, \r
+ 0x3d, 0x22, 0x73, 0x74, 0x61, 0x74, 0x73, 0x2e, 0x73, 0x68, \r
+ 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x54, 0x43, 0x50, 0x20, 0x53, \r
+ 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, \r
+ 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, \r
+ 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x74, 0x63, 0x70, \r
+ 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x43, 0x6f, \r
+ 0x6e, 0x6e, 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x73, 0x3c, \r
+ 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, \r
+ 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, \r
+ 0x3d, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, 0x2f, 0x77, \r
+ 0x77, 0x77, 0x2e, 0x66, 0x72, 0x65, 0x65, 0x72, 0x74, 0x6f, \r
+ 0x73, 0x2e, 0x6f, 0x72, 0x67, 0x2f, 0x22, 0x3e, 0x46, 0x72, \r
+ 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, 0x72, 0x67, \r
+ 0x20, 0x48, 0x6f, 0x6d, 0x65, 0x70, 0x61, 0x67, 0x65, 0x3c, \r
+ 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, \r
+ 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, \r
+ 0x3d, 0x22, 0x69, 0x6f, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, \r
+ 0x22, 0x3e, 0x49, 0x4f, 0x3c, 0x2f, 0x61, 0x3e, 0xa, 0x3c, \r
+ 0x62, 0x72, 0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x68, 0x72, \r
+ 0x3e, 0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, 0x3e, 0xa, \r
+ 0x3c, 0x68, 0x32, 0x3e, 0x52, 0x75, 0x6e, 0x2d, 0x74, 0x69, \r
+ 0x6d, 0x65, 0x20, 0x73, 0x74, 0x61, 0x74, 0x69, 0x73, 0x74, \r
+ 0x69, 0x63, 0x73, 0x3c, 0x2f, 0x68, 0x32, 0x3e, 0xa, 0x50, \r
+ 0x61, 0x67, 0x65, 0x20, 0x77, 0x69, 0x6c, 0x6c, 0x20, 0x72, \r
+ 0x65, 0x66, 0x72, 0x65, 0x73, 0x68, 0x20, 0x65, 0x76, 0x65, \r
+ 0x72, 0x79, 0x20, 0x32, 0x20, 0x73, 0x65, 0x63, 0x6f, 0x6e, \r
+ 0x64, 0x73, 0x2e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x66, 0x6f, \r
+ 0x6e, 0x74, 0x20, 0x66, 0x61, 0x63, 0x65, 0x3d, 0x22, 0x63, \r
+ 0x6f, 0x75, 0x72, 0x69, 0x65, 0x72, 0x22, 0x3e, 0x3c, 0x70, \r
+ 0x72, 0x65, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x41, \r
+ 0x62, 0x73, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x25, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x3c, \r
+ 0x62, 0x72, 0x3e, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, \r
+ 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, \r
+ 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, \r
+ 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, \r
+ 0x2a, 0x2a, 0x2a, 0x3c, 0x62, 0x72, 0x3e, 0xa, 0x25, 0x21, \r
+ 0x20, 0x72, 0x75, 0x6e, 0x2d, 0x74, 0x69, 0x6d, 0x65, 0xa, \r
+ 0x3c, 0x2f, 0x70, 0x72, 0x65, 0x3e, 0x3c, 0x2f, 0x66, 0x6f, \r
+ 0x6e, 0x74, 0x3e, 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, \r
+ 0x3e, 0xa, 0x3c, 0x2f, 0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa, \r
+ 0x3c, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, 0xa, 0};\r
+\r
+static const char data_stats_shtml[] = {\r
+ /* /stats.shtml */\r
+ 0x2f, 0x73, 0x74, 0x61, 0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0,\r
+ 0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20, \r
+ 0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49, \r
+ 0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f, \r
+ 0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20, \r
+ 0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73, \r
+ 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45, \r
+ 0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, \r
+ 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72, \r
+ 0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34, \r
+ 0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64, \r
+ 0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, \r
+ 0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20, \r
+ 0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, \r
+ 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, \r
+ 0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42, \r
+ 0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65, \r
+ 0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, \r
+ 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e, \r
+ 0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x3e, 0xa, \r
+ 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61, 0x63, 0x65, \r
+ 0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c, 0x22, 0x3e, 0xa, \r
+ 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, \r
+ 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, \r
+ 0x22, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x53, 0x74, 0x61, \r
+ 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, \r
+ 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, \r
+ 0x72, 0x65, 0x66, 0x3d, 0x22, 0x72, 0x75, 0x6e, 0x74, 0x69, \r
+ 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, \r
+ 0x52, 0x75, 0x6e, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x20, 0x53, \r
+ 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, \r
+ 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, \r
+ 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x73, 0x74, 0x61, \r
+ 0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, \r
+ 0x54, 0x43, 0x50, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, \r
+ 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, \r
+ 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, \r
+ 0x3d, 0x22, 0x74, 0x63, 0x70, 0x2e, 0x73, 0x68, 0x74, 0x6d, \r
+ 0x6c, 0x22, 0x3e, 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, \r
+ 0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, \r
+ 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, \r
+ 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x68, 0x74, 0x74, \r
+ 0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x66, 0x72, \r
+ 0x65, 0x65, 0x72, 0x74, 0x6f, 0x73, 0x2e, 0x6f, 0x72, 0x67, \r
+ 0x2f, 0x22, 0x3e, 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, \r
+ 0x53, 0x2e, 0x6f, 0x72, 0x67, 0x20, 0x48, 0x6f, 0x6d, 0x65, \r
+ 0x70, 0x61, 0x67, 0x65, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, \r
+ 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, \r
+ 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, 0x6f, 0x2e, \r
+ 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x49, 0x4f, 0x3c, \r
+ 0x2f, 0x61, 0x3e, 0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, \r
+ 0x3e, 0xa, 0x3c, 0x68, 0x72, 0x3e, 0xa, 0x3c, 0x62, 0x72, \r
+ 0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x68, 0x32, 0x3e, 0x4e, \r
+ 0x65, 0x74, 0x77, 0x6f, 0x72, 0x6b, 0x20, 0x73, 0x74, 0x61, \r
+ 0x74, 0x69, 0x73, 0x74, 0x69, 0x63, 0x73, 0x3c, 0x2f, 0x68, \r
+ 0x32, 0x3e, 0xa, 0x3c, 0x74, 0x61, 0x62, 0x6c, 0x65, 0x20, \r
+ 0x77, 0x69, 0x64, 0x74, 0x68, 0x3d, 0x22, 0x33, 0x30, 0x30, \r
+ 0x22, 0x20, 0x62, 0x6f, 0x72, 0x64, 0x65, 0x72, 0x3d, 0x22, \r
+ 0x30, 0x22, 0x3e, 0xa, 0x3c, 0x74, 0x72, 0x3e, 0x3c, 0x74, \r
+ 0x64, 0x20, 0x61, 0x6c, 0x69, 0x67, 0x6e, 0x3d, 0x22, 0x6c, \r
+ 0x65, 0x66, 0x74, 0x22, 0x3e, 0x3c, 0x66, 0x6f, 0x6e, 0x74, \r
+ 0x20, 0x66, 0x61, 0x63, 0x65, 0x3d, 0x22, 0x63, 0x6f, 0x75, \r
+ 0x72, 0x69, 0x65, 0x72, 0x22, 0x3e, 0x3c, 0x70, 0x72, 0x65, \r
+ 0x3e, 0xa, 0x49, 0x50, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, \r
+ 0x74, 0x73, 0x20, 0x64, 0x72, 0x6f, 0x70, 0x70, 0x65, 0x64, \r
+ 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74, \r
+ 0x73, 0x20, 0x72, 0x65, 0x63, 0x65, 0x69, 0x76, 0x65, 0x64, \r
+ 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74, \r
+ 0x73, 0x20, 0x73, 0x65, 0x6e, 0x74, 0xa, 0x49, 0x50, 0x20, \r
+ 0x65, 0x72, 0x72, 0x6f, 0x72, 0x73, 0x20, 0x20, 0x20, 0x20, \r
+ 0x49, 0x50, 0x20, 0x76, 0x65, 0x72, 0x73, 0x69, 0x6f, 0x6e, \r
+ 0x2f, 0x68, 0x65, 0x61, 0x64, 0x65, 0x72, 0x20, 0x6c, 0x65, \r
+ 0x6e, 0x67, 0x74, 0x68, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x49, 0x50, \r
+ 0x20, 0x6c, 0x65, 0x6e, 0x67, 0x74, 0x68, 0x2c, 0x20, 0x68, \r
+ 0x69, 0x67, 0x68, 0x20, 0x62, 0x79, 0x74, 0x65, 0xa, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x49, 0x50, 0x20, 0x6c, 0x65, 0x6e, 0x67, 0x74, \r
+ 0x68, 0x2c, 0x20, 0x6c, 0x6f, 0x77, 0x20, 0x62, 0x79, 0x74, \r
+ 0x65, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x20, 0x49, 0x50, 0x20, 0x66, 0x72, \r
+ 0x61, 0x67, 0x6d, 0x65, 0x6e, 0x74, 0x73, 0xa, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x48, 0x65, 0x61, 0x64, 0x65, 0x72, 0x20, 0x63, 0x68, \r
+ 0x65, 0x63, 0x6b, 0x73, 0x75, 0x6d, 0xa, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x57, 0x72, 0x6f, 0x6e, 0x67, 0x20, 0x70, 0x72, 0x6f, 0x74, \r
+ 0x6f, 0x63, 0x6f, 0x6c, 0xa, 0x49, 0x43, 0x4d, 0x50, 0x9, \r
+ 0x20, 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, \r
+ 0x74, 0x73, 0x20, 0x64, 0x72, 0x6f, 0x70, 0x70, 0x65, 0x64, \r
+ 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74, \r
+ 0x73, 0x20, 0x72, 0x65, 0x63, 0x65, 0x69, 0x76, 0x65, 0x64, \r
+ 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74, \r
+ 0x73, 0x20, 0x73, 0x65, 0x6e, 0x74, 0xa, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x54, 0x79, 0x70, 0x65, 0x20, 0x65, 0x72, 0x72, 0x6f, 0x72, \r
+ 0x73, 0xa, 0x54, 0x43, 0x50, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, \r
+ 0x74, 0x73, 0x20, 0x64, 0x72, 0x6f, 0x70, 0x70, 0x65, 0x64, \r
+ 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74, \r
+ 0x73, 0x20, 0x72, 0x65, 0x63, 0x65, 0x69, 0x76, 0x65, 0x64, \r
+ 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74, \r
+ 0x73, 0x20, 0x73, 0x65, 0x6e, 0x74, 0xa, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x43, 0x68, 0x65, 0x63, 0x6b, 0x73, 0x75, 0x6d, 0x20, 0x65, \r
+ 0x72, 0x72, 0x6f, 0x72, 0x73, 0xa, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x44, \r
+ 0x61, 0x74, 0x61, 0x20, 0x70, 0x61, 0x63, 0x6b, 0x65, 0x74, \r
+ 0x73, 0x20, 0x77, 0x69, 0x74, 0x68, 0x6f, 0x75, 0x74, 0x20, \r
+ 0x41, 0x43, 0x4b, 0x73, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x52, 0x65, \r
+ 0x73, 0x65, 0x74, 0x73, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x52, 0x65, \r
+ 0x74, 0x72, 0x61, 0x6e, 0x73, 0x6d, 0x69, 0x73, 0x73, 0x69, \r
+ 0x6f, 0x6e, 0x73, 0xa, 0x9, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x4e, 0x6f, 0x20, 0x63, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, \r
+ 0x69, 0x6f, 0x6e, 0x20, 0x61, 0x76, 0x61, 0x6c, 0x69, 0x61, \r
+ 0x62, 0x6c, 0x65, 0xa, 0x9, 0x20, 0x20, 0x20, 0x20, 0x20, \r
+ 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, \r
+ 0x20, 0x61, 0x74, 0x74, 0x65, 0x6d, 0x70, 0x74, 0x73, 0x20, \r
+ 0x74, 0x6f, 0x20, 0x63, 0x6c, 0x6f, 0x73, 0x65, 0x64, 0x20, \r
+ 0x70, 0x6f, 0x72, 0x74, 0x73, 0xa, 0x3c, 0x2f, 0x70, 0x72, \r
+ 0x65, 0x3e, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0x3c, \r
+ 0x2f, 0x74, 0x64, 0x3e, 0x3c, 0x74, 0x64, 0x3e, 0x3c, 0x70, \r
+ 0x72, 0x65, 0x3e, 0x25, 0x21, 0x20, 0x6e, 0x65, 0x74, 0x2d, \r
+ 0x73, 0x74, 0x61, 0x74, 0x73, 0xa, 0x3c, 0x2f, 0x70, 0x72, \r
+ 0x65, 0x3e, 0x3c, 0x2f, 0x74, 0x61, 0x62, 0x6c, 0x65, 0x3e, \r
+ 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, 0x3c, \r
+ 0x2f, 0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68, \r
+ 0x74, 0x6d, 0x6c, 0x3e, 0xa, 0};\r
+\r
+static const char data_tcp_shtml[] = {\r
+ /* /tcp.shtml */\r
+ 0x2f, 0x74, 0x63, 0x70, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0,\r
+ 0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20, \r
+ 0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49, \r
+ 0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f, \r
+ 0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20, \r
+ 0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73, \r
+ 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45, \r
+ 0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, \r
+ 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72, \r
+ 0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34, \r
+ 0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64, \r
+ 0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, \r
+ 0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20, \r
+ 0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, \r
+ 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, \r
+ 0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42, \r
+ 0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65, \r
+ 0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e, \r
+ 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e, \r
+ 0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x3e, 0xa, \r
+ 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61, 0x63, 0x65, \r
+ 0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c, 0x22, 0x3e, 0xa, \r
+ 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, \r
+ 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, \r
+ 0x22, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x53, 0x74, 0x61, \r
+ 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, \r
+ 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, \r
+ 0x72, 0x65, 0x66, 0x3d, 0x22, 0x72, 0x75, 0x6e, 0x74, 0x69, \r
+ 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, \r
+ 0x52, 0x75, 0x6e, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x20, 0x53, \r
+ 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, \r
+ 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, \r
+ 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x73, 0x74, 0x61, \r
+ 0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, \r
+ 0x54, 0x43, 0x50, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, \r
+ 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, \r
+ 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, \r
+ 0x3d, 0x22, 0x74, 0x63, 0x70, 0x2e, 0x73, 0x68, 0x74, 0x6d, \r
+ 0x6c, 0x22, 0x3e, 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, \r
+ 0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, \r
+ 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, \r
+ 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x68, 0x74, 0x74, \r
+ 0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x66, 0x72, \r
+ 0x65, 0x65, 0x72, 0x74, 0x6f, 0x73, 0x2e, 0x6f, 0x72, 0x67, \r
+ 0x2f, 0x22, 0x3e, 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, \r
+ 0x53, 0x2e, 0x6f, 0x72, 0x67, 0x20, 0x48, 0x6f, 0x6d, 0x65, \r
+ 0x70, 0x61, 0x67, 0x65, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, \r
+ 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, \r
+ 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, 0x6f, 0x2e, \r
+ 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x49, 0x4f, 0x3c, \r
+ 0x2f, 0x61, 0x3e, 0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, \r
+ 0x3e, 0xa, 0x3c, 0x68, 0x72, 0x3e, 0xa, 0x3c, 0x62, 0x72, \r
+ 0x3e, 0xa, 0x3c, 0x68, 0x32, 0x3e, 0x4e, 0x65, 0x74, 0x77, \r
+ 0x6f, 0x72, 0x6b, 0x20, 0x63, 0x6f, 0x6e, 0x6e, 0x65, 0x63, \r
+ 0x74, 0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x68, 0x32, 0x3e, \r
+ 0xa, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x74, 0x61, 0x62, 0x6c, \r
+ 0x65, 0x3e, 0xa, 0x3c, 0x74, 0x72, 0x3e, 0x3c, 0x74, 0x68, \r
+ 0x3e, 0x4c, 0x6f, 0x63, 0x61, 0x6c, 0x3c, 0x2f, 0x74, 0x68, \r
+ 0x3e, 0x3c, 0x74, 0x68, 0x3e, 0x52, 0x65, 0x6d, 0x6f, 0x74, \r
+ 0x65, 0x3c, 0x2f, 0x74, 0x68, 0x3e, 0x3c, 0x74, 0x68, 0x3e, \r
+ 0x53, 0x74, 0x61, 0x74, 0x65, 0x3c, 0x2f, 0x74, 0x68, 0x3e, \r
+ 0x3c, 0x74, 0x68, 0x3e, 0x52, 0x65, 0x74, 0x72, 0x61, 0x6e, \r
+ 0x73, 0x6d, 0x69, 0x73, 0x73, 0x69, 0x6f, 0x6e, 0x73, 0x3c, \r
+ 0x2f, 0x74, 0x68, 0x3e, 0x3c, 0x74, 0x68, 0x3e, 0x54, 0x69, \r
+ 0x6d, 0x65, 0x72, 0x3c, 0x2f, 0x74, 0x68, 0x3e, 0x3c, 0x74, \r
+ 0x68, 0x3e, 0x46, 0x6c, 0x61, 0x67, 0x73, 0x3c, 0x2f, 0x74, \r
+ 0x68, 0x3e, 0x3c, 0x2f, 0x74, 0x72, 0x3e, 0xa, 0x25, 0x21, \r
+ 0x20, 0x74, 0x63, 0x70, 0x2d, 0x63, 0x6f, 0x6e, 0x6e, 0x65, \r
+ 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x73, 0xa, 0x3c, 0x2f, 0x70, \r
+ 0x72, 0x65, 0x3e, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, \r
+ 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, 0x3c, \r
+ 0x2f, 0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68, \r
+ 0x74, 0x6d, 0x6c, 0x3e, 0xa, 0xa, 0};\r
+\r
+const struct httpd_fsdata_file file_404_html[] = {{NULL, data_404_html, data_404_html + 10, sizeof(data_404_html) - 10, 0}};\r
+\r
+const struct httpd_fsdata_file file_index_html[] = {{file_404_html, data_index_html, data_index_html + 12, sizeof(data_index_html) - 12, 0}};\r
+\r
+const struct httpd_fsdata_file file_index_shtml[] = {{file_index_html, data_index_shtml, data_index_shtml + 13, sizeof(data_index_shtml) - 13, 0}};\r
+\r
+const struct httpd_fsdata_file file_io_shtml[] = {{file_index_shtml, data_io_shtml, data_io_shtml + 10, sizeof(data_io_shtml) - 10, 0}};\r
+\r
+const struct httpd_fsdata_file file_runtime_shtml[] = {{file_io_shtml, data_runtime_shtml, data_runtime_shtml + 15, sizeof(data_runtime_shtml) - 15, 0}};\r
+\r
+const struct httpd_fsdata_file file_stats_shtml[] = {{file_runtime_shtml, data_stats_shtml, data_stats_shtml + 13, sizeof(data_stats_shtml) - 13, 0}};\r
+\r
+const struct httpd_fsdata_file file_tcp_shtml[] = {{file_stats_shtml, data_tcp_shtml, data_tcp_shtml + 11, sizeof(data_tcp_shtml) - 11, 0}};\r
+\r
+#define HTTPD_FS_ROOT file_tcp_shtml\r
+\r
+#define HTTPD_FS_NUMFILES 7\r
--- /dev/null
+/*\r
+ * Copyright (c) 2001, Swedish Institute of Computer Science.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without\r
+ * modification, are permitted provided that the following conditions\r
+ * are met:\r
+ * 1. Redistributions of source code must retain the above copyright\r
+ * notice, this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright\r
+ * notice, this list of conditions and the following disclaimer in the\r
+ * documentation and/or other materials provided with the distribution.\r
+ * 3. Neither the name of the Institute nor the names of its contributors\r
+ * may be used to endorse or promote products derived from this software\r
+ * without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND\r
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\r
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\r
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE\r
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\r
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS\r
+ * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)\r
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\r
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY\r
+ * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF\r
+ * SUCH DAMAGE.\r
+ *\r
+ * This file is part of the lwIP TCP/IP stack.\r
+ *\r
+ * Author: Adam Dunkels <adam@sics.se>\r
+ *\r
+ * $Id: httpd-fsdata.h,v 1.1 2006/06/07 09:13:08 adam Exp $\r
+ */\r
+#ifndef __HTTPD_FSDATA_H__\r
+#define __HTTPD_FSDATA_H__\r
+\r
+#include "uip.h"\r
+\r
+struct httpd_fsdata_file {\r
+ const struct httpd_fsdata_file *next;\r
+ const char *name;\r
+ const char *data;\r
+ const int len;\r
+#ifdef HTTPD_FS_STATISTICS\r
+#if HTTPD_FS_STATISTICS == 1\r
+ u16_t count;\r
+#endif /* HTTPD_FS_STATISTICS */\r
+#endif /* HTTPD_FS_STATISTICS */\r
+};\r
+\r
+struct httpd_fsdata_file_noconst {\r
+ struct httpd_fsdata_file *next;\r
+ char *name;\r
+ char *data;\r
+ int len;\r
+#ifdef HTTPD_FS_STATISTICS\r
+#if HTTPD_FS_STATISTICS == 1\r
+ u16_t count;\r
+#endif /* HTTPD_FS_STATISTICS */\r
+#endif /* HTTPD_FS_STATISTICS */\r
+};\r
+\r
+#endif /* __HTTPD_FSDATA_H__ */\r
--- /dev/null
+/**\r
+ * \addtogroup apps\r
+ * @{\r
+ */\r
+\r
+/**\r
+ * \defgroup httpd Web server\r
+ * @{\r
+ * The uIP web server is a very simplistic implementation of an HTTP\r
+ * server. It can serve web pages and files from a read-only ROM\r
+ * filesystem, and provides a very small scripting language.\r
+\r
+ */\r
+\r
+/**\r
+ * \file\r
+ * Web server\r
+ * \author\r
+ * Adam Dunkels <adam@sics.se>\r
+ */\r
+\r
+\r
+/*\r
+ * Copyright (c) 2004, Adam Dunkels.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without\r
+ * modification, are permitted provided that the following conditions\r
+ * are met:\r
+ * 1. Redistributions of source code must retain the above copyright\r
+ * notice, this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright\r
+ * notice, this list of conditions and the following disclaimer in the\r
+ * documentation and/or other materials provided with the distribution.\r
+ * 3. Neither the name of the Institute nor the names of its contributors\r
+ * may be used to endorse or promote products derived from this software\r
+ * without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND\r
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\r
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\r
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE\r
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\r
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS\r
+ * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)\r
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\r
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY\r
+ * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF\r
+ * SUCH DAMAGE.\r
+ *\r
+ * This file is part of the uIP TCP/IP stack.\r
+ *\r
+ * Author: Adam Dunkels <adam@sics.se>\r
+ *\r
+ * $Id: httpd.c,v 1.2 2006/06/11 21:46:38 adam Exp $\r
+ */\r
+\r
+#include "uip.h"\r
+#include "httpd.h"\r
+#include "httpd-fs.h"\r
+#include "httpd-cgi.h"\r
+#include "http-strings.h"\r
+\r
+#include <string.h>\r
+\r
+#define STATE_WAITING 0\r
+#define STATE_OUTPUT 1\r
+\r
+#define ISO_nl 0x0a\r
+#define ISO_space 0x20\r
+#define ISO_bang 0x21\r
+#define ISO_percent 0x25\r
+#define ISO_period 0x2e\r
+#define ISO_slash 0x2f\r
+#define ISO_colon 0x3a\r
+\r
+\r
+/*---------------------------------------------------------------------------*/\r
+static unsigned short\r
+generate_part_of_file(void *state)\r
+{\r
+ struct httpd_state *s = (struct httpd_state *)state;\r
+\r
+ if(s->file.len > uip_mss()) {\r
+ s->len = uip_mss();\r
+ } else {\r
+ s->len = s->file.len;\r
+ }\r
+ memcpy(uip_appdata, s->file.data, s->len);\r
+ \r
+ return s->len;\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+static\r
+PT_THREAD(send_file(struct httpd_state *s))\r
+{\r
+ PSOCK_BEGIN(&s->sout);\r
+ \r
+ do {\r
+ PSOCK_GENERATOR_SEND(&s->sout, generate_part_of_file, s);\r
+ s->file.len -= s->len;\r
+ s->file.data += s->len;\r
+ } while(s->file.len > 0);\r
+ \r
+ PSOCK_END(&s->sout);\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+static\r
+PT_THREAD(send_part_of_file(struct httpd_state *s))\r
+{\r
+ PSOCK_BEGIN(&s->sout);\r
+\r
+ PSOCK_SEND(&s->sout, s->file.data, s->len);\r
+ \r
+ PSOCK_END(&s->sout);\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+static void\r
+next_scriptstate(struct httpd_state *s)\r
+{\r
+ char *p;\r
+ p = strchr(s->scriptptr, ISO_nl) + 1;\r
+ s->scriptlen -= (unsigned short)(p - s->scriptptr);\r
+ s->scriptptr = p;\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+static\r
+PT_THREAD(handle_script(struct httpd_state *s))\r
+{\r
+ char *ptr;\r
+ \r
+ PT_BEGIN(&s->scriptpt);\r
+\r
+\r
+ while(s->file.len > 0) {\r
+\r
+ /* Check if we should start executing a script. */\r
+ if(*s->file.data == ISO_percent &&\r
+ *(s->file.data + 1) == ISO_bang) {\r
+ s->scriptptr = s->file.data + 3;\r
+ s->scriptlen = s->file.len - 3;\r
+ if(*(s->scriptptr - 1) == ISO_colon) {\r
+ httpd_fs_open(s->scriptptr + 1, &s->file);\r
+ PT_WAIT_THREAD(&s->scriptpt, send_file(s));\r
+ } else {\r
+ PT_WAIT_THREAD(&s->scriptpt,\r
+ httpd_cgi(s->scriptptr)(s, s->scriptptr));\r
+ }\r
+ next_scriptstate(s);\r
+ \r
+ /* The script is over, so we reset the pointers and continue\r
+ sending the rest of the file. */\r
+ s->file.data = s->scriptptr;\r
+ s->file.len = s->scriptlen;\r
+ } else {\r
+ /* See if we find the start of script marker in the block of HTML\r
+ to be sent. */\r
+\r
+ if(s->file.len > uip_mss()) {\r
+ s->len = uip_mss();\r
+ } else {\r
+ s->len = s->file.len;\r
+ }\r
+\r
+ if(*s->file.data == ISO_percent) {\r
+ ptr = strchr(s->file.data + 1, ISO_percent);\r
+ } else {\r
+ ptr = strchr(s->file.data, ISO_percent);\r
+ }\r
+ if(ptr != NULL &&\r
+ ptr != s->file.data) {\r
+ s->len = (int)(ptr - s->file.data);\r
+ if(s->len >= uip_mss()) {\r
+ s->len = uip_mss();\r
+ }\r
+ }\r
+ PT_WAIT_THREAD(&s->scriptpt, send_part_of_file(s));\r
+ s->file.data += s->len;\r
+ s->file.len -= s->len;\r
+ \r
+ }\r
+ }\r
+ \r
+ PT_END(&s->scriptpt);\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+static\r
+PT_THREAD(send_headers(struct httpd_state *s, const char *statushdr))\r
+{\r
+ char *ptr;\r
+\r
+ PSOCK_BEGIN(&s->sout);\r
+\r
+ PSOCK_SEND_STR(&s->sout, statushdr);\r
+\r
+ ptr = strrchr(s->filename, ISO_period);\r
+ if(ptr == NULL) {\r
+ PSOCK_SEND_STR(&s->sout, http_content_type_binary);\r
+ } else if(strncmp(http_html, ptr, 5) == 0 ||\r
+ strncmp(http_shtml, ptr, 6) == 0) {\r
+ PSOCK_SEND_STR(&s->sout, http_content_type_html);\r
+ } else if(strncmp(http_css, ptr, 4) == 0) {\r
+ PSOCK_SEND_STR(&s->sout, http_content_type_css);\r
+ } else if(strncmp(http_png, ptr, 4) == 0) {\r
+ PSOCK_SEND_STR(&s->sout, http_content_type_png);\r
+ } else if(strncmp(http_gif, ptr, 4) == 0) {\r
+ PSOCK_SEND_STR(&s->sout, http_content_type_gif);\r
+ } else if(strncmp(http_jpg, ptr, 4) == 0) {\r
+ PSOCK_SEND_STR(&s->sout, http_content_type_jpg);\r
+ } else {\r
+ PSOCK_SEND_STR(&s->sout, http_content_type_plain);\r
+ }\r
+ PSOCK_END(&s->sout);\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+static\r
+PT_THREAD(handle_output(struct httpd_state *s))\r
+{\r
+ char *ptr;\r
+ \r
+ PT_BEGIN(&s->outputpt);\r
+ \r
+ if(!httpd_fs_open(s->filename, &s->file)) {\r
+ httpd_fs_open(http_404_html, &s->file);\r
+ strcpy(s->filename, http_404_html);\r
+ PT_WAIT_THREAD(&s->outputpt,\r
+ send_headers(s,\r
+ http_header_404));\r
+ PT_WAIT_THREAD(&s->outputpt,\r
+ send_file(s));\r
+ } else {\r
+ PT_WAIT_THREAD(&s->outputpt,\r
+ send_headers(s,\r
+ http_header_200));\r
+ ptr = strchr(s->filename, ISO_period);\r
+ if(ptr != NULL && strncmp(ptr, http_shtml, 6) == 0) {\r
+ PT_INIT(&s->scriptpt);\r
+ PT_WAIT_THREAD(&s->outputpt, handle_script(s));\r
+ } else {\r
+ PT_WAIT_THREAD(&s->outputpt,\r
+ send_file(s));\r
+ }\r
+ }\r
+ PSOCK_CLOSE(&s->sout);\r
+ PT_END(&s->outputpt);\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+static\r
+PT_THREAD(handle_input(struct httpd_state *s))\r
+{\r
+ PSOCK_BEGIN(&s->sin);\r
+\r
+ PSOCK_READTO(&s->sin, ISO_space);\r
+\r
+ \r
+ if(strncmp(s->inputbuf, http_get, 4) != 0) {\r
+ PSOCK_CLOSE_EXIT(&s->sin);\r
+ }\r
+ PSOCK_READTO(&s->sin, ISO_space);\r
+\r
+ if(s->inputbuf[0] != ISO_slash) {\r
+ PSOCK_CLOSE_EXIT(&s->sin);\r
+ }\r
+\r
+ if(s->inputbuf[1] == ISO_space) {\r
+ strncpy(s->filename, http_index_html, sizeof(s->filename));\r
+ } else {\r
+\r
+ s->inputbuf[PSOCK_DATALEN(&s->sin) - 1] = 0;\r
+\r
+ /* Process any form input being sent to the server. */\r
+ {\r
+ extern void vApplicationProcessFormInput( char *pcInputString );\r
+ vApplicationProcessFormInput( s->inputbuf );\r
+ }\r
+\r
+ strncpy(s->filename, &s->inputbuf[0], sizeof(s->filename));\r
+ }\r
+\r
+ /* httpd_log_file(uip_conn->ripaddr, s->filename);*/\r
+ \r
+ s->state = STATE_OUTPUT;\r
+\r
+ while(1) {\r
+ PSOCK_READTO(&s->sin, ISO_nl);\r
+\r
+ if(strncmp(s->inputbuf, http_referer, 8) == 0) {\r
+ s->inputbuf[PSOCK_DATALEN(&s->sin) - 2] = 0;\r
+ /* httpd_log(&s->inputbuf[9]);*/\r
+ }\r
+ }\r
+ \r
+ PSOCK_END(&s->sin);\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+static void\r
+handle_connection(struct httpd_state *s)\r
+{\r
+ handle_input(s);\r
+ if(s->state == STATE_OUTPUT) {\r
+ handle_output(s);\r
+ }\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+void\r
+httpd_appcall(void)\r
+{\r
+ struct httpd_state *s = (struct httpd_state *)&(uip_conn->appstate);\r
+\r
+ if(uip_closed() || uip_aborted() || uip_timedout()) {\r
+ } else if(uip_connected()) {\r
+ PSOCK_INIT(&s->sin, s->inputbuf, sizeof(s->inputbuf) - 1);\r
+ PSOCK_INIT(&s->sout, s->inputbuf, sizeof(s->inputbuf) - 1);\r
+ PT_INIT(&s->outputpt);\r
+ s->state = STATE_WAITING;\r
+ /* timer_set(&s->timer, CLOCK_SECOND * 100);*/\r
+ s->timer = 0;\r
+ handle_connection(s);\r
+ } else if(s != NULL) {\r
+ if(uip_poll()) {\r
+ ++s->timer;\r
+ if(s->timer >= 20) {\r
+ uip_abort();\r
+ }\r
+ } else {\r
+ s->timer = 0;\r
+ }\r
+ handle_connection(s);\r
+ } else {\r
+ uip_abort();\r
+ }\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+/**\r
+ * \brief Initialize the web server\r
+ *\r
+ * This function initializes the web server and should be\r
+ * called at system boot-up.\r
+ */\r
+void\r
+httpd_init(void)\r
+{\r
+ uip_listen(HTONS(80));\r
+}\r
+/*---------------------------------------------------------------------------*/\r
+/** @} */\r
--- /dev/null
+/*\r
+ * Copyright (c) 2001-2005, Adam Dunkels.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without\r
+ * modification, are permitted provided that the following conditions\r
+ * are met:\r
+ * 1. Redistributions of source code must retain the above copyright\r
+ * notice, this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright\r
+ * notice, this list of conditions and the following disclaimer in the\r
+ * documentation and/or other materials provided with the distribution.\r
+ * 3. The name of the author may not be used to endorse or promote\r
+ * products derived from this software without specific prior\r
+ * written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS\r
+ * OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\r
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\r
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY\r
+ * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\r
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE\r
+ * GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\r
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,\r
+ * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING\r
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\r
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\r
+ *\r
+ * This file is part of the uIP TCP/IP stack.\r
+ *\r
+ * $Id: httpd.h,v 1.2 2006/06/11 21:46:38 adam Exp $\r
+ *\r
+ */\r
+\r
+#ifndef __HTTPD_H__\r
+#define __HTTPD_H__\r
+\r
+#include "psock.h"\r
+#include "httpd-fs.h"\r
+\r
+struct httpd_state {\r
+ unsigned char timer;\r
+ struct psock sin, sout;\r
+ struct pt outputpt, scriptpt;\r
+ char inputbuf[50];\r
+ char filename[20];\r
+ char state;\r
+ struct httpd_fs_file file;\r
+ int len;\r
+ char *scriptptr;\r
+ int scriptlen;\r
+ \r
+ unsigned short count;\r
+};\r
+\r
+void httpd_init(void);\r
+void httpd_appcall(void);\r
+\r
+void httpd_log(char *msg);\r
+void httpd_log_file(u16_t *requester, char *file);\r
+\r
+#endif /* __HTTPD_H__ */\r
--- /dev/null
+#!/usr/bin/perl\r
+\r
+open(OUTPUT, "> httpd-fsdata.c");\r
+\r
+chdir("httpd-fs");\r
+\r
+opendir(DIR, ".");\r
+@files = grep { !/^\./ && !/(CVS|~)/ } readdir(DIR);\r
+closedir(DIR);\r
+\r
+foreach $file (@files) { \r
+ \r
+ if(-d $file && $file !~ /^\./) {\r
+ print "Processing directory $file\n";\r
+ opendir(DIR, $file);\r
+ @newfiles = grep { !/^\./ && !/(CVS|~)/ } readdir(DIR);\r
+ closedir(DIR);\r
+ printf "Adding files @newfiles\n";\r
+ @files = (@files, map { $_ = "$file/$_" } @newfiles);\r
+ next;\r
+ }\r
+}\r
+\r
+foreach $file (@files) {\r
+ if(-f $file) {\r
+ \r
+ print "Adding file $file\n";\r
+ \r
+ open(FILE, $file) || die "Could not open file $file\n";\r
+\r
+ $file =~ s-^-/-;\r
+ $fvar = $file;\r
+ $fvar =~ s-/-_-g;\r
+ $fvar =~ s-\.-_-g;\r
+ # for AVR, add PROGMEM here\r
+ print(OUTPUT "static const unsigned char data".$fvar."[] = {\n");\r
+ print(OUTPUT "\t/* $file */\n\t");\r
+ for($j = 0; $j < length($file); $j++) {\r
+ printf(OUTPUT "%#02x, ", unpack("C", substr($file, $j, 1)));\r
+ }\r
+ printf(OUTPUT "0,\n");\r
+ \r
+ \r
+ $i = 0; \r
+ while(read(FILE, $data, 1)) {\r
+ if($i == 0) {\r
+ print(OUTPUT "\t");\r
+ }\r
+ printf(OUTPUT "%#02x, ", unpack("C", $data));\r
+ $i++;\r
+ if($i == 10) {\r
+ print(OUTPUT "\n");\r
+ $i = 0;\r
+ }\r
+ }\r
+ print(OUTPUT "0};\n\n");\r
+ close(FILE);\r
+ push(@fvars, $fvar);\r
+ push(@pfiles, $file);\r
+ }\r
+}\r
+\r
+for($i = 0; $i < @fvars; $i++) {\r
+ $file = $pfiles[$i];\r
+ $fvar = $fvars[$i];\r
+\r
+ if($i == 0) {\r
+ $prevfile = "NULL";\r
+ } else {\r
+ $prevfile = "file" . $fvars[$i - 1];\r
+ }\r
+ print(OUTPUT "const struct httpd_fsdata_file file".$fvar."[] = {{$prevfile, data$fvar, ");\r
+ print(OUTPUT "data$fvar + ". (length($file) + 1) .", ");\r
+ print(OUTPUT "sizeof(data$fvar) - ". (length($file) + 1) ."}};\n\n");\r
+}\r
+\r
+print(OUTPUT "#define HTTPD_FS_ROOT file$fvars[$i - 1]\n\n");\r
+print(OUTPUT "#define HTTPD_FS_NUMFILES $i\n");\r
--- /dev/null
+#!/usr/bin/perl\r
+\r
+\r
+sub stringify {\r
+ my $name = shift(@_);\r
+ open(OUTPUTC, "> $name.c");\r
+ open(OUTPUTH, "> $name.h");\r
+ \r
+ open(FILE, "$name");\r
+ \r
+ while(<FILE>) {\r
+ if(/(.+) "(.+)"/) {\r
+ $var = $1;\r
+ $data = $2;\r
+ \r
+ $datan = $data;\r
+ $datan =~ s/\\r/\r/g;\r
+ $datan =~ s/\\n/\n/g;\r
+ $datan =~ s/\\01/\01/g; \r
+ $datan =~ s/\\0/\0/g;\r
+ \r
+ printf(OUTPUTC "const char $var\[%d] = \n", length($datan) + 1);\r
+ printf(OUTPUTC "/* \"$data\" */\n");\r
+ printf(OUTPUTC "{");\r
+ for($j = 0; $j < length($datan); $j++) {\r
+ printf(OUTPUTC "%#02x, ", unpack("C", substr($datan, $j, 1)));\r
+ }\r
+ printf(OUTPUTC "};\n");\r
+ \r
+ printf(OUTPUTH "extern const char $var\[%d];\n", length($datan) + 1);\r
+ \r
+ }\r
+ }\r
+ close(OUTPUTC);\r
+ close(OUTPUTH);\r
+}\r
+stringify("http-strings");\r
+\r
+exit 0;\r
+\r
--- /dev/null
+/*\r
+ FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry.\r
+\r
+ This file is part of the FreeRTOS.org distribution.\r
+\r
+ FreeRTOS.org is free software; you can redistribute it and/or modify it\r
+ under the terms of the GNU General Public License (version 2) as published\r
+ by the Free Software Foundation and modified by the FreeRTOS exception.\r
+ **NOTE** The exception to the GPL is included to allow you to distribute a\r
+ combined work that includes FreeRTOS.org without being obliged to provide\r
+ the source code for any proprietary components. Alternative commercial\r
+ license and support terms are also available upon request. See the\r
+ licensing section of http://www.FreeRTOS.org for full details.\r
+\r
+ FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT\r
+ ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or\r
+ FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for\r
+ more details.\r
+\r
+ You should have received a copy of the GNU General Public License along\r
+ with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59\r
+ Temple Place, Suite 330, Boston, MA 02111-1307 USA.\r
+\r
+\r
+ ***************************************************************************\r
+ * *\r
+ * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation *\r
+ * *\r
+ * This is a concise, step by step, 'hands on' guide that describes both *\r
+ * general multitasking concepts and FreeRTOS specifics. It presents and *\r
+ * explains numerous examples that are written using the FreeRTOS API. *\r
+ * Full source code for all the examples is provided in an accompanying *\r
+ * .zip file. *\r
+ * *\r
+ ***************************************************************************\r
+\r
+ 1 tab == 4 spaces!\r
+\r
+ Please ensure to read the configuration and relevant port sections of the\r
+ online documentation.\r
+\r
+ http://www.FreeRTOS.org - Documentation, latest information, license and\r
+ contact details.\r
+\r
+ http://www.SafeRTOS.com - A version that is certified for use in safety\r
+ critical systems.\r
+\r
+ http://www.OpenRTOS.com - Commercial support, development, porting,\r
+ licensing and training services.\r
+*/\r
+\r
+/* Standard includes. */\r
+#include <string.h>\r
+\r
+/* Scheduler includes. */\r
+#include "FreeRTOS.h"\r
+#include "task.h"\r
+#include "semphr.h"\r
+\r
+/* uip includes. */\r
+#include "uip.h"\r
+#include "uip_arp.h"\r
+#include "httpd.h"\r
+#include "timer.h"\r
+#include "clock-arch.h"\r
+\r
+/* Demo includes. */\r
+#include "emac.h"\r
+#include "LED.h"\r
+\r
+#include "LPC17xx.h"\r
+#include "core_cm3.h"\r
+/*-----------------------------------------------------------*/\r
+\r
+/* How long to wait before attempting to connect the MAC again. */\r
+#define uipINIT_WAIT 100\r
+\r
+/* Shortcut to the header within the Rx buffer. */\r
+#define xHeader ((struct uip_eth_hdr *) &uip_buf[ 0 ])\r
+\r
+/* Standard constant. */\r
+#define uipTOTAL_FRAME_HEADER_SIZE 54\r
+\r
+\r
+/*-----------------------------------------------------------*/\r
+\r
+/*\r
+ * Send the uIP buffer to the MAC.\r
+ */\r
+static void prvENET_Send(void);\r
+\r
+/*\r
+ * Setup the MAC address in the MAC itself, and in the uIP stack.\r
+ */\r
+static void prvSetMACAddress( void );\r
+\r
+/*\r
+ * Port functions required by the uIP stack.\r
+ */\r
+void clock_init( void );\r
+clock_time_t clock_time( void );\r
+\r
+/*-----------------------------------------------------------*/\r
+\r
+/* The semaphore used by the ISR to wake the uIP task. */\r
+extern xSemaphoreHandle xEMACSemaphore;\r
+\r
+/*-----------------------------------------------------------*/\r
+\r
+void clock_init(void)\r
+{\r
+ /* This is done when the scheduler starts. */\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+clock_time_t clock_time( void )\r
+{\r
+ return xTaskGetTickCount();\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+void vuIP_Task( void *pvParameters )\r
+{\r
+portBASE_TYPE i;\r
+uip_ipaddr_t xIPAddr;\r
+struct timer periodic_timer, arp_timer;\r
+extern void ( vEMAC_ISR_Wrapper )( void );\r
+\r
+ ( void ) pvParameters;\r
+\r
+ /* Create the semaphore used by the ISR to wake this task. */\r
+ vSemaphoreCreateBinary( xEMACSemaphore );\r
+\r
+ /* Initialise the uIP stack. */\r
+ timer_set( &periodic_timer, configTICK_RATE_HZ / 2 );\r
+ timer_set( &arp_timer, configTICK_RATE_HZ * 10 );\r
+ uip_init();\r
+ uip_ipaddr( xIPAddr, configIP_ADDR0, configIP_ADDR1, configIP_ADDR2, configIP_ADDR3 );\r
+ uip_sethostaddr( xIPAddr );\r
+ uip_ipaddr( xIPAddr, configNET_MASK0, configNET_MASK1, configNET_MASK2, configNET_MASK3 );\r
+ uip_setnetmask( xIPAddr );\r
+ httpd_init();\r
+\r
+ /* Initialise the MAC. */\r
+ while( Init_EMAC() != pdPASS )\r
+ {\r
+ vTaskDelay( uipINIT_WAIT );\r
+ }\r
+\r
+ portENTER_CRITICAL();\r
+ {\r
+ ETH_INTENABLE = INT_RX_DONE;\r
+ /* set the interrupt priority */\r
+ NVIC_SetPriority( ENET_IRQn, configMAX_SYSCALL_INTERRUPT_PRIORITY );\r
+ /* enable the interrupt */\r
+ NVIC_EnableIRQ( ENET_IRQn );\r
+ prvSetMACAddress();\r
+ }\r
+ portEXIT_CRITICAL();\r
+\r
+\r
+ for( ;; )\r
+ {\r
+ /* Is there received data ready to be processed? */\r
+ uip_len = uiGetEMACRxData( uip_buf );\r
+\r
+ if( uip_len > 0 )\r
+ {\r
+ /* Standard uIP loop taken from the uIP manual. */\r
+ if( xHeader->type == htons( UIP_ETHTYPE_IP ) )\r
+ {\r
+ uip_arp_ipin();\r
+ uip_input();\r
+\r
+ /* If the above function invocation resulted in data that\r
+ should be sent out on the network, the global variable\r
+ uip_len is set to a value > 0. */\r
+ if( uip_len > 0 )\r
+ {\r
+ uip_arp_out();\r
+ prvENET_Send();\r
+ }\r
+ }\r
+ else if( xHeader->type == htons( UIP_ETHTYPE_ARP ) )\r
+ {\r
+ uip_arp_arpin();\r
+\r
+ /* If the above function invocation resulted in data that\r
+ should be sent out on the network, the global variable\r
+ uip_len is set to a value > 0. */\r
+ if( uip_len > 0 )\r
+ {\r
+ prvENET_Send();\r
+ }\r
+ }\r
+ }\r
+ else\r
+ {\r
+ if( timer_expired( &periodic_timer ) )\r
+ {\r
+ timer_reset( &periodic_timer );\r
+ for( i = 0; i < UIP_CONNS; i++ )\r
+ {\r
+ uip_periodic( i );\r
+\r
+ /* If the above function invocation resulted in data that\r
+ should be sent out on the network, the global variable\r
+ uip_len is set to a value > 0. */\r
+ if( uip_len > 0 )\r
+ {\r
+ uip_arp_out();\r
+ prvENET_Send();\r
+ }\r
+ }\r
+\r
+ /* Call the ARP timer function every 10 seconds. */\r
+ if( timer_expired( &arp_timer ) )\r
+ {\r
+ timer_reset( &arp_timer );\r
+ uip_arp_timer();\r
+ }\r
+ }\r
+ else\r
+ {\r
+ /* We did not receive a packet, and there was no periodic\r
+ processing to perform. Block for a fixed period. If a packet\r
+ is received during this period we will be woken by the ISR\r
+ giving us the Semaphore. */\r
+ xSemaphoreTake( xEMACSemaphore, configTICK_RATE_HZ / 2 );\r
+ }\r
+ }\r
+ }\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+static void prvENET_Send(void)\r
+{\r
+ RequestSend();\r
+\r
+ /* Copy the header into the Tx buffer. */\r
+ CopyToFrame_EMAC( uip_buf, uipTOTAL_FRAME_HEADER_SIZE );\r
+ if( uip_len > uipTOTAL_FRAME_HEADER_SIZE )\r
+ {\r
+ CopyToFrame_EMAC( uip_appdata, ( uip_len - uipTOTAL_FRAME_HEADER_SIZE ) );\r
+ }\r
+\r
+ DoSend_EMAC( uip_len );\r
+\r
+ RequestSend();\r
+\r
+ /* Copy the header into the Tx buffer. */\r
+ CopyToFrame_EMAC( uip_buf, uipTOTAL_FRAME_HEADER_SIZE );\r
+ if( uip_len > uipTOTAL_FRAME_HEADER_SIZE )\r
+ {\r
+ CopyToFrame_EMAC( uip_appdata, ( uip_len - uipTOTAL_FRAME_HEADER_SIZE ) );\r
+ }\r
+\r
+ DoSend_EMAC( uip_len );\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+static void prvSetMACAddress( void )\r
+{\r
+struct uip_eth_addr xAddr;\r
+\r
+ /* Configure the MAC address in the uIP stack. */\r
+ xAddr.addr[ 0 ] = configMAC_ADDR0;\r
+ xAddr.addr[ 1 ] = configMAC_ADDR1;\r
+ xAddr.addr[ 2 ] = configMAC_ADDR2;\r
+ xAddr.addr[ 3 ] = configMAC_ADDR3;\r
+ xAddr.addr[ 4 ] = configMAC_ADDR4;\r
+ xAddr.addr[ 5 ] = configMAC_ADDR5;\r
+ uip_setethaddr( xAddr );\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+void vApplicationProcessFormInput( portCHAR *pcInputString )\r
+{\r
+char *c, *pcText;\r
+static portCHAR cMessageForDisplay[ 32 ];\r
+extern xQueueHandle xLCDQueue;\r
+xLCDMessage xLCDMessage;\r
+\r
+ /* Process the form input sent by the IO page of the served HTML. */\r
+\r
+ c = strstr( pcInputString, "?" );\r
+ if( c )\r
+ {\r
+ /* Turn LED's on or off in accordance with the check box status. */\r
+ if( strstr( c, "LED0=1" ) != NULL )\r
+ {\r
+ /* Set LED7. */\r
+ vParTestSetLED( 1 << 7, 1 );\r
+ }\r
+ else\r
+ {\r
+ /* Clear LED7. */\r
+ vParTestSetLED( 1 << 7, 0 );\r
+ }\r
+\r
+ /* Find the start of the text to be displayed on the LCD. */\r
+ pcText = strstr( c, "LCD=" );\r
+ pcText += strlen( "LCD=" );\r
+\r
+ /* Terminate the file name for further processing within uIP. */\r
+ *c = 0x00;\r
+\r
+ /* Terminate the LCD string. */\r
+ c = strstr( pcText, " " );\r
+ if( c != NULL )\r
+ {\r
+ *c = 0x00;\r
+ }\r
+\r
+ /* Add required spaces. */\r
+ while( ( c = strstr( pcText, "+" ) ) != NULL )\r
+ {\r
+ *c = ' ';\r
+ }\r
+\r
+ /* Write the message to the LCD. */\r
+ strcpy( cMessageForDisplay, pcText );\r
+ xLCDMessage.pcMessage = cMessageForDisplay;\r
+ xQueueSend( xLCDQueue, &xLCDMessage, portMAX_DELAY );\r
+ }\r
+}\r
+\r
--- /dev/null
+/**\r
+ * \addtogroup uipopt\r
+ * @{\r
+ */\r
+\r
+/**\r
+ * \name Project-specific configuration options\r
+ * @{\r
+ *\r
+ * uIP has a number of configuration options that can be overridden\r
+ * for each project. These are kept in a project-specific uip-conf.h\r
+ * file and all configuration names have the prefix UIP_CONF.\r
+ */\r
+\r
+/*\r
+ * Copyright (c) 2006, Swedish Institute of Computer Science.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without\r
+ * modification, are permitted provided that the following conditions\r
+ * are met:\r
+ * 1. Redistributions of source code must retain the above copyright\r
+ * notice, this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright\r
+ * notice, this list of conditions and the following disclaimer in the\r
+ * documentation and/or other materials provided with the distribution.\r
+ * 3. Neither the name of the Institute nor the names of its contributors\r
+ * may be used to endorse or promote products derived from this software\r
+ * without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND\r
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\r
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\r
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE\r
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\r
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS\r
+ * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)\r
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\r
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY\r
+ * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF\r
+ * SUCH DAMAGE.\r
+ *\r
+ * This file is part of the uIP TCP/IP stack\r
+ *\r
+ * $Id: uip-conf.h,v 1.6 2006/06/12 08:00:31 adam Exp $\r
+ */\r
+\r
+/**\r
+ * \file\r
+ * An example uIP configuration file\r
+ * \author\r
+ * Adam Dunkels <adam@sics.se>\r
+ */\r
+\r
+#ifndef __UIP_CONF_H__\r
+#define __UIP_CONF_H__\r
+\r
+#include <stdint.h>\r
+\r
+/**\r
+ * 8 bit datatype\r
+ *\r
+ * This typedef defines the 8-bit type used throughout uIP.\r
+ *\r
+ * \hideinitializer\r
+ */\r
+typedef uint8_t u8_t;\r
+\r
+/**\r
+ * 16 bit datatype\r
+ *\r
+ * This typedef defines the 16-bit type used throughout uIP.\r
+ *\r
+ * \hideinitializer\r
+ */\r
+typedef uint16_t u16_t;\r
+\r
+/**\r
+ * Statistics datatype\r
+ *\r
+ * This typedef defines the dataype used for keeping statistics in\r
+ * uIP.\r
+ *\r
+ * \hideinitializer\r
+ */\r
+typedef unsigned short uip_stats_t;\r
+\r
+/**\r
+ * Maximum number of TCP connections.\r
+ *\r
+ * \hideinitializer\r
+ */\r
+#define UIP_CONF_MAX_CONNECTIONS 40\r
+\r
+/**\r
+ * Maximum number of listening TCP ports.\r
+ *\r
+ * \hideinitializer\r
+ */\r
+#define UIP_CONF_MAX_LISTENPORTS 40\r
+\r
+/**\r
+ * uIP buffer size.\r
+ *\r
+ * \hideinitializer\r
+ */\r
+#define UIP_CONF_BUFFER_SIZE 1480\r
+\r
+/**\r
+ * CPU byte order.\r
+ *\r
+ * \hideinitializer\r
+ */\r
+#define UIP_CONF_BYTE_ORDER LITTLE_ENDIAN\r
+\r
+/**\r
+ * Logging on or off\r
+ *\r
+ * \hideinitializer\r
+ */\r
+#define UIP_CONF_LOGGING 0\r
+\r
+/**\r
+ * UDP support on or off\r
+ *\r
+ * \hideinitializer\r
+ */\r
+#define UIP_CONF_UDP 0\r
+\r
+/**\r
+ * UDP checksums on or off\r
+ *\r
+ * \hideinitializer\r
+ */\r
+#define UIP_CONF_UDP_CHECKSUMS 1\r
+\r
+/**\r
+ * uIP statistics on or off\r
+ *\r
+ * \hideinitializer\r
+ */\r
+#define UIP_CONF_STATISTICS 1\r
+\r
+/* Here we include the header file for the application(s) we use in\r
+ our project. */\r
+/*#include "smtp.h"*/\r
+/*#include "hello-world.h"*/\r
+/*#include "telnetd.h"*/\r
+#include "webserver.h"\r
+/*#include "dhcpc.h"*/\r
+/*#include "resolv.h"*/\r
+/*#include "webclient.h"*/\r
+\r
+#endif /* __UIP_CONF_H__ */\r
+\r
+/** @} */\r
+/** @} */\r
--- /dev/null
+/*\r
+ * Copyright (c) 2002, Adam Dunkels.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without\r
+ * modification, are permitted provided that the following conditions\r
+ * are met:\r
+ * 1. Redistributions of source code must retain the above copyright\r
+ * notice, this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above\r
+ * copyright notice, this list of conditions and the following\r
+ * disclaimer in the documentation and/or other materials provided\r
+ * with the distribution.\r
+ * 3. The name of the author may not be used to endorse or promote\r
+ * products derived from this software without specific prior\r
+ * written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS\r
+ * OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\r
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\r
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY\r
+ * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\r
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE\r
+ * GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\r
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,\r
+ * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING\r
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\r
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\r
+ *\r
+ * This file is part of the uIP TCP/IP stack\r
+ *\r
+ * $Id: webserver.h,v 1.2 2006/06/11 21:46:38 adam Exp $\r
+ *\r
+ */\r
+#ifndef __WEBSERVER_H__\r
+#define __WEBSERVER_H__\r
+\r
+#include "httpd.h"\r
+\r
+typedef struct httpd_state uip_tcp_appstate_t;\r
+/* UIP_APPCALL: the name of the application function. This function\r
+ must return void and take no arguments (i.e., C type "void\r
+ appfunc(void)"). */\r
+#ifndef UIP_APPCALL\r
+#define UIP_APPCALL httpd_appcall\r
+#endif\r
+\r
+\r
+#endif /* __WEBSERVER_H__ */\r