]> git.sur5r.net Git - freertos/commitdiff
Add missing files.
authorrichardbarry <richardbarry@1d2547de-c912-0410-9cb9-b8ca96c0e9e2>
Wed, 18 Mar 2009 16:16:57 +0000 (16:16 +0000)
committerrichardbarry <richardbarry@1d2547de-c912-0410-9cb9-b8ca96c0e9e2>
Wed, 18 Mar 2009 16:16:57 +0000 (16:16 +0000)
git-svn-id: https://svn.code.sf.net/p/freertos/code/trunk@712 1d2547de-c912-0410-9cb9-b8ca96c0e9e2

Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/MCF5225x_ethernetif.c [new file with mode: 0644]
Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/__sys_arch.c [new file with mode: 0644]
Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/arch/cc.h [new file with mode: 0644]
Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/arch/cpu.h [new file with mode: 0644]
Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/arch/perf.h [new file with mode: 0644]
Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/arch/sys_arch.h [new file with mode: 0644]
Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/eth.h [new file with mode: 0644]
Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/eth_phy.h [new file with mode: 0644]
Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/fec.h [new file with mode: 0644]
Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/fecbd.h [new file with mode: 0644]
Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/mii.h [new file with mode: 0644]

diff --git a/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/MCF5225x_ethernetif.c b/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/MCF5225x_ethernetif.c
new file mode 100644 (file)
index 0000000..d956903
--- /dev/null
@@ -0,0 +1,888 @@
+/*\r
+ * Copyright (c) 2001-2004 Swedish Institute of Computer Science.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without modification,\r
+ * are permitted provided that the following conditions are met:\r
+ *\r
+ * 1. Redistributions of source code must retain the above copyright notice,\r
+ *    this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright notice,\r
+ *    this list of conditions and the following disclaimer in the documentation\r
+ *    and/or other materials provided with the distribution.\r
+ * 3. The name of the author may not be used to endorse or promote products\r
+ *    derived from this software without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED\r
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF\r
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT\r
+ * SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,\r
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT\r
+ * OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\r
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\r
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING\r
+ * IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY\r
+ * OF SUCH DAMAGE.\r
+ *\r
+ * This file is part of the lwIP TCP/IP stack.\r
+ *\r
+ * Author: Adam Dunkels <adam@sics.se>\r
+ *\r
+ */\r
+\r
+/* Standard library includes. */\r
+#include <stdio.h>\r
+#include <string.h>\r
+\r
+/* FreeRTOS includes. */\r
+#include "FreeRTOS.h"\r
+#include "task.h"\r
+\r
+xTaskHandle xEthIntTask;\r
+\r
+/* lwIP includes. */\r
+#include "lwip/def.h"\r
+#include "lwip/mem.h"\r
+#include "lwip/pbuf.h"\r
+#include "lwip/sys.h"\r
+#include "lwip/stats.h"\r
+#include "lwip/snmp.h"\r
+#include "netif/etharp.h"\r
+\r
+/* Hardware includes. */\r
+#include "fec.h"\r
+\r
+/* Delay to wait for a DMA buffer to become available if one is not already\r
+available. */\r
+#define netifBUFFER_WAIT_ATTEMPTS                                      10\r
+#define netifBUFFER_WAIT_DELAY                                         (10 / portTICK_RATE_MS)\r
+\r
+/* Delay between polling the PHY to see if a link has been established. */\r
+#define netifLINK_DELAY                                                                ( 500 / portTICK_RATE_MS )\r
+\r
+/* Delay between looking for incoming packets.  In ideal world this would be\r
+infinite. */\r
+#define netifBLOCK_TIME_WAITING_FOR_INPUT                      netifLINK_DELAY\r
+\r
+/* Name for the netif. */\r
+#define IFNAME0 'e'\r
+#define IFNAME1 'n'\r
+\r
+/* Hardware specific. */\r
+#define netifFIRST_FEC_VECTOR                                          23\r
+\r
+/*-----------------------------------------------------------*/\r
+\r
+/* The DMA descriptors.  This is a char array to allow us to align it correctly. */\r
+static unsigned portCHAR xFECTxDescriptors_unaligned[ ( configNUM_FEC_TX_BUFFERS * sizeof( FECBD ) ) + 16 ];\r
+static unsigned portCHAR xFECRxDescriptors_unaligned[ ( configNUM_FEC_RX_BUFFERS * sizeof( FECBD ) ) + 16 ];\r
+static FECBD *xFECTxDescriptors;\r
+static FECBD *xFECRxDescriptors;\r
+\r
+/* The DMA buffers.  These are char arrays to allow them to be alligned correctly. */\r
+static unsigned portCHAR ucFECTxBuffers[ ( configNUM_FEC_TX_BUFFERS * configFEC_BUFFER_SIZE ) + 16 ];\r
+static unsigned portCHAR ucFECRxBuffers[ ( configNUM_FEC_RX_BUFFERS * configFEC_BUFFER_SIZE ) + 16 ];\r
+static unsigned portBASE_TYPE uxNextRxBuffer = 0, uxNextTxBuffer = 0;\r
+\r
+/* Semaphore used by the FEC interrupt handler to wake the handler task. */\r
+static xSemaphoreHandle xFecSemaphore;\r
+\r
+#pragma options align= packed\r
+struct ethernetif\r
+{\r
+  struct eth_addr *ethaddr;\r
+  /* Add whatever per-interface state that is needed here. */\r
+};\r
+\r
+/*-----------------------------------------------------------*/\r
+\r
+/* Standard lwIP netif handlers. */\r
+static void prvInitialiseFECBuffers( void );\r
+static void low_level_init( struct netif *netif );\r
+static err_t low_level_output(struct netif *netif, struct pbuf *p);\r
+static struct pbuf *low_level_input(struct netif *netif);\r
+static void ethernetif_input( void *pParams );\r
+\r
+/* Functions adapted from Freescale provided code. */\r
+static int fec_mii_write( int phy_addr, int reg_addr, int data );\r
+static int fec_mii_read( int phy_addr, int reg_addr, uint16* data );\r
+static uint8 fec_hash_address( const uint8* addr );\r
+static void fec_set_address( const uint8 *pa );\r
+static void fec_irq_enable( void );\r
+\r
+/*-----------------------------------------------------------*/\r
+\r
+/********************************************************************/\r
+/*\r
+ * Write a value to a PHY's MII register.\r
+ *\r
+ * Parameters:\r
+ *  ch          FEC channel\r
+ *  phy_addr    Address of the PHY.\r
+ *  reg_addr    Address of the register in the PHY.\r
+ *  data        Data to be written to the PHY register.\r
+ *\r
+ * Return Values:\r
+ *  0 on failure\r
+ *  1 on success.\r
+ *\r
+ * Please refer to your PHY manual for registers and their meanings.\r
+ * mii_write() polls for the FEC's MII interrupt event and clears it. \r
+ * If after a suitable amount of time the event isn't triggered, a \r
+ * value of 0 is returned.\r
+ */\r
+static int fec_mii_write( int phy_addr, int reg_addr, int data )\r
+{\r
+int timeout;\r
+uint32 eimr;\r
+\r
+       /* Clear the MII interrupt bit */\r
+       MCF_FEC_EIR = MCF_FEC_EIR_MII;\r
+\r
+       /* Mask the MII interrupt */\r
+       eimr = MCF_FEC_EIMR;\r
+       MCF_FEC_EIMR &= ~MCF_FEC_EIMR_MII;\r
+\r
+       /* Write to the MII Management Frame Register to kick-off the MII write */\r
+       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 );\r
+\r
+       /* Poll for the MII interrupt (interrupt should be masked) */\r
+       for (timeout = 0; timeout < MII_TIMEOUT; timeout++)\r
+       {\r
+               if (MCF_FEC_EIR & MCF_FEC_EIR_MII)\r
+               {\r
+                       break;\r
+               }\r
+       }\r
+\r
+       if( timeout == MII_TIMEOUT )\r
+       {\r
+               return 0;\r
+       }\r
+\r
+       /* Clear the MII interrupt bit */\r
+       MCF_FEC_EIR = MCF_FEC_EIR_MII;\r
+\r
+       /* Restore the EIMR */\r
+       MCF_FEC_EIMR = eimr;\r
+\r
+       return 1;\r
+}\r
+\r
+/********************************************************************/\r
+/*\r
+ * Read a value from a PHY's MII register.\r
+ *\r
+ * Parameters:\r
+ *  ch          FEC channel\r
+ *  phy_addr    Address of the PHY.\r
+ *  reg_addr    Address of the register in the PHY.\r
+ *  data        Pointer to storage for the Data to be read\r
+ *              from the PHY register (passed by reference)\r
+ *\r
+ * Return Values:\r
+ *  0 on failure\r
+ *  1 on success.\r
+ *\r
+ * Please refer to your PHY manual for registers and their meanings.\r
+ * mii_read() polls for the FEC's MII interrupt event and clears it. \r
+ * If after a suitable amount of time the event isn't triggered, a \r
+ * value of 0 is returned.\r
+ */\r
+static int fec_mii_read( int phy_addr, int reg_addr, uint16* data )\r
+{\r
+int timeout;\r
+uint32 eimr;\r
+\r
+       /* Clear the MII interrupt bit */\r
+       MCF_FEC_EIR = MCF_FEC_EIR_MII;\r
+\r
+       /* Mask the MII interrupt */\r
+       eimr = MCF_FEC_EIMR;\r
+       MCF_FEC_EIMR &= ~MCF_FEC_EIMR_MII;\r
+\r
+       /* Write to the MII Management Frame Register to kick-off the MII read */\r
+       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;\r
+\r
+       /* Poll for the MII interrupt (interrupt should be masked) */\r
+       for (timeout = 0; timeout < MII_TIMEOUT; timeout++)\r
+       {\r
+               if (MCF_FEC_EIR & MCF_FEC_EIR_MII)\r
+               {\r
+                       break;\r
+               }\r
+       }\r
+\r
+       if(timeout == MII_TIMEOUT)\r
+       {\r
+               return 0;\r
+       }\r
+\r
+       /* Clear the MII interrupt bit */\r
+       MCF_FEC_EIR = MCF_FEC_EIR_MII;\r
+\r
+       /* Restore the EIMR */\r
+       MCF_FEC_EIMR = eimr;\r
+\r
+       *data = (uint16)(MCF_FEC_MMFR & 0x0000FFFF);\r
+\r
+       return 1;\r
+}\r
+\r
+\r
+/********************************************************************/\r
+/*\r
+ * Generate the hash table settings for the given address\r
+ *\r
+ * Parameters:\r
+ *  addr    48-bit (6 byte) Address to generate the hash for\r
+ *\r
+ * Return Value:\r
+ *  The 6 most significant bits of the 32-bit CRC result\r
+ */\r
+static uint8 fec_hash_address( const uint8* addr )\r
+{\r
+uint32 crc;\r
+uint8 byte;\r
+int i, j;\r
+\r
+       crc = 0xFFFFFFFF;\r
+       for(i=0; i<6; ++i)\r
+       {\r
+               byte = addr[i];\r
+               for(j=0; j<8; ++j)\r
+               {\r
+                       if((byte & 0x01)^(crc & 0x01))\r
+                       {\r
+                               crc >>= 1;\r
+                               crc = crc ^ 0xEDB88320;\r
+                       }\r
+                       else\r
+                       {\r
+                               crc >>= 1;\r
+                       }\r
+\r
+                       byte >>= 1;\r
+               }\r
+       }\r
+\r
+       return (uint8)(crc >> 26);\r
+}\r
+\r
+/********************************************************************/\r
+/*\r
+ * Set the Physical (Hardware) Address and the Individual Address\r
+ * Hash in the selected FEC\r
+ *\r
+ * Parameters:\r
+ *  ch  FEC channel\r
+ *  pa  Physical (Hardware) Address for the selected FEC\r
+ */\r
+static void fec_set_address( const uint8 *pa )\r
+{\r
+       uint8 crc;\r
+\r
+       /*\r
+       * Set the Physical Address\r
+       */\r
+       MCF_FEC_PALR = (uint32)((pa[0]<<24) | (pa[1]<<16) | (pa[2]<<8) | pa[3]);\r
+       MCF_FEC_PAUR = (uint32)((pa[4]<<24) | (pa[5]<<16));\r
+\r
+       /*\r
+       * Calculate and set the hash for given Physical Address\r
+       * in the  Individual Address Hash registers\r
+       */\r
+       crc = fec_hash_address(pa);\r
+       if(crc >= 32)\r
+       {\r
+               MCF_FEC_IAUR |= (uint32)(1 << (crc - 32));\r
+       }\r
+       else\r
+       {\r
+               MCF_FEC_IALR |= (uint32)(1 << crc);\r
+       }\r
+}\r
+\r
+\r
+/********************************************************************/\r
+/*\r
+ * Enable interrupts on the selected FEC\r
+ *\r
+ */\r
+static void fec_irq_enable( void )\r
+{\r
+int fec_vbase;\r
+\r
+#if INTC_LVL_FEC > configMAX_SYSCALL_INTERRUPT_PRIORITY\r
+       #error INTC_LVL_FEC must be less than or equal to configMAX_SYSCALL_INTERRUPT_PRIORITY\r
+#endif\r
+\r
+       fec_vbase = 64 + netifFIRST_FEC_VECTOR;\r
+    \r
+       /* Enable FEC interrupts to the ColdFire core \r
+        * Setup each ICR with a unique interrupt level combination */\r
+       fec_vbase -= 64;\r
+\r
+       /* FEC Rx Frame */\r
+       MCF_INTC0_ICR(fec_vbase+4)  = MCF_INTC_ICR_IL(INTC_LVL_FEC);\r
+\r
+       /* FEC Rx Buffer */                              \r
+       MCF_INTC0_ICR(fec_vbase+5)  = MCF_INTC_ICR_IL(INTC_LVL_FEC);\r
+\r
+       /* FEC FIFO Underrun */                              \r
+       MCF_INTC0_ICR(fec_vbase+2)  = MCF_INTC_ICR_IL(INTC_LVL_FEC+1);\r
+\r
+       /* FEC Collision Retry Limit */                              \r
+       MCF_INTC0_ICR(fec_vbase+3)  = MCF_INTC_ICR_IL(INTC_LVL_FEC+1);\r
+\r
+       /* FEC Late Collision */                                 \r
+       MCF_INTC0_ICR(fec_vbase+7)  = MCF_INTC_ICR_IL(INTC_LVL_FEC+1);\r
+\r
+       /* FEC Heartbeat Error */                                \r
+       MCF_INTC0_ICR(fec_vbase+8)  = MCF_INTC_ICR_IL(INTC_LVL_FEC+1);\r
+\r
+       /* FEC Bus Error */                              \r
+       MCF_INTC0_ICR(fec_vbase+10) = MCF_INTC_ICR_IL(INTC_LVL_FEC+1);\r
+\r
+       /* FEC Babbling Transmit */                              \r
+       MCF_INTC0_ICR(fec_vbase+11) = MCF_INTC_ICR_IL(INTC_LVL_FEC+1);\r
+\r
+       /* FEC Babbling Receive */                               \r
+       MCF_INTC0_ICR(fec_vbase+12) = MCF_INTC_ICR_IL(INTC_LVL_FEC+1);\r
+                                 \r
+       /* Enable the FEC interrupts in the mask register */    \r
+       MCF_INTC0_IMRH &= ~( MCF_INTC_IMRH_INT_MASK33 | MCF_INTC_IMRH_INT_MASK34 | MCF_INTC_IMRH_INT_MASK35 );\r
+       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_MASKALL );\r
+\r
+    /* Clear any pending FEC interrupt events */\r
+    MCF_FEC_EIR = MCF_FEC_EIR_CLEAR_ALL;\r
+\r
+    /* Unmask all FEC interrupts */\r
+    MCF_FEC_EIMR = MCF_FEC_EIMR_UNMASK_ALL;\r
+}\r
+\r
+/**\r
+ * In this function, the hardware should be initialized.\r
+ * Called from ethernetif_init().\r
+ *\r
+ * @param netif the already initialized lwip network interface structure\r
+ *        for this ethernetif\r
+ */\r
+static void low_level_init( struct netif *netif )\r
+{\r
+unsigned portSHORT usData;\r
+const unsigned portCHAR ucMACAddress[6] = \r
+{\r
+       configMAC_0, configMAC_1,configMAC_2,configMAC_3,configMAC_4,configMAC_5\r
+};\r
+\r
+       prvInitialiseFECBuffers();\r
+       vSemaphoreCreateBinary( xFecSemaphore );\r
+       \r
+       for( usData = 0; usData < 6; usData++ )\r
+       {\r
+               netif->hwaddr[ usData ] = ucMACAddress[ usData ];\r
+       }\r
+\r
+       /* Set the Reset bit and clear the Enable bit */\r
+       MCF_FEC_ECR = MCF_FEC_ECR_RESET;\r
+\r
+       /* Wait at least 8 clock cycles */\r
+       for( usData = 0; usData < 10; usData++ )\r
+       {\r
+               asm( "NOP" );\r
+       }\r
+\r
+       /* Set MII speed to 2.5MHz. */\r
+       MCF_FEC_MSCR = MCF_FEC_MSCR_MII_SPEED( ( ( configCPU_CLOCK_HZ / 1000000 ) / 5 ) + 1 );\r
+\r
+       /*\r
+        * Make sure the external interface signals are enabled\r
+        */\r
+       MCF_GPIO_PNQPAR = MCF_GPIO_PNQPAR_IRQ3_FEC_MDIO | MCF_GPIO_PNQPAR_IRQ5_FEC_MDC;\r
+\r
+\r
+    MCF_GPIO_PTIPAR = MCF_GPIO_PTIPAR_FEC_COL_FEC_COL                  \r
+                                       | MCF_GPIO_PTIPAR_FEC_CRS_FEC_CRS                       \r
+                                       | MCF_GPIO_PTIPAR_FEC_RXCLK_FEC_RXCLK           \r
+                                       | MCF_GPIO_PTIPAR_FEC_RXD0_FEC_RXD0                     \r
+                                       | MCF_GPIO_PTIPAR_FEC_RXD1_FEC_RXD1                     \r
+                                       | MCF_GPIO_PTIPAR_FEC_RXD2_FEC_RXD2                     \r
+                                       | MCF_GPIO_PTIPAR_FEC_RXD3_FEC_RXD3                     \r
+                                       | MCF_GPIO_PTIPAR_FEC_RXDV_FEC_RXDV;            \r
+\r
+       MCF_GPIO_PTJPAR = MCF_GPIO_PTJPAR_FEC_RXER_FEC_RXER                     \r
+                                       | MCF_GPIO_PTJPAR_FEC_TXCLK_FEC_TXCLK           \r
+                                       | MCF_GPIO_PTJPAR_FEC_TXD0_FEC_TXD0                     \r
+                                       | MCF_GPIO_PTJPAR_FEC_TXD1_FEC_TXD1                     \r
+                                       | MCF_GPIO_PTJPAR_FEC_TXD2_FEC_TXD2                     \r
+                                       | MCF_GPIO_PTJPAR_FEC_TXD3_FEC_TXD3                     \r
+                                       | MCF_GPIO_PTJPAR_FEC_TXEN_FEC_TXEN                     \r
+                                       | MCF_GPIO_PTJPAR_FEC_TXER_FEC_TXER;            \r
+\r
+\r
+       /* Can we talk to the PHY? */\r
+       do\r
+       {\r
+               vTaskDelay( netifLINK_DELAY );\r
+               usData = 0;\r
+               fec_mii_read( configPHY_ADDRESS, PHY_PHYIDR1, &usData );\r
+\r
+       } while( ( usData == 0xffff ) || ( usData == 0 ) );\r
+\r
+       /* Start auto negotiate. */\r
+       fec_mii_write( configPHY_ADDRESS, PHY_BMCR, ( PHY_BMCR_AN_RESTART | PHY_BMCR_AN_ENABLE ) );\r
+\r
+       /* Wait for auto negotiate to complete. */\r
+       do\r
+       {\r
+               vTaskDelay( netifLINK_DELAY );\r
+               fec_mii_read( configPHY_ADDRESS, PHY_BMSR, &usData );\r
+\r
+       } while( !( usData & PHY_BMSR_AN_COMPLETE ) );\r
+\r
+       /* When we get here we have a link - find out what has been negotiated. */\r
+       fec_mii_read( configPHY_ADDRESS, PHY_ANLPAR, &usData );\r
+       \r
+       if( ( usData & PHY_ANLPAR_100BTX_FDX ) || ( usData & PHY_ANLPAR_100BTX ) )\r
+       {\r
+               /* Speed is 100. */\r
+       }\r
+       else\r
+       {\r
+               /* Speed is 10. */\r
+       }\r
+\r
+       if( ( usData & PHY_ANLPAR_100BTX_FDX ) || ( usData & PHY_ANLPAR_10BTX_FDX ) )\r
+       {\r
+               /* Full duplex. */\r
+               MCF_FEC_RCR &= (uint32)~MCF_FEC_RCR_DRT;\r
+               MCF_FEC_TCR |= MCF_FEC_TCR_FDEN;\r
+       }\r
+       else\r
+       {\r
+               MCF_FEC_RCR |= MCF_FEC_RCR_DRT;\r
+               MCF_FEC_TCR &= (uint32)~MCF_FEC_TCR_FDEN;\r
+       }\r
+       \r
+       /* Clear the Individual and Group Address Hash registers */\r
+       MCF_FEC_IALR = 0;\r
+       MCF_FEC_IAUR = 0;\r
+       MCF_FEC_GALR = 0;\r
+       MCF_FEC_GAUR = 0;\r
+\r
+       /* Set the Physical Address for the selected FEC */\r
+       fec_set_address( ucMACAddress );\r
+\r
+       /* Set Rx Buffer Size */\r
+       MCF_FEC_EMRBR = (uint16)configFEC_BUFFER_SIZE;\r
+\r
+       /* Point to the start of the circular Rx buffer descriptor queue */\r
+       MCF_FEC_ERDSR = ( volatile unsigned portLONG ) &( xFECRxDescriptors[ 0 ] );\r
+\r
+       /* Point to the start of the circular Tx buffer descriptor queue */\r
+       MCF_FEC_ETSDR = ( volatile unsigned portLONG ) &( xFECTxDescriptors[ 0 ] );\r
+\r
+       /* Mask all FEC interrupts */\r
+       MCF_FEC_EIMR = MCF_FEC_EIMR_MASK_ALL;\r
+\r
+       /* Clear all FEC interrupt events */\r
+       MCF_FEC_EIR = MCF_FEC_EIR_CLEAR_ALL;\r
+\r
+       /* Initialize the Receive Control Register */\r
+       MCF_FEC_RCR = MCF_FEC_RCR_MAX_FL(ETH_MAX_FRM) | MCF_FEC_RCR_FCE;\r
+\r
+       MCF_FEC_RCR |= MCF_FEC_RCR_MII_MODE;\r
+\r
+       #if( configUSE_PROMISCUOUS_MODE == 1 )\r
+       {\r
+               MCF_FEC_RCR |= MCF_FEC_RCR_PROM;\r
+       }\r
+       #endif\r
+\r
+       /* Create the task that handles the EMAC. */\r
+       xTaskCreate( ethernetif_input, ( signed portCHAR * ) "ETH_INT", configETHERNET_INPUT_TASK_STACK_SIZE, (void *)netif, configETHERNET_INPUT_TASK_PRIORITY, &xEthIntTask );\r
+       \r
+       fec_irq_enable();\r
+       MCF_FEC_ECR = MCF_FEC_ECR_ETHER_EN;\r
+       MCF_FEC_RDAR = MCF_FEC_RDAR_R_DES_ACTIVE;       \r
+}\r
+\r
+/**\r
+ * This function should do the actual transmission of the packet. The packet is\r
+ * contained in the pbuf that is passed to the function. This pbuf\r
+ * might be chained.\r
+ *\r
+ * @param netif the lwip network interface structure for this ethernetif\r
+ * @param p the MAC packet to send (e.g. IP packet including MAC addresses and type)\r
+ * @return ERR_OK if the packet could be sent\r
+ *         an err_t value if the packet couldn't be sent\r
+ *\r
+ * @note Returning ERR_MEM here if a DMA queue of your MAC is full can lead to\r
+ *       strange results. You might consider waiting for space in the DMA queue\r
+ *       to become availale since the stack doesn't retry to send a packet\r
+ *       dropped because of memory failure (except for the TCP timers).\r
+ */\r
+static err_t low_level_output(struct netif *netif, struct pbuf *p)\r
+{\r
+struct pbuf *q;\r
+u32_t l = 0;\r
+unsigned portCHAR *pcTxData = NULL;\r
+portBASE_TYPE i;\r
+\r
+       ( void ) netif;\r
+\r
+       #if ETH_PAD_SIZE\r
+         pbuf_header(p, -ETH_PAD_SIZE);                        /* drop the padding word */\r
+       #endif\r
+\r
+       /* Get a DMA buffer into which we can write the data to send. */\r
+       for( i = 0; i < netifBUFFER_WAIT_ATTEMPTS; i++ )\r
+       {\r
+               if( xFECTxDescriptors[ uxNextTxBuffer ].status & TX_BD_R )\r
+               {\r
+                       /* Wait for the buffer to become available. */\r
+                       vTaskDelay( netifBUFFER_WAIT_DELAY );\r
+               }\r
+               else\r
+               {\r
+                       pcTxData = xFECTxDescriptors[ uxNextTxBuffer ].data;\r
+                       break;\r
+               }\r
+       }\r
+\r
+       if( pcTxData == NULL ) \r
+       {\r
+               /* For break point only. */\r
+               portNOP();\r
+\r
+               return ERR_BUF;\r
+       }\r
+       else \r
+       {\r
+               for( q = p; q != NULL; q = q->next ) \r
+               {\r
+                       /* Send the data from the pbuf to the interface, one pbuf at a\r
+                       time. The size of the data in each pbuf is kept in the ->len\r
+                       variable. */\r
+                       memcpy( &pcTxData[l], (u8_t*)q->payload, q->len );\r
+                       l += q->len;\r
+               }\r
+       }\r
+\r
+       /* Setup the buffer descriptor for transmission */\r
+       xFECTxDescriptors[ uxNextTxBuffer ].length = l;//nbuf->length + ETH_HDR_LEN;\r
+       xFECTxDescriptors[ uxNextTxBuffer ].status |= (TX_BD_R | TX_BD_L);\r
+\r
+       /* Continue the Tx DMA task (in case it was waiting for a new TxBD) */\r
+       MCF_FEC_TDAR = MCF_FEC_TDAR_X_DES_ACTIVE;\r
+\r
+       uxNextTxBuffer++;\r
+       if( uxNextTxBuffer >= configNUM_FEC_TX_BUFFERS )\r
+       {\r
+               uxNextTxBuffer = 0;\r
+       }\r
+\r
+       #if ETH_PAD_SIZE\r
+               pbuf_header(p, ETH_PAD_SIZE);                   /* reclaim the padding word */\r
+       #endif\r
+\r
+       LINK_STATS_INC(link.xmit);\r
+\r
+       return ERR_OK;\r
+}\r
+\r
+/**\r
+ * Should allocate a pbuf and transfer the bytes of the incoming\r
+ * packet from the interface into the pbuf.\r
+ *\r
+ * @param netif the lwip network interface structure for this ethernetif\r
+ * @return a pbuf filled with the received packet (including MAC header)\r
+ *         NULL on memory error\r
+ */\r
+static struct pbuf *low_level_input(struct netif *netif)\r
+{\r
+struct pbuf *p, *q;\r
+u16_t len, l;\r
+\r
+       ( void ) netif;\r
+\r
+       l = 0;\r
+       p = NULL;\r
+\r
+       /* Obtain the size of the packet and put it into the "len" variable. */\r
+       len = xFECRxDescriptors[ uxNextRxBuffer ].length;\r
+\r
+       if( ( len != 0 ) && ( ( xFECRxDescriptors[ uxNextRxBuffer ].status & RX_BD_E ) == 0 ) )\r
+       {\r
+               #if ETH_PAD_SIZE\r
+                       len += ETH_PAD_SIZE;                                            /* allow room for Ethernet padding */\r
+               #endif\r
+\r
+               /* We allocate a pbuf chain of pbufs from the pool. */\r
+               p = pbuf_alloc(PBUF_RAW, len, PBUF_POOL);\r
+\r
+               if (p != NULL) \r
+               {\r
+\r
+                       #if ETH_PAD_SIZE\r
+                                       pbuf_header(p, -ETH_PAD_SIZE);                  /* drop the padding word */\r
+                       #endif\r
+\r
+                       /* We iterate over the pbuf chain until we have read the entire\r
+                        * packet into the pbuf. */\r
+                       for(q = p; q != NULL; q = q->next) \r
+                       {\r
+                               /* Read enough bytes to fill this pbuf in the chain. The\r
+                                * available data in the pbuf is given by the q->len\r
+                                * variable. */\r
+                               memcpy((u8_t*)q->payload, &(xFECRxDescriptors[ uxNextRxBuffer ].data[l]), q->len);\r
+                               l = l + q->len;\r
+                       }\r
+\r
+\r
+                       #if ETH_PAD_SIZE\r
+                               pbuf_header(p, ETH_PAD_SIZE);                   /* reclaim the padding word */\r
+                       #endif\r
+\r
+                       LINK_STATS_INC(link.recv);\r
+\r
+               } \r
+               else \r
+               {\r
+\r
+                       LINK_STATS_INC(link.memerr);\r
+                       LINK_STATS_INC(link.drop);\r
+\r
+               } /* End else */\r
+               \r
+               \r
+               /* Free the descriptor. */\r
+               xFECRxDescriptors[ uxNextRxBuffer ].status |= RX_BD_E;\r
+               MCF_FEC_RDAR = MCF_FEC_RDAR_R_DES_ACTIVE;\r
+               \r
+               uxNextRxBuffer++;\r
+               if( uxNextRxBuffer >= configNUM_FEC_RX_BUFFERS )\r
+               {\r
+                       uxNextRxBuffer = 0;\r
+               }               \r
+               \r
+       } /* End if */\r
+\r
+       return p;\r
+}\r
+\r
+/**\r
+ * This function should be called when a packet is ready to be read\r
+ * from the interface. It uses the function low_level_input() that\r
+ * should handle the actual reception of bytes from the network\r
+ * interface.Then the type of the received packet is determined and\r
+ * the appropriate input function is called.\r
+ *\r
+ * @param netif the lwip network interface structure for this ethernetif\r
+ */\r
+\r
+static void ethernetif_input( void *pParams )\r
+{\r
+struct netif *netif;\r
+struct ethernetif *ethernetif;\r
+struct eth_hdr *ethhdr;\r
+struct pbuf *p;\r
+\r
+       netif = (struct netif*) pParams;\r
+       ethernetif = netif->state;\r
+\r
+       for( ;; )\r
+       {\r
+               do\r
+               {\r
+\r
+                       /* move received packet into a new pbuf */\r
+                       p = low_level_input( netif );\r
+\r
+                       if( p == NULL )\r
+                       {\r
+                               /* No packet could be read.  Wait a for an interrupt to tell us\r
+                               there is more data available. */\r
+                               xSemaphoreTake( xFecSemaphore, netifBLOCK_TIME_WAITING_FOR_INPUT );\r
+                       }\r
+\r
+               } while( p == NULL );\r
+\r
+               /* points to packet payload, which starts with an Ethernet header */\r
+               ethhdr = p->payload;\r
+\r
+               switch (htons(ethhdr->type)) {\r
+                       /* IP or ARP packet? */\r
+\r
+               case ETHTYPE_IP:\r
+\r
+                       pbuf_header( p, (s16_t)-sizeof(struct eth_hdr) );\r
+\r
+                       /* full packet send to tcpip_thread to process */\r
+                       if (netif->input(p, netif) != ERR_OK)\r
+                       {\r
+                               LWIP_DEBUGF(NETIF_DEBUG, ("ethernetif_input: IP input error\n"));\r
+                               pbuf_free(p);\r
+                               p = NULL;\r
+                       }\r
+                       break;\r
+\r
+               case ETHTYPE_ARP:\r
+\r
+                       #if ETHARP_TRUST_IP_MAC\r
+                               etharp_ip_input(netif, p);\r
+                       #endif\r
+\r
+                       etharp_arp_input(netif, ethernetif->ethaddr, p);\r
+                       break;\r
+\r
+               default:\r
+                       pbuf_free(p);\r
+                       p = NULL;\r
+                       break;\r
+               }\r
+       }\r
+}\r
+\r
+/**\r
+ * Should be called at the beginning of the program to set up the\r
+ * network interface. It calls the function low_level_init() to do the\r
+ * actual setup of the hardware.\r
+ *\r
+ * This function should be passed as a parameter to netif_add().\r
+ *\r
+ * @param netif the lwip network interface structure for this ethernetif\r
+ * @return ERR_OK if the loopif is initialized\r
+ *         ERR_MEM if private data couldn't be allocated\r
+ *         any other err_t on error\r
+ */\r
+err_t ethernetif_init(struct netif *netif)\r
+{\r
+       struct ethernetif *ethernetif;\r
+\r
+       LWIP_ASSERT("netif != NULL", (netif != NULL));\r
+\r
+       ethernetif = mem_malloc(sizeof(struct ethernetif));\r
+\r
+       if (ethernetif == NULL)\r
+       {\r
+               LWIP_DEBUGF(NETIF_DEBUG, ("ethernetif_init: out of memory\n"));\r
+               return ERR_MEM;\r
+       }\r
+\r
+       #if LWIP_NETIF_HOSTNAME\r
+       /* Initialize interface hostname */\r
+       netif->hostname = "lwip";\r
+       #endif /* LWIP_NETIF_HOSTNAME */\r
+\r
+       /*\r
+       * Initialize the snmp variables and counters inside the struct netif.\r
+       * The last argument should be replaced with your link speed, in units\r
+       * of bits per second.\r
+       */\r
+       NETIF_INIT_SNMP(netif, snmp_ifType_ethernet_csmacd, 100);\r
+\r
+       netif->state = ethernetif;\r
+       netif->name[0] = IFNAME0;\r
+       netif->name[1] = IFNAME1;\r
+\r
+       /* We directly use etharp_output() here to save a function call.\r
+       * You can instead declare your own function an call etharp_output()\r
+       * from it if you have to do some checks before sending (e.g. if link\r
+       * is available...)\r
+       */\r
+       netif->output = etharp_output;\r
+       netif->linkoutput = low_level_output;\r
+\r
+       ethernetif->ethaddr = (struct eth_addr *)&(netif->hwaddr[0]);\r
+\r
+       low_level_init(netif);\r
+\r
+       return ERR_OK;\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+static void prvInitialiseFECBuffers( void )\r
+{\r
+unsigned portBASE_TYPE ux;\r
+unsigned portCHAR *pcBufPointer;\r
+\r
+       pcBufPointer = &( xFECTxDescriptors_unaligned[ 0 ] );\r
+       while( ( ( unsigned portLONG ) pcBufPointer & 0x0fUL ) != 0 )\r
+       {\r
+               pcBufPointer++;\r
+       }\r
+       \r
+       xFECTxDescriptors = ( FECBD * ) pcBufPointer;\r
+       \r
+       pcBufPointer = &( xFECRxDescriptors_unaligned[ 0 ] );\r
+       while( ( ( unsigned portLONG ) pcBufPointer & 0x0fUL ) != 0 )\r
+       {\r
+               pcBufPointer++;\r
+       }\r
+       \r
+       xFECRxDescriptors = ( FECBD * ) pcBufPointer;\r
+\r
+\r
+       /* Setup the buffers and descriptors. */\r
+       pcBufPointer = &( ucFECTxBuffers[ 0 ] );\r
+       while( ( ( unsigned portLONG ) pcBufPointer & 0x0fUL ) != 0 )\r
+       {\r
+               pcBufPointer++;\r
+       }\r
+\r
+       for( ux = 0; ux < configNUM_FEC_TX_BUFFERS; ux++ )\r
+       {\r
+               xFECTxDescriptors[ ux ].status = TX_BD_TC;\r
+               xFECTxDescriptors[ ux ].data = pcBufPointer;\r
+               pcBufPointer += configFEC_BUFFER_SIZE;\r
+               xFECTxDescriptors[ ux ].length = 0;\r
+       }\r
+\r
+       pcBufPointer = &( ucFECRxBuffers[ 0 ] );\r
+       while( ( ( unsigned portLONG ) pcBufPointer & 0x0fUL ) != 0 )\r
+       {\r
+               pcBufPointer++;\r
+       }\r
+       \r
+       for( ux = 0; ux < configNUM_FEC_RX_BUFFERS; ux++ )\r
+       {\r
+           xFECRxDescriptors[ ux ].status = RX_BD_E;\r
+           xFECRxDescriptors[ ux ].length = configFEC_BUFFER_SIZE;\r
+           xFECRxDescriptors[ ux ].data = pcBufPointer;\r
+           pcBufPointer += configFEC_BUFFER_SIZE;\r
+       }\r
+\r
+       /* Set the wrap bit in the last descriptors to form a ring. */\r
+       xFECTxDescriptors[ configNUM_FEC_TX_BUFFERS - 1 ].status |= TX_BD_W;\r
+       xFECRxDescriptors[ configNUM_FEC_RX_BUFFERS - 1 ].status |= RX_BD_W;\r
+\r
+       uxNextRxBuffer = 0;\r
+       uxNextTxBuffer = 0;\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+__declspec(interrupt:0) void vFECISRHandler( void )\r
+{\r
+unsigned portLONG ulEvent;\r
+portBASE_TYPE xHighPriorityTaskWoken = pdFALSE;\r
+   \r
+       ulEvent = MCF_FEC_EIR & MCF_FEC_EIMR;\r
+       MCF_FEC_EIR = ulEvent;\r
+\r
+       if( ( ulEvent & MCF_FEC_EIR_RXB ) || ( ulEvent & MCF_FEC_EIR_RXF ) )\r
+       {\r
+               /* A packet has been received.  Wake the handler task. */\r
+               xSemaphoreGiveFromISR( xFecSemaphore, &xHighPriorityTaskWoken );\r
+       }\r
+\r
+       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 ) )\r
+       {\r
+               /* Sledge hammer error handling. */\r
+               prvInitialiseFECBuffers();\r
+               MCF_FEC_RDAR = MCF_FEC_RDAR_R_DES_ACTIVE;\r
+       }\r
+\r
+       portEND_SWITCHING_ISR( xHighPriorityTaskWoken );\r
+}\r
diff --git a/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/__sys_arch.c b/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/__sys_arch.c
new file mode 100644 (file)
index 0000000..a4d0f72
--- /dev/null
@@ -0,0 +1,571 @@
+/*\r
+ * Copyright (c) 2001-2003 Swedish Institute of Computer Science.\r
+ * Modifications Copyright (c) 2006 Christian Walter <wolti@sil.at>\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without modification,\r
+ * are permitted provided that the following conditions are met:\r
+ *\r
+ * 1. Redistributions of source code must retain the above copyright notice,\r
+ *    this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright notice,\r
+ *    this list of conditions and the following disclaimer in the documentation\r
+ *    and/or other materials provided with the distribution.\r
+ * 3. The name of the author may not be used to endorse or promote products\r
+ *    derived from this software without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED\r
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF\r
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT\r
+ * SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,\r
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT\r
+ * OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\r
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\r
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING\r
+ * IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY\r
+ * OF SUCH DAMAGE.\r
+ *\r
+ * This file is part of the lwIP TCP/IP stack.\r
+ *\r
+ * Author: Adam Dunkels <adam@sics.se>\r
+ * Modifcations: Christian Walter <wolti@sil.at>\r
+ *\r
+ * $Id: sys_arch.c,v 1.1 2008/08/05 00:10:49 b06862 Exp $\r
+ */\r
+\r
+/* ------------------------ System includes ------------------------------- */\r
+\r
+#include "stdlib.h"\r
+\r
+/* ------------------------ FreeRTOS includes ----------------------------- */\r
+#include "FreeRTOS.h"\r
+#include "task.h"\r
+#include "semphr.h"\r
+\r
+/* ------------------------ lwIP includes --------------------------------- */\r
+#include "lwip/debug.h"\r
+#include "lwip/def.h"\r
+#include "lwip/sys.h"\r
+#include "lwip/mem.h"\r
+#include "lwip/sio.h"\r
+#include "lwip/stats.h"\r
+\r
+/* ------------------------ Project includes ------------------------------ */\r
+\r
+/* ------------------------ Defines --------------------------------------- */\r
+/* This is the number of threads that can be started with sys_thead_new() */\r
+#define SYS_MBOX_SIZE               ( 16 )\r
+#define MS_TO_TICKS( ms )           \\r
+    ( portTickType )( ( portTickType ) ( ms ) / portTICK_RATE_MS )\r
+#define TICKS_TO_MS( ticks )        \\r
+    ( unsigned portLONG )( ( portTickType ) ( ticks ) * portTICK_RATE_MS )\r
+#define THREAD_STACK_SIZE           ( 256 /*FSL:1024*/ )\r
+#define THREAD_NAME                 "lwIP"\r
+\r
+#define THREAD_INIT( tcb ) \\r
+    do { \\r
+        tcb->next = NULL; \\r
+        tcb->pid = ( xTaskHandle )0; \\r
+        tcb->timeouts.next = NULL; \\r
+    } while( 0 )\r
+\r
+/* ------------------------ Type definitions ------------------------------ */\r
+typedef struct sys_tcb\r
+{\r
+    struct sys_tcb *next;\r
+    struct sys_timeouts timeouts;\r
+    xTaskHandle     pid;\r
+} sys_tcb_t;\r
+\r
+/* ------------------------ Prototypes ------------------------------------ */\r
+\r
+/* ------------------------ Static functions ------------------------------ */\r
+sys_tcb_t      *sys_thread_current( void );\r
+\r
+/* ------------------------ Static variables ------------------------------ */\r
+static sys_tcb_t *tasks = NULL;\r
+\r
+/* ------------------------ Start implementation -------------------------- */\r
+void\r
+sys_init( void )\r
+{\r
+    LWIP_ASSERT( "sys_init: not called first", tasks == NULL );\r
+    tasks = NULL;\r
+}\r
+\r
+/*\r
+ * This optional function does a "fast" critical region protection and returns\r
+ * the previous protection level. This function is only called during very short\r
+ * critical regions. An embedded system which supports ISR-based drivers might\r
+ * want to implement this function by disabling interrupts. Task-based systems\r
+ * might want to implement this by using a mutex or disabling tasking. This\r
+ * function should support recursive calls from the same task or interrupt. In\r
+ * other words, sys_arch_protect() could be called while already protected. In\r
+ * that case the return value indicates that it is already protected.\r
+ *\r
+ * sys_arch_protect() is only required if your port is supporting an operating\r
+ * system.\r
+ */\r
+sys_prot_t\r
+sys_arch_protect( void )\r
+{\r
+    vPortEnterCritical(  );\r
+    return 1;\r
+}\r
+\r
+/*\r
+ * This optional function does a "fast" set of critical region protection to the\r
+ * value specified by pval. See the documentation for sys_arch_protect() for\r
+ * more information. This function is only required if your port is supporting\r
+ * an operating system.\r
+ */\r
+void\r
+sys_arch_unprotect( sys_prot_t pval )\r
+{\r
+    ( void )pval;\r
+    vPortExitCritical(  );\r
+}\r
+\r
+/*\r
+ * Prints an assertion messages and aborts execution.\r
+ */\r
+void\r
+sys_assert( const char *msg )\r
+{      \r
+       /*FSL:only needed for debugging\r
+       printf(msg);\r
+       printf("\n\r");\r
+       */\r
+    vPortEnterCritical(  );\r
+    for(;;)\r
+    ;\r
+}\r
+\r
+void\r
+sys_debug( const char *const fmt, ... )\r
+{\r
+       /*FSL: same implementation as printf*/\r
+\r
+    /*FSL: removed due to lack of space*/\r
+    //printf(fmt);\r
+}\r
+\r
+/* ------------------------ Start implementation ( Threads ) -------------- */\r
+\r
+/*\r
+ * Starts a new thread with priority "prio" that will begin its execution in the\r
+ * function "thread()". The "arg" argument will be passed as an argument to the\r
+ * thread() function. The argument "ssize" is the requested stack size for the\r
+ * new thread. The id of the new thread is returned. Both the id and the\r
+ * priority are system dependent.\r
+ */\r
+sys_thread_t\r
+sys_thread_new(char *name, void ( *thread ) ( void *arg ), void *arg, int /*size_t*/ stacksize, int prio )\r
+{\r
+    sys_thread_t    thread_hdl = SYS_THREAD_NULL;\r
+    int             i;\r
+    sys_tcb_t      *p;\r
+\r
+    /* We disable the FreeRTOS scheduler because it might be the case that the new\r
+     * tasks gets scheduled inside the xTaskCreate function. To prevent this we\r
+     * disable the scheduling. Note that this can happen although we have interrupts\r
+     * disabled because xTaskCreate contains a call to taskYIELD( ).\r
+     */\r
+    vPortEnterCritical(  );\r
+\r
+    p = tasks;\r
+    i = 0;\r
+    /* We are called the first time. Initialize it. */\r
+    if( p == NULL )\r
+    {\r
+        p = (sys_tcb_t *)pvPortMalloc( sizeof( sys_tcb_t ) );\r
+        if( p != NULL )\r
+        {\r
+            tasks = p;\r
+        }\r
+    }\r
+    else\r
+    {\r
+        /* First task already counter. */\r
+        i++;\r
+        /* Cycle to the end of the list. */\r
+        while( p->next != NULL )\r
+        {\r
+            i++;\r
+            p = p->next;\r
+        }\r
+        p->next = (sys_tcb_t *)pvPortMalloc( sizeof( sys_tcb_t ) );\r
+        p = p->next;\r
+    }\r
+\r
+    if( p != NULL )\r
+    {\r
+        /* Memory allocated. Initialize the data structure. */\r
+        THREAD_INIT( p );\r
+\r
+        /* Now q points to a free element in the list. */\r
+        if( xTaskCreate( thread, (const signed char *const)name, stacksize, arg, prio, &p->pid ) == pdPASS )\r
+        {\r
+            thread_hdl = p;\r
+        }\r
+        else\r
+        {\r
+            vPortFree( p );\r
+        }\r
+    }\r
+\r
+    vPortExitCritical(  );\r
+    return thread_hdl;\r
+}\r
+\r
+void\r
+sys_arch_thread_remove( sys_thread_t hdl )\r
+{\r
+    sys_tcb_t      *current = tasks, *prev;\r
+    sys_tcb_t      *toremove = hdl;\r
+    xTaskHandle     pid = ( xTaskHandle ) 0;\r
+\r
+    LWIP_ASSERT( "sys_arch_thread_remove: assertion hdl != NULL failed!", hdl != NULL );\r
+\r
+    /* If we have to remove the first task we must update the global "tasks"\r
+     * variable. */\r
+    vPortEnterCritical(  );\r
+    if( hdl != NULL )\r
+    {\r
+        prev = NULL;\r
+        while( ( current != NULL ) && ( current != toremove ) )\r
+        {\r
+            prev = current;\r
+            current = current->next;\r
+        }\r
+        /* Found it. */\r
+        if( current == toremove )\r
+        {\r
+            /* Not the first entry in the list. */\r
+            if( prev != NULL )\r
+            {\r
+                prev->next = toremove->next;\r
+            }\r
+            else\r
+            {\r
+                tasks = toremove->next;\r
+            }\r
+            LWIP_ASSERT( "sys_arch_thread_remove: can't remove thread with timeouts!",\r
+                         toremove->timeouts.next == NULL );\r
+            pid = toremove->pid;\r
+            THREAD_INIT( toremove );\r
+            vPortFree( toremove );\r
+        }\r
+    }\r
+    /* We are done with accessing the shared datastructure. Release the \r
+     * resources.\r
+     */\r
+    vPortExitCritical(  );\r
+    if( pid != ( xTaskHandle ) 0 )\r
+    {\r
+        vTaskDelete( pid );\r
+        /* not reached. */\r
+    }\r
+}\r
+\r
+/*\r
+ * Returns the thread control block for the currently active task. In case\r
+ * of an error the functions returns NULL.\r
+ */\r
+sys_thread_t\r
+sys_arch_thread_current( void )\r
+{\r
+    sys_tcb_t      *p = tasks;\r
+    xTaskHandle     pid = xTaskGetCurrentTaskHandle(  );\r
+\r
+    vPortEnterCritical(  );\r
+    while( ( p != NULL ) && ( p->pid != pid ) )\r
+    {\r
+        p = p->next;\r
+    }\r
+    vPortExitCritical(  );\r
+    return p;\r
+}\r
+\r
+/*\r
+ * Returns a pointer to the per-thread sys_timeouts structure. In lwIP,\r
+ * each thread has a list of timeouts which is represented as a linked\r
+ * list of sys_timeout structures. The sys_timeouts structure holds a\r
+ * pointer to a linked list of timeouts. This function is called by\r
+ * the lwIP timeout scheduler and must not return a NULL value.\r
+ *\r
+ * In a single threaded sys_arch implementation, this function will\r
+ * simply return a pointer to a global sys_timeouts variable stored in\r
+ * the sys_arch module.\r
+ */\r
+struct sys_timeouts *\r
+sys_arch_timeouts( void )\r
+{\r
+    sys_tcb_t      *ptask;\r
+\r
+    ptask = sys_arch_thread_current(  );\r
+    LWIP_ASSERT( "sys_arch_timeouts: ptask != NULL", ptask != NULL );\r
+    return ptask != NULL ? &( ptask->timeouts ) : NULL;\r
+}\r
+\r
+/* ------------------------ Start implementation ( Semaphores ) ----------- */\r
+\r
+/* Creates and returns a new semaphore. The "count" argument specifies\r
+ * the initial state of the semaphore.\r
+ */\r
+sys_sem_t\r
+sys_sem_new( u8_t count )\r
+{\r
+    xSemaphoreHandle xSemaphore;\r
+\r
+    vSemaphoreCreateBinary( xSemaphore );\r
+    if( xSemaphore != SYS_SEM_NULL )\r
+    {\r
+        if( count == 0 )\r
+        {\r
+            xSemaphoreTake( xSemaphore, 1 );\r
+        }\r
+#if SYS_STATS == 1\r
+        vPortEnterCritical(  );\r
+        lwip_stats.sys.sem.used++;\r
+        if( lwip_stats.sys.sem.used > lwip_stats.sys.sem.max )\r
+        {\r
+            lwip_stats.sys.sem.max = lwip_stats.sys.sem.used;\r
+        }\r
+        vPortExitCritical(  );\r
+#endif\r
+    }\r
+    else\r
+    {\r
+        LWIP_ASSERT( "sys_sem_new: xSemaphore == SYS_SEM_NULL", xSemaphore != SYS_SEM_NULL );\r
+    }\r
+\r
+    return xSemaphore;\r
+}\r
+\r
+/* Deallocates a semaphore */\r
+void\r
+sys_sem_free( sys_sem_t sem )\r
+{\r
+    LWIP_ASSERT( "sys_sem_free: sem != SYS_SEM_NULL", sem != SYS_SEM_NULL );\r
+    if( sem != SYS_SEM_NULL )\r
+    {\r
+#if SYS_STATS == 1\r
+        vPortEnterCritical(  );\r
+        lwip_stats.sys.sem.used--;\r
+        vPortExitCritical(  );\r
+#endif\r
+        vQueueDelete( sem );\r
+    }\r
+}\r
+\r
+/* Signals a semaphore */\r
+void\r
+sys_sem_signal( sys_sem_t sem )\r
+{\r
+    LWIP_ASSERT( "sys_sem_signal: sem != SYS_SEM_NULL", sem != SYS_SEM_NULL );\r
+    xSemaphoreGive( sem );\r
+}\r
+\r
+/*\r
+ * Blocks the thread while waiting for the semaphore to be\r
+ * signaled. If the "timeout" argument is non-zero, the thread should\r
+ * only be blocked for the specified time (measured in\r
+ * milliseconds).\r
+ *\r
+ * If the timeout argument is non-zero, the return value is the number of\r
+ * milliseconds spent waiting for the semaphore to be signaled. If the\r
+ * semaphore wasn't signaled within the specified time, the return value is\r
+ * SYS_ARCH_TIMEOUT. If the thread didn't have to wait for the semaphore\r
+ * (i.e., it was already signaled), the function may return zero.\r
+ *\r
+ * Notice that lwIP implements a function with a similar name,\r
+ * sys_sem_wait(), that uses the sys_arch_sem_wait() function.\r
+ */\r
+u32_t\r
+sys_arch_sem_wait( sys_sem_t sem, u32_t timeout )\r
+{\r
+    portBASE_TYPE   xStatus;\r
+    portTickType    xTicksStart, xTicksEnd, xTicksElapsed;\r
+    u32_t           timespent;\r
+\r
+    LWIP_ASSERT( "sys_arch_sem_wait: sem != SYS_SEM_NULL", sem != SYS_SEM_NULL );\r
+    xTicksStart = xTaskGetTickCount(  );\r
+    if( timeout == 0 )\r
+    {\r
+        do\r
+        {\r
+            xStatus = xSemaphoreTake( sem, MS_TO_TICKS( 100 ) );\r
+        }\r
+        while( xStatus != pdTRUE );\r
+    }\r
+    else\r
+    {\r
+        xStatus = xSemaphoreTake( sem, MS_TO_TICKS( timeout ) );\r
+    }\r
+\r
+    /* Semaphore was signaled. */\r
+    if( xStatus == pdTRUE )\r
+    {\r
+        xTicksEnd = xTaskGetTickCount(  );\r
+        xTicksElapsed = xTicksEnd - xTicksStart;\r
+        timespent = TICKS_TO_MS( xTicksElapsed );\r
+    }\r
+    else\r
+    {\r
+        timespent = SYS_ARCH_TIMEOUT;\r
+    }\r
+    return timespent;\r
+}\r
+\r
+\r
+/* ------------------------ Start implementation ( Mailboxes ) ------------ */\r
+\r
+/* Creates an empty mailbox. */\r
+sys_mbox_t\r
+sys_mbox_new( /*paolo:void*/int size )\r
+{\r
+    xQueueHandle    mbox;\r
+\r
+    mbox = xQueueCreate( SYS_MBOX_SIZE/*size*/, sizeof( void * ) );\r
+    if( mbox != SYS_MBOX_NULL )\r
+    {\r
+#if SYS_STATS == 1\r
+        vPortEnterCritical(  );\r
+        lwip_stats.sys.mbox.used++;\r
+        if( lwip_stats.sys.mbox.used > lwip_stats.sys.mbox.max )\r
+        {\r
+            lwip_stats.sys.mbox.max = lwip_stats.sys.mbox.used;\r
+        }\r
+        vPortExitCritical(  );\r
+#endif\r
+    }\r
+    return mbox;\r
+}\r
+\r
+/*\r
+  Deallocates a mailbox. If there are messages still present in the\r
+  mailbox when the mailbox is deallocated, it is an indication of a\r
+  programming error in lwIP and the developer should be notified.\r
+*/\r
+void\r
+sys_mbox_free( sys_mbox_t mbox )\r
+{\r
+    void           *msg;\r
+\r
+    LWIP_ASSERT( "sys_mbox_free: mbox != SYS_MBOX_NULL", mbox != SYS_MBOX_NULL );\r
+    if( mbox != SYS_MBOX_NULL )\r
+    {\r
+        while( uxQueueMessagesWaiting( mbox ) != 0 )\r
+        {\r
+            if( sys_arch_mbox_fetch( mbox, &msg, 1 ) != SYS_ARCH_TIMEOUT )\r
+            {\r
+                LWIP_ASSERT( "sys_mbox_free: memory leak (msg != NULL)", msg == NULL );\r
+            }\r
+        }\r
+        vQueueDelete( mbox );\r
+#if SYS_STATS == 1\r
+        vPortEnterCritical(  );\r
+        lwip_stats.sys.mbox.used--;\r
+        vPortExitCritical(  );\r
+#endif\r
+    }\r
+}\r
+\r
+/*\r
+ * This function sends a message to a mailbox. It is unusual in that no error\r
+ * return is made. This is because the caller is responsible for ensuring that\r
+ * the mailbox queue will not fail. The caller does this by limiting the number\r
+ * of msg structures which exist for a given mailbox.\r
+ */\r
+void\r
+sys_mbox_post( sys_mbox_t mbox, void *data )\r
+{\r
+    portBASE_TYPE   xQueueSent;\r
+\r
+    /* Queue must not be full - Otherwise it is an error. */\r
+    xQueueSent = xQueueSend( mbox, &data, 0 );\r
+    LWIP_ASSERT( "sys_mbox_post: xQueueSent == pdPASS", xQueueSent == pdPASS );\r
+}\r
+\r
+/*FSL*/\r
+/*  \r
+ *Try to post the "msg" to the mailbox. Returns ERR_MEM if this one\r
+ *is full, else, ERR_OK if the "msg" is posted.\r
+ */\r
+err_t\r
+sys_mbox_trypost( sys_mbox_t mbox, void *data )\r
+{\r
+    /* Queue must not be full - Otherwise it is an error. */\r
+    if(xQueueSend( mbox, &data, 0 ) == pdPASS)\r
+    {\r
+       return ERR_OK;\r
+    }\r
+    else\r
+    {\r
+       return ERR_MEM;\r
+    }\r
+}\r
+\r
+/*\r
+ * Blocks the thread until a message arrives in the mailbox, but does\r
+ * not block the thread longer than "timeout" milliseconds (similar to\r
+ * the sys_arch_sem_wait() function). The "msg" argument is a result\r
+ * parameter that is set by the function (i.e., by doing "*msg =\r
+ * ptr"). The "msg" parameter maybe NULL to indicate that the message\r
+ * should be dropped.\r
+ *\r
+ * Note that a function with a similar name, sys_mbox_fetch(), is\r
+ * implemented by lwIP.\r
+ */\r
+u32_t\r
+sys_arch_mbox_fetch( sys_mbox_t mbox, void **msg, u32_t timeout )\r
+{\r
+    void           *ret_msg;\r
+    portBASE_TYPE   xStatus;\r
+    portTickType    xTicksStart, xTicksEnd, xTicksElapsed;\r
+    u32_t           timespent;\r
+\r
+    LWIP_ASSERT( "sys_arch_mbox_fetch: mbox != SYS_MBOX_NULL", mbox != SYS_MBOX_NULL );\r
+    xTicksStart = xTaskGetTickCount(  );\r
+    if( timeout == 0 )\r
+    {\r
+        do\r
+        {\r
+            xStatus = xQueueReceive( mbox, &ret_msg, MS_TO_TICKS( 100 ) );\r
+        }\r
+        while( xStatus != pdTRUE );\r
+    }\r
+    else\r
+    {\r
+        xStatus = xQueueReceive( mbox, &ret_msg, MS_TO_TICKS( timeout ) );\r
+    }\r
+\r
+    if( xStatus == pdTRUE )\r
+    {\r
+        if( msg )\r
+        {\r
+            *msg = ret_msg;\r
+        }\r
+        xTicksEnd = xTaskGetTickCount(  );\r
+        xTicksElapsed = xTicksEnd - xTicksStart;\r
+        timespent = TICKS_TO_MS( xTicksElapsed );\r
+    }\r
+    else\r
+    {\r
+        if( msg )\r
+        {\r
+            *msg = NULL;\r
+        }\r
+        timespent = SYS_ARCH_TIMEOUT;\r
+    }\r
+    return timespent;\r
+}\r
+\r
+u32_t\r
+sys_jiffies( void )\r
+{\r
+    portTickType    xTicks = xTaskGetTickCount(  );\r
+\r
+    return ( u32_t )TICKS_TO_MS( xTicks );\r
+}\r
diff --git a/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/arch/cc.h b/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/arch/cc.h
new file mode 100644 (file)
index 0000000..1317768
--- /dev/null
@@ -0,0 +1,79 @@
+/*\r
+ * Copyright (c) 2001-2003 Swedish Institute of Computer Science.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without modification,\r
+ * are permitted provided that the following conditions are met:\r
+ *\r
+ * 1. Redistributions of source code must retain the above copyright notice,\r
+ *    this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright notice,\r
+ *    this list of conditions and the following disclaimer in the documentation\r
+ *    and/or other materials provided with the distribution.\r
+ * 3. The name of the author may not be used to endorse or promote products\r
+ *    derived from this software without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED\r
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF\r
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT\r
+ * SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,\r
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT\r
+ * OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\r
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\r
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING\r
+ * IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY\r
+ * OF SUCH DAMAGE.\r
+ *\r
+ * This file is part of the lwIP TCP/IP stack.\r
+ *\r
+ * Author: Adam Dunkels <adam@sics.se>\r
+ * Modifcations: Christian Walter <wolti@sil.at>\r
+ */\r
+#ifndef __CC_H__\r
+#define __CC_H__\r
+\r
+/* ------------------------ System includes ------------------------------- */\r
+\r
+/* ------------------------ Project includes ------------------------------ */\r
+#include "cpu.h"\r
+#include "sys_arch.h"\r
+\r
+/* ------------------------ Defines --------------------------------------- */\r
+\r
+//#pragma options align= packed\r
+#define PACK_STRUCT_BEGIN              \r
+#define PACK_STRUCT_STRUCT      //non CW compatible: __attribute__ ((__packed__))\r
+#define PACK_STRUCT_END\r
+\r
+#define PACK_STRUCT_FIELD( x )  x\r
+\r
+/*FSL: non used on code:\r
+#define ALIGN_STRUCT_8_BEGIN\r
+#define ALIGN_STRUCT_8          //non CW compatible: __attribute__ ((aligned (8)))\r
+#define ALIGN_STRUCT_8_END\r
+*/\r
+\r
+#define LWIP_PLATFORM_ASSERT( x ) sys_assert( x )\r
+#define LWIP_PLATFORM_DIAG( x, ... ) do{ sys_debug x; } while( 0 );\r
+\r
+/* Define (sn)printf formatters for these lwIP types */\r
+#define U16_F                   "hu"\r
+#define S16_F                   "hd"\r
+#define X16_F                   "hx"\r
+#define U32_F                   "lu"\r
+#define S32_F                   "ld"\r
+#define X32_F                   "lx"\r
+\r
+/* ------------------------ Type definitions (lwIP) ----------------------- */\r
+typedef unsigned char u8_t;\r
+typedef signed char s8_t;\r
+typedef unsigned short u16_t;\r
+typedef signed short s16_t;\r
+typedef unsigned long u32_t;\r
+typedef signed long s32_t;\r
+typedef u32_t   mem_ptr_t;\r
+typedef int     sys_prot_t;\r
+\r
+/* ------------------------ Prototypes ------------------------------------ */\r
+\r
+#endif\r
diff --git a/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/arch/cpu.h b/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/arch/cpu.h
new file mode 100644 (file)
index 0000000..fcdb1bc
--- /dev/null
@@ -0,0 +1,38 @@
+/*\r
+ * Copyright (c) 2001-2003 Swedish Institute of Computer Science.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without modification,\r
+ * are permitted provided that the following conditions are met:\r
+ *\r
+ * 1. Redistributions of source code must retain the above copyright notice,\r
+ *    this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright notice,\r
+ *    this list of conditions and the following disclaimer in the documentation\r
+ *    and/or other materials provided with the distribution.\r
+ * 3. The name of the author may not be used to endorse or promote products\r
+ *    derived from this software without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED\r
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF\r
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT\r
+ * SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,\r
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT\r
+ * OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\r
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\r
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING\r
+ * IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY\r
+ * OF SUCH DAMAGE.\r
+ *\r
+ * This file is part of the lwIP TCP/IP stack.\r
+ *\r
+ * Author: Adam Dunkels <adam@sics.se>\r
+ *\r
+ */\r
+#ifndef __CPU_H__\r
+#define __CPU_H__\r
+\r
+/* ------------------------ Defines --------------------------------------- */\r
+#define BYTE_ORDER BIG_ENDIAN\r
+\r
+#endif\r
diff --git a/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/arch/perf.h b/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/arch/perf.h
new file mode 100644 (file)
index 0000000..5c58a65
--- /dev/null
@@ -0,0 +1,39 @@
+/*\r
+ * Copyright (c) 2001-2003 Swedish Institute of Computer Science.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without modification,\r
+ * are permitted provided that the following conditions are met:\r
+ *\r
+ * 1. Redistributions of source code must retain the above copyright notice,\r
+ *    this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright notice,\r
+ *    this list of conditions and the following disclaimer in the documentation\r
+ *    and/or other materials provided with the distribution.\r
+ * 3. The name of the author may not be used to endorse or promote products\r
+ *    derived from this software without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED\r
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF\r
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT\r
+ * SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,\r
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT\r
+ * OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\r
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\r
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING\r
+ * IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY\r
+ * OF SUCH DAMAGE.\r
+ *\r
+ * This file is part of the lwIP TCP/IP stack.\r
+ *\r
+ * Author: Adam Dunkels <adam@sics.se>\r
+ *\r
+ */\r
+#ifndef __PERF_H__\r
+#define __PERF_H__\r
+\r
+/* ------------------------ Defines --------------------------------------- */\r
+#define PERF_START              /* null definition */\r
+#define PERF_STOP(x)            /* null definition */\r
+\r
+#endif\r
diff --git a/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/arch/sys_arch.h b/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/arch/sys_arch.h
new file mode 100644 (file)
index 0000000..7b87a9f
--- /dev/null
@@ -0,0 +1,51 @@
+/*\r
+ * Copyright (c) 2001-2003 Swedish Institute of Computer Science.\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without modification,\r
+ * are permitted provided that the following conditions are met:\r
+ *\r
+ * 1. Redistributions of source code must retain the above copyright notice,\r
+ *    this list of conditions and the following disclaimer.\r
+ * 2. Redistributions in binary form must reproduce the above copyright notice,\r
+ *    this list of conditions and the following disclaimer in the documentation\r
+ *    and/or other materials provided with the distribution.\r
+ * 3. The name of the author may not be used to endorse or promote products\r
+ *    derived from this software without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED\r
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF\r
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT\r
+ * SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,\r
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT\r
+ * OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\r
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\r
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING\r
+ * IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY\r
+ * OF SUCH DAMAGE.\r
+ *\r
+ * This file is part of the lwIP TCP/IP stack.\r
+ *\r
+ * Author: Adam Dunkels <adam@sics.se>\r
+ *\r
+ */\r
+#ifndef __SYS_RTXC_H__\r
+#define __SYS_RTXC_H__\r
+\r
+#include "FreeRTOS.h"\r
+#include "task.h"\r
+#include "queue.h"\r
+#include "semphr.h"\r
+\r
+#define SYS_MBOX_NULL (xQueueHandle)0\r
+#define SYS_SEM_NULL  (xSemaphoreHandle)0\r
+\r
+typedef xSemaphoreHandle sys_sem_t;\r
+typedef xQueueHandle sys_mbox_t;\r
+typedef xTaskHandle sys_thread_t;\r
+\r
+/* Message queue constants. */\r
+#define archMESG_QUEUE_LENGTH  ( 6 )\r
+#define archPOST_BLOCK_TIME_MS ( ( unsigned portLONG ) 10000 )\r
+\r
+#endif\r
diff --git a/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/eth.h b/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/eth.h
new file mode 100644 (file)
index 0000000..6b0b664
--- /dev/null
@@ -0,0 +1,55 @@
+/*! \r
+ * \file    eth.h\r
+ * \brief   Definitinos for Ethernet Frames\r
+ * \version $Revision: 1.2 $\r
+ * \author  Michael Norman\r
+ */\r
+\r
+#ifndef _ETH_H\r
+#define _ETH_H\r
+\r
+/*******************************************************************/\r
+\r
+/* Ethernet standard lengths in bytes*/\r
+#define ETH_ADDR_LEN    (6)\r
+#define ETH_TYPE_LEN    (2)\r
+#define ETH_CRC_LEN     (4)\r
+#define ETH_MAX_DATA    (1500)\r
+#define ETH_MIN_DATA    (46)\r
+#define ETH_HDR_LEN     (ETH_ADDR_LEN * 2 + ETH_TYPE_LEN)\r
+\r
+/* Defined Ethernet Frame Types */\r
+#define ETH_FRM_IP      (0x0800)\r
+#define ETH_FRM_ARP     (0x0806)\r
+#define ETH_FRM_RARP    (0x8035)\r
+#define ETH_FRM_TEST    (0xA5A5)\r
+\r
+/* Maximum and Minimum Ethernet Frame Sizes */\r
+#define ETH_MAX_FRM     (ETH_HDR_LEN + ETH_MAX_DATA + ETH_CRC_LEN)\r
+#define ETH_MIN_FRM     (ETH_HDR_LEN + ETH_MIN_DATA + ETH_CRC_LEN)\r
+#define ETH_MTU         (ETH_HDR_LEN + ETH_MAX_DATA)\r
+\r
+/* Ethernet Addresses */\r
+typedef uint8 ETH_ADDR[ETH_ADDR_LEN];\r
+\r
+/* 16-bit Ethernet Frame Type, ie. Protocol */\r
+typedef uint16 ETH_FRM_TYPE;\r
+\r
+/* Ethernet Frame Header definition */\r
+typedef struct\r
+{\r
+    ETH_ADDR     dest;\r
+    ETH_ADDR     src;\r
+    ETH_FRM_TYPE type;\r
+} ETH_HDR;\r
+\r
+/* Ethernet Frame definition */\r
+typedef struct\r
+{\r
+    ETH_HDR head;\r
+    uint8*  data;\r
+} ETH_FRAME;\r
+\r
+/*******************************************************************/\r
+\r
+#endif  /* _ETH_H */\r
diff --git a/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/eth_phy.h b/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/eth_phy.h
new file mode 100644 (file)
index 0000000..9242e10
--- /dev/null
@@ -0,0 +1,87 @@
+/*!\r
+ * \file    eth.h\r
+ * \brief   Definitions for Ethernet Physical Layer Interface\r
+ * \version $Revision: 1.3 $\r
+ * \author  Michael Norman\r
+ */\r
+\r
+#ifndef _ETH_PHY_H\r
+#define _ETH_PHY_H\r
+\r
+/*******************************************************************/\r
+\r
+int\r
+eth_phy_autoneg(int phy_addr, MII_SPEED speed, MII_DUPLEX duplex);\r
+\r
+int \r
+eth_phy_manual(int phy_addr, MII_SPEED speed, MII_DUPLEX duplex, int loop);\r
+\r
+int \r
+eth_phy_get_speed(int, int*);\r
+\r
+int \r
+eth_phy_get_duplex(int, int*);\r
+\r
+int \r
+eth_phy_reg_dump(int);\r
+\r
+/*******************************************************************/\r
+\r
+/* MII Register Addresses */\r
+#define PHY_BMCR                                   (0x00)\r
+#define PHY_BMSR                    (0x01)\r
+#define PHY_PHYIDR1                                (0x02)\r
+#define PHY_PHYIDR2                                (0x03)\r
+#define PHY_ANAR                                   (0x04)\r
+#define PHY_ANLPAR                         (0x05)\r
+\r
+/* Bit definitions and macros for PHY_CTRL */\r
+#define PHY_BMCR_RESET                 (0x8000)\r
+#define PHY_BMCR_LOOP                      (0x4000)\r
+#define PHY_BMCR_SPEED                 (0x2000)\r
+#define PHY_BMCR_AN_ENABLE                 (0x1000)\r
+#define PHY_BMCR_POWERDOWN         (0x0800)\r
+#define PHY_BMCR_ISOLATE               (0x0400)\r
+#define PHY_BMCR_AN_RESTART            (0x0200)\r
+#define PHY_BMCR_FDX                       (0x0100)\r
+#define PHY_BMCR_COL_TEST              (0x0080)\r
+\r
+/* Bit definitions and macros for PHY_STAT */\r
+#define PHY_BMSR_100BT4             (0x8000)\r
+#define PHY_BMSR_100BTX_FDX         (0x4000)\r
+#define PHY_BMSR_100BTX             (0x2000)\r
+#define PHY_BMSR_10BT_FDX           (0x1000)\r
+#define PHY_BMSR_10BT               (0x0800)\r
+#define PHY_BMSR_NO_PREAMBLE        (0x0040)\r
+#define PHY_BMSR_AN_COMPLETE        (0x0020)\r
+#define PHY_BMSR_REMOTE_FAULT       (0x0010)\r
+#define PHY_BMSR_AN_ABILITY         (0x0008)\r
+#define PHY_BMSR_LINK               (0x0004)\r
+#define PHY_BMSR_JABBER             (0x0002)\r
+#define PHY_BMSR_EXTENDED           (0x0001)\r
+\r
+/* Bit definitions and macros for PHY_AN_ADV */\r
+#define PHY_ANAR_NEXT_PAGE          (0x8001)\r
+#define PHY_ANAR_REM_FAULT             (0x2001)\r
+#define PHY_ANAR_PAUSE                 (0x0401)\r
+#define PHY_ANAR_100BT4                        (0x0201)\r
+#define PHY_ANAR_100BTX_FDX            (0x0101)\r
+#define PHY_ANAR_100BTX                        (0x0081)\r
+#define PHY_ANAR_10BT_FDX                  (0x0041)\r
+#define PHY_ANAR_10BT                  (0x0021)\r
+#define PHY_ANAR_802_3                 (0x0001)\r
+\r
+/* Bit definitions and macros for PHY_AN_LINK_PAR */\r
+#define PHY_ANLPAR_NEXT_PAGE        (0x8000)\r
+#define PHY_ANLPAR_ACK              (0x4000)\r
+#define PHY_ANLPAR_REM_FAULT       (0x2000)\r
+#define PHY_ANLPAR_PAUSE                   (0x0400)\r
+#define PHY_ANLPAR_100BT4                  (0x0200)\r
+#define PHY_ANLPAR_100BTX_FDX      (0x0100)\r
+#define PHY_ANLPAR_100BTX                  (0x0080)\r
+#define PHY_ANLPAR_10BTX_FDX        (0x0040)\r
+#define PHY_ANLPAR_10BT                        (0x0020)\r
+\r
+/*******************************************************************/\r
+\r
+#endif  /* _ETH_PHY_H */\r
diff --git a/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/fec.h b/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/fec.h
new file mode 100644 (file)
index 0000000..ebca2bb
--- /dev/null
@@ -0,0 +1,166 @@
+/*\r
+ * File:    fec.h\r
+ * Purpose: Driver for the Fast Ethernet Controller (FEC)\r
+ *\r
+ * Notes:       \r
+ */\r
+\r
+#ifndef _FEC_H_\r
+#define _FEC_H_\r
+\r
+#include "eth.h"\r
+#include "fecbd.h"\r
+#include "mii.h"\r
+#include "eth_phy.h"\r
+\r
+/********************************************************************/\r
+\r
+/* External Interface Modes */\r
+#define FEC_MODE_7WIRE          0   /* Old 7-wire (AMD) mode */\r
+#define FEC_MODE_MII            1   /* Media Independent Interface */\r
+#define FEC_MODE_RMII           2   /* Reduced MII */\r
+#define FEC_MODE_LOOPBACK       3   /* Internal Loopback */\r
+\r
+#define INTC_LVL_FEC                   3\r
+/*\r
+ * FEC Configuration Parameters\r
+ */\r
+typedef struct \r
+{\r
+    uint8      ch;       /* FEC channel              */\r
+    uint8      mode;     /* Transceiver mode         */\r
+    MII_SPEED  speed;    /* Ethernet Speed           */\r
+    MII_DUPLEX duplex;   /* Ethernet Duplex          */\r
+    uint8      prom;     /* Promiscuous Mode?        */\r
+    uint8      mac[6];   /* Ethernet Address         */\r
+    uint8      phyaddr;  /* PHY address              */\r
+    uint8      initphy;  /* Init PHY?                */\r
+    int        nrxbd;    /* Number of RxBDs          */\r
+    int        ntxbd;    /* Number of TxBDs          */\r
+} FEC_CONFIG;\r
+#define YES 1\r
+#define NO 0\r
+/*\r
+ * FEC Event Log\r
+ */\r
+typedef struct {\r
+    int errors;     /* total count of errors   */\r
+    int hberr;      /* heartbeat error         */\r
+    int babr;       /* babbling receiver       */\r
+    int babt;       /* babbling transmitter    */\r
+    int gra;        /* graceful stop complete  */\r
+    int txf;        /* transmit frame          */\r
+    int txb;        /* transmit buffer         */\r
+    int rxf;        /* receive frame           */\r
+    int rxb;        /* received buffer         */\r
+    int mii;        /* MII                     */\r
+    int eberr;      /* FEC/DMA fatal bus error */\r
+    int lc;         /* late collision          */\r
+    int rl;         /* collision retry limit   */\r
+    int un;         /* Tx FIFO underflow       */\r
+    int rfsw_inv;   /* Invalid bit in RFSW     */\r
+    int rfsw_l;     /* RFSW Last in Frame      */\r
+    int rfsw_m;     /* RFSW Miss               */\r
+    int rfsw_bc;    /* RFSW Broadcast          */\r
+    int rfsw_mc;    /* RFSW Multicast          */\r
+    int rfsw_lg;    /* RFSW Length Violation   */\r
+    int rfsw_no;    /* RFSW Non-octet          */\r
+    int rfsw_cr;    /* RFSW Bad CRC            */\r
+    int rfsw_ov;    /* RFSW Overflow           */\r
+    int rfsw_tr;    /* RFSW Truncated          */\r
+} FEC_EVENT_LOG;\r
+\r
+#if 0\r
+\r
+int \r
+fec_mii_write( int, int, int);\r
+\r
+int \r
+fec_mii_read(int, int, uint16*);\r
+\r
+void\r
+fec_mii_init(int, int);\r
+\r
+void\r
+fec_mib_init(void);\r
+\r
+void\r
+fec_mib_dump(void);\r
+\r
+void\r
+fec_log_init(int);\r
+\r
+void\r
+fec_log_dump(int);\r
+\r
+void\r
+fec_reg_dump(int);\r
+\r
+void\r
+fec_duplex (int, MII_DUPLEX);\r
+\r
+void\r
+fec_rmii_speed (int, MII_SPEED);\r
+\r
+uint8\r
+fec_hash_address(const uint8*);\r
+\r
+void\r
+fec_set_address (const uint8*);\r
+\r
+void\r
+fec_reset ( void );\r
+\r
+void\r
+fec_init (int, const uint8*);\r
+\r
+void\r
+fec_rx_start(int, uint8*, int);\r
+\r
+void\r
+fec_rx_continue( void );\r
+\r
+void\r
+fec_rx_handler(void);\r
+\r
+void\r
+fec0_rx_handler(void);\r
+\r
+void\r
+fec1_rx_handler(void);\r
+\r
+void\r
+fec_tx_continue( void );\r
+\r
+void\r
+fec_tx_stop (int);\r
+\r
+void\r
+fec_tx_handler(NIF*, int);\r
+\r
+int\r
+fec_send (uint8*, uint8*, uint16 , NBUF*);\r
+\r
+int\r
+fec0_send(uint8*, uint8*, uint16 , NBUF*);\r
+\r
+int\r
+fec1_send(uint8*, uint8*, uint16 , NBUF*);\r
+\r
+void\r
+fec_irq_enable( void );\r
+\r
+void\r
+fec_irq_disable(int);\r
+\r
+int\r
+fec_eth_start(FEC_CONFIG*, int);\r
+\r
+void\r
+fec_eth_stop(int);\r
+\r
+#endif\r
+\r
+/********************************************************************/\r
+\r
+#endif /* _FEC_H_ */\r
diff --git a/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/fecbd.h b/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/fecbd.h
new file mode 100644 (file)
index 0000000..546b2ce
--- /dev/null
@@ -0,0 +1,101 @@
+/*\r
+ * File:    fecbd.h\r
+ * Purpose:     \r
+ *\r
+ * Purpose: Provide a simple buffer management driver\r
+ */\r
+\r
+#ifndef _FECBD_H_\r
+#define _FECBD_H_\r
+\r
+/********************************************************************/\r
+\r
+#define Rx  1\r
+#define Tx  0\r
+\r
+/*\r
+ * Buffer sizes in bytes \r
+ */\r
+#ifndef RX_BUF_SZ\r
+#define RX_BUF_SZ  1520 //2048 \r
+#endif\r
+#ifndef TX_BUF_SZ\r
+#define TX_BUF_SZ  1520\r
+#endif\r
+\r
+/* \r
+ * Buffer Descriptor Format \r
+ */\r
+#pragma options align= packed\r
+typedef struct\r
+{\r
+    uint16 status;  /* control and status */\r
+    uint16 length;  /* transfer length */\r
+    uint8  *data;   /* buffer address */\r
+} FECBD;\r
+\r
+/*\r
+ * Bit level definitions for status field of buffer descriptors\r
+ */\r
+#define TX_BD_R         0x8000\r
+#define TX_BD_TO1       0x4000\r
+#define TX_BD_W         0x2000\r
+#define TX_BD_TO2       0x1000\r
+#define TX_BD_INTERRUPT 0x1000  /* MCF547x/8x Only */\r
+#define TX_BD_L         0x0800\r
+#define TX_BD_TC        0x0400\r
+#define TX_BD_DEF       0x0200  /* MCF5272 Only */\r
+#define TX_BD_ABC       0x0200\r
+#define TX_BD_HB        0x0100  /* MCF5272 Only */\r
+#define TX_BD_LC        0x0080  /* MCF5272 Only */\r
+#define TX_BD_RL        0x0040  /* MCF5272 Only */\r
+#define TX_BD_UN        0x0002  /* MCF5272 Only */\r
+#define TX_BD_CSL       0x0001  /* MCF5272 Only */\r
+\r
+#define RX_BD_E         0x8000\r
+#define RX_BD_R01       0x4000\r
+#define RX_BD_W         0x2000\r
+#define RX_BD_R02       0x1000\r
+#define RX_BD_INTERRUPT 0x1000  /* MCF547x/8x Only */\r
+#define RX_BD_L         0x0800\r
+#define RX_BD_M         0x0100\r
+#define RX_BD_BC        0x0080\r
+#define RX_BD_MC        0x0040\r
+#define RX_BD_LG        0x0020\r
+#define RX_BD_NO        0x0010\r
+#define RX_BD_CR        0x0004\r
+#define RX_BD_OV        0x0002\r
+#define RX_BD_TR        0x0001\r
+#define RX_BD_ERROR     (RX_BD_NO | RX_BD_CR | RX_BD_OV | RX_BD_TR)\r
+\r
+/*\r
+ * The following defines are provided by the MCF547x/8x \r
+ * DMA API.  These are shown here to show their correlation\r
+ * to the other FEC buffer descriptor status bits\r
+ * \r
+ * #define MCD_FEC_BUF_READY   0x8000\r
+ * #define MCD_FEC_WRAP        0x2000\r
+ * #define MCD_FEC_INTERRUPT   0x1000\r
+ * #define MCD_FEC_END_FRAME   0x0800\r
+ */\r
+\r
+/* \r
+ * Functions provided in fec_bd.c \r
+ */\r
+int     fecbd_init(int, int, int);\r
+void    fecbd_flush(int);\r
+void    fecbd_dump( void );\r
+uint32  fecbd_get_start(int, int);\r
+FECBD*  fecbd_rx_alloc(int);\r
+FECBD*  fecbd_tx_alloc(int);\r
+FECBD*  fecbd_tx_free(int);\r
+\r
+/*\r
+ * Error codes\r
+ */\r
+#define ERR_MALLOC      (-1)\r
+#define ERR_NBUFALLOC   (-2)\r
+\r
+/*******************************************************************/\r
+\r
+#endif /* _FECBD_H_ */\r
diff --git a/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/mii.h b/Demo/Common/ethernet/lwIP_130/contrib/port/FreeRTOS/ColdFire/mii.h
new file mode 100644 (file)
index 0000000..26b2793
--- /dev/null
@@ -0,0 +1,43 @@
+/*!\r
+ * \file    mii.h\r
+ * \brief   Media Independent Interface (MII) driver\r
+ * \version $Revision: 1.3 $\r
+ * \author  Michael Norman\r
+ * \r
+ * \warning This driver assumes that FEC0 is used for all MII management\r
+ *          communications.  For dual PHYs, etc., insure that FEC0_MDC and\r
+ *          FEC0_MDIO are connected to the PHY's MDC and MDIO.\r
+ */\r
+\r
+#ifndef _MII_H_\r
+#define _MII_H_\r
+\r
+/*******************************************************************/\r
+\r
+int\r
+mii_write(int, int, uint16);\r
+\r
+int\r
+mii_read(int, int, uint16*);\r
+\r
+void\r
+mii_init(int);\r
+\r
+/* MII Speed Settings */\r
+typedef enum {\r
+       MII_10BASE_T,   /*!< 10Base-T  operation */\r
+       MII_100BASE_TX  /*!< 100Base-TX operation */\r
+} MII_SPEED;\r
+\r
+/* MII Duplex Settings */\r
+typedef enum {\r
+       MII_HDX,                /*!< half-duplex */\r
+       MII_FDX                 /*!< full-duplex */\r
+} MII_DUPLEX;\r
+\r
+#define MII_TIMEOUT                0x10000\r
+#define MII_LINK_TIMEOUT       0x10000\r
+\r
+/*******************************************************************/\r
+\r
+#endif /* _MII_H_ */\r