mirror of
https://github.com/FreeRTOS/FreeRTOS-Kernel.git
synced 2025-08-19 09:38:32 -04:00
Give up attempting to fix workspace - delete and re-create.
This commit is contained in:
parent
2f8d10dc34
commit
5366162bcd
62 changed files with 0 additions and 12262 deletions
|
@ -1,725 +0,0 @@
|
|||
/*
|
||||
FreeRTOS.org V5.1.0 - 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.
|
||||
***************************************************************************
|
||||
*/
|
||||
|
||||
/* Kernel includes. */
|
||||
#include "FreeRTOS.h"
|
||||
#include "semphr.h"
|
||||
#include "task.h"
|
||||
|
||||
/* Hardware includes. */
|
||||
#include "fecbd.h"
|
||||
#include "mii.h"
|
||||
#include "eth_phy.h"
|
||||
#include "eth.h"
|
||||
|
||||
/* uIP includes. */
|
||||
#include "uip.h"
|
||||
#include "uip_arp.h"
|
||||
|
||||
/* Delay between polling the PHY to see if a link has been established. */
|
||||
#define fecLINK_DELAY ( 500 / portTICK_RATE_MS )
|
||||
|
||||
/* Delay to wait for an MII access. */
|
||||
#define fecMII_DELAY ( 10 / portTICK_RATE_MS )
|
||||
#define fecMAX_POLLS ( 20 )
|
||||
|
||||
/* Constants used to delay while waiting for a tx descriptor to be free. */
|
||||
#define fecMAX_WAIT_FOR_TX_BUFFER ( 200 / portTICK_RATE_MS )
|
||||
|
||||
/* We only use a single Tx descriptor which can lead to Txed packets being sent
|
||||
twice (due to a bug in the FEC silicon). However, in this case the bug is used
|
||||
to our advantage in that it means the uip-split mechanism is not required. */
|
||||
#define fecNUM_FEC_TX_BUFFERS ( 1 )
|
||||
#define fecTX_BUFFER_TO_USE ( 0 )
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
/* The semaphore used to wake the uIP task when data arrives. */
|
||||
xSemaphoreHandle xFECSemaphore = NULL, xTxSemaphore = NULL;
|
||||
|
||||
/* The buffer used by the uIP stack. In this case the pointer is used to
|
||||
point to one of the Rx buffers to effect a zero copy policy. */
|
||||
unsigned portCHAR *uip_buf;
|
||||
|
||||
/* The DMA descriptors. This is a char array to allow us to align it correctly. */
|
||||
static unsigned portCHAR xFECTxDescriptors_unaligned[ ( fecNUM_FEC_TX_BUFFERS * sizeof( FECBD ) ) + 16 ];
|
||||
static unsigned portCHAR xFECRxDescriptors_unaligned[ ( configNUM_FEC_RX_BUFFERS * sizeof( FECBD ) ) + 16 ];
|
||||
static FECBD *xFECTxDescriptors;
|
||||
static FECBD *xFECRxDescriptors;
|
||||
|
||||
/* The DMA buffers. These are char arrays to allow them to be aligned correctly. */
|
||||
static unsigned portCHAR ucFECRxBuffers[ ( configNUM_FEC_RX_BUFFERS * configFEC_BUFFER_SIZE ) + 16 ];
|
||||
static unsigned portBASE_TYPE uxNextRxBuffer = 0, uxIndexToBufferOwner = 0;
|
||||
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
/*
|
||||
* Enable all the required interrupts in the FEC and in the interrupt controller.
|
||||
*/
|
||||
static void prvEnableFECInterrupts( void );
|
||||
|
||||
/*
|
||||
* Reset the FEC if we get into an unrecoverable state.
|
||||
*/
|
||||
static void prvResetFEC( portBASE_TYPE xCalledFromISR );
|
||||
|
||||
/********************************************************************/
|
||||
|
||||
/*
|
||||
* FUNCTION ADAPTED FROM FREESCALE SUPPLIED SOURCE
|
||||
*
|
||||
* 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, iReturn;
|
||||
uint32 eimr;
|
||||
|
||||
/* Clear the MII interrupt bit */
|
||||
MCF_FEC_EIR = MCF_FEC_EIR_MII;
|
||||
|
||||
/* Mask the MII interrupt */
|
||||
eimr = MCF_FEC_EIMR;
|
||||
MCF_FEC_EIMR &= ~MCF_FEC_EIMR_MII;
|
||||
|
||||
/* Write to the MII Management Frame Register to kick-off the MII write */
|
||||
MCF_FEC_MMFR = MCF_FEC_MMFR_ST_01 | MCF_FEC_MMFR_OP_WRITE | MCF_FEC_MMFR_PA(phy_addr) | MCF_FEC_MMFR_RA(reg_addr) | MCF_FEC_MMFR_TA_10 | MCF_FEC_MMFR_DATA( data );
|
||||
|
||||
/* Poll for the MII interrupt (interrupt should be masked) */
|
||||
for( timeout = 0; timeout < fecMAX_POLLS; timeout++ )
|
||||
{
|
||||
if( MCF_FEC_EIR & MCF_FEC_EIR_MII )
|
||||
{
|
||||
break;
|
||||
}
|
||||
else
|
||||
{
|
||||
vTaskDelay( fecMII_DELAY );
|
||||
}
|
||||
}
|
||||
|
||||
if( timeout == fecMAX_POLLS )
|
||||
{
|
||||
iReturn = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
iReturn = 1;
|
||||
}
|
||||
|
||||
/* Clear the MII interrupt bit */
|
||||
MCF_FEC_EIR = MCF_FEC_EIR_MII;
|
||||
|
||||
/* Restore the EIMR */
|
||||
MCF_FEC_EIMR = eimr;
|
||||
|
||||
return iReturn;
|
||||
}
|
||||
|
||||
/********************************************************************/
|
||||
/*
|
||||
* FUNCTION ADAPTED FROM FREESCALE SUPPLIED SOURCE
|
||||
*
|
||||
* 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 portSHORT* data )
|
||||
{
|
||||
int timeout, iReturn;
|
||||
uint32 eimr;
|
||||
|
||||
/* Clear the MII interrupt bit */
|
||||
MCF_FEC_EIR = MCF_FEC_EIR_MII;
|
||||
|
||||
/* Mask the MII interrupt */
|
||||
eimr = MCF_FEC_EIMR;
|
||||
MCF_FEC_EIMR &= ~MCF_FEC_EIMR_MII;
|
||||
|
||||
/* Write to the MII Management Frame Register to kick-off the MII read */
|
||||
MCF_FEC_MMFR = MCF_FEC_MMFR_ST_01 | MCF_FEC_MMFR_OP_READ | MCF_FEC_MMFR_PA(phy_addr) | MCF_FEC_MMFR_RA(reg_addr) | MCF_FEC_MMFR_TA_10;
|
||||
|
||||
/* Poll for the MII interrupt (interrupt should be masked) */
|
||||
for( timeout = 0; timeout < fecMAX_POLLS; timeout++ )
|
||||
{
|
||||
if (MCF_FEC_EIR & MCF_FEC_EIR_MII)
|
||||
{
|
||||
break;
|
||||
}
|
||||
else
|
||||
{
|
||||
vTaskDelay( fecMII_DELAY );
|
||||
}
|
||||
}
|
||||
|
||||
if( timeout == fecMAX_POLLS )
|
||||
{
|
||||
iReturn = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
*data = (uint16)(MCF_FEC_MMFR & 0x0000FFFF);
|
||||
iReturn = 1;
|
||||
}
|
||||
|
||||
/* Clear the MII interrupt bit */
|
||||
MCF_FEC_EIR = MCF_FEC_EIR_MII;
|
||||
|
||||
/* Restore the EIMR */
|
||||
MCF_FEC_EIMR = eimr;
|
||||
|
||||
return iReturn;
|
||||
}
|
||||
|
||||
|
||||
/********************************************************************/
|
||||
/*
|
||||
* FUNCTION ADAPTED FROM FREESCALE SUPPLIED SOURCE
|
||||
*
|
||||
* 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 portCHAR fec_hash_address( const unsigned portCHAR* addr )
|
||||
{
|
||||
unsigned portLONG crc;
|
||||
unsigned portCHAR 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 portCHAR)(crc >> 26);
|
||||
}
|
||||
|
||||
/********************************************************************/
|
||||
/*
|
||||
* FUNCTION ADAPTED FROM FREESCALE SUPPLIED SOURCE
|
||||
*
|
||||
* 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 portCHAR *pa )
|
||||
{
|
||||
unsigned portCHAR crc;
|
||||
|
||||
/*
|
||||
* Set the Physical Address
|
||||
*/
|
||||
/* Set the source address for the controller */
|
||||
MCF_FEC_PALR = ( pa[ 0 ] << 24 ) | ( pa[ 1 ] << 16 ) | ( pa[ 2 ] << 8 ) | ( pa[ 3 ] << 0 );
|
||||
MCF_FEC_PAUR = ( 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 )
|
||||
{
|
||||
MCF_FEC_IAUR |= (unsigned portLONG)(1 << (crc - 32));
|
||||
}
|
||||
else
|
||||
{
|
||||
MCF_FEC_IALR |= (unsigned portLONG)(1 << crc);
|
||||
}
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
static void prvInitialiseFECBuffers( void )
|
||||
{
|
||||
unsigned portBASE_TYPE ux;
|
||||
unsigned portCHAR *pcBufPointer;
|
||||
|
||||
/* Correctly align the Tx descriptor pointer. */
|
||||
pcBufPointer = &( xFECTxDescriptors_unaligned[ 0 ] );
|
||||
while( ( ( unsigned portLONG ) pcBufPointer & 0x0fUL ) != 0 )
|
||||
{
|
||||
pcBufPointer++;
|
||||
}
|
||||
|
||||
xFECTxDescriptors = ( FECBD * ) pcBufPointer;
|
||||
|
||||
/* Likewise the Rx descriptor pointer. */
|
||||
pcBufPointer = &( xFECRxDescriptors_unaligned[ 0 ] );
|
||||
while( ( ( unsigned portLONG ) pcBufPointer & 0x0fUL ) != 0 )
|
||||
{
|
||||
pcBufPointer++;
|
||||
}
|
||||
|
||||
xFECRxDescriptors = ( FECBD * ) pcBufPointer;
|
||||
|
||||
|
||||
/* Setup the Tx buffers and descriptors. There is no separate Tx buffer
|
||||
to point to (the Rx buffers are actually used) so the data member is
|
||||
set to NULL for now. */
|
||||
for( ux = 0; ux < fecNUM_FEC_TX_BUFFERS; ux++ )
|
||||
{
|
||||
xFECTxDescriptors[ ux ].status = TX_BD_TC;
|
||||
xFECTxDescriptors[ ux ].data = NULL;
|
||||
xFECTxDescriptors[ ux ].length = 0;
|
||||
}
|
||||
|
||||
/* Setup the Rx buffers and descriptors, having first ensured correct
|
||||
alignment. */
|
||||
pcBufPointer = &( ucFECRxBuffers[ 0 ] );
|
||||
while( ( ( unsigned portLONG ) pcBufPointer & 0x0fUL ) != 0 )
|
||||
{
|
||||
pcBufPointer++;
|
||||
}
|
||||
|
||||
for( ux = 0; ux < configNUM_FEC_RX_BUFFERS; ux++ )
|
||||
{
|
||||
xFECRxDescriptors[ ux ].status = RX_BD_E;
|
||||
xFECRxDescriptors[ ux ].length = configFEC_BUFFER_SIZE;
|
||||
xFECRxDescriptors[ ux ].data = pcBufPointer;
|
||||
pcBufPointer += configFEC_BUFFER_SIZE;
|
||||
}
|
||||
|
||||
/* Set the wrap bit in the last descriptors to form a ring. */
|
||||
xFECTxDescriptors[ fecNUM_FEC_TX_BUFFERS - 1 ].status |= TX_BD_W;
|
||||
xFECRxDescriptors[ configNUM_FEC_RX_BUFFERS - 1 ].status |= RX_BD_W;
|
||||
|
||||
uxNextRxBuffer = 0;
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
void vFECInit( void )
|
||||
{
|
||||
unsigned portSHORT usData;
|
||||
struct uip_eth_addr xAddr;
|
||||
|
||||
/* The MAC address is set at the foot of FreeRTOSConfig.h. */
|
||||
const unsigned portCHAR ucMACAddress[6] =
|
||||
{
|
||||
configMAC_0, configMAC_1,configMAC_2, configMAC_3, configMAC_4, configMAC_5
|
||||
};
|
||||
|
||||
/* Create the semaphore used by the ISR to wake the uIP task. */
|
||||
vSemaphoreCreateBinary( xFECSemaphore );
|
||||
|
||||
/* Create the semaphore used to unblock any tasks that might be waiting
|
||||
for a Tx descriptor. */
|
||||
vSemaphoreCreateBinary( xTxSemaphore );
|
||||
|
||||
/* Initialise all the buffers and descriptors used by the DMA. */
|
||||
prvInitialiseFECBuffers();
|
||||
|
||||
for( usData = 0; usData < 6; usData++ )
|
||||
{
|
||||
xAddr.addr[ usData ] = ucMACAddress[ usData ];
|
||||
}
|
||||
uip_setethaddr( xAddr );
|
||||
|
||||
/* Set the Reset bit and clear the Enable bit */
|
||||
MCF_FEC_ECR = MCF_FEC_ECR_RESET;
|
||||
|
||||
/* Wait at least 8 clock cycles */
|
||||
for( usData = 0; usData < 10; usData++ )
|
||||
{
|
||||
asm( "NOP" );
|
||||
}
|
||||
|
||||
/* Set MII speed to 2.5MHz. */
|
||||
MCF_FEC_MSCR = MCF_FEC_MSCR_MII_SPEED( ( ( ( configCPU_CLOCK_HZ / 1000000 ) / 5 ) + 1 ) );
|
||||
|
||||
/* Initialize PLDPAR to enable Ethernet LEDs. */
|
||||
MCF_GPIO_PLDPAR = MCF_GPIO_PLDPAR_ACTLED_ACTLED | MCF_GPIO_PLDPAR_LINKLED_LINKLED | MCF_GPIO_PLDPAR_SPDLED_SPDLED
|
||||
| MCF_GPIO_PLDPAR_DUPLED_DUPLED | MCF_GPIO_PLDPAR_COLLED_COLLED | MCF_GPIO_PLDPAR_RXLED_RXLED
|
||||
| MCF_GPIO_PLDPAR_TXLED_TXLED;
|
||||
|
||||
/* Initialize Port TA to enable Axcel control. */
|
||||
MCF_GPIO_PTAPAR = 0x00;
|
||||
MCF_GPIO_DDRTA = 0x0F;
|
||||
MCF_GPIO_PORTTA = 0x04;
|
||||
|
||||
/* Set phy address to zero. */
|
||||
MCF_EPHY_EPHYCTL1 = MCF_EPHY_EPHYCTL1_PHYADD( 0 );
|
||||
|
||||
/* Enable EPHY module with PHY clocks disabled. Do not turn on PHY clocks
|
||||
until both FEC and EPHY are completely setup (see Below). */
|
||||
MCF_EPHY_EPHYCTL0 = (uint8)(MCF_EPHY_EPHYCTL0_DIS100 | MCF_EPHY_EPHYCTL0_DIS10);
|
||||
|
||||
/* Enable auto_neg at start-up */
|
||||
MCF_EPHY_EPHYCTL0 = (uint8)(MCF_EPHY_EPHYCTL0 & (MCF_EPHY_EPHYCTL0_ANDIS));
|
||||
|
||||
/* Enable EPHY module. */
|
||||
MCF_EPHY_EPHYCTL0 = (uint8)(MCF_EPHY_EPHYCTL0_EPHYEN | MCF_EPHY_EPHYCTL0);
|
||||
|
||||
/* Let PHY PLLs be determined by PHY. */
|
||||
MCF_EPHY_EPHYCTL0 = (uint8)(MCF_EPHY_EPHYCTL0 & ~(MCF_EPHY_EPHYCTL0_DIS100 | MCF_EPHY_EPHYCTL0_DIS10));
|
||||
|
||||
/* Settle. */
|
||||
vTaskDelay( fecLINK_DELAY );
|
||||
|
||||
/* Can we talk to the PHY? */
|
||||
do
|
||||
{
|
||||
vTaskDelay( fecLINK_DELAY );
|
||||
usData = 0;
|
||||
fec_mii_read( configPHY_ADDRESS, PHY_PHYIDR1, &usData );
|
||||
|
||||
} while( usData == 0xffff );
|
||||
|
||||
do
|
||||
{
|
||||
/* 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 ) );
|
||||
|
||||
} while( 0 ); //while( !( usData & PHY_BMSR_LINK ) );
|
||||
|
||||
/* When we get here we have a link - find out what has been negotiated. */
|
||||
fec_mii_read( configPHY_ADDRESS, PHY_ANLPAR, &usData );
|
||||
|
||||
if( ( usData & PHY_ANLPAR_100BTX_FDX ) || ( usData & PHY_ANLPAR_100BTX ) )
|
||||
{
|
||||
/* Speed is 100. */
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Speed is 10. */
|
||||
}
|
||||
|
||||
if( ( usData & PHY_ANLPAR_100BTX_FDX ) || ( usData & PHY_ANLPAR_10BTX_FDX ) )
|
||||
{
|
||||
MCF_FEC_RCR &= (unsigned portLONG)~MCF_FEC_RCR_DRT;
|
||||
MCF_FEC_TCR |= MCF_FEC_TCR_FDEN;
|
||||
}
|
||||
else
|
||||
{
|
||||
MCF_FEC_RCR |= MCF_FEC_RCR_DRT;
|
||||
MCF_FEC_TCR &= (unsigned portLONG)~MCF_FEC_TCR_FDEN;
|
||||
}
|
||||
|
||||
/* Clear the Individual and Group Address Hash registers */
|
||||
MCF_FEC_IALR = 0;
|
||||
MCF_FEC_IAUR = 0;
|
||||
MCF_FEC_GALR = 0;
|
||||
MCF_FEC_GAUR = 0;
|
||||
|
||||
/* Set the Physical Address for the selected FEC */
|
||||
fec_set_address( ucMACAddress );
|
||||
|
||||
/* Set Rx Buffer Size */
|
||||
MCF_FEC_EMRBR = (unsigned portSHORT)configFEC_BUFFER_SIZE;
|
||||
|
||||
/* Point to the start of the circular Rx buffer descriptor queue */
|
||||
MCF_FEC_ERDSR = ( volatile unsigned portLONG ) &( xFECRxDescriptors[ 0 ] );
|
||||
|
||||
/* Point to the start of the circular Tx buffer descriptor queue */
|
||||
MCF_FEC_ETSDR = ( volatile unsigned portLONG ) &( xFECTxDescriptors[ 0 ] );
|
||||
|
||||
/* Mask all FEC interrupts */
|
||||
MCF_FEC_EIMR = ( unsigned portLONG ) -1;
|
||||
|
||||
/* Clear all FEC interrupt events */
|
||||
MCF_FEC_EIR = ( unsigned portLONG ) -1;
|
||||
|
||||
/* Initialize the Receive Control Register */
|
||||
MCF_FEC_RCR = MCF_FEC_RCR_MAX_FL(ETH_MAX_FRM) | MCF_FEC_RCR_FCE;
|
||||
|
||||
MCF_FEC_RCR |= MCF_FEC_RCR_MII_MODE;
|
||||
|
||||
#if( configUSE_PROMISCUOUS_MODE == 1 )
|
||||
{
|
||||
MCF_FEC_RCR |= MCF_FEC_RCR_PROM;
|
||||
}
|
||||
#endif
|
||||
|
||||
prvEnableFECInterrupts();
|
||||
|
||||
/* Finally... enable. */
|
||||
MCF_FEC_ECR = MCF_FEC_ECR_ETHER_EN;
|
||||
MCF_FEC_RDAR = MCF_FEC_RDAR_R_DES_ACTIVE;
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
static void prvEnableFECInterrupts( void )
|
||||
{
|
||||
const unsigned portBASE_TYPE uxFirstFECVector = 23, uxLastFECVector = 35;
|
||||
unsigned portBASE_TYPE ux;
|
||||
|
||||
#if configFEC_INTERRUPT_PRIORITY > configMAX_SYSCALL_INTERRUPT_PRIORITY
|
||||
#error configFEC_INTERRUPT_PRIORITY must be less than or equal to configMAX_SYSCALL_INTERRUPT_PRIORITY
|
||||
#endif
|
||||
|
||||
/* Set the priority of each of the FEC interrupts. */
|
||||
for( ux = uxFirstFECVector; ux <= uxLastFECVector; ux++ )
|
||||
{
|
||||
MCF_INTC0_ICR( ux ) = MCF_INTC_ICR_IL( configFEC_INTERRUPT_PRIORITY );
|
||||
}
|
||||
|
||||
/* Enable the FEC interrupts in the mask register */
|
||||
MCF_INTC0_IMRH &= ~( MCF_INTC_IMRH_INT_MASK33 | MCF_INTC_IMRH_INT_MASK34 | MCF_INTC_IMRH_INT_MASK35 );
|
||||
MCF_INTC0_IMRL &= ~( MCF_INTC_IMRL_INT_MASK25 | MCF_INTC_IMRL_INT_MASK26 | MCF_INTC_IMRL_INT_MASK27
|
||||
| MCF_INTC_IMRL_INT_MASK28 | MCF_INTC_IMRL_INT_MASK29 | MCF_INTC_IMRL_INT_MASK30
|
||||
| MCF_INTC_IMRL_INT_MASK31 | MCF_INTC_IMRL_INT_MASK23 | MCF_INTC_IMRL_INT_MASK24
|
||||
| MCF_INTC_IMRL_MASKALL );
|
||||
|
||||
/* Clear any pending FEC interrupt events */
|
||||
MCF_FEC_EIR = MCF_FEC_EIR_CLEAR_ALL;
|
||||
|
||||
/* Unmask all FEC interrupts */
|
||||
MCF_FEC_EIMR = MCF_FEC_EIMR_UNMASK_ALL;
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
static void prvResetFEC( portBASE_TYPE xCalledFromISR )
|
||||
{
|
||||
portBASE_TYPE x;
|
||||
|
||||
/* A critical section is used unless this function is being called from
|
||||
an ISR. */
|
||||
if( xCalledFromISR == pdFALSE )
|
||||
{
|
||||
taskENTER_CRITICAL();
|
||||
}
|
||||
|
||||
{
|
||||
/* Reset all buffers and descriptors. */
|
||||
prvInitialiseFECBuffers();
|
||||
|
||||
/* Set the Reset bit and clear the Enable bit */
|
||||
MCF_FEC_ECR = MCF_FEC_ECR_RESET;
|
||||
|
||||
/* Wait at least 8 clock cycles */
|
||||
for( x = 0; x < 10; x++ )
|
||||
{
|
||||
asm( "NOP" );
|
||||
}
|
||||
|
||||
/* Re-enable. */
|
||||
MCF_FEC_ECR = MCF_FEC_ECR_ETHER_EN;
|
||||
MCF_FEC_RDAR = MCF_FEC_RDAR_R_DES_ACTIVE;
|
||||
}
|
||||
|
||||
if( xCalledFromISR == pdFALSE )
|
||||
{
|
||||
taskEXIT_CRITICAL();
|
||||
}
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
unsigned short usFECGetRxedData( void )
|
||||
{
|
||||
unsigned portSHORT usLen;
|
||||
|
||||
/* Obtain the size of the packet and put it into the "len" variable. */
|
||||
usLen = xFECRxDescriptors[ uxNextRxBuffer ].length;
|
||||
|
||||
if( ( usLen != 0 ) && ( ( xFECRxDescriptors[ uxNextRxBuffer ].status & RX_BD_E ) == 0 ) )
|
||||
{
|
||||
uip_buf = xFECRxDescriptors[ uxNextRxBuffer ].data;
|
||||
}
|
||||
else
|
||||
{
|
||||
usLen = 0;
|
||||
}
|
||||
|
||||
return usLen;
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
void vFECRxProcessingCompleted( void )
|
||||
{
|
||||
/* Free the descriptor as the buffer it points to is no longer in use. */
|
||||
xFECRxDescriptors[ uxNextRxBuffer ].status |= RX_BD_E;
|
||||
MCF_FEC_RDAR = MCF_FEC_RDAR_R_DES_ACTIVE;
|
||||
uxNextRxBuffer++;
|
||||
if( uxNextRxBuffer >= configNUM_FEC_RX_BUFFERS )
|
||||
{
|
||||
uxNextRxBuffer = 0;
|
||||
}
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
void vFECSendData( void )
|
||||
{
|
||||
/* Ensure no Tx frames are outstanding. */
|
||||
if( xSemaphoreTake( xTxSemaphore, fecMAX_WAIT_FOR_TX_BUFFER ) == pdPASS )
|
||||
{
|
||||
/* Get a DMA buffer into which we can write the data to send. */
|
||||
if( xFECTxDescriptors[ fecTX_BUFFER_TO_USE ].status & TX_BD_R )
|
||||
{
|
||||
/*** ERROR didn't expect this. Sledge hammer error handling. ***/
|
||||
prvResetFEC( pdFALSE );
|
||||
|
||||
/* Make sure we leave the semaphore in the expected state as nothing
|
||||
is being transmitted this will not happen in the Tx ISR. */
|
||||
xSemaphoreGive( xTxSemaphore );
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Setup the buffer descriptor for transmission. The data being
|
||||
sent is actually stored in one of the Rx descriptor buffers,
|
||||
pointed to by uip_buf. */
|
||||
xFECTxDescriptors[ fecTX_BUFFER_TO_USE ].length = uip_len;
|
||||
xFECTxDescriptors[ fecTX_BUFFER_TO_USE ].status |= ( TX_BD_R | TX_BD_L );
|
||||
xFECTxDescriptors[ fecTX_BUFFER_TO_USE ].data = uip_buf;
|
||||
|
||||
/* Remember which Rx descriptor owns the buffer we are sending. */
|
||||
uxIndexToBufferOwner = uxNextRxBuffer;
|
||||
|
||||
/* We have finished with this Rx descriptor now. */
|
||||
uxNextRxBuffer++;
|
||||
if( uxNextRxBuffer >= configNUM_FEC_RX_BUFFERS )
|
||||
{
|
||||
uxNextRxBuffer = 0;
|
||||
}
|
||||
|
||||
/* Continue the Tx DMA (in case it was waiting for a new TxBD) */
|
||||
MCF_FEC_TDAR = MCF_FEC_TDAR_X_DES_ACTIVE;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Gave up waiting. Free the buffer back to the DMA. */
|
||||
vFECRxProcessingCompleted();
|
||||
}
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
void vFEC_ISR( void )
|
||||
{
|
||||
unsigned portLONG ulEvent;
|
||||
portBASE_TYPE xHighPriorityTaskWoken = pdFALSE;
|
||||
|
||||
/* This handler is called in response to any of the many separate FEC
|
||||
interrupt. */
|
||||
|
||||
/* Find the cause of the interrupt, then clear the interrupt. */
|
||||
ulEvent = MCF_FEC_EIR & MCF_FEC_EIMR;
|
||||
MCF_FEC_EIR = ulEvent;
|
||||
|
||||
if( ( ulEvent & MCF_FEC_EIR_RXB ) || ( ulEvent & MCF_FEC_EIR_RXF ) )
|
||||
{
|
||||
/* A packet has been received. Wake the handler task. */
|
||||
xSemaphoreGiveFromISR( xFECSemaphore, &xHighPriorityTaskWoken );
|
||||
}
|
||||
|
||||
if( ulEvent & ( MCF_FEC_EIR_UN | MCF_FEC_EIR_RL | MCF_FEC_EIR_LC | MCF_FEC_EIR_EBERR | MCF_FEC_EIR_BABT | MCF_FEC_EIR_BABR | MCF_FEC_EIR_HBERR ) )
|
||||
{
|
||||
/* Sledge hammer error handling. */
|
||||
prvResetFEC( pdTRUE );
|
||||
}
|
||||
|
||||
if( ( ulEvent & MCF_FEC_EIR_TXF ) || ( ulEvent & MCF_FEC_EIR_TXB ) )
|
||||
{
|
||||
/* The buffer being sent is pointed to by an Rx descriptor, now the
|
||||
buffer has been sent we can mark the Rx descriptor as free again. */
|
||||
xFECRxDescriptors[ uxIndexToBufferOwner ].status |= RX_BD_E;
|
||||
MCF_FEC_RDAR = MCF_FEC_RDAR_R_DES_ACTIVE;
|
||||
xSemaphoreGiveFromISR( xTxSemaphore, &xHighPriorityTaskWoken );
|
||||
}
|
||||
|
||||
portEND_SWITCHING_ISR( xHighPriorityTaskWoken );
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
/* Install the many different interrupt vectors, all of which call the same
|
||||
handler function. */
|
||||
void __attribute__ ((interrupt)) __cs3_isr_interrupt_87( void ) { vFEC_ISR(); }
|
||||
void __attribute__ ((interrupt)) __cs3_isr_interrupt_88( void ) { vFEC_ISR(); }
|
||||
void __attribute__ ((interrupt)) __cs3_isr_interrupt_89( void ) { vFEC_ISR(); }
|
||||
void __attribute__ ((interrupt)) __cs3_isr_interrupt_90( void ) { vFEC_ISR(); }
|
||||
void __attribute__ ((interrupt)) __cs3_isr_interrupt_91( void ) { vFEC_ISR(); }
|
||||
void __attribute__ ((interrupt)) __cs3_isr_interrupt_92( void ) { vFEC_ISR(); }
|
||||
void __attribute__ ((interrupt)) __cs3_isr_interrupt_93( void ) { vFEC_ISR(); }
|
||||
void __attribute__ ((interrupt)) __cs3_isr_interrupt_94( void ) { vFEC_ISR(); }
|
||||
void __attribute__ ((interrupt)) __cs3_isr_interrupt_95( void ) { vFEC_ISR(); }
|
||||
void __attribute__ ((interrupt)) __cs3_isr_interrupt_96( void ) { vFEC_ISR(); }
|
||||
void __attribute__ ((interrupt)) __cs3_isr_interrupt_97( void ) { vFEC_ISR(); }
|
||||
void __attribute__ ((interrupt)) __cs3_isr_interrupt_98( void ) { vFEC_ISR(); }
|
||||
void __attribute__ ((interrupt)) __cs3_isr_interrupt_99( void ) { vFEC_ISR(); }
|
||||
|
||||
|
|
@ -1,80 +0,0 @@
|
|||
/*
|
||||
* File: fec.h
|
||||
* Purpose: Driver for the Fast Ethernet Controller (FEC)
|
||||
*
|
||||
* Notes:
|
||||
*/
|
||||
|
||||
#ifndef _FEC_H_
|
||||
#define _FEC_H_
|
||||
|
||||
#include "eth.h"
|
||||
#include "fecbd.h"
|
||||
#include "mii.h"
|
||||
#include "eth_phy.h"
|
||||
|
||||
/********************************************************************/
|
||||
|
||||
/* External Interface Modes */
|
||||
#define FEC_MODE_7WIRE 0 /* Old 7-wire (AMD) mode */
|
||||
#define FEC_MODE_MII 1 /* Media Independent Interface */
|
||||
#define FEC_MODE_RMII 2 /* Reduced MII */
|
||||
#define FEC_MODE_LOOPBACK 3 /* Internal Loopback */
|
||||
|
||||
#define INTC_LVL_FEC 3
|
||||
/*
|
||||
* FEC Configuration Parameters
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8 ch; /* FEC channel */
|
||||
uint8 mode; /* Transceiver mode */
|
||||
MII_SPEED speed; /* Ethernet Speed */
|
||||
MII_DUPLEX duplex; /* Ethernet Duplex */
|
||||
uint8 prom; /* Promiscuous Mode? */
|
||||
uint8 mac[6]; /* Ethernet Address */
|
||||
uint8 phyaddr; /* PHY address */
|
||||
uint8 initphy; /* Init PHY? */
|
||||
int nrxbd; /* Number of RxBDs */
|
||||
int ntxbd; /* Number of TxBDs */
|
||||
} FEC_CONFIG;
|
||||
#define YES 1
|
||||
#define NO 0
|
||||
/*
|
||||
* FEC Event Log
|
||||
*/
|
||||
typedef struct {
|
||||
int errors; /* total count of errors */
|
||||
int hberr; /* heartbeat error */
|
||||
int babr; /* babbling receiver */
|
||||
int babt; /* babbling transmitter */
|
||||
int gra; /* graceful stop complete */
|
||||
int txf; /* transmit frame */
|
||||
int txb; /* transmit buffer */
|
||||
int rxf; /* receive frame */
|
||||
int rxb; /* received buffer */
|
||||
int mii; /* MII */
|
||||
int eberr; /* FEC/DMA fatal bus error */
|
||||
int lc; /* late collision */
|
||||
int rl; /* collision retry limit */
|
||||
int un; /* Tx FIFO underflow */
|
||||
int rfsw_inv; /* Invalid bit in RFSW */
|
||||
int rfsw_l; /* RFSW Last in Frame */
|
||||
int rfsw_m; /* RFSW Miss */
|
||||
int rfsw_bc; /* RFSW Broadcast */
|
||||
int rfsw_mc; /* RFSW Multicast */
|
||||
int rfsw_lg; /* RFSW Length Violation */
|
||||
int rfsw_no; /* RFSW Non-octet */
|
||||
int rfsw_cr; /* RFSW Bad CRC */
|
||||
int rfsw_ov; /* RFSW Overflow */
|
||||
int rfsw_tr; /* RFSW Truncated */
|
||||
} FEC_EVENT_LOG;
|
||||
|
||||
void vFECInit( void );
|
||||
unsigned short usFECGetRxedData( void );
|
||||
void vFECSendData( void );
|
||||
void vFECRxProcessingCompleted( void );
|
||||
|
||||
/********************************************************************/
|
||||
|
||||
#endif /* _FEC_H_ */
|
|
@ -1,55 +0,0 @@
|
|||
/*!
|
||||
* \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 uint8 ETH_ADDR[ETH_ADDR_LEN];
|
||||
|
||||
/* 16-bit Ethernet Frame Type, ie. Protocol */
|
||||
typedef uint16 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;
|
||||
uint8* data;
|
||||
} ETH_FRAME;
|
||||
|
||||
/*******************************************************************/
|
||||
|
||||
#endif /* _ETH_H */
|
|
@ -1,87 +0,0 @@
|
|||
/*!
|
||||
* \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
|
||||
|
||||
/*******************************************************************/
|
||||
|
||||
int
|
||||
eth_phy_autoneg(int phy_addr, MII_SPEED speed, MII_DUPLEX duplex);
|
||||
|
||||
int
|
||||
eth_phy_manual(int phy_addr, MII_SPEED speed, MII_DUPLEX duplex, int loop);
|
||||
|
||||
int
|
||||
eth_phy_get_speed(int, int*);
|
||||
|
||||
int
|
||||
eth_phy_get_duplex(int, int*);
|
||||
|
||||
int
|
||||
eth_phy_reg_dump(int);
|
||||
|
||||
/*******************************************************************/
|
||||
|
||||
/* 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 */
|
|
@ -1,100 +0,0 @@
|
|||
/*
|
||||
* 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
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint16 status; /* control and status */
|
||||
uint16 length; /* transfer length */
|
||||
uint8 *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 );
|
||||
uint32 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_ */
|
|
@ -1,102 +0,0 @@
|
|||
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, };
|
|
@ -1,34 +0,0 @@
|
|||
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];
|
|
@ -1,303 +0,0 @@
|
|||
/**
|
||||
* \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 "FreeRTOS.h"
|
||||
#include "partest.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))
|
||||
{
|
||||
PSOCK_BEGIN(&s->sout);
|
||||
( void ) ptr;
|
||||
PSOCK_END(&s->sout);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
httpd_cgifunction
|
||||
httpd_cgi(char *name)
|
||||
{
|
||||
const struct httpd_cgi_call **f;
|
||||
|
||||
/* Find the matching name in the table, return the function. */
|
||||
for(f = calls; *f != NULL; ++f) {
|
||||
if(strncmp((*f)->name, name, strlen((*f)->name)) == 0) {
|
||||
return (*f)->function;
|
||||
}
|
||||
}
|
||||
return nullfunction;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static unsigned short
|
||||
generate_file_stats(void *arg)
|
||||
{
|
||||
char *f = (char *)arg;
|
||||
return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE, "%5u", httpd_fs_count(f));
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static
|
||||
PT_THREAD(file_stats(struct httpd_state *s, char *ptr))
|
||||
{
|
||||
PSOCK_BEGIN(&s->sout);
|
||||
|
||||
PSOCK_GENERATOR_SEND(&s->sout, generate_file_stats, strchr(ptr, ' ') + 1);
|
||||
|
||||
PSOCK_END(&s->sout);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static const char closed[] = /* "CLOSED",*/
|
||||
{0x43, 0x4c, 0x4f, 0x53, 0x45, 0x44, 0};
|
||||
static const char syn_rcvd[] = /* "SYN-RCVD",*/
|
||||
{0x53, 0x59, 0x4e, 0x2d, 0x52, 0x43, 0x56,
|
||||
0x44, 0};
|
||||
static const char syn_sent[] = /* "SYN-SENT",*/
|
||||
{0x53, 0x59, 0x4e, 0x2d, 0x53, 0x45, 0x4e,
|
||||
0x54, 0};
|
||||
static const char established[] = /* "ESTABLISHED",*/
|
||||
{0x45, 0x53, 0x54, 0x41, 0x42, 0x4c, 0x49, 0x53, 0x48,
|
||||
0x45, 0x44, 0};
|
||||
static const char fin_wait_1[] = /* "FIN-WAIT-1",*/
|
||||
{0x46, 0x49, 0x4e, 0x2d, 0x57, 0x41, 0x49,
|
||||
0x54, 0x2d, 0x31, 0};
|
||||
static const char fin_wait_2[] = /* "FIN-WAIT-2",*/
|
||||
{0x46, 0x49, 0x4e, 0x2d, 0x57, 0x41, 0x49,
|
||||
0x54, 0x2d, 0x32, 0};
|
||||
static const char closing[] = /* "CLOSING",*/
|
||||
{0x43, 0x4c, 0x4f, 0x53, 0x49,
|
||||
0x4e, 0x47, 0};
|
||||
static const char time_wait[] = /* "TIME-WAIT,"*/
|
||||
{0x54, 0x49, 0x4d, 0x45, 0x2d, 0x57, 0x41,
|
||||
0x49, 0x54, 0};
|
||||
static const char last_ack[] = /* "LAST-ACK"*/
|
||||
{0x4c, 0x41, 0x53, 0x54, 0x2d, 0x41, 0x43,
|
||||
0x4b, 0};
|
||||
|
||||
static const char *states[] = {
|
||||
closed,
|
||||
syn_rcvd,
|
||||
syn_sent,
|
||||
established,
|
||||
fin_wait_1,
|
||||
fin_wait_2,
|
||||
closing,
|
||||
time_wait,
|
||||
last_ack};
|
||||
|
||||
|
||||
static unsigned short
|
||||
generate_tcp_stats(void *arg)
|
||||
{
|
||||
struct uip_conn *conn;
|
||||
struct httpd_state *s = (struct httpd_state *)arg;
|
||||
|
||||
conn = &uip_conns[s->count];
|
||||
return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE,
|
||||
"<tr><td>%d</td><td>%u.%u.%u.%u:%u</td><td>%s</td><td>%u</td><td>%u</td><td>%c %c</td></tr>\r\n",
|
||||
htons(conn->lport),
|
||||
htons(conn->ripaddr[0]) >> 8,
|
||||
htons(conn->ripaddr[0]) & 0xff,
|
||||
htons(conn->ripaddr[1]) >> 8,
|
||||
htons(conn->ripaddr[1]) & 0xff,
|
||||
htons(conn->rport),
|
||||
states[conn->tcpstateflags & UIP_TS_MASK],
|
||||
conn->nrtx,
|
||||
conn->timer,
|
||||
(uip_outstanding(conn))? '*':' ',
|
||||
(uip_stopped(conn))? '!':' ');
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static
|
||||
PT_THREAD(tcp_stats(struct httpd_state *s, char *ptr))
|
||||
{
|
||||
|
||||
PSOCK_BEGIN(&s->sout);
|
||||
( void ) ptr;
|
||||
for(s->count = 0; s->count < UIP_CONNS; ++s->count) {
|
||||
if((uip_conns[s->count].tcpstateflags & UIP_TS_MASK) != UIP_CLOSED) {
|
||||
PSOCK_GENERATOR_SEND(&s->sout, generate_tcp_stats, s);
|
||||
}
|
||||
}
|
||||
|
||||
PSOCK_END(&s->sout);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static unsigned short
|
||||
generate_net_stats(void *arg)
|
||||
{
|
||||
struct httpd_state *s = (struct httpd_state *)arg;
|
||||
return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE,
|
||||
"%5u\n", ((uip_stats_t *)&uip_stat)[s->count]);
|
||||
}
|
||||
|
||||
static
|
||||
PT_THREAD(net_stats(struct httpd_state *s, char *ptr))
|
||||
{
|
||||
PSOCK_BEGIN(&s->sout);
|
||||
( void ) ptr;
|
||||
#if UIP_STATISTICS
|
||||
|
||||
for(s->count = 0; s->count < sizeof(uip_stat) / sizeof(uip_stats_t);
|
||||
++s->count) {
|
||||
PSOCK_GENERATOR_SEND(&s->sout, generate_net_stats, s);
|
||||
}
|
||||
|
||||
#endif /* UIP_STATISTICS */
|
||||
|
||||
PSOCK_END(&s->sout);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
|
||||
extern void vTaskList( signed char *pcWriteBuffer );
|
||||
extern unsigned long ulGetErrorCode( void );
|
||||
|
||||
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, Error code = %d (0 = no errors)", (int)lRefreshCount, (int)ulGetErrorCode() );
|
||||
vTaskList( uip_appdata );
|
||||
strcat( uip_appdata, cCountBuf );
|
||||
|
||||
return strlen( uip_appdata );
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
|
||||
|
||||
static
|
||||
PT_THREAD(rtos_stats(struct httpd_state *s, char *ptr))
|
||||
{
|
||||
PSOCK_BEGIN(&s->sout);
|
||||
( void ) ptr;
|
||||
PSOCK_GENERATOR_SEND(&s->sout, generate_rtos_stats, NULL);
|
||||
PSOCK_END(&s->sout);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
|
||||
char *pcStatus;
|
||||
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=\"LED0\" value=\"1\" %s>LED",
|
||||
pcStatus );
|
||||
|
||||
return strlen( uip_appdata );
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
|
||||
static PT_THREAD(led_io(struct httpd_state *s, char *ptr))
|
||||
{
|
||||
PSOCK_BEGIN(&s->sout);
|
||||
( void ) ptr;
|
||||
PSOCK_GENERATOR_SEND(&s->sout, generate_io_state, NULL);
|
||||
PSOCK_END(&s->sout);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
|
||||
void vApplicationProcessFormInput( char *pcInputString )
|
||||
{
|
||||
char *c = pcInputString;
|
||||
|
||||
/* Process the form input sent by the IO page of the served HTML.
|
||||
This just contains an instruction to either turn on or off the LED. */
|
||||
while( ( *c != '?' ) && ( *c != 0x00 ) )
|
||||
{
|
||||
c++;
|
||||
}
|
||||
|
||||
if( *c == '?' )
|
||||
{
|
||||
c++;
|
||||
if( strcmp( c, "LED0=1" ) == 0 )
|
||||
{
|
||||
vParTestSetLED( 3, 1 );
|
||||
}
|
||||
else
|
||||
{
|
||||
vParTestSetLED( 3, 0 );
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/** @} */
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
@ -1,84 +0,0 @@
|
|||
/**
|
||||
* \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__ */
|
||||
|
||||
/** @} */
|
|
@ -1,132 +0,0 @@
|
|||
/*
|
||||
* 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 */
|
||||
/*-----------------------------------------------------------------------------------*/
|
|
@ -1,57 +0,0 @@
|
|||
/*
|
||||
* 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__ */
|
|
@ -1,8 +0,0 @@
|
|||
<html>
|
||||
<body bgcolor="white">
|
||||
<center>
|
||||
<h1>404 - file not found</h1>
|
||||
<h3>Go <a href="/">here</a> instead.</h3>
|
||||
</center>
|
||||
</body>
|
||||
</html>
|
|
@ -1,13 +0,0 @@
|
|||
<!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("location.href='index.shtml'",100)"bgcolor="#CCCCff">
|
||||
<font face="arial">
|
||||
Loading index.shtml. Click <a href="index.shtml">here</a> if not automatically redirected.
|
||||
</font>
|
||||
</font>
|
||||
</body>
|
||||
</html>
|
||||
|
|
@ -1,20 +0,0 @@
|
|||
<!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("location.href='index.shtml'",2000)"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> <b>|</b> <a href="logo.jpg">30K JPG</a>
|
||||
<br><p>
|
||||
<hr>
|
||||
<br><p>
|
||||
<h2>Task statistics</h2>
|
||||
Page will refresh every 2 seconds.<p>
|
||||
<font face="courier"><pre>Task State Priority Stack #<br>************************************************<br>
|
||||
%! rtos-stats
|
||||
</pre></font>
|
||||
</font>
|
||||
</body>
|
||||
</html>
|
||||
|
|
@ -1,28 +0,0 @@
|
|||
<!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> <b>|</b> <a href="logo.jpg">30K JPG</a>
|
||||
<br><p>
|
||||
<hr>
|
||||
<b>LED IO</b><br>
|
||||
|
||||
<p>
|
||||
|
||||
Use the check box to turn on or off the LED, then click "Update IO".
|
||||
|
||||
|
||||
<p>
|
||||
<form name="aForm" action="/io.shtml" method="get">
|
||||
%! led-io
|
||||
<p>
|
||||
<input type="submit" value="Update IO">
|
||||
</form>
|
||||
<br><p>
|
||||
</font>
|
||||
</body>
|
||||
</html>
|
||||
|
Binary file not shown.
Before Width: | Height: | Size: 29 KiB |
|
@ -1,41 +0,0 @@
|
|||
<!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> <b>|</b> <a href="logo.jpg">30K JPG</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>
|
|
@ -1,21 +0,0 @@
|
|||
<!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> <b>|</b> <a href="logo.jpg">30K JPG</a>
|
||||
<br><p>
|
||||
<hr>
|
||||
<br>
|
||||
<h2>Network connections</h2>
|
||||
<p>
|
||||
<table>
|
||||
<tr><th>Local</th><th>Remote</th><th>State</th><th>Retransmissions</th><th>Timer</th><th>Flags</th></tr>
|
||||
%! tcp-connections
|
||||
</pre></font>
|
||||
</font>
|
||||
</body>
|
||||
</html>
|
||||
|
File diff suppressed because it is too large
Load diff
|
@ -1,64 +0,0 @@
|
|||
/*
|
||||
* 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 unsigned char *name;
|
||||
const unsigned 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__ */
|
|
@ -1,346 +0,0 @@
|
|||
/**
|
||||
* \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));
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** @} */
|
|
@ -1,62 +0,0 @@
|
|||
/*
|
||||
* 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__ */
|
|
@ -1,78 +0,0 @@
|
|||
#!/usr/bin/perl
|
||||
|
||||
open(OUTPUT, "> httpd-fsdata.c");
|
||||
|
||||
chdir("httpd-fs");
|
||||
|
||||
opendir(DIR, ".");
|
||||
@files = grep { !/^\./ && !/(CVS|~)/ } readdir(DIR);
|
||||
closedir(DIR);
|
||||
|
||||
foreach $file (@files) {
|
||||
|
||||
if(-d $file && $file !~ /^\./) {
|
||||
print "Processing directory $file\n";
|
||||
opendir(DIR, $file);
|
||||
@newfiles = grep { !/^\./ && !/(CVS|~)/ } readdir(DIR);
|
||||
closedir(DIR);
|
||||
printf "Adding files @newfiles\n";
|
||||
@files = (@files, map { $_ = "$file/$_" } @newfiles);
|
||||
next;
|
||||
}
|
||||
}
|
||||
|
||||
foreach $file (@files) {
|
||||
if(-f $file) {
|
||||
|
||||
print "Adding file $file\n";
|
||||
|
||||
open(FILE, $file) || die "Could not open file $file\n";
|
||||
|
||||
$file =~ s-^-/-;
|
||||
$fvar = $file;
|
||||
$fvar =~ s-/-_-g;
|
||||
$fvar =~ s-\.-_-g;
|
||||
# for AVR, add PROGMEM here
|
||||
print(OUTPUT "static const unsigned char data".$fvar."[] = {\n");
|
||||
print(OUTPUT "\t/* $file */\n\t");
|
||||
for($j = 0; $j < length($file); $j++) {
|
||||
printf(OUTPUT "%#02x, ", unpack("C", substr($file, $j, 1)));
|
||||
}
|
||||
printf(OUTPUT "0,\n");
|
||||
|
||||
|
||||
$i = 0;
|
||||
while(read(FILE, $data, 1)) {
|
||||
if($i == 0) {
|
||||
print(OUTPUT "\t");
|
||||
}
|
||||
printf(OUTPUT "%#02x, ", unpack("C", $data));
|
||||
$i++;
|
||||
if($i == 10) {
|
||||
print(OUTPUT "\n");
|
||||
$i = 0;
|
||||
}
|
||||
}
|
||||
print(OUTPUT "0};\n\n");
|
||||
close(FILE);
|
||||
push(@fvars, $fvar);
|
||||
push(@pfiles, $file);
|
||||
}
|
||||
}
|
||||
|
||||
for($i = 0; $i < @fvars; $i++) {
|
||||
$file = $pfiles[$i];
|
||||
$fvar = $fvars[$i];
|
||||
|
||||
if($i == 0) {
|
||||
$prevfile = "NULL";
|
||||
} else {
|
||||
$prevfile = "file" . $fvars[$i - 1];
|
||||
}
|
||||
print(OUTPUT "const struct httpd_fsdata_file file".$fvar."[] = {{$prevfile, data$fvar, ");
|
||||
print(OUTPUT "data$fvar + ". (length($file) + 1) .", ");
|
||||
print(OUTPUT "sizeof(data$fvar) - ". (length($file) + 1) ."}};\n\n");
|
||||
}
|
||||
|
||||
print(OUTPUT "#define HTTPD_FS_ROOT file$fvars[$i - 1]\n\n");
|
||||
print(OUTPUT "#define HTTPD_FS_NUMFILES $i\n");
|
|
@ -1,43 +0,0 @@
|
|||
/*!
|
||||
* \file mii.h
|
||||
* \brief Media Independent Interface (MII) driver
|
||||
* \version $Revision: 1.3 $
|
||||
* \author Michael Norman
|
||||
*
|
||||
* \warning This driver assumes that FEC0 is used for all MII management
|
||||
* communications. For dual PHYs, etc., insure that FEC0_MDC and
|
||||
* FEC0_MDIO are connected to the PHY's MDC and MDIO.
|
||||
*/
|
||||
|
||||
#ifndef _MII_H_
|
||||
#define _MII_H_
|
||||
|
||||
/*******************************************************************/
|
||||
|
||||
int
|
||||
mii_write(int, int, uint16);
|
||||
|
||||
int
|
||||
mii_read(int, int, uint16*);
|
||||
|
||||
void
|
||||
mii_init(int);
|
||||
|
||||
/* MII Speed Settings */
|
||||
typedef enum {
|
||||
MII_10BASE_T, /*!< 10Base-T operation */
|
||||
MII_100BASE_TX /*!< 100Base-TX operation */
|
||||
} MII_SPEED;
|
||||
|
||||
/* MII Duplex Settings */
|
||||
typedef enum {
|
||||
MII_HDX, /*!< half-duplex */
|
||||
MII_FDX /*!< full-duplex */
|
||||
} MII_DUPLEX;
|
||||
|
||||
#define MII_TIMEOUT 0x10000
|
||||
#define MII_LINK_TIMEOUT 0x10000
|
||||
|
||||
/*******************************************************************/
|
||||
|
||||
#endif /* _MII_H_ */
|
|
@ -1,210 +0,0 @@
|
|||
/*
|
||||
FreeRTOS.org V5.1.0 - 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.
|
||||
***************************************************************************
|
||||
*/
|
||||
|
||||
|
||||
/* Task that controls the uIP TCP/IP stack. */
|
||||
|
||||
|
||||
/* Standard includes. */
|
||||
#include <string.h>
|
||||
|
||||
/* Scheduler includes. */
|
||||
#include "FreeRTOS.h"
|
||||
#include "task.h"
|
||||
#include "semphr.h"
|
||||
|
||||
/* uip includes. */
|
||||
#include "uip.h"
|
||||
#include "uip_arp.h"
|
||||
#include "httpd.h"
|
||||
#include "timer.h"
|
||||
#include "clock-arch.h"
|
||||
|
||||
/* Demo includes. */
|
||||
#include "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.
|
||||
*/
|
||||
void clock_init( void );
|
||||
clock_time_t clock_time( void );
|
||||
extern void timer_set(struct timer *t, clock_time_t interval);
|
||||
extern int timer_expired(struct timer *t);
|
||||
extern void timer_reset(struct timer *t);
|
||||
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
/* The semaphore used by the ISR to wake the uIP task. */
|
||||
extern xSemaphoreHandle xFECSemaphore;
|
||||
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
void clock_init(void)
|
||||
{
|
||||
/* This is done when the scheduler starts. */
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
/* Define clock functions here to avoid header file name clash between uIP
|
||||
and the Luminary Micro driver library. */
|
||||
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;
|
||||
|
||||
/* To prevent compiler warnings. */
|
||||
( void ) pvParameters;
|
||||
|
||||
/* 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 );
|
||||
|
||||
/* Initialise the WEB server. */
|
||||
httpd_init();
|
||||
|
||||
/* Initialise the Ethernet controller peripheral. */
|
||||
vFECInit();
|
||||
|
||||
for( ;; )
|
||||
{
|
||||
/* Is there received data ready to be processed? */
|
||||
uip_len = usFECGetRxedData();
|
||||
|
||||
if( uip_len > 0 )
|
||||
{
|
||||
/* Standard uIP loop taken from the uIP manual. */
|
||||
|
||||
if( xHeader->type == htons( UIP_ETHTYPE_IP ) )
|
||||
{
|
||||
uip_arp_ipin();
|
||||
uip_input();
|
||||
|
||||
/* If the above function invocation resulted in data that
|
||||
should be sent out on the network, the global variable
|
||||
uip_len is set to a value > 0. */
|
||||
if( uip_len > 0 )
|
||||
{
|
||||
uip_arp_out();
|
||||
vFECSendData();
|
||||
}
|
||||
else
|
||||
{
|
||||
/* If we are not sending data then let the FEC driver know
|
||||
the buffer is no longer required. */
|
||||
vFECRxProcessingCompleted();
|
||||
}
|
||||
}
|
||||
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 )
|
||||
{
|
||||
vFECSendData();
|
||||
}
|
||||
else
|
||||
{
|
||||
/* If we are not sending data then let the FEC driver know
|
||||
the buffer is no longer required. */
|
||||
vFECRxProcessingCompleted();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* If we are not sending data then let the FEC driver know
|
||||
the buffer is no longer required. */
|
||||
vFECRxProcessingCompleted();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if( timer_expired( &periodic_timer ) )
|
||||
{
|
||||
timer_reset( &periodic_timer );
|
||||
for( i = 0; i < UIP_CONNS; i++ )
|
||||
{
|
||||
uip_periodic( i );
|
||||
|
||||
/* If the above function invocation resulted in data that
|
||||
should be sent out on the network, the global variable
|
||||
uip_len is set to a value > 0. */
|
||||
if( uip_len > 0 )
|
||||
{
|
||||
uip_arp_out();
|
||||
vFECSendData();
|
||||
}
|
||||
}
|
||||
|
||||
/* 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 );
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
|
||||
|
|
@ -1,162 +0,0 @@
|
|||
/**
|
||||
* \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 30
|
||||
|
||||
/**
|
||||
* Maximum number of listening TCP ports.
|
||||
*
|
||||
* \hideinitializer
|
||||
*/
|
||||
#define UIP_CONF_MAX_LISTENPORTS 5
|
||||
|
||||
/**
|
||||
* uIP buffer size.
|
||||
*
|
||||
* \hideinitializer
|
||||
*/
|
||||
#define UIP_CONF_BUFFER_SIZE 1500
|
||||
|
||||
/**
|
||||
* 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 FRAME_MULTIPLE 1
|
||||
|
||||
#endif /* __UIP_CONF_H__ */
|
||||
|
||||
/** @} */
|
||||
/** @} */
|
|
@ -1,49 +0,0 @@
|
|||
/*
|
||||
* 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__ */
|
Loading…
Add table
Add a link
Reference in a new issue