]> git.sur5r.net Git - freertos/blobdiff - Demo/ColdFire_MCF52233_Eclipse/RTOSDemo/webserver/FEC.c
Remove unnecessary use of portLONG, portCHAR and portSHORT.
[freertos] / Demo / ColdFire_MCF52233_Eclipse / RTOSDemo / webserver / FEC.c
index 5e82b8223f682a4910e5b8fc93493b29c06e9096..339619521cfd9a147d6dfa8fc1675aff92d432f3 100644 (file)
@@ -1,33 +1,49 @@
 /*\r
-       FreeRTOS.org V5.1.0 - Copyright (C) 2003-2008 Richard Barry.\r
-\r
-       This file is part of the FreeRTOS.org distribution.\r
-\r
-       FreeRTOS.org is free software; you can redistribute it and/or modify\r
-       it under the terms of the GNU General Public License as published by\r
-       the Free Software Foundation; either version 2 of the License, or\r
-       (at your option) any later version.\r
-\r
-       FreeRTOS.org is distributed in the hope that it will be useful,\r
-       but WITHOUT ANY WARRANTY; without even the implied warranty of\r
-       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\r
-       GNU General Public License for more details.\r
-\r
-       You should have received a copy of the GNU General Public License\r
-       along with FreeRTOS.org; if not, write to the Free Software\r
-       Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA\r
-\r
-       A special exception to the GPL can be applied should you wish to distribute\r
-       a combined work that includes FreeRTOS.org, without being obliged to provide\r
-       the source code for any proprietary components.  See the licensing section\r
-       of http://www.FreeRTOS.org for full details of how and when the exception\r
-       can be applied.\r
-\r
-       ***************************************************************************\r
-       See http://www.FreeRTOS.org for documentation, latest information, license\r
-       and contact details.  Please ensure to read the configuration and relevant\r
-       port sections of the online documentation.\r
-       ***************************************************************************\r
+    FreeRTOS V6.0.0 - Copyright (C) 2009 Real Time Engineers Ltd.\r
+\r
+    This file is part of the FreeRTOS distribution.\r
+\r
+    FreeRTOS is free software; you can redistribute it and/or modify it    under\r
+    the terms of the GNU General Public License (version 2) as published by the\r
+    Free Software Foundation and modified by the FreeRTOS exception.\r
+    **NOTE** The exception to the GPL is included to allow you to distribute a\r
+    combined work that includes FreeRTOS without being obliged to provide the\r
+    source code for proprietary components outside of the FreeRTOS kernel.\r
+    Alternative commercial license and support terms are also available upon\r
+    request.  See the licensing section of http://www.FreeRTOS.org for full\r
+    license details.\r
+\r
+    FreeRTOS is distributed in the hope that it will be useful,    but WITHOUT\r
+    ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or\r
+    FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for\r
+    more details.\r
+\r
+    You should have received a copy of the GNU General Public License along\r
+    with FreeRTOS; if not, write to the Free Software Foundation, Inc., 59\r
+    Temple Place, Suite 330, Boston, MA  02111-1307  USA.\r
+\r
+\r
+    ***************************************************************************\r
+    *                                                                         *\r
+    * The FreeRTOS eBook and reference manual are available to purchase for a *\r
+    * small fee. Help yourself get started quickly while also helping the     *\r
+    * FreeRTOS project! See http://www.FreeRTOS.org/Documentation for details *\r
+    *                                                                         *\r
+    ***************************************************************************\r
+\r
+    1 tab == 4 spaces!\r
+\r
+    Please ensure to read the configuration and relevant port sections of the\r
+    online documentation.\r
+\r
+    http://www.FreeRTOS.org - Documentation, latest information, license and\r
+    contact details.\r
+\r
+    http://www.SafeRTOS.com - A version that is certified for use in safety\r
+    critical systems.\r
+\r
+    http://www.OpenRTOS.com - Commercial support, development, porting,\r
+    licensing and training services.\r
 */\r
 \r
 /* Kernel includes. */\r
@@ -35,7 +51,7 @@
 #include "semphr.h"\r
 #include "task.h"\r
 \r
-/* Demo includes. */\r
+/* Hardware includes. */\r
 #include "fecbd.h"\r
 #include "mii.h"\r
 #include "eth_phy.h"\r
@@ -45,9 +61,6 @@
 #include "uip.h"\r
 #include "uip_arp.h"\r
 \r
-#define MCF_FEC_MSCR_MII_SPEED(x)              (((x)&0x3F)<<0x1)\r
-#define MCF_FEC_RCR_MAX_FL(x)                  (((x)&0x7FF)<<0x10)\r
-\r
 /* Delay between polling the PHY to see if a link has been established. */\r
 #define fecLINK_DELAY                                                  ( 500 / portTICK_RATE_MS )\r
 \r
 #define fecMII_DELAY                                                   ( 10 / portTICK_RATE_MS )\r
 #define fecMAX_POLLS                                                   ( 20 )\r
 \r
-/* Delay between looking for incoming packets.  In ideal world this would be\r
-infinite. */\r
-#define netifBLOCK_TIME_WAITING_FOR_INPUT              fecLINK_DELAY\r
-\r
 /* Constants used to delay while waiting for a tx descriptor to be free. */\r
-#define fecTX_BUFFER_WAIT                                              ( 200 / portTICK_RATE_MS )\r
+#define fecMAX_WAIT_FOR_TX_BUFFER                                              ( 200 / portTICK_RATE_MS )\r
 \r
-/* We only use a single Tx descriptor - the duplicate send silicon errata\r
-actually assists in this case. */\r
+/* We only use a single Tx descriptor which can lead to Txed packets being sent\r
+twice (due to a bug in the FEC silicon).  However, in this case the bug is used\r
+to our advantage in that it means the uip-split mechanism is not required. */\r
 #define fecNUM_FEC_TX_BUFFERS                                  ( 1 )\r
 #define fecTX_BUFFER_TO_USE                                            ( 0 )\r
 /*-----------------------------------------------------------*/\r
@@ -72,7 +82,7 @@ actually assists in this case. */
 xSemaphoreHandle xFECSemaphore = NULL, xTxSemaphore = NULL;\r
 \r
 /* The buffer used by the uIP stack.  In this case the pointer is used to\r
-point to one of the Rx buffers. */\r
+point to one of the Rx buffers to effect a zero copy policy. */\r
 unsigned portCHAR *uip_buf;\r
 \r
 /* The DMA descriptors.  This is a char array to allow us to align it correctly. */\r
@@ -81,17 +91,27 @@ static unsigned portCHAR xFECRxDescriptors_unaligned[ ( configNUM_FEC_RX_BUFFERS
 static FECBD *xFECTxDescriptors;\r
 static FECBD *xFECRxDescriptors;\r
 \r
-/* The DMA buffers.  These are char arrays to allow them to be alligned correctly. */\r
+/* The DMA buffers.  These are char arrays to allow them to be aligned correctly. */\r
 static unsigned portCHAR ucFECRxBuffers[ ( configNUM_FEC_RX_BUFFERS * configFEC_BUFFER_SIZE ) + 16 ];\r
 static unsigned portBASE_TYPE uxNextRxBuffer = 0, uxIndexToBufferOwner = 0;\r
 \r
 /*-----------------------------------------------------------*/\r
 \r
+/*\r
+ * Enable all the required interrupts in the FEC and in the interrupt controller.\r
+ */\r
 static void prvEnableFECInterrupts( void );\r
+\r
+/*\r
+ * Reset the FEC if we get into an unrecoverable state.\r
+ */\r
 static void prvResetFEC( portBASE_TYPE xCalledFromISR );\r
 \r
 /********************************************************************/\r
+\r
 /*\r
+ * FUNCTION ADAPTED FROM FREESCALE SUPPLIED SOURCE\r
+ *\r
  * Write a value to a PHY's MII register.\r
  *\r
  * Parameters:\r
@@ -157,6 +177,8 @@ uint32 eimr;
 \r
 /********************************************************************/\r
 /*\r
+ * FUNCTION ADAPTED FROM FREESCALE SUPPLIED SOURCE\r
+ *\r
  * Read a value from a PHY's MII register.\r
  *\r
  * Parameters:\r
@@ -225,6 +247,8 @@ uint32 eimr;
 \r
 /********************************************************************/\r
 /*\r
+ * FUNCTION ADAPTED FROM FREESCALE SUPPLIED SOURCE\r
+ *\r
  * Generate the hash table settings for the given address\r
  *\r
  * Parameters:\r
@@ -264,6 +288,8 @@ int i, j;
 \r
 /********************************************************************/\r
 /*\r
+ * FUNCTION ADAPTED FROM FREESCALE SUPPLIED SOURCE\r
+ *\r
  * Set the Physical (Hardware) Address and the Individual Address\r
  * Hash in the selected FEC\r
  *\r
@@ -303,6 +329,7 @@ static void prvInitialiseFECBuffers( void )
 unsigned portBASE_TYPE ux;\r
 unsigned portCHAR *pcBufPointer;\r
 \r
+       /* Correctly align the Tx descriptor pointer. */\r
        pcBufPointer = &( xFECTxDescriptors_unaligned[ 0 ] );\r
        while( ( ( unsigned portLONG ) pcBufPointer & 0x0fUL ) != 0 )\r
        {\r
@@ -311,6 +338,7 @@ unsigned portCHAR *pcBufPointer;
 \r
        xFECTxDescriptors = ( FECBD * ) pcBufPointer;\r
 \r
+       /* Likewise the Rx descriptor pointer. */\r
        pcBufPointer = &( xFECRxDescriptors_unaligned[ 0 ] );\r
        while( ( ( unsigned portLONG ) pcBufPointer & 0x0fUL ) != 0 )\r
        {\r
@@ -320,9 +348,9 @@ unsigned portCHAR *pcBufPointer;
        xFECRxDescriptors = ( FECBD * ) pcBufPointer;\r
 \r
 \r
-       /* Setup the buffers and descriptors.  The data member does not point\r
-       anywhere yet as there is not yet anything to send and a zero copy policy\r
-       is used. */
+       /* Setup the Tx buffers and descriptors.  There is no separate Tx buffer\r
+       to point to (the Rx buffers are actually used) so the data member is\r
+       set to NULL for now. */\r
        for( ux = 0; ux < fecNUM_FEC_TX_BUFFERS; ux++ )\r
        {\r
                xFECTxDescriptors[ ux ].status = TX_BD_TC;\r
@@ -330,6 +358,8 @@ unsigned portCHAR *pcBufPointer;
                xFECTxDescriptors[ ux ].length = 0;\r
        }\r
 \r
+       /* Setup the Rx buffers and descriptors, having first ensured correct\r
+       alignment. */\r
        pcBufPointer = &( ucFECRxBuffers[ 0 ] );\r
        while( ( ( unsigned portLONG ) pcBufPointer & 0x0fUL ) != 0 )\r
        {\r
@@ -352,10 +382,13 @@ unsigned portCHAR *pcBufPointer;
 }\r
 /*-----------------------------------------------------------*/\r
 \r
-void vInitFEC( void )\r
+void vFECInit( void )\r
 {\r
 unsigned portSHORT usData;\r
 struct uip_eth_addr xAddr;\r
+unsigned portBASE_TYPE ux;\r
+\r
+/* The MAC address is set at the foot of FreeRTOSConfig.h. */\r
 const unsigned portCHAR ucMACAddress[6] =\r
 {\r
        configMAC_0, configMAC_1,configMAC_2, configMAC_3, configMAC_4, configMAC_5\r
@@ -363,8 +396,12 @@ const unsigned portCHAR ucMACAddress[6] =
 \r
        /* Create the semaphore used by the ISR to wake the uIP task. */\r
        vSemaphoreCreateBinary( xFECSemaphore );\r
+\r
+       /* Create the semaphore used to unblock any tasks that might be waiting\r
+       for a Tx descriptor. */\r
        vSemaphoreCreateBinary( xTxSemaphore );\r
 \r
+       /* Initialise all the buffers and descriptors used by the DMA. */\r
        prvInitialiseFECBuffers();\r
 \r
        for( usData = 0; usData < 6; usData++ )\r
@@ -431,6 +468,18 @@ const unsigned portCHAR ucMACAddress[6] =
                /* Wait for auto negotiate to complete. */\r
                do\r
                {\r
+                       ux++;\r
+                       if( ux > 10 )\r
+                       {\r
+                               /* Hardware bug workaround!  Force 100Mbps half duplex. */\r
+                               while( !fec_mii_read( configPHY_ADDRESS, 0, &usData ) ){};\r
+                               usData &= ~0x2000;                                                      /* 10Mbps */\r
+                               usData &= ~0x0100;                                                      /* Half Duplex */\r
+                               usData &= ~0x1000;                                                      /* Manual Mode */\r
+                               while( !fec_mii_write( configPHY_ADDRESS, 0, usData ) ){};\r
+                               while( !fec_mii_write( configPHY_ADDRESS, 0, (usData|0x0200) )){}; /* Force re-negotiate */\r
+                               break;\r
+                       }\r
                        vTaskDelay( fecLINK_DELAY );\r
                        fec_mii_read( configPHY_ADDRESS, PHY_BMSR, &usData );\r
 \r
@@ -498,6 +547,7 @@ const unsigned portCHAR ucMACAddress[6] =
 \r
        prvEnableFECInterrupts();\r
 \r
+       /* Finally... enable. */\r
        MCF_FEC_ECR = MCF_FEC_ECR_ETHER_EN;\r
        MCF_FEC_RDAR = MCF_FEC_RDAR_R_DES_ACTIVE;\r
 }\r
@@ -512,6 +562,7 @@ unsigned portBASE_TYPE ux;
        #error configFEC_INTERRUPT_PRIORITY must be less than or equal to configMAX_SYSCALL_INTERRUPT_PRIORITY\r
 #endif\r
 \r
+       /* Set the priority of each of the FEC interrupts. */\r
        for( ux = uxFirstFECVector; ux <= uxLastFECVector; ux++ )\r
        {\r
                MCF_INTC0_ICR( ux ) = MCF_INTC_ICR_IL( configFEC_INTERRUPT_PRIORITY );\r
@@ -536,12 +587,15 @@ static void prvResetFEC( portBASE_TYPE xCalledFromISR )
 {\r
 portBASE_TYPE x;\r
 \r
+       /* A critical section is used unless this function is being called from\r
+       an ISR. */\r
        if( xCalledFromISR == pdFALSE )\r
        {\r
                taskENTER_CRITICAL();\r
        }\r
 \r
        {\r
+               /* Reset all buffers and descriptors. */\r
                prvInitialiseFECBuffers();\r
 \r
                /* Set the Reset bit and clear the Enable bit */\r
@@ -553,6 +607,7 @@ portBASE_TYPE x;
                        asm( "NOP" );\r
                }\r
 \r
+               /* Re-enable. */\r
                MCF_FEC_ECR = MCF_FEC_ECR_ETHER_EN;\r
                MCF_FEC_RDAR = MCF_FEC_RDAR_R_DES_ACTIVE;\r
        }\r
@@ -564,7 +619,7 @@ portBASE_TYPE x;
 }\r
 /*-----------------------------------------------------------*/\r
 \r
-unsigned short usGetFECRxData( void )\r
+unsigned short usFECGetRxedData( void )\r
 {\r
 unsigned portSHORT usLen;\r
 \r
@@ -584,7 +639,7 @@ unsigned portSHORT usLen;
 }\r
 /*-----------------------------------------------------------*/\r
 \r
-void vDiscardRxData( void )\r
+void vFECRxProcessingCompleted( void )\r
 {\r
        /* Free the descriptor as the buffer it points to is no longer in use. */\r
        xFECRxDescriptors[ uxNextRxBuffer ].status |= RX_BD_E;\r
@@ -597,10 +652,10 @@ void vDiscardRxData( void )
 }\r
 /*-----------------------------------------------------------*/\r
 \r
-void vSendBufferToFEC( void )\r
+void vFECSendData( void )\r
 {\r
        /* Ensure no Tx frames are outstanding. */\r
-       if( xSemaphoreTake( xTxSemaphore, fecTX_BUFFER_WAIT ) == pdPASS )\r
+       if( xSemaphoreTake( xTxSemaphore, fecMAX_WAIT_FOR_TX_BUFFER ) == pdPASS )\r
        {\r
                /* Get a DMA buffer into which we can write the data to send. */\r
                if( xFECTxDescriptors[ fecTX_BUFFER_TO_USE ].status & TX_BD_R )\r
@@ -615,7 +670,7 @@ void vSendBufferToFEC( void )
                else\r
                {\r
                        /* Setup the buffer descriptor for transmission.  The data being\r
-                       sent is actually stored in one of the Rx descripter buffers,\r
+                       sent is actually stored in one of the Rx descriptor buffers,\r
                        pointed to by uip_buf. */\r
                        xFECTxDescriptors[ fecTX_BUFFER_TO_USE ].length = uip_len;\r
                        xFECTxDescriptors[ fecTX_BUFFER_TO_USE ].status |= ( TX_BD_R | TX_BD_L );\r
@@ -637,7 +692,8 @@ void vSendBufferToFEC( void )
        }\r
        else\r
        {\r
-               vDiscardRxData();\r
+               /* Gave up waiting.  Free the buffer back to the DMA. */\r
+               vFECRxProcessingCompleted();\r
        }\r
 }\r
 /*-----------------------------------------------------------*/\r
@@ -647,6 +703,10 @@ void vFEC_ISR( void )
 unsigned portLONG ulEvent;\r
 portBASE_TYPE xHighPriorityTaskWoken = pdFALSE;\r
 \r
+       /* This handler is called in response to any of the many separate FEC\r
+       interrupt. */\r
+\r
+       /* Find the cause of the interrupt, then clear the interrupt. */\r
        ulEvent = MCF_FEC_EIR & MCF_FEC_EIMR;\r
        MCF_FEC_EIR = ulEvent;\r
 \r
@@ -675,6 +735,8 @@ portBASE_TYPE xHighPriorityTaskWoken = pdFALSE;
 }\r
 /*-----------------------------------------------------------*/\r
 \r
+/* Install the many different interrupt vectors, all of which call the same\r
+handler function. */\r
 void __attribute__ ((interrupt)) __cs3_isr_interrupt_87( void ) { vFEC_ISR(); }\r
 void __attribute__ ((interrupt)) __cs3_isr_interrupt_88( void ) { vFEC_ISR(); }\r
 void __attribute__ ((interrupt)) __cs3_isr_interrupt_89( void ) { vFEC_ISR(); }\r