Add FreeRTOS-Plus directory.

This commit is contained in:
Richard Barry 2012-08-11 21:34:11 +00:00
parent 7bd5f21ad5
commit f508a5f653
6798 changed files with 134949 additions and 19 deletions

View file

@ -0,0 +1,705 @@
/*
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.
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.
A special 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. See the licensing section
of http://www.FreeRTOS.org for full details.
***************************************************************************
* *
* 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.
***************************************************************************
* *
* Having a problem? Start by reading the FAQ "My application does *
* not run, what could be wrong? *
* *
* http://www.FreeRTOS.org/FAQHelp.html *
* *
***************************************************************************
http://www.FreeRTOS.org - Documentation, training, latest information,
license and contact details.
http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
including FreeRTOS+Trace - an indispensable productivity tool.
Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell
the code with commercial support, indemnification, and middleware, under
the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also
provide a safety engineered and independently SIL3 certified version under
the SafeRTOS brand: http://www.SafeRTOS.com.
*/
/* Kernel includes. */
#include "FreeRTOS.h"
#include "semphr.h"
#include "task.h"
/* Demo includes. */
#include "FEC.h"
#include "fecbd.h"
#include "mii.h"
#include "eth_phy.h"
#include "eth.h"
/* uIP includes. */
#include "uip.h"
#include "uip_arp.h"
/*-----------------------------------------------------------*/
/* FEC hardware specifics. */
#define MCF_FEC_MSCR_MII_SPEED(x) (((x)&0x3F)<<0x1)
#define MCF_FEC_RDAR_R_DES_ACTIVE ( 0x1000000 )
#define MCF_FEC_TDAR_X_DES_ACTIVE ( 0x1000000 )
/* PHY hardware specifics. */
#define PHY_STATUS ( 16 )
#define PHY_DUPLEX_STATUS ( 4 )
/* Delay between polling the PHY to see if a link has been established. */
#define fecLINK_DELAY ( 500 / portTICK_RATE_MS )
/* Very short delay to use when waiting for the Tx to finish with a buffer if
we run out of Rx buffers. */
#define fecMINIMAL_DELAY ( 3 / portTICK_RATE_MS )
/* Don't block to wait for a buffer more than this many times. */
#define uipBUFFER_WAIT_ATTEMPTS ( 30 )
/* The Tx re-uses the Rx buffers and only has one descriptor. */
#define fecNUM_TX_DESCRIPTORS ( 1 )
/* The total number of buffers available, which should be greater than the
number of Rx descriptors. */
#define fecNUM_BUFFERS ( configNUM_FEC_RX_DESCRIPTORS + 2 )
/*-----------------------------------------------------------*/
/*
* Return an unused buffer to the pool of free buffers.
*/
static void prvReturnBuffer( unsigned char *pucBuffer );
/*
* Find and return the next buffer that is not in use by anything else.
*/
static unsigned char *prvGetFreeBuffer( void );
/*-----------------------------------------------------------*/
/* The semaphore used to wake the uIP task when data arrives. */
xSemaphoreHandle xFECSemaphore = NULL;
/* The buffer used by the uIP stack. In this case the pointer is used to
point to one of the Rx buffers to avoid having to copy the Rx buffer into
the uIP buffer. */
unsigned char *uip_buf;
/* The DMA descriptors. These are char arrays to allow us to align them
correctly. */
static unsigned char xFECTxDescriptors_unaligned[ ( fecNUM_TX_DESCRIPTORS * sizeof( FECBD ) ) + 16 ];
static unsigned char xFECRxDescriptors_unaligned[ ( configNUM_FEC_RX_DESCRIPTORS * sizeof( FECBD ) ) + 16 ];
static FECBD *pxFECTxDescriptor;
static FECBD *xFECRxDescriptors;
/* The DMA buffer. This is a char arrays to allow it to be aligned correctly. */
static unsigned char ucFECRxBuffers[ ( fecNUM_BUFFERS * configFEC_BUFFER_SIZE ) + 16 ];
/* Index to the next descriptor to be inspected for received data. */
static unsigned long ulNextRxDescriptor = 0;
/* Contains the start address of each Rx buffer, after it has been correctly
aligned. */
static unsigned char *pucAlignedBufferStartAddresses[ fecNUM_BUFFERS ] = { 0 };
/* Each ucBufferInUse index corresponds to a position in the same index in the
pucAlignedBufferStartAddresses array. If the index contains a 1 then the
buffer within pucAlignedBufferStartAddresses is in use, if it contains a 0 then
the buffer is free. */
static unsigned char ucBufferInUse[ fecNUM_BUFFERS ] = { 0 };
/*-----------------------------------------------------------*/
/********************************************************************/
/*
* Write a value to a PHY's MII register.
*
* Parameters:
* ch FEC channel
* phy_addr Address of the PHY.
* reg_addr Address of the register in the PHY.
* data Data to be written to the PHY register.
*
* Return Values:
* 0 on failure
* 1 on success.
*
* Please refer to your PHY manual for registers and their meanings.
* mii_write() polls for the FEC's MII interrupt event and clears it.
* If after a suitable amount of time the event isn't triggered, a
* value of 0 is returned.
*/
static int fec_mii_write( int phy_addr, int reg_addr, int data )
{
int timeout;
unsigned long eimr;
/* Clear the MII interrupt bit */
EIR = EIR_MII;
/* Mask the MII interrupt */
eimr = EIMR;
EIMR &= ~EIMR_MII;
/* Write to the MII Management Frame Register to kick-off the MII write */
MMFR = ( unsigned long ) ( FEC_MMFR_ST_01 | FEC_MMFR_OP_WRITE | FEC_MMFR_PA(phy_addr) | FEC_MMFR_RA(reg_addr) | FEC_MMFR_TA_10 | FEC_MMFR_DATA( data ) );
/* Poll for the MII interrupt (interrupt should be masked) */
for (timeout = 0; timeout < FEC_MII_TIMEOUT; timeout++)
{
if( EIR & EIR_MII)
{
break;
}
}
if( timeout == FEC_MII_TIMEOUT )
{
return 0;
}
/* Clear the MII interrupt bit */
EIR = EIR_MII;
/* Restore the EIMR */
EIMR = eimr;
return 1;
}
/********************************************************************/
/*
* Read a value from a PHY's MII register.
*
* Parameters:
* ch FEC channel
* phy_addr Address of the PHY.
* reg_addr Address of the register in the PHY.
* data Pointer to storage for the Data to be read
* from the PHY register (passed by reference)
*
* Return Values:
* 0 on failure
* 1 on success.
*
* Please refer to your PHY manual for registers and their meanings.
* mii_read() polls for the FEC's MII interrupt event and clears it.
* If after a suitable amount of time the event isn't triggered, a
* value of 0 is returned.
*/
static int fec_mii_read( int phy_addr, int reg_addr, unsigned short* data )
{
int timeout;
unsigned long eimr;
/* Clear the MII interrupt bit */
EIR = 0xffffffff;
/* Mask the MII interrupt */
eimr = EIMR;
EIMR &= ~EIMR_MII;
/* Write to the MII Management Frame Register to kick-off the MII read */
MMFR = ( unsigned long ) ( FEC_MMFR_ST_01 | FEC_MMFR_OP_READ | FEC_MMFR_PA(phy_addr) | FEC_MMFR_RA(reg_addr) | FEC_MMFR_TA_10 );
/* Poll for the MII interrupt (interrupt should be masked) */
for (timeout = 0; timeout < FEC_MII_TIMEOUT; timeout++)
{
if (EIR)
{
break;
}
}
if(timeout == FEC_MII_TIMEOUT)
{
return 0;
}
/* Clear the MII interrupt bit */
EIR = EIR_MII;
/* Restore the EIMR */
EIMR = eimr;
*data = (unsigned short)(MMFR & 0x0000FFFF);
return 1;
}
/********************************************************************/
/*
* Generate the hash table settings for the given address
*
* Parameters:
* addr 48-bit (6 byte) Address to generate the hash for
*
* Return Value:
* The 6 most significant bits of the 32-bit CRC result
*/
static unsigned char fec_hash_address( const unsigned char* addr )
{
unsigned long crc;
unsigned char byte;
int i, j;
crc = 0xFFFFFFFF;
for(i=0; i<6; ++i)
{
byte = addr[i];
for(j=0; j<8; ++j)
{
if((byte & 0x01)^(crc & 0x01))
{
crc >>= 1;
crc = crc ^ 0xEDB88320;
}
else
{
crc >>= 1;
}
byte >>= 1;
}
}
return (unsigned char)(crc >> 26);
}
/********************************************************************/
/*
* Set the Physical (Hardware) Address and the Individual Address
* Hash in the selected FEC
*
* Parameters:
* ch FEC channel
* pa Physical (Hardware) Address for the selected FEC
*/
static void fec_set_address( const unsigned char *pa )
{
unsigned char crc;
/*
* Set the Physical Address
*/
PALR = (unsigned long)((pa[0]<<24) | (pa[1]<<16) | (pa[2]<<8) | pa[3]);
PAUR = (unsigned long)((pa[4]<<24) | (pa[5]<<16));
/*
* Calculate and set the hash for given Physical Address
* in the Individual Address Hash registers
*/
crc = fec_hash_address(pa);
if(crc >= 32)
{
IAUR |= (unsigned long)(1 << (crc - 32));
}
else
{
IALR |= (unsigned long)(1 << crc);
}
}
/*-----------------------------------------------------------*/
static void prvInitialiseFECBuffers( void )
{
unsigned portBASE_TYPE ux;
unsigned char *pcBufPointer;
/* Set the pointer to a correctly aligned address. */
pcBufPointer = &( xFECTxDescriptors_unaligned[ 0 ] );
while( ( ( unsigned long ) pcBufPointer & 0x0fUL ) != 0 )
{
pcBufPointer++;
}
pxFECTxDescriptor = ( FECBD * ) pcBufPointer;
/* Likewise the pointer to the Rx descriptor. */
pcBufPointer = &( xFECRxDescriptors_unaligned[ 0 ] );
while( ( ( unsigned long ) pcBufPointer & 0x0fUL ) != 0 )
{
pcBufPointer++;
}
xFECRxDescriptors = ( FECBD * ) pcBufPointer;
/* There is no Tx buffer as the Rx buffer is reused. */
pxFECTxDescriptor->length = 0;
pxFECTxDescriptor->status = 0;
/* Align the Rx buffers. */
pcBufPointer = &( ucFECRxBuffers[ 0 ] );
while( ( ( unsigned long ) pcBufPointer & 0x0fUL ) != 0 )
{
pcBufPointer++;
}
/* Then fill in the Rx descriptors. */
for( ux = 0; ux < configNUM_FEC_RX_DESCRIPTORS; ux++ )
{
xFECRxDescriptors[ ux ].status = RX_BD_E;
xFECRxDescriptors[ ux ].length = configFEC_BUFFER_SIZE;
xFECRxDescriptors[ ux ].data = pcBufPointer;
/* Note the start address of the buffer now that it is correctly
aligned. */
pucAlignedBufferStartAddresses[ ux ] = pcBufPointer;
/* The buffer is in use by the descriptor. */
ucBufferInUse[ ux ] = pdTRUE;
pcBufPointer += configFEC_BUFFER_SIZE;
}
/* Note the start address of the last buffer as one more buffer is
allocated than there are Rx descriptors. */
pucAlignedBufferStartAddresses[ ux ] = pcBufPointer;
/* Set uip_buf to point to the last buffer. */
uip_buf = pcBufPointer;
ucBufferInUse[ ux ] = pdTRUE;
/* Set the wrap bit in the last descriptors to form a ring. */
xFECRxDescriptors[ configNUM_FEC_RX_DESCRIPTORS - 1 ].status |= RX_BD_W;
/* We start with descriptor 0. */
ulNextRxDescriptor = 0;
}
/*-----------------------------------------------------------*/
void vInitFEC( void )
{
unsigned short usData;
struct uip_eth_addr xAddr;
const unsigned char ucMACAddress[6] =
{
configMAC_0, configMAC_1,configMAC_2,configMAC_3,configMAC_4,configMAC_5
};
prvInitialiseFECBuffers();
/* Create the semaphore used to wake the uIP task when data arrives. */
vSemaphoreCreateBinary( xFECSemaphore );
/* Set the MAC address within the stack. */
for( usData = 0; usData < 6; usData++ )
{
xAddr.addr[ usData ] = ucMACAddress[ usData ];
}
uip_setethaddr( xAddr );
/* Set the Reset bit and clear the Enable bit */
ECR_RESET = 1;
/* Enable the clock. */
SCGC4 |= SCGC4_FEC_MASK;
/* Wait at least 8 clock cycles */
for( usData = 0; usData < 10; usData++ )
{
asm( "NOP" );
}
/* Set MII speed to 2.5MHz. */
MSCR = MCF_FEC_MSCR_MII_SPEED( ( ( configCPU_CLOCK_HZ / 1000000 ) / 5 ) + 1 );
/*
* Make sure the external interface signals are enabled
*/
PTCPF2_C0 = 1;
PTCPF2_C1 = 1;
PTCPF2_C2 = 1;
PTAPF1 = 0x55;
PTAPF2 = 0x55;
PTBPF1 = 0x55;
PTBPF2 = 0x55;
/* Set all pins to full drive with no filter. */
PTADS = 0x06;
PTAIFE = 0x06;
PTBDS = 0xf4;
PTBIFE = 0xf4;
PTCDS = 0;
PTCIFE = 0;
/* Can we talk to the PHY? */
do
{
vTaskDelay( fecLINK_DELAY );
usData = 0xffff;
fec_mii_read( configPHY_ADDRESS, PHY_PHYIDR1, &usData );
} while( usData == 0xffff );
/* Start auto negotiate. */
fec_mii_write( configPHY_ADDRESS, PHY_BMCR, ( PHY_BMCR_AN_RESTART | PHY_BMCR_AN_ENABLE ) );
/* Wait for auto negotiate to complete. */
do
{
vTaskDelay( fecLINK_DELAY );
fec_mii_read( configPHY_ADDRESS, PHY_BMSR, &usData );
} while( !( usData & PHY_BMSR_AN_COMPLETE ) );
/* When we get here we have a link - find out what has been negotiated. */
usData = 0;
fec_mii_read( configPHY_ADDRESS, PHY_STATUS, &usData );
/* Setup half or full duplex. */
if( usData & PHY_DUPLEX_STATUS )
{
RCR &= (unsigned long)~RCR_DRT;
TCR |= TCR_FDEN;
}
else
{
RCR |= RCR_DRT;
TCR &= (unsigned long)~TCR_FDEN;
}
/* Clear the Individual and Group Address Hash registers */
IALR = 0;
IAUR = 0;
GALR = 0;
GAUR = 0;
/* Set the Physical Address for the selected FEC */
fec_set_address( ucMACAddress );
/* Set Rx Buffer Size */
EMRBR = (unsigned short) configFEC_BUFFER_SIZE;
/* Point to the start of the circular Rx buffer descriptor queue */
ERDSR = ( volatile unsigned long ) &( xFECRxDescriptors[ 0 ] );
/* Point to the start of the circular Tx buffer descriptor queue */
ETSDR = ( volatile unsigned long ) pxFECTxDescriptor;
/* Clear all FEC interrupt events */
EIR = ( unsigned long ) -1;
/* Various mode/status setup. */
RCR = 0;
RCR_MAX_FL = configFEC_BUFFER_SIZE;
RCR_MII_MODE = 1;
#if( configUSE_PROMISCUOUS_MODE == 1 )
{
RCR |= RCR_PROM;
}
#endif
/* Enable interrupts. */
EIMR = EIR_TXF_MASK | EIMR_RXF_MASK | EIMR_RXB_MASK | EIMR_UN_MASK | EIMR_RL_MASK | EIMR_LC_MASK | EIMR_BABT_MASK | EIMR_BABR_MASK | EIMR_HBERR_MASK;
/* Enable the MAC itself. */
ECR = ECR_ETHER_EN_MASK;
/* Indicate that there have been empty receive buffers produced */
RDAR = MCF_FEC_RDAR_R_DES_ACTIVE;
}
/*-----------------------------------------------------------*/
unsigned long ulFECRx( void )
{
unsigned long ulLen = 0UL;
/* Is a buffer ready? */
if( ( xFECRxDescriptors[ ulNextRxDescriptor ].status & RX_BD_E ) == 0 )
{
/* uip_buf is about to be set to a new buffer, so return the buffer it
is already pointing to. */
prvReturnBuffer( uip_buf );
/* Obtain the size of the packet and put it into the "len" variable. */
ulLen = xFECRxDescriptors[ ulNextRxDescriptor ].length;
uip_buf = xFECRxDescriptors[ ulNextRxDescriptor ].data;
/* The buffer that this descriptor was using is now in use by the
TCP/IP stack, so allocate it a new buffer. */
xFECRxDescriptors[ ulNextRxDescriptor ].data = prvGetFreeBuffer();
/* Doing this here could cause corruption! */
xFECRxDescriptors[ ulNextRxDescriptor ].status |= RX_BD_E;
portENTER_CRITICAL();
{
ulNextRxDescriptor++;
if( ulNextRxDescriptor >= configNUM_FEC_RX_DESCRIPTORS )
{
ulNextRxDescriptor = 0;
}
}
portEXIT_CRITICAL();
/* Tell the DMA a new buffer is available. */
RDAR = MCF_FEC_RDAR_R_DES_ACTIVE;
}
return ulLen;
}
/*-----------------------------------------------------------*/
void vFECTx( void )
{
/* When we get here the Tx descriptor should show as having completed. */
while( pxFECTxDescriptor->status & TX_BD_R )
{
vTaskDelay( fecMINIMAL_DELAY );
}
portENTER_CRITICAL();
{
/* To maintain the zero copy implementation, point the Tx descriptor
to the data from the Rx buffer. */
pxFECTxDescriptor->data = uip_buf;
/* Setup the buffer descriptor for transmission */
pxFECTxDescriptor->length = uip_len;
/* NB this assumes only one Tx descriptor! */
pxFECTxDescriptor->status = ( TX_BD_R | TX_BD_L | TX_BD_TC | TX_BD_W );
}
portEXIT_CRITICAL();
/* Continue the Tx DMA task (in case it was waiting for a new TxBD) */
TDAR = MCF_FEC_TDAR_X_DES_ACTIVE;
/* uip_buf is being used by the Tx descriptor. Allocate a new buffer to
uip_buf. */
uip_buf = prvGetFreeBuffer();
}
/*-----------------------------------------------------------*/
static void prvReturnBuffer( unsigned char *pucBuffer )
{
unsigned long ul;
/* Mark a buffer as free for use. */
for( ul = 0; ul < fecNUM_BUFFERS; ul++ )
{
if( pucAlignedBufferStartAddresses[ ul ] == pucBuffer )
{
ucBufferInUse[ ul ] = pdFALSE;
break;
}
}
}
/*-----------------------------------------------------------*/
static unsigned char *prvGetFreeBuffer( void )
{
portBASE_TYPE x;
unsigned char *pucReturn = NULL;
unsigned long ulAttempts = 0;
while( pucReturn == NULL )
{
/* Look through the buffers to find one that is not in use by
anything else. */
for( x = 0; x < fecNUM_BUFFERS; x++ )
{
if( ucBufferInUse[ x ] == pdFALSE )
{
ucBufferInUse[ x ] = pdTRUE;
pucReturn = pucAlignedBufferStartAddresses[ x ];
break;
}
}
/* Was a buffer found? */
if( pucReturn == NULL )
{
ulAttempts++;
if( ulAttempts >= uipBUFFER_WAIT_ATTEMPTS )
{
break;
}
/* Wait then look again. */
vTaskDelay( fecMINIMAL_DELAY );
}
}
return pucReturn;
}
/*-----------------------------------------------------------*/
void interrupt 86 vFECISRHandler( void )
{
unsigned long ulEvent;
portBASE_TYPE xHighPriorityTaskWoken = pdFALSE;
/* Determine the cause of the interrupt. */
ulEvent = EIR & EIMR;
EIR = ulEvent;
if( ulEvent & EIR_RXF_MASK )
{
/* A packet has been received. Wake the handler task in case it is
blocked. */
xSemaphoreGiveFromISR( xFECSemaphore, &xHighPriorityTaskWoken );
}
if( ulEvent & EIR_TXF_MASK )
{
/* The Tx has completed. Mark the buffer it was using as free again. */
prvReturnBuffer( pxFECTxDescriptor->data );
pxFECTxDescriptor->data = NULL;
}
if (ulEvent & ( EIR_UN_MASK | EIR_RL_MASK | EIR_LC_MASK | EIR_EBERR_MASK | EIR_BABT_MASK | EIR_BABR_MASK | EIR_HBERR_MASK ) )
{
/* Sledge hammer error handling. */
prvInitialiseFECBuffers();
RDAR = MCF_FEC_RDAR_R_DES_ACTIVE;
}
portEND_SWITCHING_ISR( xHighPriorityTaskWoken );
}

View file

@ -0,0 +1,46 @@
/*
FreeRTOS.org V5.0.3 - Copyright (C) 2003-2008 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 as published by
the Free Software Foundation; either version 2 of the License, or
(at your option) any later version.
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
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes FreeRTOS.org, without being obliged to provide
the source code for any proprietary components. See the licensing section
of http://www.FreeRTOS.org for full details of how and when the exception
can be applied.
***************************************************************************
See http://www.FreeRTOS.org for documentation, latest information, license
and contact details. Please ensure to read the configuration and relevant
port sections of the online documentation.
***************************************************************************
*/
#ifndef INC_FEC_H
#define INC_FEC_H
/* Configure the FEC peripheral, IO and descriptors. */
void vInitFEC( void );
/* Receive any data into the uip_buf array. */
unsigned long ulFECRx( void );
/* Transmit the uip_buf array. */
void vFECTx( void );
#endif

View file

@ -0,0 +1,172 @@
/*
FreeRTOS V7.1.1 - Copyright (C) 2012 Real Time Engineers Ltd.
***************************************************************************
* *
* FreeRTOS tutorial books are available in pdf and paperback. *
* Complete, revised, and edited pdf reference manuals are also *
* available. *
* *
* Purchasing FreeRTOS documentation will not only help you, by *
* ensuring you get running as quickly as possible and with an *
* in-depth knowledge of how to use FreeRTOS, it will also help *
* the FreeRTOS project to continue with its mission of providing *
* professional grade, cross platform, de facto standard solutions *
* for microcontrollers - completely free of charge! *
* *
* >>> See http://www.FreeRTOS.org/Documentation for details. <<< *
* *
* Thank you for using FreeRTOS, and thank you for your support! *
* *
***************************************************************************
This file is part of the FreeRTOS distribution.
FreeRTOS 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 modification to the GPL is included to allow you to
distribute a combined work that includes FreeRTOS without being obliged to
provide the source code for proprietary components outside of the FreeRTOS
kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it
can be viewed here: http://www.freertos.org/a00114.html and also obtained
by writing to Richard Barry, contact details for whom are available on the
FreeRTOS WEB site.
1 tab == 4 spaces!
***************************************************************************
* *
* Having a problem? Start by reading the FAQ "My application does *
* not run, what could be wrong? *
* *
* http://www.FreeRTOS.org/FAQHelp.html *
* *
***************************************************************************
http://www.FreeRTOS.org - Documentation, training, latest information,
license and contact details.
http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
including FreeRTOS+Trace - an indispensable productivity tool.
Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell
the code with commercial support, indemnification, and middleware, under
the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also
provide a safety engineered and independently SIL3 certified version under
the SafeRTOS brand: http://www.SafeRTOS.com.
*/
/* CodeWarrior often thinks it knows better than you which files you want to
build - and changes the port.c and portasm.S files included in the project from
the ColdFire V1 versions to the x86 versions. If you get lots of errors output
when either file is compiled then delete the files from the project and then
add back in the port.c and portasm.S files that are located in the
FreeRTOS\Source\portable\GCC\ColdFire_V1 directory. Remove the line below
before compiling. */
//#error Read the comment above this line, then delete this error statement!
#ifndef FREERTOS_CONFIG_H
#define FREERTOS_CONFIG_H
#include <hidef.h>
#include "derivative.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.
*
* See http://www.freertos.org/a00110.html.
*----------------------------------------------------------*/
#define configUSE_PREEMPTION 1
#define configUSE_IDLE_HOOK 0
#define configUSE_TICK_HOOK 1
#define configCPU_CLOCK_HZ ( 50000000UL )
#define configTICK_RATE_HZ ( ( portTickType ) 100 )
#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 100 )
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 13 * 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 configCHECK_FOR_STACK_OVERFLOW 1
#define configGENERATE_RUN_TIME_STATS 0
#define configUSE_RECURSIVE_MUTEXES 1
#define configQUEUE_REGISTRY_SIZE 0
#define configUSE_COUNTING_SEMAPHORES 0
#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 6 )
#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )
/* 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
/* It is not advisable to change these values on a Coldfire V1 core. */
#define configKERNEL_INTERRUPT_PRIORITY 1
#define configMAX_SYSCALL_INTERRUPT_PRIORITY 7
/* Ethernet configuration. */
#define configMAC_0 0x00
#define configMAC_1 0x04
#define configMAC_2 0x9F
#define configMAC_3 0x00
#define configMAC_4 0xAB
#define configMAC_5 0x2B
#define configIP_ADDR0 192
#define configIP_ADDR1 168
#define configIP_ADDR2 0
#define configIP_ADDR3 222
#define configGW_ADDR0 192
#define configGW_ADDR1 168
#define configGW_ADDR2 0
#define configGW_ADDR3 3
#define configNET_MASK0 255
#define configNET_MASK1 255
#define configNET_MASK2 255
#define configNET_MASK3 0
#define configNUM_FEC_RX_DESCRIPTORS 2
#define configFEC_BUFFER_SIZE 1520 /* Should be multiple of 16. */
#define configUSE_PROMISCUOUS_MODE 0
#define configETHERNET_INPUT_TASK_STACK_SIZE ( 320 )
#define configETHERNET_INPUT_TASK_PRIORITY ( configMAX_PRIORITIES - 1 )
#define configPHY_ADDRESS 1
#if ( configFEC_BUFFER_SIZE & 0x0F ) != 0
#error configFEC_BUFFER_SIZE must be a multiple of 16.
#endif
#endif /* FREERTOS_CONFIG_H */

View file

@ -0,0 +1,155 @@
/*
FreeRTOS V7.1.1 - Copyright (C) 2012 Real Time Engineers Ltd.
***************************************************************************
* *
* FreeRTOS tutorial books are available in pdf and paperback. *
* Complete, revised, and edited pdf reference manuals are also *
* available. *
* *
* Purchasing FreeRTOS documentation will not only help you, by *
* ensuring you get running as quickly as possible and with an *
* in-depth knowledge of how to use FreeRTOS, it will also help *
* the FreeRTOS project to continue with its mission of providing *
* professional grade, cross platform, de facto standard solutions *
* for microcontrollers - completely free of charge! *
* *
* >>> See http://www.FreeRTOS.org/Documentation for details. <<< *
* *
* Thank you for using FreeRTOS, and thank you for your support! *
* *
***************************************************************************
This file is part of the FreeRTOS distribution.
FreeRTOS 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 modification to the GPL is included to allow you to
distribute a combined work that includes FreeRTOS without being obliged to
provide the source code for proprietary components outside of the FreeRTOS
kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it
can be viewed here: http://www.freertos.org/a00114.html and also obtained
by writing to Richard Barry, contact details for whom are available on the
FreeRTOS WEB site.
1 tab == 4 spaces!
***************************************************************************
* *
* Having a problem? Start by reading the FAQ "My application does *
* not run, what could be wrong? *
* *
* http://www.FreeRTOS.org/FAQHelp.html *
* *
***************************************************************************
http://www.FreeRTOS.org - Documentation, training, latest information,
license and contact details.
http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
including FreeRTOS+Trace - an indispensable productivity tool.
Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell
the code with commercial support, indemnification, and middleware, under
the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also
provide a safety engineered and independently SIL3 certified version under
the SafeRTOS brand: http://www.SafeRTOS.com.
*/
#include "FreeRTOS.h"
#include "task.h"
#include "partest.h"
#define partstNUM_LEDs 4
/*-----------------------------------------------------------
* Simple LED IO routines for the tower LEDs LED1 to LED4.
*-----------------------------------------------------------*/
void vParTestInitialise( void )
{
/* Enable pull and output drive. */
PTHPE_PTHPE3 = 1;
PTHDD_PTHDD3 = 1;
PTEPE_PTEPE5 = 1;
PTEDD_PTEDD5 = 1;
PTGPE_PTGPE5 = 1;
PTGDD_PTGDD5 = 1;
PTEPE_PTEPE3 = 1;
PTEDD_PTEDD3 = 1;
/* Enable clock to ports. */
SCGC3_PTE = 1;
SCGC3_PTF = 1;
SCGC3_PTG = 1;
/* Ensure the LEDs are off. */
vParTestSetLED( 0, 0 );
vParTestSetLED( 1, 0 );
vParTestSetLED( 2, 0 );
vParTestSetLED( 3, 0 );
}
/*-----------------------------------------------------------*/
void vParTestSetLED( unsigned portBASE_TYPE uxLED, signed portBASE_TYPE xValue )
{
switch( uxLED )
{
case 0: PTHD_PTHD3 = xValue;
break;
case 1: PTED_PTED5 = xValue;
break;
case 2: PTGD_PTGD5 = xValue;
break;
case 3: PTED_PTED3 = xValue;
break;
default : /* There are no other LEDs. */
break;
}
}
/*-----------------------------------------------------------*/
void vParTestToggleLED( unsigned portBASE_TYPE uxLED )
{
portENTER_CRITICAL();
{
switch( uxLED )
{
case 0: PTHD_PTHD3 = !PTHD_PTHD3;
break;
case 1: PTED_PTED5 = !PTED_PTED5;
break;
case 2: PTGD_PTGD5 = !PTGD_PTGD5;
break;
case 3: PTED_PTED3 = !!PTED_PTED3;
break;
default : /* There are no other LEDs. */
break;
}
}
portEXIT_CRITICAL();
}
/*-----------------------------------------------------------*/
unsigned portBASE_TYPE uxParTestGetLED( unsigned portBASE_TYPE uxLED )
{
/* We ignore the parameter as in this simple example we simply return the
state of LED3. */
( void ) uxLED;
return PTED_PTED3;
}

View file

@ -0,0 +1,15 @@
/*
* Note: This file is recreated by the project wizard whenever the MCU is
* changed and should not be edited by hand
*/
/* Include the derivative-specific header file */
#include <MCF51CN128.h>
#define _Stop asm ( mov3q #4,d0; bclr.b d0,SOPT1; stop #0x2000; )
/*!< Macro to enter stop modes, STOPE bit in SOPT1 register must be set prior to executing this macro */
#define _Wait asm ( mov3q #4,d0; bset.b d0,SOPT1; nop; stop #0x2000; )
/*!< Macro to enter wait mode */

View file

@ -0,0 +1,55 @@
/*!
* \file eth.h
* \brief Definitinos for Ethernet Frames
* \version $Revision: 1.2 $
* \author Michael Norman
*/
#ifndef _ETH_H
#define _ETH_H
/*******************************************************************/
/* Ethernet standard lengths in bytes*/
#define ETH_ADDR_LEN (6)
#define ETH_TYPE_LEN (2)
#define ETH_CRC_LEN (4)
#define ETH_MAX_DATA (1500)
#define ETH_MIN_DATA (46)
#define ETH_HDR_LEN (ETH_ADDR_LEN * 2 + ETH_TYPE_LEN)
/* Defined Ethernet Frame Types */
#define ETH_FRM_IP (0x0800)
#define ETH_FRM_ARP (0x0806)
#define ETH_FRM_RARP (0x8035)
#define ETH_FRM_TEST (0xA5A5)
/* Maximum and Minimum Ethernet Frame Sizes */
#define ETH_MAX_FRM (ETH_HDR_LEN + ETH_MAX_DATA + ETH_CRC_LEN)
#define ETH_MIN_FRM (ETH_HDR_LEN + ETH_MIN_DATA + ETH_CRC_LEN)
#define ETH_MTU (ETH_HDR_LEN + ETH_MAX_DATA)
/* Ethernet Addresses */
typedef unsigned char ETH_ADDR[ETH_ADDR_LEN];
/* 16-bit Ethernet Frame Type, ie. Protocol */
typedef unsigned short ETH_FRM_TYPE;
/* Ethernet Frame Header definition */
typedef struct
{
ETH_ADDR dest;
ETH_ADDR src;
ETH_FRM_TYPE type;
} ETH_HDR;
/* Ethernet Frame definition */
typedef struct
{
ETH_HDR head;
unsigned char* data;
} ETH_FRAME;
/*******************************************************************/
#endif /* _ETH_H */

View file

@ -0,0 +1,70 @@
/*!
* \file eth.h
* \brief Definitions for Ethernet Physical Layer Interface
* \version $Revision: 1.3 $
* \author Michael Norman
*/
#ifndef _ETH_PHY_H
#define _ETH_PHY_H
/*******************************************************************/
/* MII Register Addresses */
#define PHY_BMCR (0x00)
#define PHY_BMSR (0x01)
#define PHY_PHYIDR1 (0x02)
#define PHY_PHYIDR2 (0x03)
#define PHY_ANAR (0x04)
#define PHY_ANLPAR (0x05)
/* Bit definitions and macros for PHY_CTRL */
#define PHY_BMCR_RESET (0x8000)
#define PHY_BMCR_LOOP (0x4000)
#define PHY_BMCR_SPEED (0x2000)
#define PHY_BMCR_AN_ENABLE (0x1000)
#define PHY_BMCR_POWERDOWN (0x0800)
#define PHY_BMCR_ISOLATE (0x0400)
#define PHY_BMCR_AN_RESTART (0x0200)
#define PHY_BMCR_FDX (0x0100)
#define PHY_BMCR_COL_TEST (0x0080)
/* Bit definitions and macros for PHY_STAT */
#define PHY_BMSR_100BT4 (0x8000)
#define PHY_BMSR_100BTX_FDX (0x4000)
#define PHY_BMSR_100BTX (0x2000)
#define PHY_BMSR_10BT_FDX (0x1000)
#define PHY_BMSR_10BT (0x0800)
#define PHY_BMSR_NO_PREAMBLE (0x0040)
#define PHY_BMSR_AN_COMPLETE (0x0020)
#define PHY_BMSR_REMOTE_FAULT (0x0010)
#define PHY_BMSR_AN_ABILITY (0x0008)
#define PHY_BMSR_LINK (0x0004)
#define PHY_BMSR_JABBER (0x0002)
#define PHY_BMSR_EXTENDED (0x0001)
/* Bit definitions and macros for PHY_AN_ADV */
#define PHY_ANAR_NEXT_PAGE (0x8001)
#define PHY_ANAR_REM_FAULT (0x2001)
#define PHY_ANAR_PAUSE (0x0401)
#define PHY_ANAR_100BT4 (0x0201)
#define PHY_ANAR_100BTX_FDX (0x0101)
#define PHY_ANAR_100BTX (0x0081)
#define PHY_ANAR_10BT_FDX (0x0041)
#define PHY_ANAR_10BT (0x0021)
#define PHY_ANAR_802_3 (0x0001)
/* Bit definitions and macros for PHY_AN_LINK_PAR */
#define PHY_ANLPAR_NEXT_PAGE (0x8000)
#define PHY_ANLPAR_ACK (0x4000)
#define PHY_ANLPAR_REM_FAULT (0x2000)
#define PHY_ANLPAR_PAUSE (0x0400)
#define PHY_ANLPAR_100BT4 (0x0200)
#define PHY_ANLPAR_100BTX_FDX (0x0100)
#define PHY_ANLPAR_100BTX (0x0080)
#define PHY_ANLPAR_10BTX_FDX (0x0040)
#define PHY_ANLPAR_10BT (0x0020)
/*******************************************************************/
#endif /* _ETH_PHY_H */

View file

@ -0,0 +1,444 @@
/*
* File: exceptions.c
* Purpose: Generic exception handling for ColdFire processors
*
*/
#include "derivative.h"
#include "exceptions.h"
#include "startcf.h"
#define REGISTER_ABI __REGABI__
extern asm void interrupt 109 vPortYieldISR( void );
extern void interrupt 86 vFECISRHandler( void );
/***********************************************************************/
/*
* Set NO_PRINTF to 0 in order the exceptions.c interrupt handler
* to output messages to the standard io.
*
*/
#define NO_PRINTF 1
#if NO_PRINTF
#define VECTORDISPLAY(MESSAGE) asm { nop; };
#define VECTORDISPLAY2(MESSAGE,MESSAGE2) asm { nop; };
#define VECTORDISPLAY3(MESSAGE,MESSAGE2,MESSAGE3) asm { nop; };
#else
#include <stdio.h>
#define VECTORDISPLAY(MESSAGE1) printf(MESSAGE1);
#define VECTORDISPLAY2(MESSAGE1,MESSAGE2) printf(MESSAGE1,MESSAGE2);
#define VECTORDISPLAY3(MESSAGE1,MESSAGE2,MESSAGE3) printf(MESSAGE1,MESSAGE2,MESSAGE3);
#endif
#ifdef __cplusplus
extern "C" {
#endif
extern unsigned long far _SP_INIT[];
/***********************************************************************/
/*
* Handling of the TRK ColdFire libs (printf support in Debugger Terminal)
*
* To enable this support:
* - Set CONSOLE_IO_SUPPORT 1 in this file; this will enable
* TrapHandler_printf for the trap #14 exception.
*
* - Make sure the file console_io_cf.c is in your project.
*
* - In the debugger make sure that in the Connection "Setup" dialog,
* "Debug Options" property page, the check box
* "Enable Terminal printf support" is set.
*
*
*
*/
#define CONSOLE_IO_SUPPORT 0
#if CONSOLE_IO_SUPPORT
asm void TrapHandler_printf(void) {
HALT
RTE
}
#endif
/***********************************************************************/
/*
* This is the handler for all exceptions which are not common to all
* ColdFire Chips.
*
* Called by mcf_exception_handler
*
*/
void derivative_interrupt(unsigned long vector)
{
if (vector < 64 || vector > 192) {
VECTORDISPLAY2("User Defined Vector #%d\n",vector);
}
}
/***********************************************************************
*
* This is the exception handler for all exceptions common to all
* chips ColdFire. Most exceptions do nothing, but some of the more
* important ones are handled to some extent.
*
* Called by asm_exception_handler
*
* The ColdFire family of processors has a simplified exception stack
* frame that looks like the following:
*
* 3322222222221111 111111
* 1098765432109876 5432109876543210
* 8 +----------------+----------------+
* | Program Counter |
* 4 +----------------+----------------+
* |FS/Fmt/Vector/FS| SR |
* SP --> 0 +----------------+----------------+
*
* The stack self-aligns to a 4-byte boundary at an exception, with
* the FS/Fmt/Vector/FS field indicating the size of the adjustment
* (SP += 0,1,2,3 bytes).
* 31 28 27 26 25 18 17 16 15 0
* 4 +---------------------------------------+------------------------------------+
* | Format | FS[3..2] | Vector | FS[1..0] | SR |
* SP --> 0 +---------------------------------------+------------------------------------+
*/
#define MCF5XXX_RD_SF_FORMAT(PTR) \
((*((unsigned short *)(PTR)) >> 12) & 0x00FF)
#define MCF5XXX_RD_SF_VECTOR(PTR) \
((*((unsigned short *)(PTR)) >> 2) & 0x00FF)
#define MCF5XXX_RD_SF_FS(PTR) \
( ((*((unsigned short *)(PTR)) & 0x0C00) >> 8) | (*((unsigned short *)(PTR)) & 0x0003) )
#define MCF5XXX_SF_SR(PTR) *(((unsigned short *)(PTR))+1)
#define MCF5XXX_SF_PC(PTR) *((unsigned long *)(PTR)+1)
#define MCF5XXX_EXCEPTFMT "%s -- PC = %#08X\n"
void mcf_exception_handler(void *framepointer)
{
volatile unsigned long exceptionStackFrame = (*(unsigned long *)(framepointer));
volatile unsigned short stackFrameSR = MCF5XXX_SF_SR(framepointer);
volatile unsigned short stackFrameWord = (*(unsigned short *)(framepointer));
volatile unsigned long stackFrameFormat = (unsigned long)MCF5XXX_RD_SF_FORMAT(&stackFrameWord);
volatile unsigned long stackFrameFS = (unsigned long)MCF5XXX_RD_SF_FS(&stackFrameWord);
volatile unsigned long stackFrameVector = (unsigned long)MCF5XXX_RD_SF_VECTOR(&stackFrameWord);
volatile unsigned long stackFramePC = MCF5XXX_SF_PC(framepointer);
switch (stackFrameFormat)
{
case 4:
case 5:
case 6:
case 7:
break;
default:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT,"Illegal stack type", stackFramePC);
break;
}
switch (stackFrameVector)
{
case 2:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Access Error", stackFramePC);
switch (stackFrameFS)
{
case 4:
VECTORDISPLAY("Error on instruction fetch\n");
break;
case 8:
VECTORDISPLAY("Error on operand write\n");
break;
case 9:
VECTORDISPLAY("Attempted write to write-protected space\n");
break;
case 12:
VECTORDISPLAY("Error on operand read\n");
break;
default:
VECTORDISPLAY("Reserved Fault Status Encoding\n");
break;
}
break;
case 3:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Address Error", stackFramePC);
switch (stackFrameFS)
{
case 4:
VECTORDISPLAY("Error on instruction fetch\n");
break;
case 8:
VECTORDISPLAY("Error on operand write\n");
break;
case 9:
VECTORDISPLAY("Attempted write to write-protected space\n");
break;
case 12:
VECTORDISPLAY("Error on operand read\n");
break;
default:
VECTORDISPLAY("Reserved Fault Status Encoding\n");
break;
}
break;
case 4:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Illegal instruction", stackFramePC);
break;
case 8:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Privilege violation", stackFramePC);
break;
case 9:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Trace Exception", stackFramePC);
break;
case 10:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Unimplemented A-Line Instruction", stackFramePC);
break;
case 11:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Unimplemented F-Line Instruction", stackFramePC);
break;
case 12:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Debug Interrupt", stackFramePC);
break;
case 14:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Format Error", stackFramePC);
break;
case 15:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Unitialized Interrupt", stackFramePC);
break;
case 24:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Spurious Interrupt", stackFramePC);
break;
case 25:
case 26:
case 27:
case 28:
case 29:
case 30:
case 31:
VECTORDISPLAY2("Autovector interrupt level %d\n", stackFrameVector - 24);
break;
case 32:
case 33:
case 34:
case 35:
case 36:
case 37:
case 38:
case 39:
case 40:
case 41:
case 42:
case 43:
case 44:
case 45:
case 46:
case 47:
VECTORDISPLAY2("TRAP #%d\n", stackFrameVector - 32);
break;
case 5:
case 6:
case 7:
case 13:
case 16:
case 17:
case 18:
case 19:
case 20:
case 21:
case 22:
case 23:
case 48:
case 49:
case 50:
case 51:
case 52:
case 53:
case 54:
case 55:
case 56:
case 57:
case 58:
case 59:
case 60:
case 61:
case 62:
case 63:
VECTORDISPLAY2("Reserved: #%d\n", stackFrameVector);
break;
default:
derivative_interrupt(stackFrameVector);
break;
}
}
#if REGISTER_ABI
asm void asm_exception_handler(void)
{
link a6,#0
lea -20(sp), sp
movem.l d0-d2/a0-a1, (sp)
lea 24(sp),a0 /* A0 point to exception stack frame on the stack */
jsr mcf_exception_handler
movem.l (sp), d0-d2/a0-a1
lea 20(sp), sp
unlk a6
rte
}
#else
asm void asm_exception_handler(void)
{
link a6,#0
lea -20(sp), sp
movem.l d0-d2/a0-a1, (sp)
pea 24(sp) /* push exception frame address */
jsr mcf_exception_handler
movem.l 4(sp), d0-d2/a0-a1
lea 24(sp), sp
unlk a6
rte
}
#endif
typedef void (* vectorTableEntryType)(void);
#if CONSOLE_IO_SUPPORT
vectorTableEntryType vector_printf @Vtrap14 = TrapHandler_printf;
#endif
/*
* MCF51CN128 vector table
* CF V1 has 114 vector + SP_INIT in the vector table (115 entries)
*/
__declspec(weak) vectorTableEntryType vector_0 @INITSP = (vectorTableEntryType)&_SP_INIT;
__declspec(weak) vectorTableEntryType vector_1 @INITPC = (vectorTableEntryType)&_startup;
__declspec(weak) vectorTableEntryType vector_2 @Vaccerr = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_3 @Vadderr = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_4 @Viinstr = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_5 @VReserved5 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_6 @VReserved6 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_7 @VReserved7 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_8 @Vprviol = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_9 @Vtrace = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_10 @Vunilaop = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_11 @Vunilfop = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_12 @Vdbgi = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_13 @VReserved13 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_14 @Vferror = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_15 @VReserved15 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_16 @VReserved16 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_17 @VReserved17 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_18 @VReserved18 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_19 @VReserved19 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_20 @VReserved20 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_21 @VReserved21 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_22 @VReserved22 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_23 @VReserved23 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_24 @Vspuri = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_25 @VReserved25 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_26 @VReserved26 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_27 @VReserved27 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_28 @VReserved28 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_29 @VReserved29 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_30 @VReserved30 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_31 @VReserved31 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_32 @Vtrap0 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_33 @Vtrap1 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_34 @Vtrap2 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_35 @Vtrap3 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_36 @Vtrap4 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_37 @Vtrap5 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_38 @Vtrap6 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_39 @Vtrap7 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_40 @Vtrap8 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_41 @Vtrap9 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_42 @Vtrap10 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_43 @Vtrap11 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_44 @Vtrap12 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_45 @Vtrap13 = asm_exception_handler;
#if CONSOLE_IO_SUPPORT == 0
__declspec(weak) vectorTableEntryType vector_46 @Vtrap14 = asm_exception_handler;
#endif
__declspec(weak) vectorTableEntryType vector_47 @Vtrap15 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_48 @VReserved48 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_49 @VReserved49 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_50 @VReserved50 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_51 @VReserved51 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_52 @VReserved52 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_53 @VReserved53 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_54 @VReserved54 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_55 @VReserved55 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_56 @VReserved56 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_57 @VReserved57 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_58 @VReserved58 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_59 @VReserved59 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_60 @VReserved60 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_61 @Vunsinstr = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_62 @VReserved62 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_63 @VReserved63 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_64 @Virq = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_65 @Vlvd = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_66 @Vlol = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_67 @Vtpm1ch0 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_68 @Vtpm1ch1 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_69 @Vtpm1ch2 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_70 @Vtpm1ovf = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_71 @Vmtim1 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_72 @Vtpm2ch0 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_73 @Vtpm2ch1 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_74 @Vtpm2ch2 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_75 @Vtpm2ovf = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_76 @Vspi1 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_77 @Vspi2 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_78 @Vmtim2 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_79 @Vsci1err = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_80 @Vsci1rx = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_81 @Vsci1tx = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_82 @Vsci2err = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_83 @Vsci2rx = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_84 @Vsci2tx = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_85 @Vsci3or = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_86 @Vfectxf = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_87 @Vfecrxf = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_88 @Vfecother = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_89 @Vfechberr = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_90 @Vfecbabr = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_91 @Vfecbabt = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_92 @Vfecgra = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_93 @Vfectxb = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_94 @Vfecrxb = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_95 @Vfecmii = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_96 @Vfeceberr = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_97 @Vfeclc = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_98 @Vfecrl = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_99 @Vfecun = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_100 @Vsci3err = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_101 @Vsci3rx = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_102 @Vsci3tx = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_103 @VL7swi = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_104 @VL6swi = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_105 @VL5swi = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_106 @VL4swi = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_107 @VL3swi = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_108 @VL2swi = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_109 @VL1swi = vPortYieldISR;
__declspec(weak) vectorTableEntryType vector_110 @Viic1 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_111 @Viic2 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_112 @Vadc = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_113 @Vkeyboard = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_114 @Vrtc = asm_exception_handler;
#ifdef __cplusplus
}
#endif

View file

@ -0,0 +1,52 @@
/*
* File: exceptions.h
* Purpose: Generic exception handling for ColdFire processors
*
* Notes:
*/
#ifndef _MCF_EXCEPTIONS_H
#define _MCF_EXCEPTIONS_H
#ifdef __cplusplus
extern "C" {
#endif
/***********************************************************************/
/*
* This is the handler for all exceptions which are not common to all
* ColdFire Chips.
*
* Called by mcf_exception_handler
*
*/
void derivative_interrupt(unsigned long vector);
/***********************************************************************/
/*
* This is the exception handler for all exceptions common to all
* chips ColdFire. Most exceptions do nothing, but some of the more
* important ones are handled to some extent.
*
* Called by asm_exception_handler
*/
void mcf_exception_handler(void *framepointer);
/***********************************************************************/
/*
* This is the assembly exception handler defined in the vector table.
* This function is in assembler so that the frame pointer can be read
* from the stack.
* Note that the way to give the stack frame as argument to the c handler
* depends on the used ABI (Register, Compact or Standard).
*
*/
asm void asm_exception_handler(void);
#ifdef __cplusplus
}
#endif
#endif /* _MCF_EXCEPTIONS_H */

View file

@ -0,0 +1,444 @@
/*
* File: exceptions.c
* Purpose: Generic exception handling for ColdFire processors
*
*/
#include "derivative.h"
#include "exceptions.h"
#include "startcf.h"
#define REGISTER_ABI __REGABI__
extern asm void interrupt 109 vPortYieldISR( void );
extern void interrupt 86 vFECISRHandler( void );
/***********************************************************************/
/*
* Set NO_PRINTF to 0 in order the exceptions.c interrupt handler
* to output messages to the standard io.
*
*/
#define NO_PRINTF 1
#if NO_PRINTF
#define VECTORDISPLAY(MESSAGE) asm { nop; };
#define VECTORDISPLAY2(MESSAGE,MESSAGE2) asm { nop; };
#define VECTORDISPLAY3(MESSAGE,MESSAGE2,MESSAGE3) asm { nop; };
#else
#include <stdio.h>
#define VECTORDISPLAY(MESSAGE1) printf(MESSAGE1);
#define VECTORDISPLAY2(MESSAGE1,MESSAGE2) printf(MESSAGE1,MESSAGE2);
#define VECTORDISPLAY3(MESSAGE1,MESSAGE2,MESSAGE3) printf(MESSAGE1,MESSAGE2,MESSAGE3);
#endif
#ifdef __cplusplus
extern "C" {
#endif
extern unsigned long far _SP_INIT[];
/***********************************************************************/
/*
* Handling of the TRK ColdFire libs (printf support in Debugger Terminal)
*
* To enable this support:
* - Set CONSOLE_IO_SUPPORT 1 in this file; this will enable
* TrapHandler_printf for the trap #14 exception.
*
* - Make sure the file console_io_cf.c is in your project.
*
* - In the debugger make sure that in the Connection "Setup" dialog,
* "Debug Options" property page, the check box
* "Enable Terminal printf support" is set.
*
*
*
*/
#define CONSOLE_IO_SUPPORT 0
#if CONSOLE_IO_SUPPORT
asm void TrapHandler_printf(void) {
HALT
RTE
}
#endif
/***********************************************************************/
/*
* This is the handler for all exceptions which are not common to all
* ColdFire Chips.
*
* Called by mcf_exception_handler
*
*/
void derivative_interrupt(unsigned long vector)
{
if (vector < 64 || vector > 192) {
VECTORDISPLAY2("User Defined Vector #%d\n",vector);
}
}
/***********************************************************************
*
* This is the exception handler for all exceptions common to all
* chips ColdFire. Most exceptions do nothing, but some of the more
* important ones are handled to some extent.
*
* Called by asm_exception_handler
*
* The ColdFire family of processors has a simplified exception stack
* frame that looks like the following:
*
* 3322222222221111 111111
* 1098765432109876 5432109876543210
* 8 +----------------+----------------+
* | Program Counter |
* 4 +----------------+----------------+
* |FS/Fmt/Vector/FS| SR |
* SP --> 0 +----------------+----------------+
*
* The stack self-aligns to a 4-byte boundary at an exception, with
* the FS/Fmt/Vector/FS field indicating the size of the adjustment
* (SP += 0,1,2,3 bytes).
* 31 28 27 26 25 18 17 16 15 0
* 4 +---------------------------------------+------------------------------------+
* | Format | FS[3..2] | Vector | FS[1..0] | SR |
* SP --> 0 +---------------------------------------+------------------------------------+
*/
#define MCF5XXX_RD_SF_FORMAT(PTR) \
((*((unsigned short *)(PTR)) >> 12) & 0x00FF)
#define MCF5XXX_RD_SF_VECTOR(PTR) \
((*((unsigned short *)(PTR)) >> 2) & 0x00FF)
#define MCF5XXX_RD_SF_FS(PTR) \
( ((*((unsigned short *)(PTR)) & 0x0C00) >> 8) | (*((unsigned short *)(PTR)) & 0x0003) )
#define MCF5XXX_SF_SR(PTR) *(((unsigned short *)(PTR))+1)
#define MCF5XXX_SF_PC(PTR) *((unsigned long *)(PTR)+1)
#define MCF5XXX_EXCEPTFMT "%s -- PC = %#08X\n"
void mcf_exception_handler(void *framepointer)
{
volatile unsigned long exceptionStackFrame = (*(unsigned long *)(framepointer));
volatile unsigned short stackFrameSR = MCF5XXX_SF_SR(framepointer);
volatile unsigned short stackFrameWord = (*(unsigned short *)(framepointer));
volatile unsigned long stackFrameFormat = (unsigned long)MCF5XXX_RD_SF_FORMAT(&stackFrameWord);
volatile unsigned long stackFrameFS = (unsigned long)MCF5XXX_RD_SF_FS(&stackFrameWord);
volatile unsigned long stackFrameVector = (unsigned long)MCF5XXX_RD_SF_VECTOR(&stackFrameWord);
volatile unsigned long stackFramePC = MCF5XXX_SF_PC(framepointer);
switch (stackFrameFormat)
{
case 4:
case 5:
case 6:
case 7:
break;
default:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT,"Illegal stack type", stackFramePC);
break;
}
switch (stackFrameVector)
{
case 2:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Access Error", stackFramePC);
switch (stackFrameFS)
{
case 4:
VECTORDISPLAY("Error on instruction fetch\n");
break;
case 8:
VECTORDISPLAY("Error on operand write\n");
break;
case 9:
VECTORDISPLAY("Attempted write to write-protected space\n");
break;
case 12:
VECTORDISPLAY("Error on operand read\n");
break;
default:
VECTORDISPLAY("Reserved Fault Status Encoding\n");
break;
}
break;
case 3:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Address Error", stackFramePC);
switch (stackFrameFS)
{
case 4:
VECTORDISPLAY("Error on instruction fetch\n");
break;
case 8:
VECTORDISPLAY("Error on operand write\n");
break;
case 9:
VECTORDISPLAY("Attempted write to write-protected space\n");
break;
case 12:
VECTORDISPLAY("Error on operand read\n");
break;
default:
VECTORDISPLAY("Reserved Fault Status Encoding\n");
break;
}
break;
case 4:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Illegal instruction", stackFramePC);
break;
case 8:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Privilege violation", stackFramePC);
break;
case 9:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Trace Exception", stackFramePC);
break;
case 10:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Unimplemented A-Line Instruction", stackFramePC);
break;
case 11:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Unimplemented F-Line Instruction", stackFramePC);
break;
case 12:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Debug Interrupt", stackFramePC);
break;
case 14:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Format Error", stackFramePC);
break;
case 15:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Unitialized Interrupt", stackFramePC);
break;
case 24:
VECTORDISPLAY3(MCF5XXX_EXCEPTFMT, "Spurious Interrupt", stackFramePC);
break;
case 25:
case 26:
case 27:
case 28:
case 29:
case 30:
case 31:
VECTORDISPLAY2("Autovector interrupt level %d\n", stackFrameVector - 24);
break;
case 32:
case 33:
case 34:
case 35:
case 36:
case 37:
case 38:
case 39:
case 40:
case 41:
case 42:
case 43:
case 44:
case 45:
case 46:
case 47:
VECTORDISPLAY2("TRAP #%d\n", stackFrameVector - 32);
break;
case 5:
case 6:
case 7:
case 13:
case 16:
case 17:
case 18:
case 19:
case 20:
case 21:
case 22:
case 23:
case 48:
case 49:
case 50:
case 51:
case 52:
case 53:
case 54:
case 55:
case 56:
case 57:
case 58:
case 59:
case 60:
case 61:
case 62:
case 63:
VECTORDISPLAY2("Reserved: #%d\n", stackFrameVector);
break;
default:
derivative_interrupt(stackFrameVector);
break;
}
}
#if REGISTER_ABI
asm void asm_exception_handler(void)
{
link a6,#0
lea -20(sp), sp
movem.l d0-d2/a0-a1, (sp)
lea 24(sp),a0 /* A0 point to exception stack frame on the stack */
jsr mcf_exception_handler
movem.l (sp), d0-d2/a0-a1
lea 20(sp), sp
unlk a6
rte
}
#else
asm void asm_exception_handler(void)
{
link a6,#0
lea -20(sp), sp
movem.l d0-d2/a0-a1, (sp)
pea 24(sp) /* push exception frame address */
jsr mcf_exception_handler
movem.l 4(sp), d0-d2/a0-a1
lea 24(sp), sp
unlk a6
rte
}
#endif
typedef void (* vectorTableEntryType)(void);
#if CONSOLE_IO_SUPPORT
vectorTableEntryType vector_printf @Vtrap14 = TrapHandler_printf;
#endif
/*
* MCF51CN128 vector table
* CF V1 has 114 vector + SP_INIT in the vector table (115 entries)
*/
__declspec(weak) vectorTableEntryType vector_0 @INITSP = (vectorTableEntryType)&_SP_INIT;
__declspec(weak) vectorTableEntryType vector_1 @INITPC = (vectorTableEntryType)&_startup;
__declspec(weak) vectorTableEntryType vector_2 @Vaccerr = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_3 @Vadderr = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_4 @Viinstr = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_5 @VReserved5 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_6 @VReserved6 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_7 @VReserved7 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_8 @Vprviol = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_9 @Vtrace = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_10 @Vunilaop = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_11 @Vunilfop = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_12 @Vdbgi = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_13 @VReserved13 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_14 @Vferror = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_15 @VReserved15 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_16 @VReserved16 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_17 @VReserved17 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_18 @VReserved18 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_19 @VReserved19 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_20 @VReserved20 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_21 @VReserved21 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_22 @VReserved22 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_23 @VReserved23 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_24 @Vspuri = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_25 @VReserved25 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_26 @VReserved26 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_27 @VReserved27 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_28 @VReserved28 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_29 @VReserved29 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_30 @VReserved30 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_31 @VReserved31 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_32 @Vtrap0 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_33 @Vtrap1 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_34 @Vtrap2 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_35 @Vtrap3 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_36 @Vtrap4 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_37 @Vtrap5 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_38 @Vtrap6 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_39 @Vtrap7 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_40 @Vtrap8 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_41 @Vtrap9 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_42 @Vtrap10 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_43 @Vtrap11 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_44 @Vtrap12 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_45 @Vtrap13 = asm_exception_handler;
#if CONSOLE_IO_SUPPORT == 0
__declspec(weak) vectorTableEntryType vector_46 @Vtrap14 = asm_exception_handler;
#endif
__declspec(weak) vectorTableEntryType vector_47 @Vtrap15 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_48 @VReserved48 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_49 @VReserved49 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_50 @VReserved50 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_51 @VReserved51 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_52 @VReserved52 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_53 @VReserved53 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_54 @VReserved54 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_55 @VReserved55 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_56 @VReserved56 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_57 @VReserved57 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_58 @VReserved58 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_59 @VReserved59 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_60 @VReserved60 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_61 @Vunsinstr = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_62 @VReserved62 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_63 @VReserved63 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_64 @Virq = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_65 @Vlvd = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_66 @Vlol = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_67 @Vtpm1ch0 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_68 @Vtpm1ch1 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_69 @Vtpm1ch2 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_70 @Vtpm1ovf = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_71 @Vmtim1 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_72 @Vtpm2ch0 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_73 @Vtpm2ch1 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_74 @Vtpm2ch2 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_75 @Vtpm2ovf = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_76 @Vspi1 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_77 @Vspi2 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_78 @Vmtim2 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_79 @Vsci1err = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_80 @Vsci1rx = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_81 @Vsci1tx = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_82 @Vsci2err = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_83 @Vsci2rx = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_84 @Vsci2tx = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_85 @Vsci3or = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_86 @Vfectxf = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_87 @Vfecrxf = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_88 @Vfecother = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_89 @Vfechberr = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_90 @Vfecbabr = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_91 @Vfecbabt = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_92 @Vfecgra = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_93 @Vfectxb = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_94 @Vfecrxb = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_95 @Vfecmii = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_96 @Vfeceberr = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_97 @Vfeclc = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_98 @Vfecrl = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_99 @Vfecun = vFECISRHandler;
__declspec(weak) vectorTableEntryType vector_100 @Vsci3err = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_101 @Vsci3rx = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_102 @Vsci3tx = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_103 @VL7swi = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_104 @VL6swi = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_105 @VL5swi = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_106 @VL4swi = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_107 @VL3swi = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_108 @VL2swi = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_109 @VL1swi = vPortYieldISR;
__declspec(weak) vectorTableEntryType vector_110 @Viic1 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_111 @Viic2 = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_112 @Vadc = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_113 @Vkeyboard = asm_exception_handler;
__declspec(weak) vectorTableEntryType vector_114 @Vrtc = asm_exception_handler;
#ifdef __cplusplus
}
#endif

View file

@ -0,0 +1,101 @@
/*
* File: fecbd.h
* Purpose:
*
* Purpose: Provide a simple buffer management driver
*/
#ifndef _FECBD_H_
#define _FECBD_H_
/********************************************************************/
#define Rx 1
#define Tx 0
/*
* Buffer sizes in bytes
*/
#ifndef RX_BUF_SZ
#define RX_BUF_SZ 1520 //2048
#endif
#ifndef TX_BUF_SZ
#define TX_BUF_SZ 1520
#endif
/*
* Buffer Descriptor Format
*/
#pragma options align= packed
typedef struct
{
unsigned short status; /* control and status */
unsigned short length; /* transfer length */
unsigned char *data; /* buffer address */
} FECBD;
/*
* Bit level definitions for status field of buffer descriptors
*/
#define TX_BD_R 0x8000
#define TX_BD_TO1 0x4000
#define TX_BD_W 0x2000
#define TX_BD_TO2 0x1000
#define TX_BD_INTERRUPT 0x1000 /* MCF547x/8x Only */
#define TX_BD_L 0x0800
#define TX_BD_TC 0x0400
#define TX_BD_DEF 0x0200 /* MCF5272 Only */
#define TX_BD_ABC 0x0200
#define TX_BD_HB 0x0100 /* MCF5272 Only */
#define TX_BD_LC 0x0080 /* MCF5272 Only */
#define TX_BD_RL 0x0040 /* MCF5272 Only */
#define TX_BD_UN 0x0002 /* MCF5272 Only */
#define TX_BD_CSL 0x0001 /* MCF5272 Only */
#define RX_BD_E 0x8000
#define RX_BD_R01 0x4000
#define RX_BD_W 0x2000
#define RX_BD_R02 0x1000
#define RX_BD_INTERRUPT 0x1000 /* MCF547x/8x Only */
#define RX_BD_L 0x0800
#define RX_BD_M 0x0100
#define RX_BD_BC 0x0080
#define RX_BD_MC 0x0040
#define RX_BD_LG 0x0020
#define RX_BD_NO 0x0010
#define RX_BD_CR 0x0004
#define RX_BD_OV 0x0002
#define RX_BD_TR 0x0001
#define RX_BD_ERROR (RX_BD_NO | RX_BD_CR | RX_BD_OV | RX_BD_TR)
/*
* The following defines are provided by the MCF547x/8x
* DMA API. These are shown here to show their correlation
* to the other FEC buffer descriptor status bits
*
* #define MCD_FEC_BUF_READY 0x8000
* #define MCD_FEC_WRAP 0x2000
* #define MCD_FEC_INTERRUPT 0x1000
* #define MCD_FEC_END_FRAME 0x0800
*/
/*
* Functions provided in fec_bd.c
*/
int fecbd_init(int, int, int);
void fecbd_flush(int);
void fecbd_dump( void );
unsigned long fecbd_get_start(int, int);
FECBD* fecbd_rx_alloc(int);
FECBD* fecbd_tx_alloc(int);
FECBD* fecbd_tx_free(int);
/*
* Error codes
*/
#define ERR_MALLOC (-1)
#define ERR_NBUFALLOC (-2)
/*******************************************************************/
#endif /* _FECBD_H_ */

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,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,284 @@
/**
* \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(io, "led-io", led_io );
static const struct httpd_cgi_call *calls[] = { &file, &tcp, &net, &rtos, &io, NULL };
/*---------------------------------------------------------------------------*/
static
PT_THREAD(nullfunction(struct httpd_state *s, char *ptr))
{
( void ) ptr;
PSOCK_BEGIN(&s->sout);
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))
{
( void ) ptr;
PSOCK_BEGIN(&s->sout);
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))
{
( void ) ptr;
PSOCK_BEGIN(&s->sout);
#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 );
extern unsigned long ulCheckErrors;
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", lRefreshCount );
vTaskList( uip_appdata );
strcat( uip_appdata, cCountBuf );
/* Have any errors been latched? */
if( ulCheckErrors != 0 )
{
strcat( uip_appdata, "<p><br><p>The check function has detected an error! Error code = " );
sprintf( cCountBuf, "%x", ulCheckErrors );
strcat( uip_appdata, cCountBuf );
}
else
{
strcat( uip_appdata, "<p><br><p>All tasks are executing with no errors reported.<p>" );
}
return strlen( uip_appdata );
}
/*---------------------------------------------------------------------------*/
static
PT_THREAD(rtos_stats(struct httpd_state *s, char *ptr))
{
( void ) ptr;
PSOCK_BEGIN(&s->sout);
PSOCK_GENERATOR_SEND(&s->sout, generate_rtos_stats, NULL);
PSOCK_END(&s->sout);
}
/*---------------------------------------------------------------------------*/
char *pcStatus;
extern unsigned long uxParTestGetLED( unsigned long uxLED );
static unsigned short generate_io_state( void *arg )
{
( void ) arg;
if( uxParTestGetLED( 3 ) )
{
pcStatus = "checked";
}
else
{
pcStatus = "";
}
sprintf( uip_appdata, "<input type=\"checkbox\" name=\"LED3\" value=\"1\" %s>LED", pcStatus );
return strlen( uip_appdata );
}
/*---------------------------------------------------------------------------*/
static PT_THREAD(led_io(struct httpd_state *s, char *ptr))
{
( void ) ptr;
PSOCK_BEGIN(&s->sout);
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">RTOS Stats</a> <b>|</b> <a href="tcp.shtml">Connections</a> <b>|</b> <a href="io.shtml">IO</a>
<br><p>
<hr>
<br><p>
<h2>Task status</h2>
This page shows dynamically generated task state information. The page will refresh evey 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">RTOS Stats</a> <b>|</b> <a href="tcp.shtml">Connections</a> <b>|</b> <a href="io.shtml">IO</a>
<br><p>
<hr>
<b>Dynamic IO demonstration</b><br>
<p>
This page demonstrates two way communication. By using the check box this WEB interface can influence the program execution.<p>
Use the check box and "Update IO button" to set the state of LED1. Refresh the page to display the state of LED1.
<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,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 bgcolor="#CCCCff">
<font face="arial">
<a href="index.shtml">RTOS 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,22 @@
<!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">RTOS Stats</a> <b>|</b> <a href="tcp.shtml">Connections</a> <b>|</b> <a href="io.shtml">IO</a>
<br><p>
<hr>
<br>
<h2>Network connections</h2>
This page displays dynamically generated status information on the TCP/IP connections.
<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,445 @@
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, 0x52, 0x54, 0x4f, 0x53, 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, 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, 0x75, 0x73, 0x3c, 0x2f, 0x68, 0x32,
0x3e, 0xa, 0x54, 0x68, 0x69, 0x73, 0x20, 0x70, 0x61, 0x67,
0x65, 0x20, 0x73, 0x68, 0x6f, 0x77, 0x73, 0x20, 0x64, 0x79,
0x6e, 0x61, 0x6d, 0x69, 0x63, 0x61, 0x6c, 0x6c, 0x79, 0x20,
0x67, 0x65, 0x6e, 0x65, 0x72, 0x61, 0x74, 0x65, 0x64, 0x20,
0x74, 0x61, 0x73, 0x6b, 0x20, 0x73, 0x74, 0x61, 0x74, 0x65,
0x20, 0x69, 0x6e, 0x66, 0x6f, 0x72, 0x6d, 0x61, 0x74, 0x69,
0x6f, 0x6e, 0x2e, 0x20, 0x20, 0x54, 0x68, 0x65, 0x20, 0x70,
0x61, 0x67, 0x65, 0x20, 0x77, 0x69, 0x6c, 0x6c, 0x20, 0x72,
0x65, 0x66, 0x72, 0x65, 0x73, 0x68, 0x20, 0x65, 0x76, 0x65,
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, 0x52, 0x54, 0x4f, 0x53, 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,
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, 0x44, 0x79, 0x6e, 0x61, 0x6d, 0x69, 0x63,
0x20, 0x49, 0x4f, 0x20, 0x64, 0x65, 0x6d, 0x6f, 0x6e, 0x73,
0x74, 0x72, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x3c, 0x2f, 0x62,
0x3e, 0x3c, 0x62, 0x72, 0x3e, 0xa, 0xa, 0x3c, 0x70, 0x3e,
0xa, 0x54, 0x68, 0x69, 0x73, 0x20, 0x70, 0x61, 0x67, 0x65,
0x20, 0x64, 0x65, 0x6d, 0x6f, 0x6e, 0x73, 0x74, 0x72, 0x61,
0x74, 0x65, 0x73, 0x20, 0x74, 0x77, 0x6f, 0x20, 0x77, 0x61,
0x79, 0x20, 0x63, 0x6f, 0x6d, 0x6d, 0x75, 0x6e, 0x69, 0x63,
0x61, 0x74, 0x69, 0x6f, 0x6e, 0x2e, 0x20, 0x20, 0x42, 0x79,
0x20, 0x75, 0x73, 0x69, 0x6e, 0x67, 0x20, 0x74, 0x68, 0x65,
0x20, 0x63, 0x68, 0x65, 0x63, 0x6b, 0x20, 0x62, 0x6f, 0x78,
0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x57, 0x45, 0x42, 0x20,
0x69, 0x6e, 0x74, 0x65, 0x72, 0x66, 0x61, 0x63, 0x65, 0x20,
0x63, 0x61, 0x6e, 0x20, 0x69, 0x6e, 0x66, 0x6c, 0x75, 0x65,
0x6e, 0x63, 0x65, 0x20, 0x74, 0x68, 0x65, 0x20, 0x70, 0x72,
0x6f, 0x67, 0x72, 0x61, 0x6d, 0x20, 0x65, 0x78, 0x65, 0x63,
0x75, 0x74, 0x69, 0x6f, 0x6e, 0x2e, 0x3c, 0x70, 0x3e, 0xa,
0x55, 0x73, 0x65, 0x20, 0x74, 0x68, 0x65, 0x20, 0x63, 0x68,
0x65, 0x63, 0x6b, 0x20, 0x62, 0x6f, 0x78, 0x20, 0x61, 0x6e,
0x64, 0x20, 0x22, 0x55, 0x70, 0x64, 0x61, 0x74, 0x65, 0x20,
0x49, 0x4f, 0x20, 0x62, 0x75, 0x74, 0x74, 0x6f, 0x6e, 0x22,
0x20, 0x74, 0x6f, 0x20, 0x73, 0x65, 0x74, 0x20, 0x74, 0x68,
0x65, 0x20, 0x73, 0x74, 0x61, 0x74, 0x65, 0x20, 0x6f, 0x66,
0x20, 0x4c, 0x45, 0x44, 0x31, 0x2e, 0x20, 0x20, 0x52, 0x65,
0x66, 0x72, 0x65, 0x73, 0x68, 0x20, 0x74, 0x68, 0x65, 0x20,
0x70, 0x61, 0x67, 0x65, 0x20, 0x74, 0x6f, 0x20, 0x64, 0x69,
0x73, 0x70, 0x6c, 0x61, 0x79, 0x20, 0x74, 0x68, 0x65, 0x20,
0x73, 0x74, 0x61, 0x74, 0x65, 0x20, 0x6f, 0x66, 0x20, 0x4c,
0x45, 0x44, 0x31, 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_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, 0x20, 0x62,
0x67, 0x63, 0x6f, 0x6c, 0x6f, 0x72, 0x3d, 0x22, 0x23, 0x43,
0x43, 0x43, 0x43, 0x66, 0x66, 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,
0x52, 0x54, 0x4f, 0x53, 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, 0x52, 0x54, 0x4f, 0x53, 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,
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, 0x54, 0x68, 0x69, 0x73, 0x20, 0x70,
0x61, 0x67, 0x65, 0x20, 0x64, 0x69, 0x73, 0x70, 0x6c, 0x61,
0x79, 0x73, 0x20, 0x64, 0x79, 0x6e, 0x61, 0x6d, 0x69, 0x63,
0x61, 0x6c, 0x6c, 0x79, 0x20, 0x67, 0x65, 0x6e, 0x65, 0x72,
0x61, 0x74, 0x65, 0x64, 0x20, 0x73, 0x74, 0x61, 0x74, 0x75,
0x73, 0x20, 0x69, 0x6e, 0x66, 0x6f, 0x72, 0x6d, 0x61, 0x74,
0x69, 0x6f, 0x6e, 0x20, 0x6f, 0x6e, 0x20, 0x74, 0x68, 0x65,
0x20, 0x54, 0x43, 0x50, 0x2f, 0x49, 0x50, 0x20, 0x63, 0x6f,
0x6e, 0x6e, 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x73, 0x2e,
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}};
const struct httpd_fsdata_file file_index_html[] = {{file_404_html, data_index_html, data_index_html + 12, sizeof(data_index_html) - 12}};
const struct httpd_fsdata_file file_index_shtml[] = {{file_index_html, data_index_shtml, data_index_shtml + 13, sizeof(data_index_shtml) - 13}};
const struct httpd_fsdata_file file_io_shtml[] = {{file_index_shtml, data_io_shtml, data_io_shtml + 10, sizeof(data_io_shtml) - 10}};
const struct httpd_fsdata_file file_stats_shtml[] = {{file_io_shtml, data_stats_shtml, data_stats_shtml + 13, sizeof(data_stats_shtml) - 13}};
const struct httpd_fsdata_file file_tcp_shtml[] = {{file_stats_shtml, data_tcp_shtml, data_tcp_shtml + 11, sizeof(data_tcp_shtml) - 11}};
#define HTTPD_FS_ROOT file_tcp_shtml
#define HTTPD_FS_NUMFILES 6

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, long xInputLength );
vApplicationProcessFormInput( s->inputbuf, PSOCK_DATALEN(&s->sin) );
}
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 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 @@
#pragma pack()

View file

@ -0,0 +1 @@
#pragma pack(1)

View file

@ -0,0 +1,240 @@
/*
FreeRTOS V7.1.1 - Copyright (C) 2012 Real Time Engineers Ltd.
***************************************************************************
* *
* FreeRTOS tutorial books are available in pdf and paperback. *
* Complete, revised, and edited pdf reference manuals are also *
* available. *
* *
* Purchasing FreeRTOS documentation will not only help you, by *
* ensuring you get running as quickly as possible and with an *
* in-depth knowledge of how to use FreeRTOS, it will also help *
* the FreeRTOS project to continue with its mission of providing *
* professional grade, cross platform, de facto standard solutions *
* for microcontrollers - completely free of charge! *
* *
* >>> See http://www.FreeRTOS.org/Documentation for details. <<< *
* *
* Thank you for using FreeRTOS, and thank you for your support! *
* *
***************************************************************************
This file is part of the FreeRTOS distribution.
FreeRTOS 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 modification to the GPL is included to allow you to
distribute a combined work that includes FreeRTOS without being obliged to
provide the source code for proprietary components outside of the FreeRTOS
kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it
can be viewed here: http://www.freertos.org/a00114.html and also obtained
by writing to Richard Barry, contact details for whom are available on the
FreeRTOS WEB site.
1 tab == 4 spaces!
***************************************************************************
* *
* Having a problem? Start by reading the FAQ "My application does *
* not run, what could be wrong? *
* *
* http://www.FreeRTOS.org/FAQHelp.html *
* *
***************************************************************************
http://www.FreeRTOS.org - Documentation, training, latest information,
license and contact details.
http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
including FreeRTOS+Trace - an indispensable productivity tool.
Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell
the code with commercial support, indemnification, and middleware, under
the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also
provide a safety engineered and independently SIL3 certified version under
the SafeRTOS brand: http://www.SafeRTOS.com.
*/
/* 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"
#include "timer.h"
/* Demo includes. */
#include "FEC.h"
#include "partest.h"
/*-----------------------------------------------------------*/
/* Shortcut to the header within the Rx buffer. */
#define xHeader ((struct uip_eth_hdr *) &uip_buf[ 0 ])
/*-----------------------------------------------------------*/
/*
* Port functions required by the uIP stack.
*/
clock_time_t clock_time( void );
/*-----------------------------------------------------------*/
/* The semaphore used by the ISR to wake the uIP task. */
extern xSemaphoreHandle xFECSemaphore;
/*-----------------------------------------------------------*/
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 )( void );
/* Just to get rid of the compiler warning. */
( void ) pvParameters;
/* Enable/Reset the Ethernet Controller */
/* Create the semaphore used by the ISR to wake this task. */
vSemaphoreCreateBinary( xFECSemaphore );
/* 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();
vInitFEC();
for( ;; )
{
/* Is there received data ready to be processed? */
uip_len = ( unsigned short ) ulFECRx();
if( ( uip_len > 0 ) && ( uip_buf != NULL ) )
{
/* 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();
vFECTx();
}
}
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 )
{
vFECTx();
}
}
}
else
{
if( ( timer_expired( &periodic_timer ) ) && ( uip_buf != NULL ) )
{
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();
vFECTx();
}
}
/* 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( xFECSemaphore, configTICK_RATE_HZ / 2 );
}
}
}
}
/*-----------------------------------------------------------*/
void vApplicationProcessFormInput( char *pcInputString, portBASE_TYPE xInputLength )
{
char *c;
/* Just to get rid of the compiler warning - other ports/demos use the parameter. */
( void ) xInputLength;
/* 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, "LED3=1" ) != NULL )
{
/* Turn LED 3 on. */
vParTestSetLED( 3, 1 );
}
else
{
/* Turn LED 3 off. */
vParTestSetLED( 3, 0 );
}
}
}

View file

@ -0,0 +1,163 @@
/**
* \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 15
/**
* Maximum number of listening TCP ports.
*
* \hideinitializer
*/
#define UIP_CONF_MAX_LISTENPORTS 2
/**
* uIP buffer size.
*
* \hideinitializer
*/
#define UIP_CONF_BUFFER_SIZE 1480
/**
* CPU byte order.
*
* \hideinitializer
*/
#define UIP_CONF_BYTE_ORDER UIP_BIG_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"*/
#define UIP_CONF_EXTERNAL_BUFFER
#define PACK_STRUCT_START
#define PACK_STRUCT_END
#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__ */

View file

@ -0,0 +1,456 @@
/*
FreeRTOS V7.1.1 - Copyright (C) 2012 Real Time Engineers Ltd.
***************************************************************************
* *
* FreeRTOS tutorial books are available in pdf and paperback. *
* Complete, revised, and edited pdf reference manuals are also *
* available. *
* *
* Purchasing FreeRTOS documentation will not only help you, by *
* ensuring you get running as quickly as possible and with an *
* in-depth knowledge of how to use FreeRTOS, it will also help *
* the FreeRTOS project to continue with its mission of providing *
* professional grade, cross platform, de facto standard solutions *
* for microcontrollers - completely free of charge! *
* *
* >>> See http://www.FreeRTOS.org/Documentation for details. <<< *
* *
* Thank you for using FreeRTOS, and thank you for your support! *
* *
***************************************************************************
This file is part of the FreeRTOS distribution.
FreeRTOS 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 modification to the GPL is included to allow you to
distribute a combined work that includes FreeRTOS without being obliged to
provide the source code for proprietary components outside of the FreeRTOS
kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it
can be viewed here: http://www.freertos.org/a00114.html and also obtained
by writing to Richard Barry, contact details for whom are available on the
FreeRTOS WEB site.
1 tab == 4 spaces!
***************************************************************************
* *
* Having a problem? Start by reading the FAQ "My application does *
* not run, what could be wrong? *
* *
* http://www.FreeRTOS.org/FAQHelp.html *
* *
***************************************************************************
http://www.FreeRTOS.org - Documentation, training, latest information,
license and contact details.
http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
including FreeRTOS+Trace - an indispensable productivity tool.
Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell
the code with commercial support, indemnification, and middleware, under
the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also
provide a safety engineered and independently SIL3 certified version under
the SafeRTOS brand: http://www.SafeRTOS.com.
*/
/*
* Creates all the demo application tasks, then starts the scheduler. The WEB
* documentation provides more details of the standard demo application tasks.
* In addition to the standard demo tasks, the following tasks and tests are
* defined and/or created within this file:
*
* "Web server" - Very basic demonstration of the uIP stack. The WEB server
* simply generates a page that shows the current state of all the tasks within
* the system, including the high water mark of each task stack. The high water
* mark is displayed as the amount of stack that has never been used, so the
* closer the value is to zero the closer the task has come to overflowing its
* stack. The IP address and net mask are set within FreeRTOSConfig.h. Sub
* pages display some TCP/IP status information and permit LED3 to be turned on
* and off using a check box.
*
* Tick hook function that implements a "Check" function - This is executed
* every 5 seconds from the tick hook function. It checks to ensure that all
* the standard demo tasks are still operational and running without error.
* The system status (pass/fail) is then displayed underneith the task table on
* the served WEB pages.
*
* "Reg test" tasks - These fill the registers with known values, then check
* that each register still contains its expected value. Each task uses
* different values. The tasks run with very low priority so get preempted very
* frequently. A register containing an unexpected value is indicative of an
* error in the context switching mechanism.
*
*/
/* Standard includes. */
#include <stdio.h>
/* Scheduler includes. */
#include "FreeRTOS.h"
#include "task.h"
#include "queue.h"
#include "semphr.h"
/* Demo app includes. */
#include "BlockQ.h"
#include "death.h"
#include "flash.h"
#include "partest.h"
#include "GenQTest.h"
#include "QPeek.h"
#include "recmutex.h"
/*-----------------------------------------------------------*/
/* ComTest constants - there is no free LED for the comtest tasks. */
#define mainCOM_TEST_BAUD_RATE ( ( unsigned long ) 19200 )
#define mainCOM_TEST_LED ( 5 )
/* Task priorities. */
#define mainQUEUE_POLL_PRIORITY ( tskIDLE_PRIORITY + 2 )
#define mainCHECK_TASK_PRIORITY ( tskIDLE_PRIORITY + 3 )
#define mainSEM_TEST_PRIORITY ( tskIDLE_PRIORITY + 1 )
#define mainBLOCK_Q_PRIORITY ( tskIDLE_PRIORITY + 2 )
#define mainCREATOR_TASK_PRIORITY ( tskIDLE_PRIORITY + 2 )
#define mainINTEGER_TASK_PRIORITY ( tskIDLE_PRIORITY )
#define mainGEN_QUEUE_TASK_PRIORITY ( tskIDLE_PRIORITY )
#define mainWEB_TASK_PRIORITY ( tskIDLE_PRIORITY + 2 )
/* WEB server requires enough stack for the string handling functions. */
#define mainBASIC_WEB_STACK_SIZE ( configMINIMAL_STACK_SIZE * 2 )
/*
* Configure the hardware for the demo.
*/
static void prvSetupHardware( void );
/*
* Implements the 'check' function as described at the top of this file.
*/
static void prvCheckFunction( void );
/*
* Implement the 'Reg test' functionality as described at the top of this file.
*/
static void vRegTest1Task( void *pvParameters );
static void vRegTest2Task( void *pvParameters );
/*
* The task that handles the uIP stack. All TCP/IP processing is performed in
* this task.
*/
extern void vuIP_Task( void *pvParameters );
/*-----------------------------------------------------------*/
/* Counters used to detect errors within the reg test tasks. */
static volatile unsigned long ulRegTest1Counter = 0x11111111, ulRegTest2Counter = 0x22222222;
/* Flag that latches any errors detected in the system. */
unsigned long ulCheckErrors = 0;
/*-----------------------------------------------------------*/
int main( void )
{
extern void vBasicWEBServer( void *pv );
/* Setup the hardware ready for this demo. */
prvSetupHardware();
xTaskCreate( vuIP_Task, ( signed char * ) "uIP", mainBASIC_WEB_STACK_SIZE, NULL, mainCHECK_TASK_PRIORITY - 1, NULL );
/* Start the standard demo tasks. */
vStartLEDFlashTasks( tskIDLE_PRIORITY );
vStartGenericQueueTasks( mainGEN_QUEUE_TASK_PRIORITY );
vStartQueuePeekTasks();
vStartRecursiveMutexTasks();
vStartBlockingQueueTasks( mainBLOCK_Q_PRIORITY );
/* Start the reg test tasks - defined in this file. */
xTaskCreate( vRegTest1Task, ( signed char * ) "Reg1", configMINIMAL_STACK_SIZE, ( void * ) &ulRegTest1Counter, tskIDLE_PRIORITY, NULL );
xTaskCreate( vRegTest2Task, ( signed char * ) "Reg2", configMINIMAL_STACK_SIZE, ( void * ) &ulRegTest2Counter, tskIDLE_PRIORITY, NULL );
/* Start the scheduler. */
vTaskStartScheduler();
/* Will only get here if there was insufficient memory to create the idle
task. */
for( ;; )
{
}
}
/*-----------------------------------------------------------*/
void vApplicationTickHook( void )
{
static unsigned long ulExecutionCount = 0, ulLastRegTest1Count = 0, ulLastRegTest2Count = 0;
const unsigned long ulExecutionRate = 5000 / portTICK_RATE_MS;
/* Increment the count of how many times the tick hook has been called. */
ulExecutionCount++;
/* Is it time to perform the check again? */
if( ulExecutionCount >= ulExecutionRate )
{
/* Reset the execution count so this function is called again in 5
seconds time. */
ulExecutionCount = 0;
/* Has an error been found in any task? */
if( xAreGenericQueueTasksStillRunning() != pdTRUE )
{
ulCheckErrors |= 0x01UL;
}
if( xAreQueuePeekTasksStillRunning() != pdTRUE )
{
ulCheckErrors |= 0x02UL;
}
if( xAreBlockingQueuesStillRunning() != pdTRUE )
{
ulCheckErrors |= 0x04UL;
}
if( xAreRecursiveMutexTasksStillRunning() != pdTRUE )
{
ulCheckErrors |= 0x200UL;
}
if( ulLastRegTest1Count == ulRegTest1Counter )
{
ulCheckErrors |= 0x1000UL;
}
if( ulLastRegTest2Count == ulRegTest2Counter )
{
ulCheckErrors |= 0x1000UL;
}
ulLastRegTest1Count = ulRegTest1Counter;
ulLastRegTest2Count = ulRegTest2Counter;
}
}
/*-----------------------------------------------------------*/
static void prvSetupHardware( void )
{
/* Disable the watchdog, STOP and WAIT modes. */
SOPT1 = 0;
/* --- Setup clock to use external 25MHz source. --- */
/* Extal and xtal pin ON. */
PTDPF1_D4 = 0x03;
PTDPF1_D5 = 0x03;
/* Switch from FEI to FBE (FLL bypassed external)
enable external clock source */
MCGC2 = MCGC2_ERCLKEN_MASK /* Activate external reference clock */
| MCGC2_EREFS_MASK /* Because crystal is being used */
| MCGC2_RANGE_MASK; /* High range */
/* Select clock mode and clear IREFs. */
MCGC1 = (0x02 << 6 ) /* CLKS = 10 -> external reference clock. */
| (0x04 << 3 ) /* RDIV = 2^4 -> 25MHz/16 = 1.5625 MHz */
| MCGC1_IRCLKEN_MASK; /* IRCLK to RTC enabled */
/* Wait for Reference and Clock status bits to update. */
while( MCGSC_IREFST | ( MCGSC_CLKST != 0x02 ) )
{
/* Nothing to do here. */
}
/* Switch from FBE to PBE (PLL bypassed internal) mode. */
MCGC3 = 0x08 /* Set PLL multi 50MHz. */
| MCGC3_PLLS_MASK; /* Select PLL. */
/* Wait for PLL status and lock bits to update. */
while( !MCGSC_PLLST | !MCGSC_LOCK )
{
/* Nothing to do here. */
}
/* Now in PBE Mode, finally switch from PBE to PEE (PLL enabled external
mode). */
MCGC1_CLKS = 0b00; /* PLL clock to system (MCGOUT) */
/* Wait for the clock status bits to update. */
while( MCGSC_CLKST != 0x03 )
{
/* Nothing to do here. */
}
/* Setup the IO for the LED outputs. */
vParTestInitialise();
}
/*-----------------------------------------------------------*/
void vApplicationStackOverflowHook( xTaskHandle pxTask, signed char *pcTaskName )
{
/* This will get called if a stack overflow is detected during the context
switch. Set configCHECK_FOR_STACK_OVERFLOWS to 2 to also check for stack
problems within nested interrupts, but only do this for debug purposes as
it will increase the context switch time. */
( void ) pxTask;
( void ) pcTaskName;
for( ;; )
{
}
}
/*-----------------------------------------------------------*/
static void vRegTest1Task( void *pvParameters )
{
/* Just to remove compiler warnings. */
( void ) pvParameters;
/* Set all the registers to known values, then check that each retains its
expected value - as described at the top of this file. If an error is
found then the loop counter will no longer be incremented allowing the check
task to recognise the error. */
asm volatile ( "reg_test_1_start: \n\t"
" moveq #1, d0 \n\t"
" moveq #2, d1 \n\t"
" moveq #3, d2 \n\t"
" moveq #4, d3 \n\t"
" moveq #5, d4 \n\t"
" moveq #6, d5 \n\t"
" moveq #7, d6 \n\t"
" moveq #8, d7 \n\t"
" move #9, a0 \n\t"
" move #10, a1 \n\t"
" move #11, a2 \n\t"
" move #12, a3 \n\t"
" move #13, a4 \n\t"
" move #15, a6 \n\t"
" \n\t"
" cmpi.l #1, d0 \n\t"
" bne reg_test_1_error \n\t"
" cmpi.l #2, d1 \n\t"
" bne reg_test_1_error \n\t"
" cmpi.l #3, d2 \n\t"
" bne reg_test_1_error \n\t"
" cmpi.l #4, d3 \n\t"
" bne reg_test_1_error \n\t"
" cmpi.l #5, d4 \n\t"
" bne reg_test_1_error \n\t"
" cmpi.l #6, d5 \n\t"
" bne reg_test_1_error \n\t"
" cmpi.l #7, d6 \n\t"
" bne reg_test_1_error \n\t"
" cmpi.l #8, d7 \n\t"
" bne reg_test_1_error \n\t"
" move a0, d0 \n\t"
" cmpi.l #9, d0 \n\t"
" bne reg_test_1_error \n\t"
" move a1, d0 \n\t"
" cmpi.l #10, d0 \n\t"
" bne reg_test_1_error \n\t"
" move a2, d0 \n\t"
" cmpi.l #11, d0 \n\t"
" bne reg_test_1_error \n\t"
" move a3, d0 \n\t"
" cmpi.l #12, d0 \n\t"
" bne reg_test_1_error \n\t"
" move a4, d0 \n\t"
" cmpi.l #13, d0 \n\t"
" bne reg_test_1_error \n\t"
" move a6, d0 \n\t"
" cmpi.l #15, d0 \n\t"
" bne reg_test_1_error \n\t"
" move ulRegTest1Counter, d0 \n\t"
" addq #1, d0 \n\t"
" move d0, ulRegTest1Counter \n\t"
" bra reg_test_1_start \n\t"
"reg_test_1_error: \n\t"
" bra reg_test_1_error \n\t"
);
}
/*-----------------------------------------------------------*/
static void vRegTest2Task( void *pvParameters )
{
/* Just to remove compiler warnings. */
( void ) pvParameters;
/* Set all the registers to known values, then check that each retains its
expected value - as described at the top of this file. If an error is
found then the loop counter will no longer be incremented allowing the check
task to recognise the error. */
asm volatile ( "reg_test_2_start: \n\t"
" moveq #10, d0 \n\t"
" moveq #20, d1 \n\t"
" moveq #30, d2 \n\t"
" moveq #40, d3 \n\t"
" moveq #50, d4 \n\t"
" moveq #60, d5 \n\t"
" moveq #70, d6 \n\t"
" moveq #80, d7 \n\t"
" move #90, a0 \n\t"
" move #100, a1 \n\t"
" move #110, a2 \n\t"
" move #120, a3 \n\t"
" move #130, a4 \n\t"
" move #150, a6 \n\t"
" \n\t"
" cmpi.l #10, d0 \n\t"
" bne reg_test_2_error \n\t"
" cmpi.l #20, d1 \n\t"
" bne reg_test_2_error \n\t"
" cmpi.l #30, d2 \n\t"
" bne reg_test_2_error \n\t"
" cmpi.l #40, d3 \n\t"
" bne reg_test_2_error \n\t"
" cmpi.l #50, d4 \n\t"
" bne reg_test_2_error \n\t"
" cmpi.l #60, d5 \n\t"
" bne reg_test_2_error \n\t"
" cmpi.l #70, d6 \n\t"
" bne reg_test_2_error \n\t"
" cmpi.l #80, d7 \n\t"
" bne reg_test_2_error \n\t"
" move a0, d0 \n\t"
" cmpi.l #90, d0 \n\t"
" bne reg_test_2_error \n\t"
" move a1, d0 \n\t"
" cmpi.l #100, d0 \n\t"
" bne reg_test_2_error \n\t"
" move a2, d0 \n\t"
" cmpi.l #110, d0 \n\t"
" bne reg_test_2_error \n\t"
" move a3, d0 \n\t"
" cmpi.l #120, d0 \n\t"
" bne reg_test_2_error \n\t"
" move a4, d0 \n\t"
" cmpi.l #130, d0 \n\t"
" bne reg_test_2_error \n\t"
" move a6, d0 \n\t"
" cmpi.l #150, d0 \n\t"
" bne reg_test_2_error \n\t"
" move ulRegTest1Counter, d0 \n\t"
" addq #1, d0 \n\t"
" move d0, ulRegTest2Counter \n\t"
" bra reg_test_2_start \n\t"
"reg_test_2_error: \n\t"
" bra reg_test_2_error \n\t"
);
}
/*-----------------------------------------------------------*/

View file

@ -0,0 +1,147 @@
/*
* File: mii.h
* Purpose:
*
* Notes:
*/
#ifndef _MII_H_
#define _MII_H_
/********************************************************************/
/* Timeout for MII communications */
#define FEC_MII_TIMEOUT 0x10000
/********************************************************************/
//Fucntion Protoypes
int FEC_Mii_Write(int, int, int);
int FEC_Mii_Read(int, int, unsigned short*);
void FEC_Mii_Init(void);
void fec_mii_reg_printf(void);
/********************************************************************/
//Register Mask and Other
//===============
/* Definition of allowed values for MDCSEL */
#define MII_MDCSEL(x) x/5000000
#define MII_WRITE 0x01
#define MII_READ 0x02
#define TCMD_START 0x01 /* Transmit buffer frame */
#define TCMD_PAUSE 0x02 /* Transmit PAUSE frame */
#define TCMD_ABORT 0x03 /* Abort transmission */
/* PHY registers symbolic names */
/* (located in MII memory map, accessible through MDIO) */
#define PHY_REG_CR 0x00 /* Control Register */
#define PHY_REG_SR 0x01 /* Status Register */
#define PHY_REG_ID1 0x02 /* PHY Identification Register 1 */
#define PHY_REG_ID2 0x03 /* PHY Identification Register 2 */
#define PHY_REG_ANAR 0x04 /* Auto-Negotiation Advertisement Register */
#define PHY_REG_ANLPAR 0x05 /* Auto-Negotiation Link Partner Ability Register */
#define PHY_REG_ER 0x06 /* Auto-Negotiation Expansion Register */
#define PHY_REG_NPTR 0x07 /* Auto-Negotiation Next Page Transfer Register */
#define PHY_REG_IR 0x10 /* Interrupt Register */
#define PHY_REG_PSR 0x11 /* Proprietary Status Register */
#define PHY_REG_PCR 0x12 /* Proprietary Control Register */
#define PHY_REG_10BTBC 0x13 /* 10Base-T Bypass Control Register */
#define PHY_REG_100BXBC 0x14 /* 100Base-X Bypass Control Register */
#define PHY_REG_ADDR 0x15 /* Test & Trim Control Register */
#define PHY_REG_DSPRC 0x17 /* DSP Reset Control */
#define PHY_REG_DSPRR1 0x18 /* 100Base-X DSP Read Registers */
#define PHY_REG_DSPRR2 0x19
#define PHY_REG_DSPRR3 0x1A
#define PHY_REG_DSPWR1 0x1B /* 100Base-X DSP Write Registers */
#define PHY_REG_DSPWR2 0x1C
#define PHY_REG_DSPWR3 0x1D
/* PHY registers structure */
/* 0 - Control Register */
#define PHY_R0_RESET 0x8000 /* Reset */
#define PHY_R0_LB 0x4000 /* Loop Back */
#define PHY_R0_DR 0x2000 /* Data Rate (100Mb/s) */
#define PHY_R0_ANE 0x1000 /* Auto-Negotiation Enable */
#define PHY_R0_PD 0x0800 /* Power Down */
#define PHY_R0_ISOLATE 0x0400 /* Isolate (MII is disconnected) */
#define PHY_R0_RAN 0x0200 /* Restart Auto-Negotiation */
#define PHY_R0_DPLX 0x0100 /* Duplex (Full duplex) */
#define PHY_R0_CT 0x0080 /* Collision Test (Enable) */
/* 1 - Status Register */
#define PHY_R1_100T4 0x8000 /* 100BASET4 Supported */
#define PHY_R1_100F 0x4000 /* 100Mb/s Full Duplex Supported */
#define PHY_R1_100H 0x2000 /* 100Mb/s Half Duplex Supported */
#define PHY_R1_10F 0x1000 /* 10Mb/s Full Duplex Supported */
#define PHY_R1_10H 0x0800 /* 10Mb/s Half Duplex Supported */
#define PHY_R1_SUP 0x0040 /* MI Preamble Supression (capable of) */
#define PHY_R1_ANC 0x0020 /* Auto Negotiation Complete */
#define PHY_R1_RF 0x0010 /* Remote Fault */
#define PHY_R1_ANA 0x0008 /* Auto-Negotiation Ability (present) */
#define PHY_R1_LS 0x0004 /* Link Status (Link is Up) */
#define PHY_R1_JD 0x0002 /* Jabber Detect (detected) */
#define PHY_R1_EC 0x0001 /* Extended Capability (regs 2 to 31 exists) */
/* 2 - PHY Identifier Register 1 */
/* 3 - PHY Identifier Register 2 */
/* read only - contains Manufacturer's info etc.
see documentation for the detailed description */
/* 4 - Auto Negotiation Advertisement Register */
#define PHY_R4_NP 0x8000 /* Next Page (capable of sending next pages) */
#define PHY_R4_RF 0x2000 /* Remote Fault */
#define PHY_R4_FC 0x0400 /* Flow Control */
#define PHY_R4_100F 0x0100 /* 100Base-TX Full Duplex Capable */
#define PHY_R4_100H 0x0080 /* 100Base-TX Half Duplex Capable */
#define PHY_R4_10F 0x0040 /* 10Base-T Full Duplex Capable */
#define PHY_R4_10H 0x0020 /* 10Base-T Half Duplex Capable */
/* bits 4 to 0 are Selector Field (IEEE Std 802.3 = 00001) */
/* 5 - Auto Negotiation Link Partner Ability Register (Base Page & Next Page) */
/* read only - please consult PHY documentation */
#define PHY_R5_FCTL 0x0400 /* 10Base-T Half Duplex Capable */
/* 16 - Interrupt Control Register */
#define PHY_R16_ACKIE 0x4000 //Acknowledge Bit Received Interrupt Enable
#define PHY_R16_PRIE 0x2000 //Page Received INT Enable
#define PHY_R16_LCIE 0x1000 //Link Changed Enable
#define PHY_R16_ANIE 0x0800 //Auto-Negotiation Changed Enable
#define PHY_R16_PDFIE 0x0400 //Parallel Detect Fault Enable
#define PHY_R16_RFIE 0x0200 //Remote Fault Interrupt Enable
#define PHY_R16_JABIE 0x0100 //Jabber Interrupt Enable
#define PHY_R16_ACKR 0x0040 //Acknowledge Bit Received Interrupt
#define PHY_R16_PGR 0x0020 //Page Received
#define PHY_R16_LKC 0x0010 //Link Changed
#define PHY_R16_ANC 0x0008 //Auto-Negotiation Changed
#define PHY_R16_PDF 0x0004 //Parallel Detect Fault
#define PHY_R16_RMTF 0x0002 //Remote Fault Interrupt
#define PHY_R16_JABI 0x0001 //Jabber Interrupt
////Proprietary Status Register
#define PHY_R17_LNK 0x4000 //
#define PHY_R17_DPM 0x2000 //Duplex Mode
#define PHY_R17_SPD 0x1000 //Speed
#define PHY_R17_ANNC 0x0400 //Auto-Negotiation Complete
#define PHY_R17_PRCVD 0x0200 //
#define PHY_R17_ANCM 0x0100 // Auto-Negotiation (A-N) Common Operating Mode
#define PHY_R17_PLR 0x0020 //
/* Bit definitions and macros for MCF_FEC_MMFR */
#define FEC_MMFR_DATA(x) (((x)&0x0000FFFF)<<0)
#define FEC_MMFR_TA(x) (((x)&0x00000003)<<16)
#define FEC_MMFR_RA(x) (((x)&0x0000001F)<<18)
#define FEC_MMFR_PA(x) (((x)&0x0000001F)<<23)
#define FEC_MMFR_OP(x) (((x)&0x00000003)<<28)
#define FEC_MMFR_ST(x) (((x)&0x00000003)<<30)
#define FEC_MMFR_ST_01 (0x40000000)
#define FEC_MMFR_OP_READ (0x20000000)
#define FEC_MMFR_OP_WRITE (0x10000000)
#define FEC_MMFR_TA_10 (0x00020000)
/********************************************************************/
#endif /* _MII_H_ */

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,312 @@
/*
* CF_Startup.c - Default init/startup/termination routines for
* Embedded Metrowerks C++
*
* Copyright © 1993-1998 Metrowerks, Inc. All Rights Reserved.
* Copyright © 2005 Freescale semiConductor Inc. All Rights Reserved.
*
*
* THEORY OF OPERATION
*
* This version of thestartup code is intended for linker relocated
* executables. The startup code will assign the stack pointer to
* __SP_INIT, assign the address of the data relative base address
* to a5, initialize the .bss/.sbss sections to zero, call any
* static C++ initializers and then call main. Upon returning from
* main it will call C++ destructors and call exit to terminate.
*/
#ifdef __cplusplus
#pragma cplusplus off
#endif
#pragma PID off
#pragma PIC off
#include "startcf.h"
#include "RuntimeConfig.h"
/* imported data */
extern unsigned long far _SP_INIT, _SDA_BASE;
extern unsigned long far _START_BSS, _END_BSS;
extern unsigned long far _START_SBSS, _END_SBSS;
extern unsigned long far __DATA_RAM, __DATA_ROM, __DATA_END;
/* imported routines */
extern void __call_static_initializers(void);
extern int main(int, char **);
extern void exit(int);
/* exported routines */
extern void _ExitProcess(void);
extern asm void _startup(void);
extern void __initialize_hardware(void);
extern void __initialize_system(void);
/*
* Dummy routine for initializing hardware. For user's custom systems, you
* can create your own routine of the same name that will perform HW
* initialization. The linker will do the right thing to ignore this
* definition and use the version in your file.
*/
#pragma overload void __initialize_hardware(void);
void __initialize_hardware(void)
{
}
/*
* Dummy routine for initializing systems. For user's custom systems,
* you can create your own routine of the same name that will perform
* initialization. The linker will do the right thing to ignore this
* definition and use the version in your file.
*/
#pragma overload void __initialize_system(void);
void __initialize_system(void)
{
}
/*
* Dummy routine for initializing C++. This routine will get overloaded by the C++ runtime.
*/
#pragma overload void __call_static_initializers(void);
void __call_static_initializers(void)
{
}
/*
* Routine to copy a single section from ROM to RAM ...
*/
static __declspec(register_abi) void __copy_rom_section(char* dst, const char* src, unsigned long size)
{
if (dst != src)
while (size--)
*dst++ = *src++;
}
/*
* Routine that copies all sections the user marked as ROM into
* their target RAM addresses ...
*
* __S_romp is automatically generated by the linker if it
* is referenced by the program. It is a table of RomInfo
* structures. The final entry in the table has all-zero
* fields.
*/
static void __copy_rom_sections_to_ram(void)
{
RomInfo *info;
/*
* Go through the entire table, copying sections from ROM to RAM.
*/
for (info = _S_romp; info->Source != 0L || info->Target != 0L || info->Size != 0; ++info)
__copy_rom_section( (char *)info->Target,(char *)info->Source, info->Size);
}
/*
* Exit handler called from the exit routine, if your OS needs
* to do something special for exit handling just replace this
* routines with what the OS needs to do ...
*/
asm void _ExitProcess(void)
{
illegal
rts
}
/*
* Routine to clear out blocks of memory should give good
* performance regardless of 68k or ColdFire part.
*/
static __declspec(register_abi) void clear_mem(char *dst, unsigned long n)
{
unsigned long i;
long *lptr;
if (n >= 32)
{
/* align start address to a 4 byte boundary */
i = (- (unsigned long) dst) & 3;
if (i)
{
n -= i;
do
*dst++ = 0;
while (--i);
}
/* use an unrolled loop to zero out 32byte blocks */
i = n >> 5;
if (i)
{
lptr = (long *)dst;
dst += i * 32;
do
{
*lptr++ = 0;
*lptr++ = 0;
*lptr++ = 0;
*lptr++ = 0;
*lptr++ = 0;
*lptr++ = 0;
*lptr++ = 0;
*lptr++ = 0;
}
while (--i);
}
i = (n & 31) >> 2;
/* handle any 4 byte blocks left */
if (i)
{
lptr = (long *)dst;
dst += i * 4;
do
*lptr++ = 0;
while (--i);
}
n &= 3;
}
/* handle any byte blocks left */
if (n)
do
*dst++ = 0;
while (--n);
}
/*
* Startup routine for embedded application ...
*/
asm void _startup(void)
{
/* disable interrupts */
move.w #0x2700,sr
/* Pre-init SP, in case memory for stack is not valid it should be setup using
MEMORY_INIT before __initialize_hardware is called
*/
lea __SP_AFTER_RESET,a7;
/* initialize memory */
MEMORY_INIT
/* initialize any hardware specific issues */
jsr __initialize_hardware
/* setup the stack pointer */
lea _SP_INIT,a7
/* setup A6 dummy stackframe */
movea.l #0,a6
link a6,#0
/* setup A5 */
lea _SDA_BASE,a5
/* zero initialize the .bss section */
lea _END_BSS, a0
lea _START_BSS, a1
suba.l a1, a0
move.l a0, d0
beq __skip_bss__
lea _START_BSS, a0
/* call clear_mem with base pointer in a0 and size in d0 */
jsr clear_mem
__skip_bss__:
/* zero initialize the .sbss section */
lea _END_SBSS, a0
lea _START_SBSS, a1
suba.l a1, a0
move.l a0, d0
beq __skip_sbss__
lea _START_SBSS, a0
/* call clear_mem with base pointer in a0 and size in d0 */
jsr clear_mem
__skip_sbss__:
/* copy all ROM sections to their RAM locations ... */
#if SUPPORT_ROM_TO_RAM
/*
* _S_romp is a null terminated array of
* typedef struct RomInfo {
* unsigned long Source;
* unsigned long Target;
* unsigned long Size;
* } RomInfo;
*
* Watch out if you're rebasing using _PICPID_DELTA
*/
lea _S_romp, a0
move.l a0, d0
beq __skip_rom_copy__
jsr __copy_rom_sections_to_ram
#else
/*
* There's a single block to copy from ROM to RAM, perform
* the copy directly without using the __S_romp structure
*/
lea __DATA_RAM, a0
lea __DATA_ROM, a1
cmpa a0,a1
beq __skip_rom_copy__
move.l #__DATA_END, d0
sub.l a0, d0
jsr __copy_rom_section
#endif
__skip_rom_copy__:
/* call C++ static initializers (__sinit__(void)) */
jsr __call_static_initializers
jsr __initialize_system
/* call main(int, char **) */
pea __argv
clr.l -(sp) /* clearing a long is ok since it's caller cleanup */
jsr main
addq.l #8, sp
unlk a6
/* now call exit(0) to terminate the application */
clr.l -(sp)
jsr exit
addq.l #4, sp
/* should never reach here but just in case */
illegal
rts
/* exit will never return */
__argv:
dc.l 0
}

View file

@ -0,0 +1,77 @@
/******************************************************************************
FILE : startcf.h
PURPOSE : startup code for ColdFire
LANGUAGE: C
Notes:
1) Default entry point is _startup.
. disable interrupts
. the SP is set to __SP_AFTER_RESET
. SP must be initialized to valid memory
in case the memory it points to is not valid using MEMORY_INIT macro
2) __initialize_hardware is called. Here you can initialize memory and some peripherics
at this point global variables are not initialized yet
3) After __initialize_hardware memory is setup; initialize SP to _SP_INIT and perform
needed initialisations for the language (clear memory, data rom copy).
4) void __initialize_system(void); is called
to allow additional hardware initialization (UART, GPIOs, etc...)
5) Jump to main
*/
/********************************************************************************/
#ifndef STARTCF_H
#define STARTCF_H
#ifdef __cplusplus
extern "C" {
#endif
#ifdef STARTCF_INCLUDE
#include STARTCF_INCLUDE
#endif
#pragma warn_any_ptr_int_conv off
#pragma warn_absolute off
extern unsigned long far __SP_INIT[];
extern unsigned long far __SP_AFTER_RESET[];
#ifndef MEMORY_INIT
/* If MEMORY_INIT is set then it performs
minimal memory initialization (to preset SP to __SP_AFTER_RESET, etc...)
*/
#define MEMORY_INIT
#endif
void _startup(void);
#ifndef SUPPORT_ROM_TO_RAM
/*
* If SUPPORT_ROM_TO_RAM is set, _S_romp is used to define the copy to be performed.
* If it is not set, there's a single block to copy, performed directly without
* using the __S_romp structure, based on __DATA_RAM, __DATA_ROM and
* __DATA_END symbols.
*
* Set to 0 for more aggressive dead stripping ...
*/
#define SUPPORT_ROM_TO_RAM 1
#endif
/* format of the ROM table info entry ... */
typedef struct RomInfo {
void *Source;
void *Target;
unsigned long Size;
} RomInfo;
/* imported data */
extern far RomInfo _S_romp[]; /* linker defined symbol */
#ifdef __cplusplus
}
#endif
#endif

View file

@ -0,0 +1,497 @@
/* FILENAME: stdlib.c
*
* Functions normally found in a standard C lib.
*
* 12/28/2005 - added memcmp and memmove
*
* Notes: These functions support ASCII only!!!
*/
//#include "m51cn128evb.h"
#include "stdlib.h"
#define TRUE 1
#define FALSE 0
#define NULL 0
/****************************************************************/
int
isspace (int ch)
{
if ((ch == ' ') || (ch == '\t')) /* \n ??? */
return TRUE;
else
return FALSE;
}
/****************************************************************/
int
isalnum (int ch)
{
/* ASCII only */
if (((ch >= '0') && (ch <= '9')) ||
((ch >= 'A') && (ch <= 'Z')) ||
((ch >= 'a') && (ch <= 'z')))
return TRUE;
else
return FALSE;
}
/****************************************************************/
int
isdigit (int ch)
{
/* ASCII only */
if ((ch >= '0') && (ch <= '9'))
return TRUE;
else
return FALSE;
}
/****************************************************************/
int
isupper (int ch)
{
/* ASCII only */
if ((ch >= 'A') && (ch <= 'Z'))
return TRUE;
else
return FALSE;
}
/****************************************************************/
int
strcasecmp (const char *s1, const char *s2)
{
char c1, c2;
int result = 0;
while (result == 0)
{
c1 = *s1++;
c2 = *s2++;
if ((c1 >= 'a') && (c1 <= 'z'))
c1 = (char)(c1 - ' ');
if ((c2 >= 'a') && (c2 <= 'z'))
c2 = (char)(c2 - ' ');
if ((result = (c1 - c2)) != 0)
break;
if ((c1 == 0) || (c2 == 0))
break;
}
return result;
}
/****************************************************************/
int
stricmp (const char *s1, const char *s2)
{
return (strcasecmp(s1, s2));
}
/****************************************************************/
int
strncasecmp (const char *s1, const char *s2, int n)
{
char c1, c2;
int k = 0;
int result = 0;
while ( k++ < n )
{
c1 = *s1++;
c2 = *s2++;
if ((c1 >= 'a') && (c1 <= 'z'))
c1 = (char)(c1 - ' ');
if ((c2 >= 'a') && (c2 <= 'z'))
c2 = (char)(c2 - ' ');
if ((result = (c1 - c2)) != 0)
break;
if ((c1 == 0) || (c2 == 0))
break;
}
return result;
}
/****************************************************************/
int
strnicmp (const char *s1, const char *s2, int n)
{
return (strncasecmp(s1, s2, n));
}
/****************************************************************/
unsigned long
strtoul (char *str, char **ptr, int base)
{
unsigned long rvalue = 0;
int neg = 0;
int c;
/* Validate parameters */
if ((str != NULL) && (base >= 0) && (base <= 36))
{
/* Skip leading white spaces */
while (isspace(*str))
{
++str;
}
/* Check for notations */
switch (str[0])
{
case '0':
if (base == 0)
{
if ((str[1] == 'x') || (str[1] == 'X'))
{
base = 16;
str += 2;
}
else
{
base = 8;
str++;
}
}
break;
case '-':
neg = 1;
str++;
break;
case '+':
str++;
break;
default:
break;
}
if (base == 0)
base = 10;
/* Valid "digits" are 0..9, A..Z, a..z */
while (isalnum(c = *str))
{
/* Convert char to num in 0..36 */
if ((c -= ('a' - 10)) < 10) /* 'a'..'z' */
{
if ((c += ('a' - 'A')) < 10) /* 'A'..'Z' */
{
c += ('A' - '0' - 10); /* '0'..'9' */
}
}
/* check c against base */
if (c >= base)
{
break;
}
if (neg)
{
rvalue = (rvalue * base) - c;
}
else
{
rvalue = (rvalue * base) + c;
}
++str;
}
}
/* Upon exit, 'str' points to the character at which valid info */
/* STOPS. No chars including and beyond 'str' are used. */
if (ptr != NULL)
*ptr = str;
return rvalue;
}
/****************************************************************/
int
atoi (const char *str)
{
char *s = (char *)str;
return ((int)strtoul(s, NULL, 10));
}
/****************************************************************/
int
strlen (const char *str)
{
char *s = (char *)str;
int len = 0;
if (s == NULL)
return 0;
while (*s++ != '\0')
++len;
return len;
}
/****************************************************************/
char *
strcat (char *dest, const char *src)
{
char *dp;
char *sp = (char *)src;
if ((dest != NULL) && (src != NULL))
{
dp = &dest[strlen(dest)];
while (*sp != '\0')
{
*dp++ = *sp++;
}
*dp = '\0';
}
return dest;
}
/****************************************************************/
char *
strncat (char *dest, const char *src, int n)
{
char *dp;
char *sp = (char *)src;
if ((dest != NULL) && (src != NULL) && (n > 0))
{
dp = &dest[strlen(dest)];
while ((*sp != '\0') && (n-- > 0))
{
*dp++ = *sp++;
}
*dp = '\0';
}
return dest;
}
/****************************************************************/
char *
strcpy (char *dest, const char *src)
{
char *dp = (char *)dest;
char *sp = (char *)src;
if ((dest != NULL) && (src != NULL))
{
while (*sp != '\0')
{
*dp++ = *sp++;
}
*dp = '\0';
}
return dest;
}
/****************************************************************/
char *
strncpy (char *dest, const char *src, int n)
{
char *dp = (char *)dest;
char *sp = (char *)src;
if ((dest != NULL) && (src != NULL) && (n > 0))
{
while ((*sp != '\0') && (n-- > 0))
{
*dp++ = *sp++;
}
*dp = '\0';
}
return dest;
}
/****************************************************************/
int
strcmp (const char *s1, const char *s2)
{
/* No checks for NULL */
char *s1p = (char *)s1;
char *s2p = (char *)s2;
while (*s2p != '\0')
{
if (*s1p != *s2p)
break;
++s1p;
++s2p;
}
return (*s1p - *s2p);
}
/****************************************************************/
int
strncmp (const char *s1, const char *s2, int n)
{
/* No checks for NULL */
char *s1p = (char *)s1;
char *s2p = (char *)s2;
if (n <= 0)
return 0;
while (*s2p != '\0')
{
if (*s1p != *s2p)
break;
if (--n == 0)
break;
++s1p;
++s2p;
}
return (*s1p - *s2p);
}
/****************************************************************/
char *
strstr(const char *s1, const char *s2)
{
char *sp = (char *)s1;
int len1 = strlen(s1);
int len2 = strlen(s2);
while (len1 >= len2)
{
if (strncmp(sp, s2, len2) == 0)
{
return (sp);
}
++sp;
--len1;
}
return (NULL);
}
/****************************************************************/
char *
strchr(const char *str, int c)
{
char *sp = (char *)str;
char ch = (char)(c & 0xff);
while (*sp != '\0')
{
if (*sp == ch)
{
return (sp);
}
++sp;
}
return (NULL);
}
/****************************************************************/
void *
memcpy (void *dest, const void *src, unsigned n)
{
unsigned char *dbp = (unsigned char *)dest;
unsigned char *sbp = (unsigned char *)src;
if ((dest != NULL) && (src != NULL) && (n > 0))
{
while (n--)
*dbp++ = *sbp++;
}
return dest;
}
/****************************************************************/
void *
memset (void *s, int c, unsigned n)
{
/* Not optimized, but very portable */
unsigned char *sp = (unsigned char *)s;
if ((s != NULL) && (n > 0))
{
while (n--)
{
*sp++ = (unsigned char)c;
}
}
return s;
}
/****************************************************************/
int
memcmp (const void *s1, const void *s2, unsigned n)
{
unsigned char *s1p, *s2p;
if (s1 && s2 && (n > 0))
{
s1p = (unsigned char *)s1;
s2p = (unsigned char *)s2;
while ((--n >= 0) && (*s1p == *s2p))
{
if (*s1p != *s2p)
return (*s1p - *s2p);
++s1p;
++s2p;
}
}
return (0);
}
/****************************************************************/
void *
memmove (void *dest, const void *src, unsigned n)
{
unsigned char *dbp = (unsigned char *)dest;
unsigned char *sbp = (unsigned char *)src;
unsigned char *dend = dbp + n;
unsigned char *send = sbp + n;
if ((dest != NULL) && (src != NULL) && (n > 0))
{
/* see if a memcpy would overwrite source buffer */
if ((sbp < dbp) && (dbp < send))
{
while (n--)
*(--dend) = *(--send);
}
else
{
while (n--)
*dbp++ = *sbp++;
}
}
return dest;
}
/****************************************************************/
char *
strrchr(const char *s, int c)
{
const char *last = NULL;
if (c == '\0')
return strchr(s, c);
while ((s = strchr(s, c)) != NULL) {
last = s;
s++;
}
return (char *) last;
}

View file

@ -0,0 +1,79 @@
/*
* File: stdlib.h
* Purpose: Function prototypes for standard library functions
*
* Notes:
*/
#ifndef _STDLIB_H
#define _STDLIB_H
/********************************************************************
* Standard library functions
********************************************************************/
int
isspace (int);
int
isalnum (int);
int
isdigit (int);
int
isupper (int);
int
strcasecmp (const char *, const char *);
int
strncasecmp (const char *, const char *, int);
unsigned long
strtoul (char *, char **, int);
int
strlen (const char *);
char *
strcat (char *, const char *);
char *
strncat (char *, const char *, int);
char *
strcpy (char *, const char *);
char *
strncpy (char *, const char *, int);
int
strcmp (const char *, const char *);
int
strncmp (const char *, const char *, int);
void *
memcpy (void *, const void *, unsigned);
void *
memset (void *, int, unsigned);
void
free (void *);
void *
malloc (unsigned);
#define RAND_MAX 32767
int
rand (void);
void
srand (int);
/********************************************************************/
#endif