Add Rowley LPC1768 demo.

This commit is contained in:
Richard Barry 2009-07-05 08:54:12 +00:00
parent 428dbc9342
commit fe9d735641
39 changed files with 9317 additions and 0 deletions

View File

@ -0,0 +1,149 @@
/******************************************************************************/
/* CortexM3.H: Header file for Cortex-M3 */
/******************************************************************************/
/* This file is part of the uVision/ARM development tools. */
/* Copyright (c) 2008 Keil Software. All rights reserved. */
/******************************************************************************/
#ifndef __CortexM3_H
#define __CortexM3_H
#define REG8(x) (*((volatile unsigned char *)(x)))
#define REG16(x) (*((volatile unsigned short *)(x)))
#define REG32(x) (*((volatile unsigned long *)(x)))
/* NVIC Registers */
#define NVIC_INT_TYPE REG32(0xE000E004)
#define NVIC_ST_CTRL REG32(0xE000E010)
#define NVIC_ST_RELOAD REG32(0xE000E014)
#define NVIC_ST_CURRENT REG32(0xE000E018)
#define NVIC_ST_CALIB REG32(0xE000E01C)
#define NVIC_ENABLE0 REG32(0xE000E100)
#define NVIC_ENABLE1 REG32(0xE000E104)
#define NVIC_ENABLE2 REG32(0xE000E108)
#define NVIC_ENABLE3 REG32(0xE000E10C)
#define NVIC_ENABLE4 REG32(0xE000E110)
#define NVIC_ENABLE5 REG32(0xE000E114)
#define NVIC_ENABLE6 REG32(0xE000E118)
#define NVIC_ENABLE7 REG32(0xE000E11C)
#define NVIC_DISABLE0 REG32(0xE000E180)
#define NVIC_DISABLE1 REG32(0xE000E184)
#define NVIC_DISABLE2 REG32(0xE000E188)
#define NVIC_DISABLE3 REG32(0xE000E18C)
#define NVIC_DISABLE4 REG32(0xE000E190)
#define NVIC_DISABLE5 REG32(0xE000E194)
#define NVIC_DISABLE6 REG32(0xE000E198)
#define NVIC_DISABLE7 REG32(0xE000E19C)
#define NVIC_PEND0 REG32(0xE000E200)
#define NVIC_PEND1 REG32(0xE000E204)
#define NVIC_PEND2 REG32(0xE000E208)
#define NVIC_PEND3 REG32(0xE000E20C)
#define NVIC_PEND4 REG32(0xE000E210)
#define NVIC_PEND5 REG32(0xE000E214)
#define NVIC_PEND6 REG32(0xE000E218)
#define NVIC_PEND7 REG32(0xE000E21C)
#define NVIC_UNPEND0 REG32(0xE000E280)
#define NVIC_UNPEND1 REG32(0xE000E284)
#define NVIC_UNPEND2 REG32(0xE000E288)
#define NVIC_UNPEND3 REG32(0xE000E28C)
#define NVIC_UNPEND4 REG32(0xE000E290)
#define NVIC_UNPEND5 REG32(0xE000E294)
#define NVIC_UNPEND6 REG32(0xE000E298)
#define NVIC_UNPEND7 REG32(0xE000E29C)
#define NVIC_ACTIVE0 REG32(0xE000E300)
#define NVIC_ACTIVE1 REG32(0xE000E304)
#define NVIC_ACTIVE2 REG32(0xE000E308)
#define NVIC_ACTIVE3 REG32(0xE000E30C)
#define NVIC_ACTIVE4 REG32(0xE000E310)
#define NVIC_ACTIVE5 REG32(0xE000E314)
#define NVIC_ACTIVE6 REG32(0xE000E318)
#define NVIC_ACTIVE7 REG32(0xE000E31C)
#define NVIC_PRI0 REG32(0xE000E400)
#define NVIC_PRI1 REG32(0xE000E404)
#define NVIC_PRI2 REG32(0xE000E408)
#define NVIC_PRI3 REG32(0xE000E40C)
#define NVIC_PRI4 REG32(0xE000E410)
#define NVIC_PRI5 REG32(0xE000E414)
#define NVIC_PRI6 REG32(0xE000E418)
#define NVIC_PRI7 REG32(0xE000E41C)
#define NVIC_PRI8 REG32(0xE000E420)
#define NVIC_PRI9 REG32(0xE000E424)
#define NVIC_PRI10 REG32(0xE000E428)
#define NVIC_PRI11 REG32(0xE000E42C)
#define NVIC_PRI12 REG32(0xE000E430)
#define NVIC_PRI13 REG32(0xE000E434)
#define NVIC_PRI14 REG32(0xE000E438)
#define NVIC_PRI15 REG32(0xE000E43C)
#define NVIC_PRI16 REG32(0xE000E440)
#define NVIC_PRI17 REG32(0xE000E444)
#define NVIC_PRI18 REG32(0xE000E448)
#define NVIC_PRI19 REG32(0xE000E44C)
#define NVIC_PRI20 REG32(0xE000E450)
#define NVIC_PRI21 REG32(0xE000E454)
#define NVIC_PRI22 REG32(0xE000E458)
#define NVIC_PRI23 REG32(0xE000E45C)
#define NVIC_PRI24 REG32(0xE000E460)
#define NVIC_PRI25 REG32(0xE000E464)
#define NVIC_PRI26 REG32(0xE000E468)
#define NVIC_PRI27 REG32(0xE000E46C)
#define NVIC_PRI28 REG32(0xE000E470)
#define NVIC_PRI29 REG32(0xE000E474)
#define NVIC_PRI30 REG32(0xE000E478)
#define NVIC_PRI31 REG32(0xE000E47C)
#define NVIC_PRI32 REG32(0xE000E480)
#define NVIC_PRI33 REG32(0xE000E484)
#define NVIC_PRI34 REG32(0xE000E488)
#define NVIC_PRI35 REG32(0xE000E48C)
#define NVIC_PRI36 REG32(0xE000E490)
#define NVIC_PRI37 REG32(0xE000E494)
#define NVIC_PRI38 REG32(0xE000E498)
#define NVIC_PRI39 REG32(0xE000E49C)
#define NVIC_PRI40 REG32(0xE000E4A0)
#define NVIC_PRI41 REG32(0xE000E4A4)
#define NVIC_PRI42 REG32(0xE000E4A8)
#define NVIC_PRI43 REG32(0xE000E4AC)
#define NVIC_PRI44 REG32(0xE000E4B0)
#define NVIC_PRI45 REG32(0xE000E4B4)
#define NVIC_PRI46 REG32(0xE000E4B8)
#define NVIC_PRI47 REG32(0xE000E4BC)
#define NVIC_PRI48 REG32(0xE000E4C0)
#define NVIC_PRI49 REG32(0xE000E4C4)
#define NVIC_PRI50 REG32(0xE000E4C8)
#define NVIC_PRI51 REG32(0xE000E4CC)
#define NVIC_PRI52 REG32(0xE000E4D0)
#define NVIC_PRI53 REG32(0xE000E4D4)
#define NVIC_PRI54 REG32(0xE000E4D8)
#define NVIC_PRI55 REG32(0xE000E4DC)
#define NVIC_PRI56 REG32(0xE000E4E0)
#define NVIC_PRI57 REG32(0xE000E4E4)
#define NVIC_PRI58 REG32(0xE000E4E8)
#define NVIC_PRI59 REG32(0xE000E4EC)
#define NVIC_CPUID REG32(0xE000ED00)
#define NVIC_INT_CTRL REG32(0xE000ED04)
#define NVIC_VECT_TABLE REG32(0xE000ED08)
#define NVIC_AP_INT_RST REG32(0xE000ED0C)
#define NVIC_SYS_CTRL REG32(0xE000ED10)
#define NVIC_CFG_CTRL REG32(0xE000ED14)
#define NVIC_SYS_H_PRI1 REG32(0xE000ED18)
#define NVIC_SYS_H_PRI2 REG32(0xE000ED1C)
#define NVIC_SYS_H_PRI3 REG32(0xE000ED20)
#define NVIC_SYS_H_CTRL REG32(0xE000ED24)
#define NVIC_FAULT_STA REG32(0xE000ED28)
#define NVIC_HARD_F_STA REG32(0xE000ED2C)
#define NVIC_DBG_F_STA REG32(0xE000ED30)
#define NVIC_MM_F_ADR REG32(0xE000ED34)
#define NVIC_BUS_F_ADR REG32(0xE000ED38)
#define NVIC_SW_TRIG REG32(0xE000EF00)
/* MPU Registers */
#define MPU_TYPE REG32(0xE000ED90)
#define MPU_CTRL REG32(0xE000ED94)
#define MPU_RG_NUM REG32(0xE000ED98)
#define MPU_RG_ADDR REG32(0xE000ED9C)
#define MPU_RG_AT_SZ REG32(0xE000EDA0)
#endif // __CortexM3_H

View File

@ -0,0 +1,158 @@
/*
FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry.
This file is part of the FreeRTOS.org distribution.
FreeRTOS.org is free software; you can redistribute it and/or modify it
under the terms of the GNU General Public License (version 2) as published
by the Free Software Foundation and modified by the FreeRTOS exception.
**NOTE** The exception to the GPL is included to allow you to distribute a
combined work that includes FreeRTOS.org without being obliged to provide
the source code for any proprietary components. Alternative commercial
license and support terms are also available upon request. See the
licensing section of http://www.FreeRTOS.org for full details.
FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
more details.
You should have received a copy of the GNU General Public License along
with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59
Temple Place, Suite 330, Boston, MA 02111-1307 USA.
***************************************************************************
* *
* Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation *
* *
* This is a concise, step by step, 'hands on' guide that describes both *
* general multitasking concepts and FreeRTOS specifics. It presents and *
* explains numerous examples that are written using the FreeRTOS API. *
* Full source code for all the examples is provided in an accompanying *
* .zip file. *
* *
***************************************************************************
1 tab == 4 spaces!
Please ensure to read the configuration and relevant port sections of the
online documentation.
http://www.FreeRTOS.org - Documentation, latest information, license and
contact details.
http://www.SafeRTOS.com - A version that is certified for use in safety
critical systems.
http://www.OpenRTOS.com - Commercial support, development, porting,
licensing and training services.
*/
#ifndef FREERTOS_CONFIG_H
#define FREERTOS_CONFIG_H
#include "LPC17xx.h"
#include "LPC17xx_defs.h"
/*-----------------------------------------------------------
* Application specific definitions.
*
* These definitions should be adjusted for your particular hardware and
* application requirements.
*
* THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
* FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
*----------------------------------------------------------*/
#define configUSE_PREEMPTION 1
#define configUSE_IDLE_HOOK 0
#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 )
#define configUSE_TICK_HOOK 1
#define configCPU_CLOCK_HZ ( ( unsigned portLONG ) 64000000 )
#define configTICK_RATE_HZ ( ( portTickType ) 1000 )
#define configMINIMAL_STACK_SIZE ( ( unsigned portSHORT ) 80 )
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 19 * 1024 ) )
#define configMAX_TASK_NAME_LEN ( 12 )
#define configUSE_TRACE_FACILITY 1
#define configUSE_16_BIT_TICKS 0
#define configIDLE_SHOULD_YIELD 0
#define configUSE_CO_ROUTINES 0
#define configUSE_MUTEXES 1
#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )
#define configUSE_COUNTING_SEMAPHORES 0
#define configUSE_ALTERNATIVE_API 0
#define configCHECK_FOR_STACK_OVERFLOW 2
#define configUSE_RECURSIVE_MUTEXES 1
#define configQUEUE_REGISTRY_SIZE 10
#define configGENERATE_RUN_TIME_STATS 1
/* Set the following definitions to 1 to include the API function, or zero
to exclude the API function. */
#define INCLUDE_vTaskPrioritySet 1
#define INCLUDE_uxTaskPriorityGet 1
#define INCLUDE_vTaskDelete 1
#define INCLUDE_vTaskCleanUpResources 0
#define INCLUDE_vTaskSuspend 1
#define INCLUDE_vTaskDelayUntil 1
#define INCLUDE_vTaskDelay 1
#define INCLUDE_uxTaskGetStackHighWaterMark 1
/*-----------------------------------------------------------
* Ethernet configuration.
*-----------------------------------------------------------*/
/* MAC address configuration. */
#define configMAC_ADDR0 0x00
#define configMAC_ADDR1 0x12
#define configMAC_ADDR2 0x13
#define configMAC_ADDR3 0x10
#define configMAC_ADDR4 0x15
#define configMAC_ADDR5 0x11
/* IP address configuration. */
#define configIP_ADDR0 192
#define configIP_ADDR1 168
#define configIP_ADDR2 0
#define configIP_ADDR3 201
/* Netmask configuration. */
#define configNET_MASK0 255
#define configNET_MASK1 255
#define configNET_MASK2 255
#define configNET_MASK3 0
/* Use the system definition, if there is one */
#ifdef __NVIC_PRIO_BITS
#define configPRIO_BITS __NVIC_PRIO_BITS
#else
#define configPRIO_BITS 5 /* 32 priority levels */
#endif
/* The lowest priority. */
#define configKERNEL_INTERRUPT_PRIORITY ( 31 << (8 - configPRIO_BITS) )
/* Priority 5, or 160 as only the top three bits are implemented. */
#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( 5 << (8 - configPRIO_BITS) )
/*-----------------------------------------------------------
* Macros required to setup the timer for the run time stats.
*-----------------------------------------------------------*/
extern void vConfigureTimerForRunTimeStats( void );
#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() vConfigureTimerForRunTimeStats()
#define portGET_RUN_TIME_COUNTER_VALUE() T0TC
/* The structure that is passed on the xLCDQueue. Put here for convenience. */
typedef struct
{
char *pcMessage;
} xLCDMessage;
#endif /* FREERTOS_CONFIG_H */

View File

@ -0,0 +1,59 @@
/*
FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry.
This file is part of the FreeRTOS.org distribution.
FreeRTOS.org is free software; you can redistribute it and/or modify it
under the terms of the GNU General Public License (version 2) as published
by the Free Software Foundation and modified by the FreeRTOS exception.
**NOTE** The exception to the GPL is included to allow you to distribute a
combined work that includes FreeRTOS.org without being obliged to provide
the source code for any proprietary components. Alternative commercial
license and support terms are also available upon request. See the
licensing section of http://www.FreeRTOS.org for full details.
FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
more details.
You should have received a copy of the GNU General Public License along
with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59
Temple Place, Suite 330, Boston, MA 02111-1307 USA.
***************************************************************************
* *
* Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation *
* *
* This is a concise, step by step, 'hands on' guide that describes both *
* general multitasking concepts and FreeRTOS specifics. It presents and *
* explains numerous examples that are written using the FreeRTOS API. *
* Full source code for all the examples is provided in an accompanying *
* .zip file. *
* *
***************************************************************************
1 tab == 4 spaces!
Please ensure to read the configuration and relevant port sections of the
online documentation.
http://www.FreeRTOS.org - Documentation, latest information, license and
contact details.
http://www.SafeRTOS.com - A version that is certified for use in safety
critical systems.
http://www.OpenRTOS.com - Commercial support, development, porting,
licensing and training services.
*/
#ifndef LED_HH
#define LED_HH
void vToggleLED( unsigned long ulLED );
void vSetLEDState( unsigned long ulLED, long lState );
long lGetLEDState( unsigned long ulLED );
#endif

View File

@ -0,0 +1,364 @@
/*****************************************************************************
* Copyright (c) 2009 Rowley Associates Limited. *
* *
* This file may be distributed under the terms of the License Agreement *
* provided with this software. *
* *
* THIS FILE IS PROVIDED AS IS WITH NO WARRANTY OF ANY KIND, INCLUDING THE *
* WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. *
*****************************************************************************/
/*****************************************************************************
* Preprocessor Definitions
* ------------------------
*
* STARTUP_FROM_RESET
*
* If defined, the program will startup from power-on/reset. If not defined
* the program will just loop endlessly from power-on/reset.
*
* This definition is not defined by default on this target because the
* debugger is unable to reset this target and maintain control of it over the
* JTAG interface. The advantage of doing this is that it allows the debugger
* to reset the CPU and run programs from a known reset CPU state on each run.
* It also acts as a safety net if you accidently download a program in FLASH
* that crashes and prevents the debugger from taking control over JTAG
* rendering the target unusable over JTAG. The obvious disadvantage of doing
* this is that your application will not startup without the debugger.
*
* We advise that on this target you keep STARTUP_FROM_RESET undefined whilst
* you are developing and only define STARTUP_FROM_RESET when development is
* complete.A
*
*
* CONFIGURE_USB
*
* If defined, the USB clock will be configured.
*
*****************************************************************************/
#include <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 */

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,147 @@
/*
FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry.
This file is part of the FreeRTOS.org distribution.
FreeRTOS.org is free software; you can redistribute it and/or modify it
under the terms of the GNU General Public License (version 2) as published
by the Free Software Foundation and modified by the FreeRTOS exception.
**NOTE** The exception to the GPL is included to allow you to distribute a
combined work that includes FreeRTOS.org without being obliged to provide
the source code for any proprietary components. Alternative commercial
license and support terms are also available upon request. See the
licensing section of http://www.FreeRTOS.org for full details.
FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
more details.
You should have received a copy of the GNU General Public License along
with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59
Temple Place, Suite 330, Boston, MA 02111-1307 USA.
***************************************************************************
* *
* Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation *
* *
* This is a concise, step by step, 'hands on' guide that describes both *
* general multitasking concepts and FreeRTOS specifics. It presents and *
* explains numerous examples that are written using the FreeRTOS API. *
* Full source code for all the examples is provided in an accompanying *
* .zip file. *
* *
***************************************************************************
1 tab == 4 spaces!
Please ensure to read the configuration and relevant port sections of the
online documentation.
http://www.FreeRTOS.org - Documentation, latest information, license and
contact details.
http://www.SafeRTOS.com - A version that is certified for use in safety
critical systems.
http://www.OpenRTOS.com - Commercial support, development, porting,
licensing and training services.
*/
/* FreeRTOS.org includes. */
#include "FreeRTOS.h"
/* Demo application includes. */
#include "partest.h"
#define partstFIRST_IO ( ( unsigned portLONG ) 0x04 )
#define partstNUM_LEDS ( 5 )
#define partstALL_OUTPUTS_OFF ( ( unsigned portLONG ) 0xff )
/*-----------------------------------------------------------
* Simple parallel port IO routines.
*-----------------------------------------------------------*/
void vParTestInitialise( void )
{
PINSEL10 = 0;
FIO2DIR = 0x000000FF;
FIO2MASK = 0x00000000;
FIO2CLR = 0xFF;
SCS |= (1<<0); //fast mode for port 0 and 1
FIO2CLR = partstALL_OUTPUTS_OFF;
}
/*-----------------------------------------------------------*/
void vParTestSetLED( unsigned portBASE_TYPE uxLED, signed portBASE_TYPE xValue )
{
unsigned portLONG ulLED = partstFIRST_IO;
if( uxLED < partstNUM_LEDS )
{
/* Rotate to the wanted bit of port */
ulLED <<= ( unsigned portLONG ) uxLED;
/* Set of clear the output. */
if( xValue )
{
FIO2CLR = ulLED;
}
else
{
FIO2SET = ulLED;
}
}
}
/*-----------------------------------------------------------*/
void vParTestToggleLED( unsigned portBASE_TYPE uxLED )
{
unsigned portLONG ulLED = partstFIRST_IO, ulCurrentState;
if( uxLED < partstNUM_LEDS )
{
/* Rotate to the wanted bit of port 0. Only P10 to P13 have an LED
attached. */
ulLED <<= ( unsigned portLONG ) uxLED;
/* If this bit is already set, clear it, and visa versa. */
ulCurrentState = FIO2PIN;
if( ulCurrentState & ulLED )
{
FIO2CLR = ulLED;
}
else
{
FIO2SET = ulLED;
}
}
}
/*-----------------------------------------------------------*/
unsigned portBASE_TYPE uxParTextGetLED( unsigned portBASE_TYPE uxLED )
{
unsigned portLONG ulLED = partstFIRST_IO;
ulLED <<= ( unsigned portLONG ) uxLED;
return ( FIO2PIN & ulLED );
}
/*-----------------------------------------------------------*/
long lParTestGetLEDState( unsigned portBASE_TYPE uxLED )
{
return 0;
}
/*-----------------------------------------------------------*/
int __putchar( int x )
{
/* Not used. */
}

View File

@ -0,0 +1,57 @@
<!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 &quot;load(\&quot;$(TargetsDir)/LPC1000/LPC1000_LinkPatch.js\&quot;);patch(\&quot;$(TargetPath)\&quot;);&quot;" 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>

View File

@ -0,0 +1,55 @@
<!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>

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,405 @@
/*
FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry.
This file is part of the FreeRTOS.org distribution.
FreeRTOS.org is free software; you can redistribute it and/or modify it
under the terms of the GNU General Public License (version 2) as published
by the Free Software Foundation and modified by the FreeRTOS exception.
**NOTE** The exception to the GPL is included to allow you to distribute a
combined work that includes FreeRTOS.org without being obliged to provide
the source code for any proprietary components. Alternative commercial
license and support terms are also available upon request. See the
licensing section of http://www.FreeRTOS.org for full details.
FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
more details.
You should have received a copy of the GNU General Public License along
with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59
Temple Place, Suite 330, Boston, MA 02111-1307 USA.
***************************************************************************
* *
* Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation *
* *
* This is a concise, step by step, 'hands on' guide that describes both *
* general multitasking concepts and FreeRTOS specifics. It presents and *
* explains numerous examples that are written using the FreeRTOS API. *
* Full source code for all the examples is provided in an accompanying *
* .zip file. *
* *
***************************************************************************
1 tab == 4 spaces!
Please ensure to read the configuration and relevant port sections of the
online documentation.
http://www.FreeRTOS.org - Documentation, latest information, license and
contact details.
http://www.SafeRTOS.com - A version that is certified for use in safety
critical systems.
http://www.OpenRTOS.com - Commercial support, development, porting,
licensing and training services.
*/
/*
* Creates all the demo application tasks, then starts the scheduler. The WEB
* documentation provides more details of the standard demo application tasks
* (which just exist to test the kernel port and provide an example of how to use
* each FreeRTOS API function).
*
* In addition to the standard demo tasks, the following tasks and tests are
* defined and/or created within this file:
*
* "LCD" task - the LCD task is a 'gatekeeper' task. It is the only task that
* is permitted to access the display directly. Other tasks wishing to write a
* message to the LCD send the message on a queue to the LCD task instead of
* accessing the LCD themselves. The LCD task just blocks on the queue waiting
* for messages - waking and displaying the messages as they arrive. The use
* of a gatekeeper in this manner permits both tasks and interrupts to write to
* the LCD without worrying about mutual exclusion. This is demonstrated by the
* check hook (see below) which sends messages to the display even though it
* executes from an interrupt context.
*
* "Check" hook - This only executes fully every five seconds from the tick
* hook. Its main function is to check that all the standard demo tasks are
* still operational. Should any unexpected behaviour be discovered within a
* demo task then the tick hook will write an error to the LCD (via the LCD task).
* If all the demo tasks are executing with their expected behaviour then the
* check hook writes PASS to the LCD (again via the LCD task), as described above.
* The check hook also toggles LED 4 each time it executes.
*
* LED tasks - These just demonstrate how multiple instances of a single task
* definition can be created. Each LED task simply toggles an LED. The task
* parameter is used to pass the number of the LED to be toggled into the task.
*
* "uIP" task - This is the task that handles the uIP stack. All TCP/IP
* processing is performed in this task.
*/
/* Standard includes. */
#include <stdio.h>
/* Scheduler includes. */
#include "FreeRTOS.h"
#include "task.h"
#include "queue.h"
#include "semphr.h"
/* Hardware library includes. */
#include "LPC17xx_defs.h"
/* Demo app includes. */
#include "BlockQ.h"
#include "integer.h"
#include "blocktim.h"
#include "flash.h"
#include "partest.h"
#include "semtest.h"
#include "PollQ.h"
#include "GenQTest.h"
#include "QPeek.h"
#include "recmutex.h"
/*-----------------------------------------------------------*/
/* The number of LED tasks that will be created. */
#define mainNUM_LED_TASKS ( 6 )
/* The time between cycles of the 'check' functionality (defined within the
tick hook. */
#define mainCHECK_DELAY ( ( portTickType ) 5000 / portTICK_RATE_MS )
/* Task priorities. */
#define mainQUEUE_POLL_PRIORITY ( tskIDLE_PRIORITY + 2 )
#define mainSEM_TEST_PRIORITY ( tskIDLE_PRIORITY + 1 )
#define mainBLOCK_Q_PRIORITY ( tskIDLE_PRIORITY + 2 )
#define mainUIP_TASK_PRIORITY ( tskIDLE_PRIORITY + 3 )
#define mainLCD_TASK_PRIORITY ( tskIDLE_PRIORITY + 2 )
#define mainINTEGER_TASK_PRIORITY ( tskIDLE_PRIORITY )
#define mainGEN_QUEUE_TASK_PRIORITY ( tskIDLE_PRIORITY )
#define mainFLASH_TASK_PRIORITY ( tskIDLE_PRIORITY + 2 )
/* The WEB server has a larger stack as it utilises stack hungry string
handling library calls. */
#define mainBASIC_WEB_STACK_SIZE ( configMINIMAL_STACK_SIZE * 4 )
/* The length of the queue used to send messages to the LCD task. */
#define mainQUEUE_SIZE ( 3 )
/* The task that is toggled by the check task. */
#define mainCHECK_TASK_LED ( 4 )
/*-----------------------------------------------------------*/
/*
* Configure the hardware for the demo.
*/
static void prvSetupHardware( void );
/*
* Very simple task that toggles an LED.
*/
static void vLEDTask( void *pvParameters );
/*
* The task that handles the uIP stack. All TCP/IP processing is performed in
* this task.
*/
extern void vuIP_Task( void *pvParameters );
/*
* The LCD gatekeeper task as described in the comments at the top of this file.
* */
static void vLCDTask( void *pvParameters );
/*-----------------------------------------------------------*/
/* The queue used to send messages to the LCD task. */
xQueueHandle xLCDQueue;
/*-----------------------------------------------------------*/
int main( void )
{
long l;
/* Configure the hardware for use by this demo. */
prvSetupHardware();
/* Start the standard demo tasks. These are just here to exercise the
kernel port and provide examples of how the FreeRTOS API can be used. */
vStartBlockingQueueTasks( mainBLOCK_Q_PRIORITY );
vCreateBlockTimeTasks();
vStartSemaphoreTasks( mainSEM_TEST_PRIORITY );
vStartPolledQueueTasks( mainQUEUE_POLL_PRIORITY );
vStartIntegerMathTasks( mainINTEGER_TASK_PRIORITY );
vStartGenericQueueTasks( mainGEN_QUEUE_TASK_PRIORITY );
vStartQueuePeekTasks();
vStartRecursiveMutexTasks();
vStartLEDFlashTasks( mainFLASH_TASK_PRIORITY );
/* Create the uIP task. The WEB server runs in this task. */
xTaskCreate( vuIP_Task, ( signed char * ) "uIP", mainBASIC_WEB_STACK_SIZE, ( void * ) NULL, mainUIP_TASK_PRIORITY, NULL );
/* Create the queue used by the LCD task. Messages for display on the LCD
are received via this queue. */
xLCDQueue = xQueueCreate( mainQUEUE_SIZE, sizeof( xLCDMessage ) );
/* Start the LCD gatekeeper task - as described in the comments at the top
of this file. */
xTaskCreate( vLCDTask, ( signed portCHAR * ) "LCD", configMINIMAL_STACK_SIZE * 2, NULL, mainLCD_TASK_PRIORITY, NULL );
/* Start the scheduler. */
vTaskStartScheduler();
/* Will only get here if there was insufficient memory to create the idle
task. The idle task is created within vTaskStartScheduler(). */
for( ;; );
}
/*-----------------------------------------------------------*/
void vLCDTask( void *pvParameters )
{
xLCDMessage xMessage;
unsigned long ulRow = 0;
char cIPAddr[ 17 ]; /* To fit max IP address length of xxx.xxx.xxx.xxx\0 */
( void ) pvParameters;
/* The LCD gatekeeper task as described in the comments at the top of this
file. */
/* Initialise the LCD and display a startup message that includes the
configured IP address. */
sprintf( cIPAddr, "%d.%d.%d.%d", configIP_ADDR0, configIP_ADDR1, configIP_ADDR2, configIP_ADDR3 );
for( ;; )
{
/* Wait for a message to arrive to be displayed. */
while( xQueueReceive( xLCDQueue, &xMessage, portMAX_DELAY ) != pdPASS );
}
}
/*-----------------------------------------------------------*/
void vApplicationTickHook( void )
{
static xLCDMessage xMessage = { "PASS" };
static unsigned portLONG ulTicksSinceLastDisplay = 0;
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
/* Called from every tick interrupt as described in the comments at the top
of this file.
Have enough ticks passed to make it time to perform our health status
check again? */
ulTicksSinceLastDisplay++;
if( ulTicksSinceLastDisplay >= mainCHECK_DELAY )
{
/* Reset the counter so these checks run again in mainCHECK_DELAY
ticks time. */
ulTicksSinceLastDisplay = 0;
/* Has an error been found in any task? */
if( xAreGenericQueueTasksStillRunning() != pdTRUE )
{
xMessage.pcMessage = "ERROR: GEN Q";
}
else if( xAreQueuePeekTasksStillRunning() != pdTRUE )
{
xMessage.pcMessage = "ERROR: PEEK Q";
}
else if( xAreBlockingQueuesStillRunning() != pdTRUE )
{
xMessage.pcMessage = "ERROR: BLOCK Q";
}
else if( xAreBlockTimeTestTasksStillRunning() != pdTRUE )
{
xMessage.pcMessage = "ERROR: BLOCK TIME";
}
else if( xAreSemaphoreTasksStillRunning() != pdTRUE )
{
xMessage.pcMessage = "ERROR: SEMAPHR";
}
else if( xArePollingQueuesStillRunning() != pdTRUE )
{
xMessage.pcMessage = "ERROR: POLL Q";
}
else if( xAreIntegerMathsTaskStillRunning() != pdTRUE )
{
xMessage.pcMessage = "ERROR: INT MATH";
}
else if( xAreRecursiveMutexTasksStillRunning() != pdTRUE )
{
xMessage.pcMessage = "ERROR: REC MUTEX";
}
/* Send the message to the OLED gatekeeper for display. The
xHigherPriorityTaskWoken parameter is not actually used here
as this function is running in the tick interrupt anyway - but
it must still be supplied. */
xHigherPriorityTaskWoken = pdFALSE;
xQueueSendFromISR( xLCDQueue, &xMessage, &xHigherPriorityTaskWoken );
/* Also toggle and LED. This can be done from here because in this port
the LED toggling functions don't use critical sections. */
vParTestToggleLED( mainCHECK_TASK_LED );
}
}
/*-----------------------------------------------------------*/
void prvSetupHardware( void )
{
/* Disable peripherals power. */
PCONP = 0;
/* Enable GPIO power. */
PCONP = PCONP_PCGPIO;
/* Disable TPIU. */
PINSEL10 = 0;
/* Disconnect the main PLL. */
PLL0CON &= ~PLLCON_PLLC;
PLL0FEED = PLLFEED_FEED1;
PLL0FEED = PLLFEED_FEED2;
while ((PLL0STAT & PLLSTAT_PLLC) != 0);
/* Turn off the main PLL. */
PLL0CON &= ~PLLCON_PLLE;
PLL0FEED = PLLFEED_FEED1;
PLL0FEED = PLLFEED_FEED2;
while ((PLL0STAT & PLLSTAT_PLLE) != 0);
/* No CPU clock divider. */
CCLKCFG = 0;
/* OSCEN. */
SCS = 0x20;
while ((SCS & 0x40) == 0);
/* Use main oscillator. */
CLKSRCSEL = 1;
PLL0CFG = (PLLCFG_MUL16 | PLLCFG_DIV1);
PLL0FEED = PLLFEED_FEED1;
PLL0FEED = PLLFEED_FEED2;
/* Activate the PLL by turning it on then feeding the correct
sequence of bytes. */
PLL0CON = PLLCON_PLLE;
PLL0FEED = PLLFEED_FEED1;
PLL0FEED = PLLFEED_FEED2;
/* 6x CPU clock divider (64 MHz) */
CCLKCFG = 5;
/* Wait for the PLL to lock. */
while ((PLL0STAT & PLLSTAT_PLOCK) == 0);
/* Connect the PLL. */
PLL0CON = PLLCON_PLLC | PLLCON_PLLE;
PLL0FEED = PLLFEED_FEED1;
PLL0FEED = PLLFEED_FEED2;
/* Setup the peripheral bus to be the same as the PLL output (64 MHz). */
PCLKSEL0 = 0x05555555;
/* Configure LED GPIOs as outputs. */
FIO2DIR = 0xff;
FIO2CLR = 0xff;
FIO2MASK = 0;
}
/*-----------------------------------------------------------*/
void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed portCHAR *pcTaskName )
{
/* This function will get called if a task overflows its stack. */
( void ) pxTask;
( void ) pcTaskName;
for( ;; );
}
/*-----------------------------------------------------------*/
void vConfigureTimerForRunTimeStats( void )
{
const unsigned long TCR_COUNT_RESET = 2, CTCR_CTM_TIMER = 0x00, TCR_COUNT_ENABLE = 0x01;
/* This function configures a timer that is used as the time base when
collecting run time statistical information - basically the percentage
of CPU time that each task is utilising. It is called automatically when
the scheduler is started (assuming configGENERATE_RUN_TIME_STATS is set
to 1. */
/* Power up and feed the timer. */
PCONP |= 0x02UL;
PCLKSEL0 = (PCLKSEL0 & (~(0x3<<2))) | (0x01 << 2);
/* Reset Timer 0 */
T0TCR = TCR_COUNT_RESET;
/* Just count up. */
T0CTCR = CTCR_CTM_TIMER;
/* Prescale to a frequency that is good enough to get a decent resolution,
but not too fast so as to overflow all the time. */
T0PR = ( configCPU_CLOCK_HZ / 10000UL ) - 1UL;
/* Start the counter. */
T0TCR = TCR_COUNT_ENABLE;
}
/*-----------------------------------------------------------*/

View File

@ -0,0 +1,293 @@
/*
Copyright 2001, 2002 Georges Menie (www.menie.org)
stdarg version contributed by Christian Ettinger
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU Lesser General Public License as published by
the Free Software Foundation; either version 2 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public License
along with this program; if not, write to the Free Software
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
/*
putchar is the only external dependency for this file,
if you have a working putchar, leave it commented out.
If not, uncomment the define below and
replace outbyte(c) by your own function call.
*/
#define putchar(c) c
#include <stdarg.h>
static void printchar(char **str, int c)
{
//extern int putchar(int c);
if (str) {
**str = (char)c;
++(*str);
}
else
{
(void)putchar(c);
}
}
#define PAD_RIGHT 1
#define PAD_ZERO 2
static int prints(char **out, const char *string, int width, int pad)
{
register int pc = 0, padchar = ' ';
if (width > 0) {
register int len = 0;
register const char *ptr;
for (ptr = string; *ptr; ++ptr) ++len;
if (len >= width) width = 0;
else width -= len;
if (pad & PAD_ZERO) padchar = '0';
}
if (!(pad & PAD_RIGHT)) {
for ( ; width > 0; --width) {
printchar (out, padchar);
++pc;
}
}
for ( ; *string ; ++string) {
printchar (out, *string);
++pc;
}
for ( ; width > 0; --width) {
printchar (out, padchar);
++pc;
}
return pc;
}
/* the following should be enough for 32 bit int */
#define PRINT_BUF_LEN 12
static int printi(char **out, int i, int b, int sg, int width, int pad, int letbase)
{
char print_buf[PRINT_BUF_LEN];
register char *s;
register int t, neg = 0, pc = 0;
register unsigned int u = (unsigned int)i;
if (i == 0) {
print_buf[0] = '0';
print_buf[1] = '\0';
return prints (out, print_buf, width, pad);
}
if (sg && b == 10 && i < 0) {
neg = 1;
u = (unsigned int)-i;
}
s = print_buf + PRINT_BUF_LEN-1;
*s = '\0';
while (u) {
t = (unsigned int)u % b;
if( t >= 10 )
t += letbase - '0' - 10;
*--s = (char)(t + '0');
u /= b;
}
if (neg) {
if( width && (pad & PAD_ZERO) ) {
printchar (out, '-');
++pc;
--width;
}
else {
*--s = '-';
}
}
return pc + prints (out, s, width, pad);
}
static int print( char **out, const char *format, va_list args )
{
register int width, pad;
register int pc = 0;
char scr[2];
for (; *format != 0; ++format) {
if (*format == '%') {
++format;
width = pad = 0;
if (*format == '\0') break;
if (*format == '%') goto out;
if (*format == '-') {
++format;
pad = PAD_RIGHT;
}
while (*format == '0') {
++format;
pad |= PAD_ZERO;
}
for ( ; *format >= '0' && *format <= '9'; ++format) {
width *= 10;
width += *format - '0';
}
if( *format == 's' ) {
register char *s = (char *)va_arg( args, int );
pc += prints (out, s?s:"(null)", width, pad);
continue;
}
if( *format == 'd' ) {
pc += printi (out, va_arg( args, int ), 10, 1, width, pad, 'a');
continue;
}
if( *format == 'x' ) {
pc += printi (out, va_arg( args, int ), 16, 0, width, pad, 'a');
continue;
}
if( *format == 'X' ) {
pc += printi (out, va_arg( args, int ), 16, 0, width, pad, 'A');
continue;
}
if( *format == 'u' ) {
pc += printi (out, va_arg( args, int ), 10, 0, width, pad, 'a');
continue;
}
if( *format == 'c' ) {
/* char are converted to int then pushed on the stack */
scr[0] = (char)va_arg( args, int );
scr[1] = '\0';
pc += prints (out, scr, width, pad);
continue;
}
}
else {
out:
printchar (out, *format);
++pc;
}
}
if (out) **out = '\0';
va_end( args );
return pc;
}
int printf(const char *format, ...)
{
va_list args;
va_start( args, format );
return print( 0, format, args );
}
int sprintf(char *out, const char *format, ...)
{
va_list args;
va_start( args, format );
return print( &out, format, args );
}
int snprintf( char *buf, unsigned int count, const char *format, ... )
{
va_list args;
( void ) count;
va_start( args, format );
return print( &buf, format, args );
}
#ifdef TEST_PRINTF
int main(void)
{
char *ptr = "Hello world!";
char *np = 0;
int i = 5;
unsigned int bs = sizeof(int)*8;
int mi;
char buf[80];
mi = (1 << (bs-1)) + 1;
printf("%s\n", ptr);
printf("printf test\n");
printf("%s is null pointer\n", np);
printf("%d = 5\n", i);
printf("%d = - max int\n", mi);
printf("char %c = 'a'\n", 'a');
printf("hex %x = ff\n", 0xff);
printf("hex %02x = 00\n", 0);
printf("signed %d = unsigned %u = hex %x\n", -3, -3, -3);
printf("%d %s(s)%", 0, "message");
printf("\n");
printf("%d %s(s) with %%\n", 0, "message");
sprintf(buf, "justif: \"%-10s\"\n", "left"); printf("%s", buf);
sprintf(buf, "justif: \"%10s\"\n", "right"); printf("%s", buf);
sprintf(buf, " 3: %04d zero padded\n", 3); printf("%s", buf);
sprintf(buf, " 3: %-4d left justif.\n", 3); printf("%s", buf);
sprintf(buf, " 3: %4d right justif.\n", 3); printf("%s", buf);
sprintf(buf, "-3: %04d zero padded\n", -3); printf("%s", buf);
sprintf(buf, "-3: %-4d left justif.\n", -3); printf("%s", buf);
sprintf(buf, "-3: %4d right justif.\n", -3); printf("%s", buf);
return 0;
}
/*
* if you compile this file with
* gcc -Wall $(YOUR_C_OPTIONS) -DTEST_PRINTF -c printf.c
* you will get a normal warning:
* printf.c:214: warning: spurious trailing `%' in format
* this line is testing an invalid % at the end of the format string.
*
* this should display (on 32bit int machine) :
*
* Hello world!
* printf test
* (null) is null pointer
* 5 = 5
* -2147483647 = - max int
* char a = 'a'
* hex ff = ff
* hex 00 = 00
* signed -3 = unsigned 4294967293 = hex fffffffd
* 0 message(s)
* 0 message(s) with %
* justif: "left "
* justif: " right"
* 3: 0003 zero padded
* 3: 3 left justif.
* 3: 3 right justif.
* -3: -003 zero padded
* -3: -3 left justif.
* -3: -3 right justif.
*/
#endif
/* To keep linker happy. */
int write( int i, char* c, int n)
{
(void)i;
(void)n;
(void)c;
return 0;
}

View File

@ -0,0 +1,40 @@
/******************************************************************************
* @file: system_LPC17xx.h
* @purpose: CMSIS Cortex-M3 Device Peripheral Access Layer Header File
* for the NXP LPC17xx Device Series
* @version: V1.0
* @date: 25. Nov. 2008
*----------------------------------------------------------------------------
*
* Copyright (C) 2008 ARM Limited. All rights reserved.
*
* ARM Limited (ARM) is supplying this software for use with Cortex-M3
* processor based microcontrollers. This file can be freely distributed
* within development tools that are supporting such ARM based processors.
*
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
* ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
* CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
*
******************************************************************************/
#ifndef __SYSTEM_LPC17xx_H
#define __SYSTEM_LPC17xx_H
extern uint32_t SystemFrequency; /*!< System Clock Frequency (Core Clock) */
/**
* Initialize the system
*
* @param none
* @return none
*
* @brief Setup the microcontroller system.
* Initialize the System and update the SystemFrequency variable.
*/
extern void SystemInit (void);
#endif

View File

@ -0,0 +1,42 @@
/*
* Copyright (c) 2006, Swedish Institute of Computer Science.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the Institute nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*
* This file is part of the uIP TCP/IP stack
*
* $Id: clock-arch.h,v 1.2 2006/06/12 08:00:31 adam Exp $
*/
#ifndef __CLOCK_ARCH_H__
#define __CLOCK_ARCH_H__
#include "FreeRTOS.h"
typedef unsigned long clock_time_t;
#define CLOCK_CONF_SECOND configTICK_RATE_HZ
#endif /* __CLOCK_ARCH_H__ */

View File

@ -0,0 +1,465 @@
/******************************************************************
***** *****
***** Ver.: 1.0 *****
***** Date: 07/05/2001 *****
***** Auth: Andreas Dannenberg *****
***** HTWK Leipzig *****
***** university of applied sciences *****
***** Germany *****
***** Func: ethernet packet-driver for use with LAN- *****
***** controller CS8900 from Crystal/Cirrus Logic *****
***** *****
***** Keil: Module modified for use with Philips *****
***** LPC2378 EMAC Ethernet controller *****
***** *****
******************************************************************/
/* Adapted from file originally written by Andreas Dannenberg. Supplied with permission. */
#include "FreeRTOS.h"
#include "semphr.h"
#include "task.h"
#include "emac.h"
#include "LPC17xx_defs.h"
#define configPINSEL2_VALUE 0x50150105
/* The semaphore used to wake the uIP task when data arives. */
xSemaphoreHandle xEMACSemaphore = NULL;
static unsigned short *rptr;
static unsigned short *tptr;
static unsigned short SwapBytes( unsigned short Data )
{
return( Data >> 8 ) | ( Data << 8 );
}
// Keil: function added to write PHY
int write_PHY( int PhyReg, int Value )
{
unsigned int tout;
const unsigned int uiMaxTime = 10;
MAC_MADR = DP83848C_DEF_ADR | PhyReg;
MAC_MWTD = Value;
/* Wait utill operation completed */
tout = 0;
for( tout = 0; tout < uiMaxTime; tout++ )
{
if( (MAC_MIND & MIND_BUSY) == 0 )
{
break;
}
vTaskDelay( 2 );
}
if( tout < uiMaxTime )
{
return pdPASS;
}
else
{
return pdFAIL;
}
}
// Keil: function added to read PHY
unsigned short read_PHY( unsigned char PhyReg, portBASE_TYPE *pxStatus )
{
unsigned int tout;
const unsigned int uiMaxTime = 10;
MAC_MADR = DP83848C_DEF_ADR | PhyReg;
MAC_MCMD = MCMD_READ;
/* Wait until operation completed */
tout = 0;
for( tout = 0; tout < uiMaxTime; tout++ )
{
if( (MAC_MIND & MIND_BUSY) == 0 )
{
break;
}
vTaskDelay( 2 );
}
MAC_MCMD = 0;
if( tout >= uiMaxTime )
{
*pxStatus = pdFAIL;
}
return( MAC_MRDD );
}
// Keil: function added to initialize Rx Descriptors
void rx_descr_init( void )
{
unsigned int i;
for( i = 0; i < NUM_RX_FRAG; i++ )
{
RX_DESC_PACKET( i ) = RX_BUF( i );
RX_DESC_CTRL( i ) = RCTRL_INT | ( ETH_FRAG_SIZE - 1 );
RX_STAT_INFO( i ) = 0;
RX_STAT_HASHCRC( i ) = 0;
}
/* Set EMAC Receive Descriptor Registers. */
MAC_RXDESCRIPTOR = RX_DESC_BASE;
MAC_RXSTATUS = RX_STAT_BASE;
MAC_RXDESCRIPTORNUM = NUM_RX_FRAG - 1;
/* Rx Descriptors Point to 0 */
MAC_RXCONSUMEINDEX = 0;
}
// Keil: function added to initialize Tx Descriptors
void tx_descr_init( void )
{
unsigned int i;
for( i = 0; i < NUM_TX_FRAG; i++ )
{
TX_DESC_PACKET( i ) = TX_BUF( i );
TX_DESC_CTRL( i ) = 0;
TX_STAT_INFO( i ) = 0;
}
/* Set EMAC Transmit Descriptor Registers. */
MAC_TXDESCRIPTOR = TX_DESC_BASE;
MAC_TXSTATUS = TX_STAT_BASE;
MAC_TXDESCRIPTORNUM = NUM_TX_FRAG - 1;
/* Tx Descriptors Point to 0 */
MAC_TXPRODUCEINDEX = 0;
}
// configure port-pins for use with LAN-controller,
// reset it and send the configuration-sequence
portBASE_TYPE Init_EMAC( void )
{
portBASE_TYPE xReturn = pdPASS;
// Keil: function modified to access the EMAC
// Initializes the EMAC ethernet controller
volatile unsigned int regv, tout, id1, id2;
/* Enable P1 Ethernet Pins. */
PINSEL2 = configPINSEL2_VALUE;
PINSEL3 = ( PINSEL3 &~0x0000000F ) | 0x00000005;
/* Power Up the EMAC controller. */
PCONP |= PCONP_PCENET;
vTaskDelay( 2 );
/* Reset all EMAC internal modules. */
MAC_MAC1 = MAC1_RES_TX | MAC1_RES_MCS_TX | MAC1_RES_RX | MAC1_RES_MCS_RX | MAC1_SIM_RES | MAC1_SOFT_RES;
MAC_COMMAND = CR_REG_RES | CR_TX_RES | CR_RX_RES | CR_PASS_RUNT_FRM;
/* A short delay after reset. */
vTaskDelay( 2 );
/* Initialize MAC control registers. */
MAC_MAC1 = MAC1_PASS_ALL;
MAC_MAC2 = MAC2_CRC_EN | MAC2_PAD_EN;
MAC_MAXF = ETH_MAX_FLEN;
MAC_CLRT = CLRT_DEF;
MAC_IPGR = IPGR_DEF;
/* Enable Reduced MII interface. */
MAC_COMMAND = CR_RMII | CR_PASS_RUNT_FRM;
/* Reset Reduced MII Logic. */
MAC_SUPP = SUPP_RES_RMII;
vTaskDelay( 2 );
MAC_SUPP = 0;
/* Put the PHY in reset mode */
write_PHY( PHY_REG_BMCR, 0x8000 );
xReturn = write_PHY( PHY_REG_BMCR, 0x8000 );
/* Wait for hardware reset to end. */
for( tout = 0; tout < 100; tout++ )
{
vTaskDelay( 10 );
regv = read_PHY( PHY_REG_BMCR, &xReturn );
if( !(regv & 0x8000) )
{
/* Reset complete */
break;
}
}
/* Check if this is a DP83848C PHY. */
id1 = read_PHY( PHY_REG_IDR1, &xReturn );
id2 = read_PHY( PHY_REG_IDR2, &xReturn );
if( ((id1 << 16) | (id2 & 0xFFF0)) == DP83848C_ID )
{
/* Set the Ethernet MAC Address registers */
MAC_SA0 = ( emacETHADDR0 << 8 ) | emacETHADDR1;
MAC_SA1 = ( emacETHADDR2 << 8 ) | emacETHADDR3;
MAC_SA2 = ( emacETHADDR4 << 8 ) | emacETHADDR5;
/* Initialize Tx and Rx DMA Descriptors */
rx_descr_init();
tx_descr_init();
/* Receive Broadcast and Perfect Match Packets */
MAC_RXFILTERCTRL = RFC_UCAST_EN | RFC_BCAST_EN | RFC_PERFECT_EN;
/* Create the semaphore used ot wake the uIP task. */
vSemaphoreCreateBinary( xEMACSemaphore );
/* Configure the PHY device */
/* Use autonegotiation about the link speed. */
if( write_PHY(PHY_REG_BMCR, PHY_AUTO_NEG) )
{
/* Wait to complete Auto_Negotiation. */
for( tout = 0; tout < 10; tout++ )
{
vTaskDelay( 100 );
regv = read_PHY( PHY_REG_BMSR, &xReturn );
if( regv & 0x0020 )
{
/* Autonegotiation Complete. */
break;
}
}
}
}
else
{
xReturn = pdFAIL;
}
/* Check the link status. */
if( xReturn == pdPASS )
{
xReturn = pdFAIL;
for( tout = 0; tout < 10; tout++ )
{
vTaskDelay( 100 );
regv = read_PHY( PHY_REG_STS, &xReturn );
if( regv & 0x0001 )
{
/* Link is on. */
xReturn = pdPASS;
break;
}
}
}
if( xReturn == pdPASS )
{
/* Configure Full/Half Duplex mode. */
if( regv & 0x0004 )
{
/* Full duplex is enabled. */
MAC_MAC2 |= MAC2_FULL_DUP;
MAC_COMMAND |= CR_FULL_DUP;
MAC_IPGT = IPGT_FULL_DUP;
}
else
{
/* Half duplex mode. */
MAC_IPGT = IPGT_HALF_DUP;
}
/* Configure 100MBit/10MBit mode. */
if( regv & 0x0002 )
{
/* 10MBit mode. */
MAC_SUPP = 0;
}
else
{
/* 100MBit mode. */
MAC_SUPP = SUPP_SPEED;
}
/* Reset all interrupts */
MAC_INTCLEAR = 0xFFFF;
/* Enable receive and transmit mode of MAC Ethernet core */
MAC_COMMAND |= ( CR_RX_EN | CR_TX_EN );
MAC_MAC1 |= MAC1_REC_EN;
}
return xReturn;
}
// reads a word in little-endian byte order from RX_BUFFER
unsigned short ReadFrame_EMAC( void )
{
return( *rptr++ );
}
// reads a word in big-endian byte order from RX_FRAME_PORT
// (useful to avoid permanent byte-swapping while reading
// TCP/IP-data)
unsigned short ReadFrameBE_EMAC( void )
{
unsigned short ReturnValue;
ReturnValue = SwapBytes( *rptr++ );
return( ReturnValue );
}
// copies bytes from frame port to MCU-memory
// NOTES: * an odd number of byte may only be transfered
// if the frame is read to the end!
// * MCU-memory MUST start at word-boundary
void CopyFromFrame_EMAC( void *Dest, unsigned short Size )
{
unsigned short *piDest; // Keil: Pointer added to correct expression
piDest = Dest; // Keil: Line added
while( Size > 1 )
{
*piDest++ = ReadFrame_EMAC();
Size -= 2;
}
if( Size )
{ // check for leftover byte...
*( unsigned char * ) piDest = ( char ) ReadFrame_EMAC(); // the LAN-Controller will return 0
} // for the highbyte
}
// does a dummy read on frame-I/O-port
// NOTE: only an even number of bytes is read!
void DummyReadFrame_EMAC( unsigned short Size ) // discards an EVEN number of bytes
{ // from RX-fifo
while( Size > 1 )
{
ReadFrame_EMAC();
Size -= 2;
}
}
// Reads the length of the received ethernet frame and checks if the
// destination address is a broadcast message or not
// returns the frame length
unsigned short StartReadFrame( void )
{
unsigned short RxLen;
unsigned int idx;
idx = MAC_RXCONSUMEINDEX;
RxLen = ( RX_STAT_INFO(idx) & RINFO_SIZE ) - 3;
rptr = ( unsigned short * ) RX_DESC_PACKET( idx );
return( RxLen );
}
void EndReadFrame( void )
{
unsigned int idx;
/* DMA free packet. */
idx = MAC_RXCONSUMEINDEX;
if( ++idx == NUM_RX_FRAG )
{
idx = 0;
}
MAC_RXCONSUMEINDEX = idx;
}
unsigned int CheckFrameReceived( void )
{
// Packet received ?
if( MAC_RXPRODUCEINDEX != MAC_RXCONSUMEINDEX )
{ // more packets received ?
return( 1 );
}
else
{
return( 0 );
}
}
unsigned int uiGetEMACRxData( unsigned char *ucBuffer )
{
unsigned int uiLen = 0;
if( MAC_RXPRODUCEINDEX != MAC_RXCONSUMEINDEX )
{
uiLen = StartReadFrame();
CopyFromFrame_EMAC( ucBuffer, uiLen );
EndReadFrame();
}
return uiLen;
}
// requests space in EMAC memory for storing an outgoing frame
void RequestSend( void )
{
unsigned int idx;
idx = MAC_TXPRODUCEINDEX;
tptr = ( unsigned short * ) TX_DESC_PACKET( idx );
}
// check if ethernet controller is ready to accept the
// frame we want to send
unsigned int Rdy4Tx( void )
{
return( 1 ); // the ethernet controller transmits much faster
} // than the CPU can load its buffers
// writes a word in little-endian byte order to TX_BUFFER
void WriteFrame_EMAC( unsigned short Data )
{
*tptr++ = Data;
}
// copies bytes from MCU-memory to frame port
// NOTES: * an odd number of byte may only be transfered
// if the frame is written to the end!
// * MCU-memory MUST start at word-boundary
void CopyToFrame_EMAC( void *Source, unsigned int Size )
{
unsigned short *piSource;
piSource = Source;
Size = ( Size + 1 ) & 0xFFFE; // round Size up to next even number
while( Size > 0 )
{
WriteFrame_EMAC( *piSource++ );
Size -= 2;
}
}
void DoSend_EMAC( unsigned short FrameSize )
{
unsigned int idx;
idx = MAC_TXPRODUCEINDEX;
TX_DESC_CTRL( idx ) = FrameSize | TCTRL_LAST;
if( ++idx == NUM_TX_FRAG )
{
idx = 0;
}
MAC_TXPRODUCEINDEX = idx;
}
void vEMAC_ISR( void )
{
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
/* Clear the interrupt. */
MAC_INTCLEAR = 0xffff;
/* Ensure the uIP task is not blocked as data has arrived. */
xSemaphoreGiveFromISR( xEMACSemaphore, &xHigherPriorityTaskWoken );
portEND_SWITCHING_ISR( xHigherPriorityTaskWoken );
}

View File

@ -0,0 +1,324 @@
/*----------------------------------------------------------------------------
* LPC2378 Ethernet Definitions
*----------------------------------------------------------------------------
* Name: EMAC.H
* Purpose: Philips LPC2378 EMAC hardware definitions
*----------------------------------------------------------------------------
* Copyright (c) 2006 KEIL - An ARM Company. All rights reserved.
*---------------------------------------------------------------------------*/
#ifndef __EMAC_H
#define __EMAC_H
/* MAC address definition. The MAC address must be unique on the network. */
#define emacETHADDR0 0
#define emacETHADDR1 0xbd
#define emacETHADDR2 0x33
#define emacETHADDR3 0x02
#define emacETHADDR4 0x64
#define emacETHADDR5 0x24
/* EMAC Memory Buffer configuration for 16K Ethernet RAM. */
#define NUM_RX_FRAG 4 /* Num.of RX Fragments 4*1536= 6.0kB */
#define NUM_TX_FRAG 2 /* Num.of TX Fragments 2*1536= 3.0kB */
#define ETH_FRAG_SIZE 1536 /* Packet Fragment size 1536 Bytes */
#define ETH_MAX_FLEN 1536 /* Max. Ethernet Frame Size */
/* EMAC variables located in 16K Ethernet SRAM */
//extern unsigned char xEthDescriptors[];
#define RX_DESC_BASE (0x2007c000UL)
#define RX_STAT_BASE (RX_DESC_BASE + NUM_RX_FRAG*8)
#define TX_DESC_BASE (RX_STAT_BASE + NUM_RX_FRAG*8)
#define TX_STAT_BASE (TX_DESC_BASE + NUM_TX_FRAG*8)
#define RX_BUF_BASE (TX_STAT_BASE + NUM_TX_FRAG*4)
#define TX_BUF_BASE (RX_BUF_BASE + NUM_RX_FRAG*ETH_FRAG_SIZE)
#define TX_BUF_END (TX_BUF_BASE + NUM_TX_FRAG*ETH_FRAG_SIZE)
/* RX and TX descriptor and status definitions. */
#define RX_DESC_PACKET(i) (*(unsigned int *)(RX_DESC_BASE + 8*i))
#define RX_DESC_CTRL(i) (*(unsigned int *)(RX_DESC_BASE+4 + 8*i))
#define RX_STAT_INFO(i) (*(unsigned int *)(RX_STAT_BASE + 8*i))
#define RX_STAT_HASHCRC(i) (*(unsigned int *)(RX_STAT_BASE+4 + 8*i))
#define TX_DESC_PACKET(i) (*(unsigned int *)(TX_DESC_BASE + 8*i))
#define TX_DESC_CTRL(i) (*(unsigned int *)(TX_DESC_BASE+4 + 8*i))
#define TX_STAT_INFO(i) (*(unsigned int *)(TX_STAT_BASE + 4*i))
#define RX_BUF(i) (RX_BUF_BASE + ETH_FRAG_SIZE*i)
#define TX_BUF(i) (TX_BUF_BASE + ETH_FRAG_SIZE*i)
/* MAC Configuration Register 1 */
#define MAC1_REC_EN 0x00000001 /* Receive Enable */
#define MAC1_PASS_ALL 0x00000002 /* Pass All Receive Frames */
#define MAC1_RX_FLOWC 0x00000004 /* RX Flow Control */
#define MAC1_TX_FLOWC 0x00000008 /* TX Flow Control */
#define MAC1_LOOPB 0x00000010 /* Loop Back Mode */
#define MAC1_RES_TX 0x00000100 /* Reset TX Logic */
#define MAC1_RES_MCS_TX 0x00000200 /* Reset MAC TX Control Sublayer */
#define MAC1_RES_RX 0x00000400 /* Reset RX Logic */
#define MAC1_RES_MCS_RX 0x00000800 /* Reset MAC RX Control Sublayer */
#define MAC1_SIM_RES 0x00004000 /* Simulation Reset */
#define MAC1_SOFT_RES 0x00008000 /* Soft Reset MAC */
/* MAC Configuration Register 2 */
#define MAC2_FULL_DUP 0x00000001 /* Full Duplex Mode */
#define MAC2_FRM_LEN_CHK 0x00000002 /* Frame Length Checking */
#define MAC2_HUGE_FRM_EN 0x00000004 /* Huge Frame Enable */
#define MAC2_DLY_CRC 0x00000008 /* Delayed CRC Mode */
#define MAC2_CRC_EN 0x00000010 /* Append CRC to every Frame */
#define MAC2_PAD_EN 0x00000020 /* Pad all Short Frames */
#define MAC2_VLAN_PAD_EN 0x00000040 /* VLAN Pad Enable */
#define MAC2_ADET_PAD_EN 0x00000080 /* Auto Detect Pad Enable */
#define MAC2_PPREAM_ENF 0x00000100 /* Pure Preamble Enforcement */
#define MAC2_LPREAM_ENF 0x00000200 /* Long Preamble Enforcement */
#undef MAC2_NO_BACKOFF /* Remove compiler warning. */
#define MAC2_NO_BACKOFF 0x00001000 /* No Backoff Algorithm */
#define MAC2_BACK_PRESSURE 0x00002000 /* Backoff Presurre / No Backoff */
#define MAC2_EXCESS_DEF 0x00004000 /* Excess Defer */
/* Back-to-Back Inter-Packet-Gap Register */
#define IPGT_FULL_DUP 0x00000015 /* Recommended value for Full Duplex */
#define IPGT_HALF_DUP 0x00000012 /* Recommended value for Half Duplex */
/* Non Back-to-Back Inter-Packet-Gap Register */
#define IPGR_DEF 0x00000012 /* Recommended value */
/* Collision Window/Retry Register */
#define CLRT_DEF 0x0000370F /* Default value */
/* PHY Support Register */
#undef SUPP_SPEED /* Remove compiler warning. */
#define SUPP_SPEED 0x00000100 /* Reduced MII Logic Current Speed */
#define SUPP_RES_RMII 0x00000800 /* Reset Reduced MII Logic */
/* Test Register */
#define TEST_SHCUT_PQUANTA 0x00000001 /* Shortcut Pause Quanta */
#define TEST_TST_PAUSE 0x00000002 /* Test Pause */
#define TEST_TST_BACKP 0x00000004 /* Test Back Pressure */
/* MII Management Configuration Register */
#define MCFG_SCAN_INC 0x00000001 /* Scan Increment PHY Address */
#define MCFG_SUPP_PREAM 0x00000002 /* Suppress Preamble */
#define MCFG_CLK_SEL 0x0000001C /* Clock Select Mask */
#define MCFG_RES_MII 0x00008000 /* Reset MII Management Hardware */
/* MII Management Command Register */
#undef MCMD_READ /* Remove compiler warning. */
#define MCMD_READ 0x00000001 /* MII Read */
#undef MCMD_SCAN /* Remove compiler warning. */
#define MCMD_SCAN 0x00000002 /* MII Scan continuously */
#define MII_WR_TOUT 0x00050000 /* MII Write timeout count */
#define MII_RD_TOUT 0x00050000 /* MII Read timeout count */
/* MII Management Address Register */
#define MADR_REG_ADR 0x0000001F /* MII Register Address Mask */
#define MADR_PHY_ADR 0x00001F00 /* PHY Address Mask */
/* MII Management Indicators Register */
#undef MIND_BUSY /* Remove compiler warning. */
#define MIND_BUSY 0x00000001 /* MII is Busy */
#define MIND_SCAN 0x00000002 /* MII Scanning in Progress */
#define MIND_NOT_VAL 0x00000004 /* MII Read Data not valid */
#define MIND_MII_LINK_FAIL 0x00000008 /* MII Link Failed */
/* Command Register */
#define CR_RX_EN 0x00000001 /* Enable Receive */
#define CR_TX_EN 0x00000002 /* Enable Transmit */
#define CR_REG_RES 0x00000008 /* Reset Host Registers */
#define CR_TX_RES 0x00000010 /* Reset Transmit Datapath */
#define CR_RX_RES 0x00000020 /* Reset Receive Datapath */
#define CR_PASS_RUNT_FRM 0x00000040 /* Pass Runt Frames */
#define CR_PASS_RX_FILT 0x00000080 /* Pass RX Filter */
#define CR_TX_FLOW_CTRL 0x00000100 /* TX Flow Control */
#define CR_RMII 0x00000200 /* Reduced MII Interface */
#define CR_FULL_DUP 0x00000400 /* Full Duplex */
/* Status Register */
#define SR_RX_EN 0x00000001 /* Enable Receive */
#define SR_TX_EN 0x00000002 /* Enable Transmit */
/* Transmit Status Vector 0 Register */
#define TSV0_CRC_ERR 0x00000001 /* CRC error */
#define TSV0_LEN_CHKERR 0x00000002 /* Length Check Error */
#define TSV0_LEN_OUTRNG 0x00000004 /* Length Out of Range */
#define TSV0_DONE 0x00000008 /* Tramsmission Completed */
#define TSV0_MCAST 0x00000010 /* Multicast Destination */
#define TSV0_BCAST 0x00000020 /* Broadcast Destination */
#define TSV0_PKT_DEFER 0x00000040 /* Packet Deferred */
#define TSV0_EXC_DEFER 0x00000080 /* Excessive Packet Deferral */
#define TSV0_EXC_COLL 0x00000100 /* Excessive Collision */
#define TSV0_LATE_COLL 0x00000200 /* Late Collision Occured */
#define TSV0_GIANT 0x00000400 /* Giant Frame */
#define TSV0_UNDERRUN 0x00000800 /* Buffer Underrun */
#define TSV0_BYTES 0x0FFFF000 /* Total Bytes Transferred */
#define TSV0_CTRL_FRAME 0x10000000 /* Control Frame */
#define TSV0_PAUSE 0x20000000 /* Pause Frame */
#define TSV0_BACK_PRESS 0x40000000 /* Backpressure Method Applied */
#define TSV0_VLAN 0x80000000 /* VLAN Frame */
/* Transmit Status Vector 1 Register */
#define TSV1_BYTE_CNT 0x0000FFFF /* Transmit Byte Count */
#define TSV1_COLL_CNT 0x000F0000 /* Transmit Collision Count */
/* Receive Status Vector Register */
#define RSV_BYTE_CNT 0x0000FFFF /* Receive Byte Count */
#define RSV_PKT_IGNORED 0x00010000 /* Packet Previously Ignored */
#define RSV_RXDV_SEEN 0x00020000 /* RXDV Event Previously Seen */
#define RSV_CARR_SEEN 0x00040000 /* Carrier Event Previously Seen */
#define RSV_REC_CODEV 0x00080000 /* Receive Code Violation */
#define RSV_CRC_ERR 0x00100000 /* CRC Error */
#define RSV_LEN_CHKERR 0x00200000 /* Length Check Error */
#define RSV_LEN_OUTRNG 0x00400000 /* Length Out of Range */
#define RSV_REC_OK 0x00800000 /* Frame Received OK */
#define RSV_MCAST 0x01000000 /* Multicast Frame */
#define RSV_BCAST 0x02000000 /* Broadcast Frame */
#define RSV_DRIB_NIBB 0x04000000 /* Dribble Nibble */
#define RSV_CTRL_FRAME 0x08000000 /* Control Frame */
#define RSV_PAUSE 0x10000000 /* Pause Frame */
#define RSV_UNSUPP_OPC 0x20000000 /* Unsupported Opcode */
#define RSV_VLAN 0x40000000 /* VLAN Frame */
/* Flow Control Counter Register */
#define FCC_MIRR_CNT 0x0000FFFF /* Mirror Counter */
#define FCC_PAUSE_TIM 0xFFFF0000 /* Pause Timer */
/* Flow Control Status Register */
#define FCS_MIRR_CNT 0x0000FFFF /* Mirror Counter Current */
/* Receive Filter Control Register */
#define RFC_UCAST_EN 0x00000001 /* Accept Unicast Frames Enable */
#define RFC_BCAST_EN 0x00000002 /* Accept Broadcast Frames Enable */
#define RFC_MCAST_EN 0x00000004 /* Accept Multicast Frames Enable */
#define RFC_UCAST_HASH_EN 0x00000008 /* Accept Unicast Hash Filter Frames */
#define RFC_MCAST_HASH_EN 0x00000010 /* Accept Multicast Hash Filter Fram.*/
#define RFC_PERFECT_EN 0x00000020 /* Accept Perfect Match Enable */
#define RFC_MAGP_WOL_EN 0x00001000 /* Magic Packet Filter WoL Enable */
#define RFC_PFILT_WOL_EN 0x00002000 /* Perfect Filter WoL Enable */
/* Receive Filter WoL Status/Clear Registers */
#define WOL_UCAST 0x00000001 /* Unicast Frame caused WoL */
#define WOL_BCAST 0x00000002 /* Broadcast Frame caused WoL */
#define WOL_MCAST 0x00000004 /* Multicast Frame caused WoL */
#define WOL_UCAST_HASH 0x00000008 /* Unicast Hash Filter Frame WoL */
#define WOL_MCAST_HASH 0x00000010 /* Multicast Hash Filter Frame WoL */
#define WOL_PERFECT 0x00000020 /* Perfect Filter WoL */
#define WOL_RX_FILTER 0x00000080 /* RX Filter caused WoL */
#define WOL_MAG_PACKET 0x00000100 /* Magic Packet Filter caused WoL */
/* Interrupt Status/Enable/Clear/Set Registers */
#define INT_RX_OVERRUN 0x00000001 /* Overrun Error in RX Queue */
#define INT_RX_ERR 0x00000002 /* Receive Error */
#define INT_RX_FIN 0x00000004 /* RX Finished Process Descriptors */
#define INT_RX_DONE 0x00000008 /* Receive Done */
#define INT_TX_UNDERRUN 0x00000010 /* Transmit Underrun */
#define INT_TX_ERR 0x00000020 /* Transmit Error */
#define INT_TX_FIN 0x00000040 /* TX Finished Process Descriptors */
#define INT_TX_DONE 0x00000080 /* Transmit Done */
#define INT_SOFT_INT 0x00001000 /* Software Triggered Interrupt */
#define INT_WAKEUP 0x00002000 /* Wakeup Event Interrupt */
/* Power Down Register */
#define PD_POWER_DOWN 0x80000000 /* Power Down MAC */
/* RX Descriptor Control Word */
#define RCTRL_SIZE 0x000007FF /* Buffer size mask */
#define RCTRL_INT 0x80000000 /* Generate RxDone Interrupt */
/* RX Status Hash CRC Word */
#define RHASH_SA 0x000001FF /* Hash CRC for Source Address */
#define RHASH_DA 0x001FF000 /* Hash CRC for Destination Address */
/* RX Status Information Word */
#define RINFO_SIZE 0x000007FF /* Data size in bytes */
#define RINFO_CTRL_FRAME 0x00040000 /* Control Frame */
#define RINFO_VLAN 0x00080000 /* VLAN Frame */
#define RINFO_FAIL_FILT 0x00100000 /* RX Filter Failed */
#define RINFO_MCAST 0x00200000 /* Multicast Frame */
#define RINFO_BCAST 0x00400000 /* Broadcast Frame */
#define RINFO_CRC_ERR 0x00800000 /* CRC Error in Frame */
#define RINFO_SYM_ERR 0x01000000 /* Symbol Error from PHY */
#define RINFO_LEN_ERR 0x02000000 /* Length Error */
#define RINFO_RANGE_ERR 0x04000000 /* Range Error (exceeded max. size) */
#define RINFO_ALIGN_ERR 0x08000000 /* Alignment Error */
#define RINFO_OVERRUN 0x10000000 /* Receive overrun */
#define RINFO_NO_DESCR 0x20000000 /* No new Descriptor available */
#define RINFO_LAST_FLAG 0x40000000 /* Last Fragment in Frame */
#define RINFO_ERR 0x80000000 /* Error Occured (OR of all errors) */
#define RINFO_ERR_MASK (RINFO_FAIL_FILT | RINFO_CRC_ERR | RINFO_SYM_ERR | \
RINFO_LEN_ERR | RINFO_ALIGN_ERR | RINFO_OVERRUN)
/* TX Descriptor Control Word */
#define TCTRL_SIZE 0x000007FF /* Size of data buffer in bytes */
#define TCTRL_OVERRIDE 0x04000000 /* Override Default MAC Registers */
#define TCTRL_HUGE 0x08000000 /* Enable Huge Frame */
#define TCTRL_PAD 0x10000000 /* Pad short Frames to 64 bytes */
#define TCTRL_CRC 0x20000000 /* Append a hardware CRC to Frame */
#define TCTRL_LAST 0x40000000 /* Last Descriptor for TX Frame */
#define TCTRL_INT 0x80000000 /* Generate TxDone Interrupt */
/* TX Status Information Word */
#define TINFO_COL_CNT 0x01E00000 /* Collision Count */
#define TINFO_DEFER 0x02000000 /* Packet Deferred (not an error) */
#define TINFO_EXCESS_DEF 0x04000000 /* Excessive Deferral */
#define TINFO_EXCESS_COL 0x08000000 /* Excessive Collision */
#define TINFO_LATE_COL 0x10000000 /* Late Collision Occured */
#define TINFO_UNDERRUN 0x20000000 /* Transmit Underrun */
#define TINFO_NO_DESCR 0x40000000 /* No new Descriptor available */
#define TINFO_ERR 0x80000000 /* Error Occured (OR of all errors) */
/* DP83848C PHY Registers */
#define PHY_REG_BMCR 0x00 /* Basic Mode Control Register */
#define PHY_REG_BMSR 0x01 /* Basic Mode Status Register */
#define PHY_REG_IDR1 0x02 /* PHY Identifier 1 */
#define PHY_REG_IDR2 0x03 /* PHY Identifier 2 */
#define PHY_REG_ANAR 0x04 /* Auto-Negotiation Advertisement */
#define PHY_REG_ANLPAR 0x05 /* Auto-Neg. Link Partner Abitily */
#define PHY_REG_ANER 0x06 /* Auto-Neg. Expansion Register */
#define PHY_REG_ANNPTR 0x07 /* Auto-Neg. Next Page TX */
/* PHY Extended Registers */
#define PHY_REG_STS 0x10 /* Status Register */
#define PHY_REG_MICR 0x11 /* MII Interrupt Control Register */
#define PHY_REG_MISR 0x12 /* MII Interrupt Status Register */
#define PHY_REG_FCSCR 0x14 /* False Carrier Sense Counter */
#define PHY_REG_RECR 0x15 /* Receive Error Counter */
#define PHY_REG_PCSR 0x16 /* PCS Sublayer Config. and Status */
#define PHY_REG_RBR 0x17 /* RMII and Bypass Register */
#define PHY_REG_LEDCR 0x18 /* LED Direct Control Register */
#define PHY_REG_PHYCR 0x19 /* PHY Control Register */
#define PHY_REG_10BTSCR 0x1A /* 10Base-T Status/Control Register */
#define PHY_REG_CDCTRL1 0x1B /* CD Test Control and BIST Extens. */
#define PHY_REG_EDCR 0x1D /* Energy Detect Control Register */
#define PHY_FULLD_100M 0x2100 /* Full Duplex 100Mbit */
#define PHY_HALFD_100M 0x2000 /* Half Duplex 100Mbit */
#define PHY_FULLD_10M 0x0100 /* Full Duplex 10Mbit */
#define PHY_HALFD_10M 0x0000 /* Half Duplex 10MBit */
#define PHY_AUTO_NEG 0x3000 /* Select Auto Negotiation */
#define DP83848C_DEF_ADR 0x0100 /* Default PHY device address */
#define DP83848C_ID 0x20005C90 /* PHY Identifier */
// prototypes
portBASE_TYPE Init_EMAC(void);
unsigned short ReadFrameBE_EMAC(void);
void CopyToFrame_EMAC(void *Source, unsigned int Size);
void CopyFromFrame_EMAC(void *Dest, unsigned short Size);
void DummyReadFrame_EMAC(unsigned short Size);
unsigned short StartReadFrame(void);
void EndReadFrame(void);
unsigned int CheckFrameReceived(void);
void RequestSend(void);
unsigned int Rdy4Tx(void);
void DoSend_EMAC(unsigned short FrameSize);
void vEMACWaitForInput( void );
unsigned int uiGetEMACRxData( unsigned char *ucBuffer );
#endif
/*----------------------------------------------------------------------------
* end of file
*---------------------------------------------------------------------------*/

View File

@ -0,0 +1,35 @@
http_http "http://"
http_200 "200 "
http_301 "301 "
http_302 "302 "
http_get "GET "
http_10 "HTTP/1.0"
http_11 "HTTP/1.1"
http_content_type "content-type: "
http_texthtml "text/html"
http_location "location: "
http_host "host: "
http_crnl "\r\n"
http_index_html "/index.html"
http_404_html "/404.html"
http_referer "Referer:"
http_header_200 "HTTP/1.0 200 OK\r\nServer: uIP/1.0 http://www.sics.se/~adam/uip/\r\nConnection: close\r\n"
http_header_404 "HTTP/1.0 404 Not found\r\nServer: uIP/1.0 http://www.sics.se/~adam/uip/\r\nConnection: close\r\n"
http_content_type_plain "Content-type: text/plain\r\n\r\n"
http_content_type_html "Content-type: text/html\r\n\r\n"
http_content_type_css "Content-type: text/css\r\n\r\n"
http_content_type_text "Content-type: text/text\r\n\r\n"
http_content_type_png "Content-type: image/png\r\n\r\n"
http_content_type_gif "Content-type: image/gif\r\n\r\n"
http_content_type_jpg "Content-type: image/jpeg\r\n\r\n"
http_content_type_binary "Content-type: application/octet-stream\r\n\r\n"
http_html ".html"
http_shtml ".shtml"
http_htm ".htm"
http_css ".css"
http_png ".png"
http_gif ".gif"
http_jpg ".jpg"
http_text ".txt"
http_txt ".txt"

View File

@ -0,0 +1,102 @@
const char http_http[8] =
/* "http://" */
{0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, 0x2f, };
const char http_200[5] =
/* "200 " */
{0x32, 0x30, 0x30, 0x20, };
const char http_301[5] =
/* "301 " */
{0x33, 0x30, 0x31, 0x20, };
const char http_302[5] =
/* "302 " */
{0x33, 0x30, 0x32, 0x20, };
const char http_get[5] =
/* "GET " */
{0x47, 0x45, 0x54, 0x20, };
const char http_10[9] =
/* "HTTP/1.0" */
{0x48, 0x54, 0x54, 0x50, 0x2f, 0x31, 0x2e, 0x30, };
const char http_11[9] =
/* "HTTP/1.1" */
{0x48, 0x54, 0x54, 0x50, 0x2f, 0x31, 0x2e, 0x31, };
const char http_content_type[15] =
/* "content-type: " */
{0x63, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, };
const char http_texthtml[10] =
/* "text/html" */
{0x74, 0x65, 0x78, 0x74, 0x2f, 0x68, 0x74, 0x6d, 0x6c, };
const char http_location[11] =
/* "location: " */
{0x6c, 0x6f, 0x63, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x3a, 0x20, };
const char http_host[7] =
/* "host: " */
{0x68, 0x6f, 0x73, 0x74, 0x3a, 0x20, };
const char http_crnl[3] =
/* "\r\n" */
{0xd, 0xa, };
const char http_index_html[12] =
/* "/index.html" */
{0x2f, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x68, 0x74, 0x6d, 0x6c, };
const char http_404_html[10] =
/* "/404.html" */
{0x2f, 0x34, 0x30, 0x34, 0x2e, 0x68, 0x74, 0x6d, 0x6c, };
const char http_referer[9] =
/* "Referer:" */
{0x52, 0x65, 0x66, 0x65, 0x72, 0x65, 0x72, 0x3a, };
const char http_header_200[84] =
/* "HTTP/1.0 200 OK\r\nServer: uIP/1.0 http://www.sics.se/~adam/uip/\r\nConnection: close\r\n" */
{0x48, 0x54, 0x54, 0x50, 0x2f, 0x31, 0x2e, 0x30, 0x20, 0x32, 0x30, 0x30, 0x20, 0x4f, 0x4b, 0xd, 0xa, 0x53, 0x65, 0x72, 0x76, 0x65, 0x72, 0x3a, 0x20, 0x75, 0x49, 0x50, 0x2f, 0x31, 0x2e, 0x30, 0x20, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x73, 0x69, 0x63, 0x73, 0x2e, 0x73, 0x65, 0x2f, 0x7e, 0x61, 0x64, 0x61, 0x6d, 0x2f, 0x75, 0x69, 0x70, 0x2f, 0xd, 0xa, 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x3a, 0x20, 0x63, 0x6c, 0x6f, 0x73, 0x65, 0xd, 0xa, };
const char http_header_404[91] =
/* "HTTP/1.0 404 Not found\r\nServer: uIP/1.0 http://www.sics.se/~adam/uip/\r\nConnection: close\r\n" */
{0x48, 0x54, 0x54, 0x50, 0x2f, 0x31, 0x2e, 0x30, 0x20, 0x34, 0x30, 0x34, 0x20, 0x4e, 0x6f, 0x74, 0x20, 0x66, 0x6f, 0x75, 0x6e, 0x64, 0xd, 0xa, 0x53, 0x65, 0x72, 0x76, 0x65, 0x72, 0x3a, 0x20, 0x75, 0x49, 0x50, 0x2f, 0x31, 0x2e, 0x30, 0x20, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x73, 0x69, 0x63, 0x73, 0x2e, 0x73, 0x65, 0x2f, 0x7e, 0x61, 0x64, 0x61, 0x6d, 0x2f, 0x75, 0x69, 0x70, 0x2f, 0xd, 0xa, 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x3a, 0x20, 0x63, 0x6c, 0x6f, 0x73, 0x65, 0xd, 0xa, };
const char http_content_type_plain[29] =
/* "Content-type: text/plain\r\n\r\n" */
{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x74, 0x65, 0x78, 0x74, 0x2f, 0x70, 0x6c, 0x61, 0x69, 0x6e, 0xd, 0xa, 0xd, 0xa, };
const char http_content_type_html[28] =
/* "Content-type: text/html\r\n\r\n" */
{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x74, 0x65, 0x78, 0x74, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0xd, 0xa, 0xd, 0xa, };
const char http_content_type_css [27] =
/* "Content-type: text/css\r\n\r\n" */
{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x74, 0x65, 0x78, 0x74, 0x2f, 0x63, 0x73, 0x73, 0xd, 0xa, 0xd, 0xa, };
const char http_content_type_text[28] =
/* "Content-type: text/text\r\n\r\n" */
{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x74, 0x65, 0x78, 0x74, 0x2f, 0x74, 0x65, 0x78, 0x74, 0xd, 0xa, 0xd, 0xa, };
const char http_content_type_png [28] =
/* "Content-type: image/png\r\n\r\n" */
{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x69, 0x6d, 0x61, 0x67, 0x65, 0x2f, 0x70, 0x6e, 0x67, 0xd, 0xa, 0xd, 0xa, };
const char http_content_type_gif [28] =
/* "Content-type: image/gif\r\n\r\n" */
{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x69, 0x6d, 0x61, 0x67, 0x65, 0x2f, 0x67, 0x69, 0x66, 0xd, 0xa, 0xd, 0xa, };
const char http_content_type_jpg [29] =
/* "Content-type: image/jpeg\r\n\r\n" */
{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x69, 0x6d, 0x61, 0x67, 0x65, 0x2f, 0x6a, 0x70, 0x65, 0x67, 0xd, 0xa, 0xd, 0xa, };
const char http_content_type_binary[43] =
/* "Content-type: application/octet-stream\r\n\r\n" */
{0x43, 0x6f, 0x6e, 0x74, 0x65, 0x6e, 0x74, 0x2d, 0x74, 0x79, 0x70, 0x65, 0x3a, 0x20, 0x61, 0x70, 0x70, 0x6c, 0x69, 0x63, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x2f, 0x6f, 0x63, 0x74, 0x65, 0x74, 0x2d, 0x73, 0x74, 0x72, 0x65, 0x61, 0x6d, 0xd, 0xa, 0xd, 0xa, };
const char http_html[6] =
/* ".html" */
{0x2e, 0x68, 0x74, 0x6d, 0x6c, };
const char http_shtml[7] =
/* ".shtml" */
{0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, };
const char http_htm[5] =
/* ".htm" */
{0x2e, 0x68, 0x74, 0x6d, };
const char http_css[5] =
/* ".css" */
{0x2e, 0x63, 0x73, 0x73, };
const char http_png[5] =
/* ".png" */
{0x2e, 0x70, 0x6e, 0x67, };
const char http_gif[5] =
/* ".gif" */
{0x2e, 0x67, 0x69, 0x66, };
const char http_jpg[5] =
/* ".jpg" */
{0x2e, 0x6a, 0x70, 0x67, };
const char http_text[5] =
/* ".txt" */
{0x2e, 0x74, 0x78, 0x74, };
const char http_txt[5] =
/* ".txt" */
{0x2e, 0x74, 0x78, 0x74, };

View File

@ -0,0 +1,34 @@
extern const char http_http[8];
extern const char http_200[5];
extern const char http_301[5];
extern const char http_302[5];
extern const char http_get[5];
extern const char http_10[9];
extern const char http_11[9];
extern const char http_content_type[15];
extern const char http_texthtml[10];
extern const char http_location[11];
extern const char http_host[7];
extern const char http_crnl[3];
extern const char http_index_html[12];
extern const char http_404_html[10];
extern const char http_referer[9];
extern const char http_header_200[84];
extern const char http_header_404[91];
extern const char http_content_type_plain[29];
extern const char http_content_type_html[28];
extern const char http_content_type_css [27];
extern const char http_content_type_text[28];
extern const char http_content_type_png [28];
extern const char http_content_type_gif [28];
extern const char http_content_type_jpg [29];
extern const char http_content_type_binary[43];
extern const char http_html[6];
extern const char http_shtml[7];
extern const char http_htm[5];
extern const char http_css[5];
extern const char http_png[5];
extern const char http_gif[5];
extern const char http_jpg[5];
extern const char http_text[5];
extern const char http_txt[5];

View File

@ -0,0 +1,305 @@
/**
* \addtogroup httpd
* @{
*/
/**
* \file
* Web server script interface
* \author
* Adam Dunkels <adam@sics.se>
*
*/
/*
* Copyright (c) 2001-2006, Adam Dunkels.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. The name of the author may not be used to endorse or promote
* products derived from this software without specific prior
* written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE
* GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
* This file is part of the uIP TCP/IP stack.
*
* $Id: httpd-cgi.c,v 1.2 2006/06/11 21:46:37 adam Exp $
*
*/
#include "uip.h"
#include "psock.h"
#include "httpd.h"
#include "httpd-cgi.h"
#include "httpd-fs.h"
#include <stdio.h>
#include <string.h>
HTTPD_CGI_CALL(file, "file-stats", file_stats);
HTTPD_CGI_CALL(tcp, "tcp-connections", tcp_stats);
HTTPD_CGI_CALL(net, "net-stats", net_stats);
HTTPD_CGI_CALL(rtos, "rtos-stats", rtos_stats );
HTTPD_CGI_CALL(run, "run-time", run_time );
HTTPD_CGI_CALL(io, "led-io", led_io );
static const struct httpd_cgi_call *calls[] = { &file, &tcp, &net, &rtos, &run, &io, NULL };
/*---------------------------------------------------------------------------*/
static
PT_THREAD(nullfunction(struct httpd_state *s, char *ptr))
{
PSOCK_BEGIN(&s->sout);
( void ) ptr;
PSOCK_END(&s->sout);
}
/*---------------------------------------------------------------------------*/
httpd_cgifunction
httpd_cgi(char *name)
{
const struct httpd_cgi_call **f;
/* Find the matching name in the table, return the function. */
for(f = calls; *f != NULL; ++f) {
if(strncmp((*f)->name, name, strlen((*f)->name)) == 0) {
return (*f)->function;
}
}
return nullfunction;
}
/*---------------------------------------------------------------------------*/
static unsigned short
generate_file_stats(void *arg)
{
char *f = (char *)arg;
return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE, "%5u", httpd_fs_count(f));
}
/*---------------------------------------------------------------------------*/
static
PT_THREAD(file_stats(struct httpd_state *s, char *ptr))
{
PSOCK_BEGIN(&s->sout);
PSOCK_GENERATOR_SEND(&s->sout, generate_file_stats, strchr(ptr, ' ') + 1);
PSOCK_END(&s->sout);
}
/*---------------------------------------------------------------------------*/
static const char closed[] = /* "CLOSED",*/
{0x43, 0x4c, 0x4f, 0x53, 0x45, 0x44, 0};
static const char syn_rcvd[] = /* "SYN-RCVD",*/
{0x53, 0x59, 0x4e, 0x2d, 0x52, 0x43, 0x56,
0x44, 0};
static const char syn_sent[] = /* "SYN-SENT",*/
{0x53, 0x59, 0x4e, 0x2d, 0x53, 0x45, 0x4e,
0x54, 0};
static const char established[] = /* "ESTABLISHED",*/
{0x45, 0x53, 0x54, 0x41, 0x42, 0x4c, 0x49, 0x53, 0x48,
0x45, 0x44, 0};
static const char fin_wait_1[] = /* "FIN-WAIT-1",*/
{0x46, 0x49, 0x4e, 0x2d, 0x57, 0x41, 0x49,
0x54, 0x2d, 0x31, 0};
static const char fin_wait_2[] = /* "FIN-WAIT-2",*/
{0x46, 0x49, 0x4e, 0x2d, 0x57, 0x41, 0x49,
0x54, 0x2d, 0x32, 0};
static const char closing[] = /* "CLOSING",*/
{0x43, 0x4c, 0x4f, 0x53, 0x49,
0x4e, 0x47, 0};
static const char time_wait[] = /* "TIME-WAIT,"*/
{0x54, 0x49, 0x4d, 0x45, 0x2d, 0x57, 0x41,
0x49, 0x54, 0};
static const char last_ack[] = /* "LAST-ACK"*/
{0x4c, 0x41, 0x53, 0x54, 0x2d, 0x41, 0x43,
0x4b, 0};
static const char *states[] = {
closed,
syn_rcvd,
syn_sent,
established,
fin_wait_1,
fin_wait_2,
closing,
time_wait,
last_ack};
static unsigned short
generate_tcp_stats(void *arg)
{
struct uip_conn *conn;
struct httpd_state *s = (struct httpd_state *)arg;
conn = &uip_conns[s->count];
return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE,
"<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",
htons(conn->lport),
htons(conn->ripaddr[0]) >> 8,
htons(conn->ripaddr[0]) & 0xff,
htons(conn->ripaddr[1]) >> 8,
htons(conn->ripaddr[1]) & 0xff,
htons(conn->rport),
states[conn->tcpstateflags & UIP_TS_MASK],
conn->nrtx,
conn->timer,
(uip_outstanding(conn))? '*':' ',
(uip_stopped(conn))? '!':' ');
}
/*---------------------------------------------------------------------------*/
static
PT_THREAD(tcp_stats(struct httpd_state *s, char *ptr))
{
PSOCK_BEGIN(&s->sout);
( void ) ptr;
for(s->count = 0; s->count < UIP_CONNS; ++s->count) {
if((uip_conns[s->count].tcpstateflags & UIP_TS_MASK) != UIP_CLOSED) {
PSOCK_GENERATOR_SEND(&s->sout, generate_tcp_stats, s);
}
}
PSOCK_END(&s->sout);
}
/*---------------------------------------------------------------------------*/
static unsigned short
generate_net_stats(void *arg)
{
struct httpd_state *s = (struct httpd_state *)arg;
return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE,
"%5u\n", ((uip_stats_t *)&uip_stat)[s->count]);
}
static
PT_THREAD(net_stats(struct httpd_state *s, char *ptr))
{
PSOCK_BEGIN(&s->sout);
( void ) ptr;
#if UIP_STATISTICS
for(s->count = 0; s->count < sizeof(uip_stat) / sizeof(uip_stats_t);
++s->count) {
PSOCK_GENERATOR_SEND(&s->sout, generate_net_stats, s);
}
#endif /* UIP_STATISTICS */
PSOCK_END(&s->sout);
}
/*---------------------------------------------------------------------------*/
extern void vTaskList( signed char *pcWriteBuffer );
static char cCountBuf[ 32 ];
long lRefreshCount = 0;
static unsigned short
generate_rtos_stats(void *arg)
{
( void ) arg;
lRefreshCount++;
sprintf( cCountBuf, "<p><br>Refresh count = %d", (int)lRefreshCount );
vTaskList( uip_appdata );
strcat( uip_appdata, cCountBuf );
return strlen( uip_appdata );
}
/*---------------------------------------------------------------------------*/
static
PT_THREAD(rtos_stats(struct httpd_state *s, char *ptr))
{
PSOCK_BEGIN(&s->sout);
( void ) ptr;
PSOCK_GENERATOR_SEND(&s->sout, generate_rtos_stats, NULL);
PSOCK_END(&s->sout);
}
/*---------------------------------------------------------------------------*/
char *pcStatus;
unsigned long ulString;
static unsigned short generate_io_state( void *arg )
{
extern long lParTestGetLEDState( unsigned long ulLED );
( void ) arg;
if( lParTestGetLEDState( 1 << 7 ) == 0 )
{
pcStatus = "";
}
else
{
pcStatus = "checked";
}
sprintf( uip_appdata,
"<input type=\"checkbox\" name=\"LED0\" value=\"1\" %s>LED 7"\
"<p>"\
"<input type=\"text\" name=\"LCD\" value=\"Enter LCD text\" size=\"16\">",
pcStatus );
return strlen( uip_appdata );
}
/*---------------------------------------------------------------------------*/
extern void vTaskGetRunTimeStats( signed char *pcWriteBuffer );
static unsigned short
generate_runtime_stats(void *arg)
{
( void ) arg;
lRefreshCount++;
sprintf( cCountBuf, "<p><br>Refresh count = %d", (int)lRefreshCount );
vTaskGetRunTimeStats( uip_appdata );
strcat( uip_appdata, cCountBuf );
return strlen( uip_appdata );
}
/*---------------------------------------------------------------------------*/
static
PT_THREAD(run_time(struct httpd_state *s, char *ptr))
{
PSOCK_BEGIN(&s->sout);
( void ) ptr;
PSOCK_GENERATOR_SEND(&s->sout, generate_runtime_stats, NULL);
PSOCK_END(&s->sout);
}
/*---------------------------------------------------------------------------*/
static PT_THREAD(led_io(struct httpd_state *s, char *ptr))
{
PSOCK_BEGIN(&s->sout);
( void ) ptr;
PSOCK_GENERATOR_SEND(&s->sout, generate_io_state, NULL);
PSOCK_END(&s->sout);
}
/** @} */

View File

@ -0,0 +1,84 @@
/**
* \addtogroup httpd
* @{
*/
/**
* \file
* Web server script interface header file
* \author
* Adam Dunkels <adam@sics.se>
*
*/
/*
* Copyright (c) 2001, Adam Dunkels.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. The name of the author may not be used to endorse or promote
* products derived from this software without specific prior
* written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE
* GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
* This file is part of the uIP TCP/IP stack.
*
* $Id: httpd-cgi.h,v 1.2 2006/06/11 21:46:38 adam Exp $
*
*/
#ifndef __HTTPD_CGI_H__
#define __HTTPD_CGI_H__
#include "psock.h"
#include "httpd.h"
typedef PT_THREAD((* httpd_cgifunction)(struct httpd_state *, char *));
httpd_cgifunction httpd_cgi(char *name);
struct httpd_cgi_call {
const char *name;
const httpd_cgifunction function;
};
/**
* \brief HTTPD CGI function declaration
* \param name The C variable name of the function
* \param str The string name of the function, used in the script file
* \param function A pointer to the function that implements it
*
* This macro is used for declaring a HTTPD CGI
* function. This function is then added to the list of
* HTTPD CGI functions with the httpd_cgi_add() function.
*
* \hideinitializer
*/
#define HTTPD_CGI_CALL(name, str, function) \
static PT_THREAD(function(struct httpd_state *, char *)); \
static const struct httpd_cgi_call name = {str, function}
void httpd_cgi_init(void);
#endif /* __HTTPD_CGI_H__ */
/** @} */

View File

@ -0,0 +1,132 @@
/*
* Copyright (c) 2001, Swedish Institute of Computer Science.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the Institute nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*
* This file is part of the lwIP TCP/IP stack.
*
* Author: Adam Dunkels <adam@sics.se>
*
* $Id: httpd-fs.c,v 1.1 2006/06/07 09:13:08 adam Exp $
*/
#include "httpd.h"
#include "httpd-fs.h"
#include "httpd-fsdata.h"
#ifndef NULL
#define NULL 0
#endif /* NULL */
#include "httpd-fsdata.c"
#if HTTPD_FS_STATISTICS
static u16_t count[HTTPD_FS_NUMFILES];
#endif /* HTTPD_FS_STATISTICS */
/*-----------------------------------------------------------------------------------*/
static u8_t
httpd_fs_strcmp(const char *str1, const char *str2)
{
u8_t i;
i = 0;
loop:
if(str2[i] == 0 ||
str1[i] == '\r' ||
str1[i] == '\n') {
return 0;
}
if(str1[i] != str2[i]) {
return 1;
}
++i;
goto loop;
}
/*-----------------------------------------------------------------------------------*/
int
httpd_fs_open(const char *name, struct httpd_fs_file *file)
{
#if HTTPD_FS_STATISTICS
u16_t i = 0;
#endif /* HTTPD_FS_STATISTICS */
struct httpd_fsdata_file_noconst *f;
for(f = (struct httpd_fsdata_file_noconst *)HTTPD_FS_ROOT;
f != NULL;
f = (struct httpd_fsdata_file_noconst *)f->next) {
if(httpd_fs_strcmp(name, f->name) == 0) {
file->data = f->data;
file->len = f->len;
#if HTTPD_FS_STATISTICS
++count[i];
#endif /* HTTPD_FS_STATISTICS */
return 1;
}
#if HTTPD_FS_STATISTICS
++i;
#endif /* HTTPD_FS_STATISTICS */
}
return 0;
}
/*-----------------------------------------------------------------------------------*/
void
httpd_fs_init(void)
{
#if HTTPD_FS_STATISTICS
u16_t i;
for(i = 0; i < HTTPD_FS_NUMFILES; i++) {
count[i] = 0;
}
#endif /* HTTPD_FS_STATISTICS */
}
/*-----------------------------------------------------------------------------------*/
#if HTTPD_FS_STATISTICS
u16_t httpd_fs_count
(char *name)
{
struct httpd_fsdata_file_noconst *f;
u16_t i;
i = 0;
for(f = (struct httpd_fsdata_file_noconst *)HTTPD_FS_ROOT;
f != NULL;
f = (struct httpd_fsdata_file_noconst *)f->next) {
if(httpd_fs_strcmp(name, f->name) == 0) {
return count[i];
}
++i;
}
return 0;
}
#endif /* HTTPD_FS_STATISTICS */
/*-----------------------------------------------------------------------------------*/

View File

@ -0,0 +1,57 @@
/*
* Copyright (c) 2001, Swedish Institute of Computer Science.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the Institute nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*
* This file is part of the lwIP TCP/IP stack.
*
* Author: Adam Dunkels <adam@sics.se>
*
* $Id: httpd-fs.h,v 1.1 2006/06/07 09:13:08 adam Exp $
*/
#ifndef __HTTPD_FS_H__
#define __HTTPD_FS_H__
#define HTTPD_FS_STATISTICS 1
struct httpd_fs_file {
char *data;
int len;
};
/* file must be allocated by caller and will be filled in
by the function. */
int httpd_fs_open(const char *name, struct httpd_fs_file *file);
#ifdef HTTPD_FS_STATISTICS
#if HTTPD_FS_STATISTICS == 1
u16_t httpd_fs_count(char *name);
#endif /* HTTPD_FS_STATISTICS */
#endif /* HTTPD_FS_STATISTICS */
void httpd_fs_init(void);
#endif /* __HTTPD_FS_H__ */

View File

@ -0,0 +1,8 @@
<html>
<body bgcolor="white">
<center>
<h1>404 - file not found</h1>
<h3>Go <a href="/">here</a> instead.</h3>
</center>
</body>
</html>

View File

@ -0,0 +1,13 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN" "http://www.w3.org/TR/html4/loose.dtd">
<html>
<head>
<title>FreeRTOS.org uIP WEB server demo</title>
</head>
<BODY onLoad="window.setTimeout(&quot;location.href='index.shtml'&quot;,100)">
<font face="arial">
Loading index.shtml. Click <a href="index.shtml">here</a> if not automatically redirected.
</font>
</font>
</body>
</html>

View File

@ -0,0 +1,20 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN" "http://www.w3.org/TR/html4/loose.dtd">
<html>
<head>
<title>FreeRTOS.org uIP WEB server demo</title>
</head>
<BODY onLoad="window.setTimeout(&quot;location.href='index.shtml'&quot;,2000)">
<font face="arial">
<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>
<br><p>
<hr>
<br><p>
<h2>Task statistics</h2>
Page will refresh every 2 seconds.<p>
<font face="courier"><pre>Task State Priority Stack #<br>************************************************<br>
%! rtos-stats
</pre></font>
</font>
</body>
</html>

View File

@ -0,0 +1,28 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN" "http://www.w3.org/TR/html4/loose.dtd">
<html>
<head>
<title>FreeRTOS.org uIP WEB server demo</title>
</head>
<BODY>
<font face="arial">
<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>
<br><p>
<hr>
<b>LED and LCD IO</b><br>
<p>
Use the check box to turn on or off the LED, enter text to display on the OLED display, then click "Update IO".
<p>
<form name="aForm" action="/io.shtml" method="get">
%! led-io
<p>
<input type="submit" value="Update IO">
</form>
<br><p>
</font>
</body>
</html>

View File

@ -0,0 +1,20 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN" "http://www.w3.org/TR/html4/loose.dtd">
<html>
<head>
<title>FreeRTOS.org uIP WEB server demo</title>
</head>
<BODY onLoad="window.setTimeout(&quot;location.href='runtime.shtml'&quot;,2000)">
<font face="arial">
<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>
<br><p>
<hr>
<br><p>
<h2>Run-time statistics</h2>
Page will refresh every 2 seconds.<p>
<font face="courier"><pre>Task Abs Time % Time<br>****************************************<br>
%! run-time
</pre></font>
</font>
</body>
</html>

View File

@ -0,0 +1,41 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN" "http://www.w3.org/TR/html4/loose.dtd">
<html>
<head>
<title>FreeRTOS.org uIP WEB server demo</title>
</head>
<BODY>
<font face="arial">
<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>
<br><p>
<hr>
<br><p>
<h2>Network statistics</h2>
<table width="300" border="0">
<tr><td align="left"><font face="courier"><pre>
IP Packets dropped
Packets received
Packets sent
IP errors IP version/header length
IP length, high byte
IP length, low byte
IP fragments
Header checksum
Wrong protocol
ICMP Packets dropped
Packets received
Packets sent
Type errors
TCP Packets dropped
Packets received
Packets sent
Checksum errors
Data packets without ACKs
Resets
Retransmissions
No connection avaliable
Connection attempts to closed ports
</pre></font></td><td><pre>%! net-stats
</pre></table>
</font>
</body>
</html>

View File

@ -0,0 +1,21 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN" "http://www.w3.org/TR/html4/loose.dtd">
<html>
<head>
<title>FreeRTOS.org uIP WEB server demo</title>
</head>
<BODY>
<font face="arial">
<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>
<br><p>
<hr>
<br>
<h2>Network connections</h2>
<p>
<table>
<tr><th>Local</th><th>Remote</th><th>State</th><th>Retransmissions</th><th>Timer</th><th>Flags</th></tr>
%! tcp-connections
</pre></font>
</font>
</body>
</html>

View File

@ -0,0 +1,557 @@
static const char data_404_html[] = {
/* /404.html */
0x2f, 0x34, 0x30, 0x34, 0x2e, 0x68, 0x74, 0x6d, 0x6c, 0,
0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, 0x20, 0x20, 0x3c,
0x62, 0x6f, 0x64, 0x79, 0x20, 0x62, 0x67, 0x63, 0x6f, 0x6c,
0x6f, 0x72, 0x3d, 0x22, 0x77, 0x68, 0x69, 0x74, 0x65, 0x22,
0x3e, 0xa, 0x20, 0x20, 0x20, 0x20, 0x3c, 0x63, 0x65, 0x6e,
0x74, 0x65, 0x72, 0x3e, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x3c, 0x68, 0x31, 0x3e, 0x34, 0x30, 0x34, 0x20, 0x2d,
0x20, 0x66, 0x69, 0x6c, 0x65, 0x20, 0x6e, 0x6f, 0x74, 0x20,
0x66, 0x6f, 0x75, 0x6e, 0x64, 0x3c, 0x2f, 0x68, 0x31, 0x3e,
0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x3c, 0x68, 0x33,
0x3e, 0x47, 0x6f, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65,
0x66, 0x3d, 0x22, 0x2f, 0x22, 0x3e, 0x68, 0x65, 0x72, 0x65,
0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x69, 0x6e, 0x73, 0x74, 0x65,
0x61, 0x64, 0x2e, 0x3c, 0x2f, 0x68, 0x33, 0x3e, 0xa, 0x20,
0x20, 0x20, 0x20, 0x3c, 0x2f, 0x63, 0x65, 0x6e, 0x74, 0x65,
0x72, 0x3e, 0xa, 0x20, 0x20, 0x3c, 0x2f, 0x62, 0x6f, 0x64,
0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x3e,
0};
static const char data_index_html[] = {
/* /index.html */
0x2f, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x68, 0x74, 0x6d, 0x6c, 0,
0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20,
0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49,
0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f,
0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20,
0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73,
0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45,
0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f,
0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72,
0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34,
0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64,
0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa,
0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20,
0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e,
0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f,
0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42,
0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65,
0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e,
0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e,
0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x20, 0x6f,
0x6e, 0x4c, 0x6f, 0x61, 0x64, 0x3d, 0x22, 0x77, 0x69, 0x6e,
0x64, 0x6f, 0x77, 0x2e, 0x73, 0x65, 0x74, 0x54, 0x69, 0x6d,
0x65, 0x6f, 0x75, 0x74, 0x28, 0x26, 0x71, 0x75, 0x6f, 0x74,
0x3b, 0x6c, 0x6f, 0x63, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x2e,
0x68, 0x72, 0x65, 0x66, 0x3d, 0x27, 0x69, 0x6e, 0x64, 0x65,
0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x27, 0x26, 0x71,
0x75, 0x6f, 0x74, 0x3b, 0x2c, 0x31, 0x30, 0x30, 0x29, 0x22,
0x3e, 0xa, 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61,
0x63, 0x65, 0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c, 0x22,
0x3e, 0xa, 0x4c, 0x6f, 0x61, 0x64, 0x69, 0x6e, 0x67, 0x20,
0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d,
0x6c, 0x2e, 0x20, 0x20, 0x43, 0x6c, 0x69, 0x63, 0x6b, 0x20,
0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69,
0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c,
0x22, 0x3e, 0x68, 0x65, 0x72, 0x65, 0x3c, 0x2f, 0x61, 0x3e,
0x20, 0x69, 0x66, 0x20, 0x6e, 0x6f, 0x74, 0x20, 0x61, 0x75,
0x74, 0x6f, 0x6d, 0x61, 0x74, 0x69, 0x63, 0x61, 0x6c, 0x6c,
0x79, 0x20, 0x72, 0x65, 0x64, 0x69, 0x72, 0x65, 0x63, 0x74,
0x65, 0x64, 0x2e, 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74,
0x3e, 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa,
0x3c, 0x2f, 0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f,
0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, 0xa, 0};
static const char data_index_shtml[] = {
/* /index.shtml */
0x2f, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0,
0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20,
0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49,
0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f,
0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20,
0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73,
0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45,
0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f,
0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72,
0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34,
0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64,
0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa,
0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20,
0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e,
0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f,
0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42,
0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65,
0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e,
0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e,
0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x20, 0x6f,
0x6e, 0x4c, 0x6f, 0x61, 0x64, 0x3d, 0x22, 0x77, 0x69, 0x6e,
0x64, 0x6f, 0x77, 0x2e, 0x73, 0x65, 0x74, 0x54, 0x69, 0x6d,
0x65, 0x6f, 0x75, 0x74, 0x28, 0x26, 0x71, 0x75, 0x6f, 0x74,
0x3b, 0x6c, 0x6f, 0x63, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x2e,
0x68, 0x72, 0x65, 0x66, 0x3d, 0x27, 0x69, 0x6e, 0x64, 0x65,
0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x27, 0x26, 0x71,
0x75, 0x6f, 0x74, 0x3b, 0x2c, 0x32, 0x30, 0x30, 0x30, 0x29,
0x22, 0x3e, 0xa, 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66,
0x61, 0x63, 0x65, 0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c,
0x22, 0x3e, 0xa, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66,
0x3d, 0x22, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68,
0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20,
0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20,
0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c,
0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x72, 0x75,
0x6e, 0x74, 0x69, 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d,
0x6c, 0x22, 0x3e, 0x52, 0x75, 0x6e, 0x20, 0x54, 0x69, 0x6d,
0x65, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61,
0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e,
0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22,
0x73, 0x74, 0x61, 0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d,
0x6c, 0x22, 0x3e, 0x54, 0x43, 0x50, 0x20, 0x53, 0x74, 0x61,
0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e,
0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68,
0x72, 0x65, 0x66, 0x3d, 0x22, 0x74, 0x63, 0x70, 0x2e, 0x73,
0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x43, 0x6f, 0x6e, 0x6e,
0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x61,
0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e,
0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22,
0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77,
0x2e, 0x66, 0x72, 0x65, 0x65, 0x72, 0x74, 0x6f, 0x73, 0x2e,
0x6f, 0x72, 0x67, 0x2f, 0x22, 0x3e, 0x46, 0x72, 0x65, 0x65,
0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, 0x72, 0x67, 0x20, 0x48,
0x6f, 0x6d, 0x65, 0x70, 0x61, 0x67, 0x65, 0x3c, 0x2f, 0x61,
0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e,
0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22,
0x69, 0x6f, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e,
0x49, 0x4f, 0x3c, 0x2f, 0x61, 0x3e, 0xa, 0x3c, 0x62, 0x72,
0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x68, 0x72, 0x3e, 0xa,
0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x68,
0x32, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x73, 0x74, 0x61,
0x74, 0x69, 0x73, 0x74, 0x69, 0x63, 0x73, 0x3c, 0x2f, 0x68,
0x32, 0x3e, 0xa, 0x50, 0x61, 0x67, 0x65, 0x20, 0x77, 0x69,
0x6c, 0x6c, 0x20, 0x72, 0x65, 0x66, 0x72, 0x65, 0x73, 0x68,
0x20, 0x65, 0x76, 0x65, 0x72, 0x79, 0x20, 0x32, 0x20, 0x73,
0x65, 0x63, 0x6f, 0x6e, 0x64, 0x73, 0x2e, 0x3c, 0x70, 0x3e,
0xa, 0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61, 0x63,
0x65, 0x3d, 0x22, 0x63, 0x6f, 0x75, 0x72, 0x69, 0x65, 0x72,
0x22, 0x3e, 0x3c, 0x70, 0x72, 0x65, 0x3e, 0x54, 0x61, 0x73,
0x6b, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x53, 0x74, 0x61, 0x74, 0x65, 0x20, 0x20, 0x50, 0x72,
0x69, 0x6f, 0x72, 0x69, 0x74, 0x79, 0x20, 0x20, 0x53, 0x74,
0x61, 0x63, 0x6b, 0x9, 0x23, 0x3c, 0x62, 0x72, 0x3e, 0x2a,
0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a,
0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a,
0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a,
0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a,
0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x3c, 0x62, 0x72,
0x3e, 0xa, 0x25, 0x21, 0x20, 0x72, 0x74, 0x6f, 0x73, 0x2d,
0x73, 0x74, 0x61, 0x74, 0x73, 0xa, 0x3c, 0x2f, 0x70, 0x72,
0x65, 0x3e, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa,
0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, 0x3c, 0x2f,
0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68, 0x74,
0x6d, 0x6c, 0x3e, 0xa, 0xa, 0};
static const char data_io_shtml[] = {
/* /io.shtml */
0x2f, 0x69, 0x6f, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0,
0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20,
0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49,
0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f,
0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20,
0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73,
0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45,
0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f,
0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72,
0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34,
0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64,
0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa,
0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20,
0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e,
0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f,
0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42,
0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65,
0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e,
0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e,
0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x3e, 0xa,
0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61, 0x63, 0x65,
0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c, 0x22, 0x3e, 0xa,
0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69,
0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c,
0x22, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x53, 0x74, 0x61,
0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e,
0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68,
0x72, 0x65, 0x66, 0x3d, 0x22, 0x72, 0x75, 0x6e, 0x74, 0x69,
0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e,
0x52, 0x75, 0x6e, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x20, 0x53,
0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c,
0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61,
0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x73, 0x74, 0x61,
0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e,
0x54, 0x43, 0x50, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c,
0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f,
0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66,
0x3d, 0x22, 0x74, 0x63, 0x70, 0x2e, 0x73, 0x68, 0x74, 0x6d,
0x6c, 0x22, 0x3e, 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74,
0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c,
0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61,
0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x68, 0x74, 0x74,
0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x66, 0x72,
0x65, 0x65, 0x72, 0x74, 0x6f, 0x73, 0x2e, 0x6f, 0x72, 0x67,
0x2f, 0x22, 0x3e, 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f,
0x53, 0x2e, 0x6f, 0x72, 0x67, 0x20, 0x48, 0x6f, 0x6d, 0x65,
0x70, 0x61, 0x67, 0x65, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c,
0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61,
0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, 0x6f, 0x2e,
0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x49, 0x4f, 0x3c,
0x2f, 0x61, 0x3e, 0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70,
0x3e, 0xa, 0x3c, 0x68, 0x72, 0x3e, 0xa, 0x3c, 0x62, 0x3e,
0x4c, 0x45, 0x44, 0x20, 0x61, 0x6e, 0x64, 0x20, 0x4c, 0x43,
0x44, 0x20, 0x49, 0x4f, 0x3c, 0x2f, 0x62, 0x3e, 0x3c, 0x62,
0x72, 0x3e, 0xa, 0xa, 0x3c, 0x70, 0x3e, 0xa, 0xa, 0x55,
0x73, 0x65, 0x20, 0x74, 0x68, 0x65, 0x20, 0x63, 0x68, 0x65,
0x63, 0x6b, 0x20, 0x62, 0x6f, 0x78, 0x20, 0x74, 0x6f, 0x20,
0x74, 0x75, 0x72, 0x6e, 0x20, 0x6f, 0x6e, 0x20, 0x6f, 0x72,
0x20, 0x6f, 0x66, 0x66, 0x20, 0x74, 0x68, 0x65, 0x20, 0x4c,
0x45, 0x44, 0x2c, 0x20, 0x65, 0x6e, 0x74, 0x65, 0x72, 0x20,
0x74, 0x65, 0x78, 0x74, 0x20, 0x74, 0x6f, 0x20, 0x64, 0x69,
0x73, 0x70, 0x6c, 0x61, 0x79, 0x20, 0x6f, 0x6e, 0x20, 0x74,
0x68, 0x65, 0x20, 0x4f, 0x4c, 0x45, 0x44, 0x20, 0x64, 0x69,
0x73, 0x70, 0x6c, 0x61, 0x79, 0x2c, 0x20, 0x74, 0x68, 0x65,
0x6e, 0x20, 0x63, 0x6c, 0x69, 0x63, 0x6b, 0x20, 0x22, 0x55,
0x70, 0x64, 0x61, 0x74, 0x65, 0x20, 0x49, 0x4f, 0x22, 0x2e,
0xa, 0xa, 0xa, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x66, 0x6f,
0x72, 0x6d, 0x20, 0x6e, 0x61, 0x6d, 0x65, 0x3d, 0x22, 0x61,
0x46, 0x6f, 0x72, 0x6d, 0x22, 0x20, 0x61, 0x63, 0x74, 0x69,
0x6f, 0x6e, 0x3d, 0x22, 0x2f, 0x69, 0x6f, 0x2e, 0x73, 0x68,
0x74, 0x6d, 0x6c, 0x22, 0x20, 0x6d, 0x65, 0x74, 0x68, 0x6f,
0x64, 0x3d, 0x22, 0x67, 0x65, 0x74, 0x22, 0x3e, 0xa, 0x25,
0x21, 0x20, 0x6c, 0x65, 0x64, 0x2d, 0x69, 0x6f, 0xa, 0x3c,
0x70, 0x3e, 0xa, 0x3c, 0x69, 0x6e, 0x70, 0x75, 0x74, 0x20,
0x74, 0x79, 0x70, 0x65, 0x3d, 0x22, 0x73, 0x75, 0x62, 0x6d,
0x69, 0x74, 0x22, 0x20, 0x76, 0x61, 0x6c, 0x75, 0x65, 0x3d,
0x22, 0x55, 0x70, 0x64, 0x61, 0x74, 0x65, 0x20, 0x49, 0x4f,
0x22, 0x3e, 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x72, 0x6d, 0x3e,
0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c,
0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, 0x3c, 0x2f, 0x62,
0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68, 0x74, 0x6d,
0x6c, 0x3e, 0xa, 0xa, 0};
static const char data_runtime_shtml[] = {
/* /runtime.shtml */
0x2f, 0x72, 0x75, 0x6e, 0x74, 0x69, 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0,
0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20,
0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49,
0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f,
0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20,
0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73,
0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45,
0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f,
0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72,
0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34,
0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64,
0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa,
0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20,
0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e,
0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f,
0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42,
0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65,
0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e,
0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e,
0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x20, 0x6f,
0x6e, 0x4c, 0x6f, 0x61, 0x64, 0x3d, 0x22, 0x77, 0x69, 0x6e,
0x64, 0x6f, 0x77, 0x2e, 0x73, 0x65, 0x74, 0x54, 0x69, 0x6d,
0x65, 0x6f, 0x75, 0x74, 0x28, 0x26, 0x71, 0x75, 0x6f, 0x74,
0x3b, 0x6c, 0x6f, 0x63, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x2e,
0x68, 0x72, 0x65, 0x66, 0x3d, 0x27, 0x72, 0x75, 0x6e, 0x74,
0x69, 0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x27,
0x26, 0x71, 0x75, 0x6f, 0x74, 0x3b, 0x2c, 0x32, 0x30, 0x30,
0x30, 0x29, 0x22, 0x3e, 0xa, 0x3c, 0x66, 0x6f, 0x6e, 0x74,
0x20, 0x66, 0x61, 0x63, 0x65, 0x3d, 0x22, 0x61, 0x72, 0x69,
0x61, 0x6c, 0x22, 0x3e, 0xa, 0x3c, 0x61, 0x20, 0x68, 0x72,
0x65, 0x66, 0x3d, 0x22, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x2e,
0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x54, 0x61, 0x73,
0x6b, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61,
0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e,
0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22,
0x72, 0x75, 0x6e, 0x74, 0x69, 0x6d, 0x65, 0x2e, 0x73, 0x68,
0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x52, 0x75, 0x6e, 0x20, 0x54,
0x69, 0x6d, 0x65, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c,
0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f,
0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66,
0x3d, 0x22, 0x73, 0x74, 0x61, 0x74, 0x73, 0x2e, 0x73, 0x68,
0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x54, 0x43, 0x50, 0x20, 0x53,
0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c,
0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61,
0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x74, 0x63, 0x70,
0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x43, 0x6f,
0x6e, 0x6e, 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x73, 0x3c,
0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f,
0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66,
0x3d, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f, 0x2f, 0x77,
0x77, 0x77, 0x2e, 0x66, 0x72, 0x65, 0x65, 0x72, 0x74, 0x6f,
0x73, 0x2e, 0x6f, 0x72, 0x67, 0x2f, 0x22, 0x3e, 0x46, 0x72,
0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f, 0x72, 0x67,
0x20, 0x48, 0x6f, 0x6d, 0x65, 0x70, 0x61, 0x67, 0x65, 0x3c,
0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f,
0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66,
0x3d, 0x22, 0x69, 0x6f, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c,
0x22, 0x3e, 0x49, 0x4f, 0x3c, 0x2f, 0x61, 0x3e, 0xa, 0x3c,
0x62, 0x72, 0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x68, 0x72,
0x3e, 0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70, 0x3e, 0xa,
0x3c, 0x68, 0x32, 0x3e, 0x52, 0x75, 0x6e, 0x2d, 0x74, 0x69,
0x6d, 0x65, 0x20, 0x73, 0x74, 0x61, 0x74, 0x69, 0x73, 0x74,
0x69, 0x63, 0x73, 0x3c, 0x2f, 0x68, 0x32, 0x3e, 0xa, 0x50,
0x61, 0x67, 0x65, 0x20, 0x77, 0x69, 0x6c, 0x6c, 0x20, 0x72,
0x65, 0x66, 0x72, 0x65, 0x73, 0x68, 0x20, 0x65, 0x76, 0x65,
0x72, 0x79, 0x20, 0x32, 0x20, 0x73, 0x65, 0x63, 0x6f, 0x6e,
0x64, 0x73, 0x2e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x66, 0x6f,
0x6e, 0x74, 0x20, 0x66, 0x61, 0x63, 0x65, 0x3d, 0x22, 0x63,
0x6f, 0x75, 0x72, 0x69, 0x65, 0x72, 0x22, 0x3e, 0x3c, 0x70,
0x72, 0x65, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x41,
0x62, 0x73, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x25, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x3c,
0x62, 0x72, 0x3e, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a,
0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a,
0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a,
0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a, 0x2a,
0x2a, 0x2a, 0x2a, 0x3c, 0x62, 0x72, 0x3e, 0xa, 0x25, 0x21,
0x20, 0x72, 0x75, 0x6e, 0x2d, 0x74, 0x69, 0x6d, 0x65, 0xa,
0x3c, 0x2f, 0x70, 0x72, 0x65, 0x3e, 0x3c, 0x2f, 0x66, 0x6f,
0x6e, 0x74, 0x3e, 0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74,
0x3e, 0xa, 0x3c, 0x2f, 0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa,
0x3c, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa, 0xa, 0};
static const char data_stats_shtml[] = {
/* /stats.shtml */
0x2f, 0x73, 0x74, 0x61, 0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0,
0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20,
0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49,
0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f,
0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20,
0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73,
0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45,
0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f,
0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72,
0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34,
0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64,
0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa,
0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20,
0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e,
0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f,
0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42,
0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65,
0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e,
0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e,
0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x3e, 0xa,
0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61, 0x63, 0x65,
0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c, 0x22, 0x3e, 0xa,
0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69,
0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c,
0x22, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x53, 0x74, 0x61,
0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e,
0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68,
0x72, 0x65, 0x66, 0x3d, 0x22, 0x72, 0x75, 0x6e, 0x74, 0x69,
0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e,
0x52, 0x75, 0x6e, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x20, 0x53,
0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c,
0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61,
0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x73, 0x74, 0x61,
0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e,
0x54, 0x43, 0x50, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c,
0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f,
0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66,
0x3d, 0x22, 0x74, 0x63, 0x70, 0x2e, 0x73, 0x68, 0x74, 0x6d,
0x6c, 0x22, 0x3e, 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74,
0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c,
0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61,
0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x68, 0x74, 0x74,
0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x66, 0x72,
0x65, 0x65, 0x72, 0x74, 0x6f, 0x73, 0x2e, 0x6f, 0x72, 0x67,
0x2f, 0x22, 0x3e, 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f,
0x53, 0x2e, 0x6f, 0x72, 0x67, 0x20, 0x48, 0x6f, 0x6d, 0x65,
0x70, 0x61, 0x67, 0x65, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c,
0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61,
0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, 0x6f, 0x2e,
0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x49, 0x4f, 0x3c,
0x2f, 0x61, 0x3e, 0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70,
0x3e, 0xa, 0x3c, 0x68, 0x72, 0x3e, 0xa, 0x3c, 0x62, 0x72,
0x3e, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x68, 0x32, 0x3e, 0x4e,
0x65, 0x74, 0x77, 0x6f, 0x72, 0x6b, 0x20, 0x73, 0x74, 0x61,
0x74, 0x69, 0x73, 0x74, 0x69, 0x63, 0x73, 0x3c, 0x2f, 0x68,
0x32, 0x3e, 0xa, 0x3c, 0x74, 0x61, 0x62, 0x6c, 0x65, 0x20,
0x77, 0x69, 0x64, 0x74, 0x68, 0x3d, 0x22, 0x33, 0x30, 0x30,
0x22, 0x20, 0x62, 0x6f, 0x72, 0x64, 0x65, 0x72, 0x3d, 0x22,
0x30, 0x22, 0x3e, 0xa, 0x3c, 0x74, 0x72, 0x3e, 0x3c, 0x74,
0x64, 0x20, 0x61, 0x6c, 0x69, 0x67, 0x6e, 0x3d, 0x22, 0x6c,
0x65, 0x66, 0x74, 0x22, 0x3e, 0x3c, 0x66, 0x6f, 0x6e, 0x74,
0x20, 0x66, 0x61, 0x63, 0x65, 0x3d, 0x22, 0x63, 0x6f, 0x75,
0x72, 0x69, 0x65, 0x72, 0x22, 0x3e, 0x3c, 0x70, 0x72, 0x65,
0x3e, 0xa, 0x49, 0x50, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65,
0x74, 0x73, 0x20, 0x64, 0x72, 0x6f, 0x70, 0x70, 0x65, 0x64,
0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74,
0x73, 0x20, 0x72, 0x65, 0x63, 0x65, 0x69, 0x76, 0x65, 0x64,
0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74,
0x73, 0x20, 0x73, 0x65, 0x6e, 0x74, 0xa, 0x49, 0x50, 0x20,
0x65, 0x72, 0x72, 0x6f, 0x72, 0x73, 0x20, 0x20, 0x20, 0x20,
0x49, 0x50, 0x20, 0x76, 0x65, 0x72, 0x73, 0x69, 0x6f, 0x6e,
0x2f, 0x68, 0x65, 0x61, 0x64, 0x65, 0x72, 0x20, 0x6c, 0x65,
0x6e, 0x67, 0x74, 0x68, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x49, 0x50,
0x20, 0x6c, 0x65, 0x6e, 0x67, 0x74, 0x68, 0x2c, 0x20, 0x68,
0x69, 0x67, 0x68, 0x20, 0x62, 0x79, 0x74, 0x65, 0xa, 0x20,
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x20, 0x49, 0x50, 0x20, 0x6c, 0x65, 0x6e, 0x67, 0x74,
0x68, 0x2c, 0x20, 0x6c, 0x6f, 0x77, 0x20, 0x62, 0x79, 0x74,
0x65, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x20, 0x49, 0x50, 0x20, 0x66, 0x72,
0x61, 0x67, 0x6d, 0x65, 0x6e, 0x74, 0x73, 0xa, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x48, 0x65, 0x61, 0x64, 0x65, 0x72, 0x20, 0x63, 0x68,
0x65, 0x63, 0x6b, 0x73, 0x75, 0x6d, 0xa, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
0x57, 0x72, 0x6f, 0x6e, 0x67, 0x20, 0x70, 0x72, 0x6f, 0x74,
0x6f, 0x63, 0x6f, 0x6c, 0xa, 0x49, 0x43, 0x4d, 0x50, 0x9,
0x20, 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65,
0x74, 0x73, 0x20, 0x64, 0x72, 0x6f, 0x70, 0x70, 0x65, 0x64,
0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74,
0x73, 0x20, 0x72, 0x65, 0x63, 0x65, 0x69, 0x76, 0x65, 0x64,
0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74,
0x73, 0x20, 0x73, 0x65, 0x6e, 0x74, 0xa, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
0x54, 0x79, 0x70, 0x65, 0x20, 0x65, 0x72, 0x72, 0x6f, 0x72,
0x73, 0xa, 0x54, 0x43, 0x50, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65,
0x74, 0x73, 0x20, 0x64, 0x72, 0x6f, 0x70, 0x70, 0x65, 0x64,
0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74,
0x73, 0x20, 0x72, 0x65, 0x63, 0x65, 0x69, 0x76, 0x65, 0x64,
0xa, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x50, 0x61, 0x63, 0x6b, 0x65, 0x74,
0x73, 0x20, 0x73, 0x65, 0x6e, 0x74, 0xa, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
0x43, 0x68, 0x65, 0x63, 0x6b, 0x73, 0x75, 0x6d, 0x20, 0x65,
0x72, 0x72, 0x6f, 0x72, 0x73, 0xa, 0x20, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x44,
0x61, 0x74, 0x61, 0x20, 0x70, 0x61, 0x63, 0x6b, 0x65, 0x74,
0x73, 0x20, 0x77, 0x69, 0x74, 0x68, 0x6f, 0x75, 0x74, 0x20,
0x41, 0x43, 0x4b, 0x73, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x52, 0x65,
0x73, 0x65, 0x74, 0x73, 0xa, 0x20, 0x20, 0x20, 0x20, 0x20,
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x52, 0x65,
0x74, 0x72, 0x61, 0x6e, 0x73, 0x6d, 0x69, 0x73, 0x73, 0x69,
0x6f, 0x6e, 0x73, 0xa, 0x9, 0x20, 0x20, 0x20, 0x20, 0x20,
0x4e, 0x6f, 0x20, 0x63, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74,
0x69, 0x6f, 0x6e, 0x20, 0x61, 0x76, 0x61, 0x6c, 0x69, 0x61,
0x62, 0x6c, 0x65, 0xa, 0x9, 0x20, 0x20, 0x20, 0x20, 0x20,
0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e,
0x20, 0x61, 0x74, 0x74, 0x65, 0x6d, 0x70, 0x74, 0x73, 0x20,
0x74, 0x6f, 0x20, 0x63, 0x6c, 0x6f, 0x73, 0x65, 0x64, 0x20,
0x70, 0x6f, 0x72, 0x74, 0x73, 0xa, 0x3c, 0x2f, 0x70, 0x72,
0x65, 0x3e, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0x3c,
0x2f, 0x74, 0x64, 0x3e, 0x3c, 0x74, 0x64, 0x3e, 0x3c, 0x70,
0x72, 0x65, 0x3e, 0x25, 0x21, 0x20, 0x6e, 0x65, 0x74, 0x2d,
0x73, 0x74, 0x61, 0x74, 0x73, 0xa, 0x3c, 0x2f, 0x70, 0x72,
0x65, 0x3e, 0x3c, 0x2f, 0x74, 0x61, 0x62, 0x6c, 0x65, 0x3e,
0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, 0x3c,
0x2f, 0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68,
0x74, 0x6d, 0x6c, 0x3e, 0xa, 0};
static const char data_tcp_shtml[] = {
/* /tcp.shtml */
0x2f, 0x74, 0x63, 0x70, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0,
0x3c, 0x21, 0x44, 0x4f, 0x43, 0x54, 0x59, 0x50, 0x45, 0x20,
0x48, 0x54, 0x4d, 0x4c, 0x20, 0x50, 0x55, 0x42, 0x4c, 0x49,
0x43, 0x20, 0x22, 0x2d, 0x2f, 0x2f, 0x57, 0x33, 0x43, 0x2f,
0x2f, 0x44, 0x54, 0x44, 0x20, 0x48, 0x54, 0x4d, 0x4c, 0x20,
0x34, 0x2e, 0x30, 0x31, 0x20, 0x54, 0x72, 0x61, 0x6e, 0x73,
0x69, 0x74, 0x69, 0x6f, 0x6e, 0x61, 0x6c, 0x2f, 0x2f, 0x45,
0x4e, 0x22, 0x20, 0x22, 0x68, 0x74, 0x74, 0x70, 0x3a, 0x2f,
0x2f, 0x77, 0x77, 0x77, 0x2e, 0x77, 0x33, 0x2e, 0x6f, 0x72,
0x67, 0x2f, 0x54, 0x52, 0x2f, 0x68, 0x74, 0x6d, 0x6c, 0x34,
0x2f, 0x6c, 0x6f, 0x6f, 0x73, 0x65, 0x2e, 0x64, 0x74, 0x64,
0x22, 0x3e, 0xa, 0x3c, 0x68, 0x74, 0x6d, 0x6c, 0x3e, 0xa,
0x20, 0x20, 0x3c, 0x68, 0x65, 0x61, 0x64, 0x3e, 0xa, 0x20,
0x20, 0x20, 0x20, 0x3c, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e,
0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f, 0x53, 0x2e, 0x6f,
0x72, 0x67, 0x20, 0x75, 0x49, 0x50, 0x20, 0x57, 0x45, 0x42,
0x20, 0x73, 0x65, 0x72, 0x76, 0x65, 0x72, 0x20, 0x64, 0x65,
0x6d, 0x6f, 0x3c, 0x2f, 0x74, 0x69, 0x74, 0x6c, 0x65, 0x3e,
0xa, 0x20, 0x20, 0x3c, 0x2f, 0x68, 0x65, 0x61, 0x64, 0x3e,
0xa, 0x20, 0x20, 0x3c, 0x42, 0x4f, 0x44, 0x59, 0x3e, 0xa,
0x3c, 0x66, 0x6f, 0x6e, 0x74, 0x20, 0x66, 0x61, 0x63, 0x65,
0x3d, 0x22, 0x61, 0x72, 0x69, 0x61, 0x6c, 0x22, 0x3e, 0xa,
0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69,
0x6e, 0x64, 0x65, 0x78, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c,
0x22, 0x3e, 0x54, 0x61, 0x73, 0x6b, 0x20, 0x53, 0x74, 0x61,
0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e,
0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68,
0x72, 0x65, 0x66, 0x3d, 0x22, 0x72, 0x75, 0x6e, 0x74, 0x69,
0x6d, 0x65, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e,
0x52, 0x75, 0x6e, 0x20, 0x54, 0x69, 0x6d, 0x65, 0x20, 0x53,
0x74, 0x61, 0x74, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c,
0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61,
0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x73, 0x74, 0x61,
0x74, 0x73, 0x2e, 0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e,
0x54, 0x43, 0x50, 0x20, 0x53, 0x74, 0x61, 0x74, 0x73, 0x3c,
0x2f, 0x61, 0x3e, 0x20, 0x3c, 0x62, 0x3e, 0x7c, 0x3c, 0x2f,
0x62, 0x3e, 0x20, 0x3c, 0x61, 0x20, 0x68, 0x72, 0x65, 0x66,
0x3d, 0x22, 0x74, 0x63, 0x70, 0x2e, 0x73, 0x68, 0x74, 0x6d,
0x6c, 0x22, 0x3e, 0x43, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74,
0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c,
0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61,
0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x68, 0x74, 0x74,
0x70, 0x3a, 0x2f, 0x2f, 0x77, 0x77, 0x77, 0x2e, 0x66, 0x72,
0x65, 0x65, 0x72, 0x74, 0x6f, 0x73, 0x2e, 0x6f, 0x72, 0x67,
0x2f, 0x22, 0x3e, 0x46, 0x72, 0x65, 0x65, 0x52, 0x54, 0x4f,
0x53, 0x2e, 0x6f, 0x72, 0x67, 0x20, 0x48, 0x6f, 0x6d, 0x65,
0x70, 0x61, 0x67, 0x65, 0x3c, 0x2f, 0x61, 0x3e, 0x20, 0x3c,
0x62, 0x3e, 0x7c, 0x3c, 0x2f, 0x62, 0x3e, 0x20, 0x3c, 0x61,
0x20, 0x68, 0x72, 0x65, 0x66, 0x3d, 0x22, 0x69, 0x6f, 0x2e,
0x73, 0x68, 0x74, 0x6d, 0x6c, 0x22, 0x3e, 0x49, 0x4f, 0x3c,
0x2f, 0x61, 0x3e, 0xa, 0x3c, 0x62, 0x72, 0x3e, 0x3c, 0x70,
0x3e, 0xa, 0x3c, 0x68, 0x72, 0x3e, 0xa, 0x3c, 0x62, 0x72,
0x3e, 0xa, 0x3c, 0x68, 0x32, 0x3e, 0x4e, 0x65, 0x74, 0x77,
0x6f, 0x72, 0x6b, 0x20, 0x63, 0x6f, 0x6e, 0x6e, 0x65, 0x63,
0x74, 0x69, 0x6f, 0x6e, 0x73, 0x3c, 0x2f, 0x68, 0x32, 0x3e,
0xa, 0x3c, 0x70, 0x3e, 0xa, 0x3c, 0x74, 0x61, 0x62, 0x6c,
0x65, 0x3e, 0xa, 0x3c, 0x74, 0x72, 0x3e, 0x3c, 0x74, 0x68,
0x3e, 0x4c, 0x6f, 0x63, 0x61, 0x6c, 0x3c, 0x2f, 0x74, 0x68,
0x3e, 0x3c, 0x74, 0x68, 0x3e, 0x52, 0x65, 0x6d, 0x6f, 0x74,
0x65, 0x3c, 0x2f, 0x74, 0x68, 0x3e, 0x3c, 0x74, 0x68, 0x3e,
0x53, 0x74, 0x61, 0x74, 0x65, 0x3c, 0x2f, 0x74, 0x68, 0x3e,
0x3c, 0x74, 0x68, 0x3e, 0x52, 0x65, 0x74, 0x72, 0x61, 0x6e,
0x73, 0x6d, 0x69, 0x73, 0x73, 0x69, 0x6f, 0x6e, 0x73, 0x3c,
0x2f, 0x74, 0x68, 0x3e, 0x3c, 0x74, 0x68, 0x3e, 0x54, 0x69,
0x6d, 0x65, 0x72, 0x3c, 0x2f, 0x74, 0x68, 0x3e, 0x3c, 0x74,
0x68, 0x3e, 0x46, 0x6c, 0x61, 0x67, 0x73, 0x3c, 0x2f, 0x74,
0x68, 0x3e, 0x3c, 0x2f, 0x74, 0x72, 0x3e, 0xa, 0x25, 0x21,
0x20, 0x74, 0x63, 0x70, 0x2d, 0x63, 0x6f, 0x6e, 0x6e, 0x65,
0x63, 0x74, 0x69, 0x6f, 0x6e, 0x73, 0xa, 0x3c, 0x2f, 0x70,
0x72, 0x65, 0x3e, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e,
0xa, 0x3c, 0x2f, 0x66, 0x6f, 0x6e, 0x74, 0x3e, 0xa, 0x3c,
0x2f, 0x62, 0x6f, 0x64, 0x79, 0x3e, 0xa, 0x3c, 0x2f, 0x68,
0x74, 0x6d, 0x6c, 0x3e, 0xa, 0xa, 0};
const struct httpd_fsdata_file file_404_html[] = {{NULL, data_404_html, data_404_html + 10, sizeof(data_404_html) - 10, 0}};
const struct httpd_fsdata_file file_index_html[] = {{file_404_html, data_index_html, data_index_html + 12, sizeof(data_index_html) - 12, 0}};
const struct httpd_fsdata_file file_index_shtml[] = {{file_index_html, data_index_shtml, data_index_shtml + 13, sizeof(data_index_shtml) - 13, 0}};
const struct httpd_fsdata_file file_io_shtml[] = {{file_index_shtml, data_io_shtml, data_io_shtml + 10, sizeof(data_io_shtml) - 10, 0}};
const struct httpd_fsdata_file file_runtime_shtml[] = {{file_io_shtml, data_runtime_shtml, data_runtime_shtml + 15, sizeof(data_runtime_shtml) - 15, 0}};
const struct httpd_fsdata_file file_stats_shtml[] = {{file_runtime_shtml, data_stats_shtml, data_stats_shtml + 13, sizeof(data_stats_shtml) - 13, 0}};
const struct httpd_fsdata_file file_tcp_shtml[] = {{file_stats_shtml, data_tcp_shtml, data_tcp_shtml + 11, sizeof(data_tcp_shtml) - 11, 0}};
#define HTTPD_FS_ROOT file_tcp_shtml
#define HTTPD_FS_NUMFILES 7

View File

@ -0,0 +1,64 @@
/*
* Copyright (c) 2001, Swedish Institute of Computer Science.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the Institute nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*
* This file is part of the lwIP TCP/IP stack.
*
* Author: Adam Dunkels <adam@sics.se>
*
* $Id: httpd-fsdata.h,v 1.1 2006/06/07 09:13:08 adam Exp $
*/
#ifndef __HTTPD_FSDATA_H__
#define __HTTPD_FSDATA_H__
#include "uip.h"
struct httpd_fsdata_file {
const struct httpd_fsdata_file *next;
const char *name;
const char *data;
const int len;
#ifdef HTTPD_FS_STATISTICS
#if HTTPD_FS_STATISTICS == 1
u16_t count;
#endif /* HTTPD_FS_STATISTICS */
#endif /* HTTPD_FS_STATISTICS */
};
struct httpd_fsdata_file_noconst {
struct httpd_fsdata_file *next;
char *name;
char *data;
int len;
#ifdef HTTPD_FS_STATISTICS
#if HTTPD_FS_STATISTICS == 1
u16_t count;
#endif /* HTTPD_FS_STATISTICS */
#endif /* HTTPD_FS_STATISTICS */
};
#endif /* __HTTPD_FSDATA_H__ */

View File

@ -0,0 +1,346 @@
/**
* \addtogroup apps
* @{
*/
/**
* \defgroup httpd Web server
* @{
* The uIP web server is a very simplistic implementation of an HTTP
* server. It can serve web pages and files from a read-only ROM
* filesystem, and provides a very small scripting language.
*/
/**
* \file
* Web server
* \author
* Adam Dunkels <adam@sics.se>
*/
/*
* Copyright (c) 2004, Adam Dunkels.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the Institute nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*
* This file is part of the uIP TCP/IP stack.
*
* Author: Adam Dunkels <adam@sics.se>
*
* $Id: httpd.c,v 1.2 2006/06/11 21:46:38 adam Exp $
*/
#include "uip.h"
#include "httpd.h"
#include "httpd-fs.h"
#include "httpd-cgi.h"
#include "http-strings.h"
#include <string.h>
#define STATE_WAITING 0
#define STATE_OUTPUT 1
#define ISO_nl 0x0a
#define ISO_space 0x20
#define ISO_bang 0x21
#define ISO_percent 0x25
#define ISO_period 0x2e
#define ISO_slash 0x2f
#define ISO_colon 0x3a
/*---------------------------------------------------------------------------*/
static unsigned short
generate_part_of_file(void *state)
{
struct httpd_state *s = (struct httpd_state *)state;
if(s->file.len > uip_mss()) {
s->len = uip_mss();
} else {
s->len = s->file.len;
}
memcpy(uip_appdata, s->file.data, s->len);
return s->len;
}
/*---------------------------------------------------------------------------*/
static
PT_THREAD(send_file(struct httpd_state *s))
{
PSOCK_BEGIN(&s->sout);
do {
PSOCK_GENERATOR_SEND(&s->sout, generate_part_of_file, s);
s->file.len -= s->len;
s->file.data += s->len;
} while(s->file.len > 0);
PSOCK_END(&s->sout);
}
/*---------------------------------------------------------------------------*/
static
PT_THREAD(send_part_of_file(struct httpd_state *s))
{
PSOCK_BEGIN(&s->sout);
PSOCK_SEND(&s->sout, s->file.data, s->len);
PSOCK_END(&s->sout);
}
/*---------------------------------------------------------------------------*/
static void
next_scriptstate(struct httpd_state *s)
{
char *p;
p = strchr(s->scriptptr, ISO_nl) + 1;
s->scriptlen -= (unsigned short)(p - s->scriptptr);
s->scriptptr = p;
}
/*---------------------------------------------------------------------------*/
static
PT_THREAD(handle_script(struct httpd_state *s))
{
char *ptr;
PT_BEGIN(&s->scriptpt);
while(s->file.len > 0) {
/* Check if we should start executing a script. */
if(*s->file.data == ISO_percent &&
*(s->file.data + 1) == ISO_bang) {
s->scriptptr = s->file.data + 3;
s->scriptlen = s->file.len - 3;
if(*(s->scriptptr - 1) == ISO_colon) {
httpd_fs_open(s->scriptptr + 1, &s->file);
PT_WAIT_THREAD(&s->scriptpt, send_file(s));
} else {
PT_WAIT_THREAD(&s->scriptpt,
httpd_cgi(s->scriptptr)(s, s->scriptptr));
}
next_scriptstate(s);
/* The script is over, so we reset the pointers and continue
sending the rest of the file. */
s->file.data = s->scriptptr;
s->file.len = s->scriptlen;
} else {
/* See if we find the start of script marker in the block of HTML
to be sent. */
if(s->file.len > uip_mss()) {
s->len = uip_mss();
} else {
s->len = s->file.len;
}
if(*s->file.data == ISO_percent) {
ptr = strchr(s->file.data + 1, ISO_percent);
} else {
ptr = strchr(s->file.data, ISO_percent);
}
if(ptr != NULL &&
ptr != s->file.data) {
s->len = (int)(ptr - s->file.data);
if(s->len >= uip_mss()) {
s->len = uip_mss();
}
}
PT_WAIT_THREAD(&s->scriptpt, send_part_of_file(s));
s->file.data += s->len;
s->file.len -= s->len;
}
}
PT_END(&s->scriptpt);
}
/*---------------------------------------------------------------------------*/
static
PT_THREAD(send_headers(struct httpd_state *s, const char *statushdr))
{
char *ptr;
PSOCK_BEGIN(&s->sout);
PSOCK_SEND_STR(&s->sout, statushdr);
ptr = strrchr(s->filename, ISO_period);
if(ptr == NULL) {
PSOCK_SEND_STR(&s->sout, http_content_type_binary);
} else if(strncmp(http_html, ptr, 5) == 0 ||
strncmp(http_shtml, ptr, 6) == 0) {
PSOCK_SEND_STR(&s->sout, http_content_type_html);
} else if(strncmp(http_css, ptr, 4) == 0) {
PSOCK_SEND_STR(&s->sout, http_content_type_css);
} else if(strncmp(http_png, ptr, 4) == 0) {
PSOCK_SEND_STR(&s->sout, http_content_type_png);
} else if(strncmp(http_gif, ptr, 4) == 0) {
PSOCK_SEND_STR(&s->sout, http_content_type_gif);
} else if(strncmp(http_jpg, ptr, 4) == 0) {
PSOCK_SEND_STR(&s->sout, http_content_type_jpg);
} else {
PSOCK_SEND_STR(&s->sout, http_content_type_plain);
}
PSOCK_END(&s->sout);
}
/*---------------------------------------------------------------------------*/
static
PT_THREAD(handle_output(struct httpd_state *s))
{
char *ptr;
PT_BEGIN(&s->outputpt);
if(!httpd_fs_open(s->filename, &s->file)) {
httpd_fs_open(http_404_html, &s->file);
strcpy(s->filename, http_404_html);
PT_WAIT_THREAD(&s->outputpt,
send_headers(s,
http_header_404));
PT_WAIT_THREAD(&s->outputpt,
send_file(s));
} else {
PT_WAIT_THREAD(&s->outputpt,
send_headers(s,
http_header_200));
ptr = strchr(s->filename, ISO_period);
if(ptr != NULL && strncmp(ptr, http_shtml, 6) == 0) {
PT_INIT(&s->scriptpt);
PT_WAIT_THREAD(&s->outputpt, handle_script(s));
} else {
PT_WAIT_THREAD(&s->outputpt,
send_file(s));
}
}
PSOCK_CLOSE(&s->sout);
PT_END(&s->outputpt);
}
/*---------------------------------------------------------------------------*/
static
PT_THREAD(handle_input(struct httpd_state *s))
{
PSOCK_BEGIN(&s->sin);
PSOCK_READTO(&s->sin, ISO_space);
if(strncmp(s->inputbuf, http_get, 4) != 0) {
PSOCK_CLOSE_EXIT(&s->sin);
}
PSOCK_READTO(&s->sin, ISO_space);
if(s->inputbuf[0] != ISO_slash) {
PSOCK_CLOSE_EXIT(&s->sin);
}
if(s->inputbuf[1] == ISO_space) {
strncpy(s->filename, http_index_html, sizeof(s->filename));
} else {
s->inputbuf[PSOCK_DATALEN(&s->sin) - 1] = 0;
/* Process any form input being sent to the server. */
{
extern void vApplicationProcessFormInput( char *pcInputString );
vApplicationProcessFormInput( s->inputbuf );
}
strncpy(s->filename, &s->inputbuf[0], sizeof(s->filename));
}
/* httpd_log_file(uip_conn->ripaddr, s->filename);*/
s->state = STATE_OUTPUT;
while(1) {
PSOCK_READTO(&s->sin, ISO_nl);
if(strncmp(s->inputbuf, http_referer, 8) == 0) {
s->inputbuf[PSOCK_DATALEN(&s->sin) - 2] = 0;
/* httpd_log(&s->inputbuf[9]);*/
}
}
PSOCK_END(&s->sin);
}
/*---------------------------------------------------------------------------*/
static void
handle_connection(struct httpd_state *s)
{
handle_input(s);
if(s->state == STATE_OUTPUT) {
handle_output(s);
}
}
/*---------------------------------------------------------------------------*/
void
httpd_appcall(void)
{
struct httpd_state *s = (struct httpd_state *)&(uip_conn->appstate);
if(uip_closed() || uip_aborted() || uip_timedout()) {
} else if(uip_connected()) {
PSOCK_INIT(&s->sin, s->inputbuf, sizeof(s->inputbuf) - 1);
PSOCK_INIT(&s->sout, s->inputbuf, sizeof(s->inputbuf) - 1);
PT_INIT(&s->outputpt);
s->state = STATE_WAITING;
/* timer_set(&s->timer, CLOCK_SECOND * 100);*/
s->timer = 0;
handle_connection(s);
} else if(s != NULL) {
if(uip_poll()) {
++s->timer;
if(s->timer >= 20) {
uip_abort();
}
} else {
s->timer = 0;
}
handle_connection(s);
} else {
uip_abort();
}
}
/*---------------------------------------------------------------------------*/
/**
* \brief Initialize the web server
*
* This function initializes the web server and should be
* called at system boot-up.
*/
void
httpd_init(void)
{
uip_listen(HTONS(80));
}
/*---------------------------------------------------------------------------*/
/** @} */

View File

@ -0,0 +1,62 @@
/*
* Copyright (c) 2001-2005, Adam Dunkels.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. The name of the author may not be used to endorse or promote
* products derived from this software without specific prior
* written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE
* GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
* This file is part of the uIP TCP/IP stack.
*
* $Id: httpd.h,v 1.2 2006/06/11 21:46:38 adam Exp $
*
*/
#ifndef __HTTPD_H__
#define __HTTPD_H__
#include "psock.h"
#include "httpd-fs.h"
struct httpd_state {
unsigned char timer;
struct psock sin, sout;
struct pt outputpt, scriptpt;
char inputbuf[50];
char filename[20];
char state;
struct httpd_fs_file file;
int len;
char *scriptptr;
int scriptlen;
unsigned short count;
};
void httpd_init(void);
void httpd_appcall(void);
void httpd_log(char *msg);
void httpd_log_file(u16_t *requester, char *file);
#endif /* __HTTPD_H__ */

View File

@ -0,0 +1,78 @@
#!/usr/bin/perl
open(OUTPUT, "> httpd-fsdata.c");
chdir("httpd-fs");
opendir(DIR, ".");
@files = grep { !/^\./ && !/(CVS|~)/ } readdir(DIR);
closedir(DIR);
foreach $file (@files) {
if(-d $file && $file !~ /^\./) {
print "Processing directory $file\n";
opendir(DIR, $file);
@newfiles = grep { !/^\./ && !/(CVS|~)/ } readdir(DIR);
closedir(DIR);
printf "Adding files @newfiles\n";
@files = (@files, map { $_ = "$file/$_" } @newfiles);
next;
}
}
foreach $file (@files) {
if(-f $file) {
print "Adding file $file\n";
open(FILE, $file) || die "Could not open file $file\n";
$file =~ s-^-/-;
$fvar = $file;
$fvar =~ s-/-_-g;
$fvar =~ s-\.-_-g;
# for AVR, add PROGMEM here
print(OUTPUT "static const unsigned char data".$fvar."[] = {\n");
print(OUTPUT "\t/* $file */\n\t");
for($j = 0; $j < length($file); $j++) {
printf(OUTPUT "%#02x, ", unpack("C", substr($file, $j, 1)));
}
printf(OUTPUT "0,\n");
$i = 0;
while(read(FILE, $data, 1)) {
if($i == 0) {
print(OUTPUT "\t");
}
printf(OUTPUT "%#02x, ", unpack("C", $data));
$i++;
if($i == 10) {
print(OUTPUT "\n");
$i = 0;
}
}
print(OUTPUT "0};\n\n");
close(FILE);
push(@fvars, $fvar);
push(@pfiles, $file);
}
}
for($i = 0; $i < @fvars; $i++) {
$file = $pfiles[$i];
$fvar = $fvars[$i];
if($i == 0) {
$prevfile = "NULL";
} else {
$prevfile = "file" . $fvars[$i - 1];
}
print(OUTPUT "const struct httpd_fsdata_file file".$fvar."[] = {{$prevfile, data$fvar, ");
print(OUTPUT "data$fvar + ". (length($file) + 1) .", ");
print(OUTPUT "sizeof(data$fvar) - ". (length($file) + 1) ."}};\n\n");
}
print(OUTPUT "#define HTTPD_FS_ROOT file$fvars[$i - 1]\n\n");
print(OUTPUT "#define HTTPD_FS_NUMFILES $i\n");

View File

@ -0,0 +1,40 @@
#!/usr/bin/perl
sub stringify {
my $name = shift(@_);
open(OUTPUTC, "> $name.c");
open(OUTPUTH, "> $name.h");
open(FILE, "$name");
while(<FILE>) {
if(/(.+) "(.+)"/) {
$var = $1;
$data = $2;
$datan = $data;
$datan =~ s/\\r/\r/g;
$datan =~ s/\\n/\n/g;
$datan =~ s/\\01/\01/g;
$datan =~ s/\\0/\0/g;
printf(OUTPUTC "const char $var\[%d] = \n", length($datan) + 1);
printf(OUTPUTC "/* \"$data\" */\n");
printf(OUTPUTC "{");
for($j = 0; $j < length($datan); $j++) {
printf(OUTPUTC "%#02x, ", unpack("C", substr($datan, $j, 1)));
}
printf(OUTPUTC "};\n");
printf(OUTPUTH "extern const char $var\[%d];\n", length($datan) + 1);
}
}
close(OUTPUTC);
close(OUTPUTH);
}
stringify("http-strings");
exit 0;

View File

@ -0,0 +1,327 @@
/*
FreeRTOS.org V5.3.1 - Copyright (C) 2003-2009 Richard Barry.
This file is part of the FreeRTOS.org distribution.
FreeRTOS.org is free software; you can redistribute it and/or modify it
under the terms of the GNU General Public License (version 2) as published
by the Free Software Foundation and modified by the FreeRTOS exception.
**NOTE** The exception to the GPL is included to allow you to distribute a
combined work that includes FreeRTOS.org without being obliged to provide
the source code for any proprietary components. Alternative commercial
license and support terms are also available upon request. See the
licensing section of http://www.FreeRTOS.org for full details.
FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
more details.
You should have received a copy of the GNU General Public License along
with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59
Temple Place, Suite 330, Boston, MA 02111-1307 USA.
***************************************************************************
* *
* Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation *
* *
* This is a concise, step by step, 'hands on' guide that describes both *
* general multitasking concepts and FreeRTOS specifics. It presents and *
* explains numerous examples that are written using the FreeRTOS API. *
* Full source code for all the examples is provided in an accompanying *
* .zip file. *
* *
***************************************************************************
1 tab == 4 spaces!
Please ensure to read the configuration and relevant port sections of the
online documentation.
http://www.FreeRTOS.org - Documentation, latest information, license and
contact details.
http://www.SafeRTOS.com - A version that is certified for use in safety
critical systems.
http://www.OpenRTOS.com - Commercial support, development, porting,
licensing and training services.
*/
/* Standard includes. */
#include <string.h>
/* Scheduler includes. */
#include "FreeRTOS.h"
#include "task.h"
#include "semphr.h"
/* uip includes. */
#include "uip.h"
#include "uip_arp.h"
#include "httpd.h"
#include "timer.h"
#include "clock-arch.h"
/* Demo includes. */
#include "emac.h"
#include "LED.h"
#include "LPC17xx.h"
#include "core_cm3.h"
/*-----------------------------------------------------------*/
/* How long to wait before attempting to connect the MAC again. */
#define uipINIT_WAIT 100
/* Shortcut to the header within the Rx buffer. */
#define xHeader ((struct uip_eth_hdr *) &uip_buf[ 0 ])
/* Standard constant. */
#define uipTOTAL_FRAME_HEADER_SIZE 54
/*-----------------------------------------------------------*/
/*
* Send the uIP buffer to the MAC.
*/
static void prvENET_Send(void);
/*
* Setup the MAC address in the MAC itself, and in the uIP stack.
*/
static void prvSetMACAddress( void );
/*
* Port functions required by the uIP stack.
*/
void clock_init( void );
clock_time_t clock_time( void );
/*-----------------------------------------------------------*/
/* The semaphore used by the ISR to wake the uIP task. */
extern xSemaphoreHandle xEMACSemaphore;
/*-----------------------------------------------------------*/
void clock_init(void)
{
/* This is done when the scheduler starts. */
}
/*-----------------------------------------------------------*/
clock_time_t clock_time( void )
{
return xTaskGetTickCount();
}
/*-----------------------------------------------------------*/
void vuIP_Task( void *pvParameters )
{
portBASE_TYPE i;
uip_ipaddr_t xIPAddr;
struct timer periodic_timer, arp_timer;
extern void ( vEMAC_ISR_Wrapper )( void );
( void ) pvParameters;
/* Create the semaphore used by the ISR to wake this task. */
vSemaphoreCreateBinary( xEMACSemaphore );
/* Initialise the uIP stack. */
timer_set( &periodic_timer, configTICK_RATE_HZ / 2 );
timer_set( &arp_timer, configTICK_RATE_HZ * 10 );
uip_init();
uip_ipaddr( xIPAddr, configIP_ADDR0, configIP_ADDR1, configIP_ADDR2, configIP_ADDR3 );
uip_sethostaddr( xIPAddr );
uip_ipaddr( xIPAddr, configNET_MASK0, configNET_MASK1, configNET_MASK2, configNET_MASK3 );
uip_setnetmask( xIPAddr );
httpd_init();
/* Initialise the MAC. */
while( Init_EMAC() != pdPASS )
{
vTaskDelay( uipINIT_WAIT );
}
portENTER_CRITICAL();
{
ETH_INTENABLE = INT_RX_DONE;
/* set the interrupt priority */
NVIC_SetPriority( ENET_IRQn, configMAX_SYSCALL_INTERRUPT_PRIORITY );
/* enable the interrupt */
NVIC_EnableIRQ( ENET_IRQn );
prvSetMACAddress();
}
portEXIT_CRITICAL();
for( ;; )
{
/* Is there received data ready to be processed? */
uip_len = uiGetEMACRxData( uip_buf );
if( uip_len > 0 )
{
/* Standard uIP loop taken from the uIP manual. */
if( xHeader->type == htons( UIP_ETHTYPE_IP ) )
{
uip_arp_ipin();
uip_input();
/* If the above function invocation resulted in data that
should be sent out on the network, the global variable
uip_len is set to a value > 0. */
if( uip_len > 0 )
{
uip_arp_out();
prvENET_Send();
}
}
else if( xHeader->type == htons( UIP_ETHTYPE_ARP ) )
{
uip_arp_arpin();
/* If the above function invocation resulted in data that
should be sent out on the network, the global variable
uip_len is set to a value > 0. */
if( uip_len > 0 )
{
prvENET_Send();
}
}
}
else
{
if( timer_expired( &periodic_timer ) )
{
timer_reset( &periodic_timer );
for( i = 0; i < UIP_CONNS; i++ )
{
uip_periodic( i );
/* If the above function invocation resulted in data that
should be sent out on the network, the global variable
uip_len is set to a value > 0. */
if( uip_len > 0 )
{
uip_arp_out();
prvENET_Send();
}
}
/* Call the ARP timer function every 10 seconds. */
if( timer_expired( &arp_timer ) )
{
timer_reset( &arp_timer );
uip_arp_timer();
}
}
else
{
/* We did not receive a packet, and there was no periodic
processing to perform. Block for a fixed period. If a packet
is received during this period we will be woken by the ISR
giving us the Semaphore. */
xSemaphoreTake( xEMACSemaphore, configTICK_RATE_HZ / 2 );
}
}
}
}
/*-----------------------------------------------------------*/
static void prvENET_Send(void)
{
RequestSend();
/* Copy the header into the Tx buffer. */
CopyToFrame_EMAC( uip_buf, uipTOTAL_FRAME_HEADER_SIZE );
if( uip_len > uipTOTAL_FRAME_HEADER_SIZE )
{
CopyToFrame_EMAC( uip_appdata, ( uip_len - uipTOTAL_FRAME_HEADER_SIZE ) );
}
DoSend_EMAC( uip_len );
RequestSend();
/* Copy the header into the Tx buffer. */
CopyToFrame_EMAC( uip_buf, uipTOTAL_FRAME_HEADER_SIZE );
if( uip_len > uipTOTAL_FRAME_HEADER_SIZE )
{
CopyToFrame_EMAC( uip_appdata, ( uip_len - uipTOTAL_FRAME_HEADER_SIZE ) );
}
DoSend_EMAC( uip_len );
}
/*-----------------------------------------------------------*/
static void prvSetMACAddress( void )
{
struct uip_eth_addr xAddr;
/* Configure the MAC address in the uIP stack. */
xAddr.addr[ 0 ] = configMAC_ADDR0;
xAddr.addr[ 1 ] = configMAC_ADDR1;
xAddr.addr[ 2 ] = configMAC_ADDR2;
xAddr.addr[ 3 ] = configMAC_ADDR3;
xAddr.addr[ 4 ] = configMAC_ADDR4;
xAddr.addr[ 5 ] = configMAC_ADDR5;
uip_setethaddr( xAddr );
}
/*-----------------------------------------------------------*/
void vApplicationProcessFormInput( portCHAR *pcInputString )
{
char *c, *pcText;
static portCHAR cMessageForDisplay[ 32 ];
extern xQueueHandle xLCDQueue;
xLCDMessage xLCDMessage;
/* Process the form input sent by the IO page of the served HTML. */
c = strstr( pcInputString, "?" );
if( c )
{
/* Turn LED's on or off in accordance with the check box status. */
if( strstr( c, "LED0=1" ) != NULL )
{
/* Set LED7. */
vParTestSetLED( 1 << 7, 1 );
}
else
{
/* Clear LED7. */
vParTestSetLED( 1 << 7, 0 );
}
/* Find the start of the text to be displayed on the LCD. */
pcText = strstr( c, "LCD=" );
pcText += strlen( "LCD=" );
/* Terminate the file name for further processing within uIP. */
*c = 0x00;
/* Terminate the LCD string. */
c = strstr( pcText, " " );
if( c != NULL )
{
*c = 0x00;
}
/* Add required spaces. */
while( ( c = strstr( pcText, "+" ) ) != NULL )
{
*c = ' ';
}
/* Write the message to the LCD. */
strcpy( cMessageForDisplay, pcText );
xLCDMessage.pcMessage = cMessageForDisplay;
xQueueSend( xLCDQueue, &xLCDMessage, portMAX_DELAY );
}
}

View File

@ -0,0 +1,157 @@
/**
* \addtogroup uipopt
* @{
*/
/**
* \name Project-specific configuration options
* @{
*
* uIP has a number of configuration options that can be overridden
* for each project. These are kept in a project-specific uip-conf.h
* file and all configuration names have the prefix UIP_CONF.
*/
/*
* Copyright (c) 2006, Swedish Institute of Computer Science.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the Institute nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*
* This file is part of the uIP TCP/IP stack
*
* $Id: uip-conf.h,v 1.6 2006/06/12 08:00:31 adam Exp $
*/
/**
* \file
* An example uIP configuration file
* \author
* Adam Dunkels <adam@sics.se>
*/
#ifndef __UIP_CONF_H__
#define __UIP_CONF_H__
#include <stdint.h>
/**
* 8 bit datatype
*
* This typedef defines the 8-bit type used throughout uIP.
*
* \hideinitializer
*/
typedef uint8_t u8_t;
/**
* 16 bit datatype
*
* This typedef defines the 16-bit type used throughout uIP.
*
* \hideinitializer
*/
typedef uint16_t u16_t;
/**
* Statistics datatype
*
* This typedef defines the dataype used for keeping statistics in
* uIP.
*
* \hideinitializer
*/
typedef unsigned short uip_stats_t;
/**
* Maximum number of TCP connections.
*
* \hideinitializer
*/
#define UIP_CONF_MAX_CONNECTIONS 40
/**
* Maximum number of listening TCP ports.
*
* \hideinitializer
*/
#define UIP_CONF_MAX_LISTENPORTS 40
/**
* uIP buffer size.
*
* \hideinitializer
*/
#define UIP_CONF_BUFFER_SIZE 1480
/**
* CPU byte order.
*
* \hideinitializer
*/
#define UIP_CONF_BYTE_ORDER LITTLE_ENDIAN
/**
* Logging on or off
*
* \hideinitializer
*/
#define UIP_CONF_LOGGING 0
/**
* UDP support on or off
*
* \hideinitializer
*/
#define UIP_CONF_UDP 0
/**
* UDP checksums on or off
*
* \hideinitializer
*/
#define UIP_CONF_UDP_CHECKSUMS 1
/**
* uIP statistics on or off
*
* \hideinitializer
*/
#define UIP_CONF_STATISTICS 1
/* Here we include the header file for the application(s) we use in
our project. */
/*#include "smtp.h"*/
/*#include "hello-world.h"*/
/*#include "telnetd.h"*/
#include "webserver.h"
/*#include "dhcpc.h"*/
/*#include "resolv.h"*/
/*#include "webclient.h"*/
#endif /* __UIP_CONF_H__ */
/** @} */
/** @} */

View File

@ -0,0 +1,49 @@
/*
* Copyright (c) 2002, Adam Dunkels.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* 3. The name of the author may not be used to endorse or promote
* products derived from this software without specific prior
* written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE
* GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
* This file is part of the uIP TCP/IP stack
*
* $Id: webserver.h,v 1.2 2006/06/11 21:46:38 adam Exp $
*
*/
#ifndef __WEBSERVER_H__
#define __WEBSERVER_H__
#include "httpd.h"
typedef struct httpd_state uip_tcp_appstate_t;
/* UIP_APPCALL: the name of the application function. This function
must return void and take no arguments (i.e., C type "void
appfunc(void)"). */
#ifndef UIP_APPCALL
#define UIP_APPCALL httpd_appcall
#endif
#endif /* __WEBSERVER_H__ */