Split the LPC18xx FreeRTOS+UDP drivers between those that use the LPCOpen library and those that use the older CMSIS library.

pull/4/head
Richard Barry 12 years ago
parent a1145a1b78
commit 0ca2110982

@ -0,0 +1,310 @@
/*
* FreeRTOS+UDP V1.0.0 (C) 2013 Real Time Engineers ltd.
*
* This file is part of the FreeRTOS+UDP distribution. The FreeRTOS+UDP license
* terms are different to the FreeRTOS license terms.
*
* FreeRTOS+UDP uses a dual license model that allows the software to be used
* under a pure GPL open source license (as opposed to the modified GPL license
* under which FreeRTOS is distributed) or a commercial license. Details of
* both license options follow:
*
* - Open source licensing -
* FreeRTOS+UDP is a free download and may be used, modified, evaluated and
* distributed without charge provided the user adheres to version two of the
* GNU General Public License (GPL) and does not remove the copyright notice or
* this text. The GPL V2 text is available on the gnu.org web site, and on the
* following URL: http://www.FreeRTOS.org/gpl-2.0.txt.
*
* - Commercial licensing -
* Businesses and individuals that for commercial or other reasons cannot comply
* with the terms of the GPL V2 license must obtain a commercial license before
* incorporating FreeRTOS+UDP into proprietary software for distribution in any
* form. Commercial licenses can be purchased from http://shop.freertos.org/udp
* and do not require any source files to be changed.
*
* FreeRTOS+UDP is distributed in the hope that it will be useful. You cannot
* use FreeRTOS+UDP unless you agree that you use the software 'as is'.
* FreeRTOS+UDP is provided WITHOUT ANY WARRANTY; without even the implied
* warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
* PURPOSE. Real Time Engineers Ltd. disclaims all conditions and terms, be they
* implied, expressed, or statutory.
*
* 1 tab == 4 spaces!
*
* http://www.FreeRTOS.org
* http://www.FreeRTOS.org/udp
*
*/
/* Standard includes. */
#include <stdint.h>
/* FreeRTOS includes. */
#include "FreeRTOS.h"
#include "task.h"
#include "queue.h"
#include "semphr.h"
/* FreeRTOS+UDP includes. */
#include "FreeRTOS_UDP_IP.h"
#include "FreeRTOS_IP_Private.h"
#include "FreeRTOS_Sockets.h"
#include "NetworkBufferManagement.h"
/* Driver includes. */
#include "lpc18xx_emac.h"
/* Demo includes. */
#include "NetworkInterface.h"
#if configMAC_INTERRUPT_PRIORITY > configMAC_INTERRUPT_PRIORITY
#error configMAC_INTERRUPT_PRIORITY must be greater than or equal to configMAC_INTERRUPT_PRIORITY (higher numbers mean lower logical priority)
#endif
#ifndef configNUM_RX_ETHERNET_DMA_DESCRIPTORS
#error configNUM_RX_ETHERNET_DMA_DESCRIPTORS must be defined in FreeRTOSConfig.h to set the number of RX DMA descriptors
#endif
#ifndef configNUM_TX_ETHERNET_DMA_DESCRIPTORS
#error configNUM_TX_ETHERNET_DMA_DESCRIPTORS must be defined in FreeRTOSConfig.h to set the number of TX DMA descriptors
#endif
/* If a packet cannot be sent immediately then the task performing the send
operation will be held in the Blocked state (so other tasks can execute) for
niTX_BUFFER_FREE_WAIT ticks. It will do this a maximum of niMAX_TX_ATTEMPTS
before giving up. */
#define niTX_BUFFER_FREE_WAIT ( ( portTickType ) 2UL / portTICK_RATE_MS )
#define niMAX_TX_ATTEMPTS ( 5 )
/*-----------------------------------------------------------*/
/*
* A deferred interrupt handler task that processes received frames.
*/
static void prvEMACDeferredInterruptHandlerTask( void *pvParameters );
/*-----------------------------------------------------------*/
/* The queue used to communicate Ethernet events to the IP task. */
extern xQueueHandle xNetworkEventQueue;
/* The semaphore used to wake the deferred interrupt handler task when an Rx
interrupt is received. */
static xSemaphoreHandle xEMACRxEventSemaphore = NULL;
/*-----------------------------------------------------------*/
portBASE_TYPE xNetworkInterfaceInitialise( void )
{
EMAC_CFG_Type Emac_Config;
portBASE_TYPE xReturn;
extern uint8_t ucMACAddress[ 6 ];
Emac_Config.pbEMAC_Addr = ucMACAddress;
xReturn = EMAC_Init( &Emac_Config );
if( xReturn == pdPASS )
{
LPC_ETHERNET->DMA_INT_EN = DMA_INT_NOR_SUM | DMA_INT_RECEIVE;
/* Create the event semaphore if it has not already been created. */
if( xEMACRxEventSemaphore == NULL )
{
vSemaphoreCreateBinary( xEMACRxEventSemaphore );
#if ipconfigINCLUDE_EXAMPLE_FREERTOS_PLUS_TRACE_CALLS == 1
{
/* If the trace recorder code is included name the semaphore for
viewing in FreeRTOS+Trace. */
vTraceSetQueueName( xEMACRxEventSemaphore, "MAC_RX" );
}
#endif /* ipconfigINCLUDE_EXAMPLE_FREERTOS_PLUS_TRACE_CALLS == 1 */
}
configASSERT( xEMACRxEventSemaphore );
/* The Rx deferred interrupt handler task is created at the highest
possible priority to ensure the interrupt handler can return directly to
it no matter which task was running when the interrupt occurred. */
xTaskCreate( prvEMACDeferredInterruptHandlerTask, /* The function that implements the task. */
( const signed char * const ) "MACTsk",
configMINIMAL_STACK_SIZE, /* Stack allocated to the task (defined in words, not bytes). */
NULL, /* The task parameter is not used. */
configMAX_PRIORITIES - 1, /* The priority assigned to the task. */
NULL ); /* The handle is not required, so NULL is passed. */
/* Enable the interrupt and set its priority as configured. THIS
DRIVER REQUIRES configMAC_INTERRUPT_PRIORITY TO BE DEFINED, PREFERABLY
IN FreeRTOSConfig.h. */
NVIC_SetPriority( ETHERNET_IRQn, configMAC_INTERRUPT_PRIORITY );
NVIC_EnableIRQ( ETHERNET_IRQn );
}
return xReturn;
}
/*-----------------------------------------------------------*/
portBASE_TYPE xNetworkInterfaceOutput( xNetworkBufferDescriptor_t * const pxNetworkBuffer )
{
portBASE_TYPE xReturn = pdFAIL;
int32_t x;
/* Attempt to obtain access to a Tx descriptor. */
for( x = 0; x < niMAX_TX_ATTEMPTS; x++ )
{
if( EMAC_CheckTransmitIndex() == TRUE )
{
/* Assign the buffer being transmitted to the Tx descriptor. */
EMAC_SetNextPacketToSend( pxNetworkBuffer->pucEthernetBuffer );
/* The EMAC now owns the buffer and will free it when it has been
transmitted. Set pucBuffer to NULL to ensure the buffer is not
freed when the network buffer structure is returned to the pool
of network buffers. */
pxNetworkBuffer->pucEthernetBuffer = NULL;
/* Initiate the Tx. */
EMAC_StartTransmitNextBuffer( pxNetworkBuffer->xDataLength );
iptraceNETWORK_INTERFACE_TRANSMIT();
/* The Tx has been initiated. */
xReturn = pdPASS;
break;
}
else
{
iptraceWAITING_FOR_TX_DMA_DESCRIPTOR();
vTaskDelay( niTX_BUFFER_FREE_WAIT );
}
}
/* Finished with the network buffer. */
vNetworkBufferRelease( pxNetworkBuffer );
return xReturn;
}
/*-----------------------------------------------------------*/
void ETH_IRQHandler( void )
{
uint32_t ulInterruptCause;
ulInterruptCause = LPC_ETHERNET->DMA_STAT ;
/* Clear the interrupt. */
LPC_ETHERNET->DMA_STAT |= ( DMA_INT_NOR_SUM | DMA_INT_RECEIVE );
/* Clear fatal error conditions. NOTE: The driver does not clear all
errors, only those actually experienced. For future reference, range
errors are not actually errors so can be ignored. */
if( ( ulInterruptCause & ( 1 << 13 ) ) != 0U )
{
LPC_ETHERNET->DMA_STAT |= ( 1 << 13 );
}
/* Unblock the deferred interrupt handler task if the event was an Rx. */
if( ( ulInterruptCause & DMA_INT_RECEIVE ) != 0UL )
{
xSemaphoreGiveFromISR( xEMACRxEventSemaphore, NULL );
}
/* ulInterruptCause is used for convenience here. A context switch is
wanted, but coding portEND_SWITCHING_ISR( 1 ) would likely result in a
compiler warning. */
portEND_SWITCHING_ISR( ulInterruptCause );
}
/*-----------------------------------------------------------*/
static void prvEMACDeferredInterruptHandlerTask( void *pvParameters )
{
xNetworkBufferDescriptor_t *pxNetworkBuffer;
xIPStackEvent_t xRxEvent = { eEthernetRxEvent, NULL };
( void ) pvParameters;
configASSERT( xEMACRxEventSemaphore );
for( ;; )
{
/* Wait for the EMAC interrupt to indicate that another packet has been
received. The while() loop is only needed if INCLUDE_vTaskSuspend is
set to 0 in FreeRTOSConfig.h. If INCLUDE_vTaskSuspend is set to 1
then portMAX_DELAY would be an indefinite block time and
xSemaphoreTake() would only return when the semaphore was actually
obtained. */
while( xSemaphoreTake( xEMACRxEventSemaphore, portMAX_DELAY ) == pdFALSE );
/* At least one packet has been received. */
while( EMAC_CheckReceiveIndex() != FALSE )
{
/* The buffer filled by the DMA is going to be passed into the IP
stack. Allocate another buffer for the DMA descriptor. */
pxNetworkBuffer = pxNetworkBufferGet( ipTOTAL_ETHERNET_FRAME_SIZE, ( portTickType ) 0 );
if( pxNetworkBuffer != NULL )
{
/* Swap the buffer just allocated and referenced from the
pxNetworkBuffer with the buffer that has already been filled by
the DMA. pxNetworkBuffer will then hold a reference to the
buffer that already contains the data without any data having
been copied between buffers. */
EMAC_NextPacketToRead( pxNetworkBuffer );
#if ipconfigETHERNET_DRIVER_FILTERS_FRAME_TYPES == 1
{
if( pxNetworkBuffer->xDataLength > 0 )
{
/* If the frame would not be processed by the IP stack then
don't even bother sending it to the IP stack. */
if( eConsiderFrameForProcessing( pxNetworkBuffer->pucEthernetBuffer ) != eProcessBuffer )
{
pxNetworkBuffer->xDataLength = 0;
}
}
}
#endif
if( pxNetworkBuffer->xDataLength > 0 )
{
/* Store a pointer to the network buffer structure in the
padding space that was left in front of the Ethernet frame.
The pointer is needed to ensure the network buffer structure
can be located when it is time for it to be freed if the
Ethernet frame gets used as a zero copy buffer. */
*( ( xNetworkBufferDescriptor_t ** ) ( ( pxNetworkBuffer->pucEthernetBuffer - ipBUFFER_PADDING ) ) ) = pxNetworkBuffer;
/* Data was received and stored. Send it to the IP task
for processing. */
xRxEvent.pvData = ( void * ) pxNetworkBuffer;
if( xQueueSendToBack( xNetworkEventQueue, &xRxEvent, ( portTickType ) 0 ) == pdFALSE )
{
/* The buffer could not be sent to the IP task so the
buffer must be released. */
vNetworkBufferRelease( pxNetworkBuffer );
iptraceETHERNET_RX_EVENT_LOST();
}
else
{
iptraceNETWORK_INTERFACE_RECEIVE();
}
}
else
{
/* The buffer does not contain any data so there is no
point sending it to the IP task. Just release it. */
vNetworkBufferRelease( pxNetworkBuffer );
iptraceETHERNET_RX_EVENT_LOST();
}
}
else
{
iptraceETHERNET_RX_EVENT_LOST();
}
/* Release the descriptor. */
EMAC_UpdateRxConsumeIndex();
}
}
}
/*-----------------------------------------------------------*/

@ -0,0 +1,610 @@
/**********************************************************************
* Copyright(C) 2011, NXP Semiconductor
* All rights reserved.
* Heavily modified by Real Time Engineers ltd.
***********************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* NXP Semiconductors assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. NXP Semiconductors
* reserves the right to make changes in the software without
* notification. NXP Semiconductors also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
**********************************************************************/
/* FreeRTOS includes. */
#include "FreeRTOS.h"
#include "task.h"
/* FreeRTOS+UDP includes. */
#include "FreeRTOS_UDP_IP.h"
#include "FreeRTOS_IP_Private.h"
#include "NetworkBufferManagement.h"
/* Library includes. */
#include "lpc18xx_emac.h"
#include "lpc18xx_rgu.h"
#include "lpc18xx_scu.h"
#include "lpc18xx_gpio.h"
#define emacTIMEOUT_DELAY ( 2 )
#define emacNEGOTIATE_DELAY ( 10 / portTICK_RATE_MS )
#define emacEXPECTED_RX_STATUS_MASK ( RX_FIRST_SEGM | RX_LAST_SEGM )
/* Rx descriptors and data array. */
static volatile RX_Desc Rx_Desc[ configNUM_RX_ETHERNET_DMA_DESCRIPTORS ];
static unsigned int RxDescIndex = 0;
/** Rx Status data array - Must be 8-Byte aligned */
#if defined ( __CC_ARM )
static __align(8) RX_Stat Rx_Stat[ configNUM_RX_ETHERNET_DMA_DESCRIPTORS ];
#elif defined ( __ICCARM__ )
#pragma data_alignment=8
static RX_Stat Rx_Stat[ configNUM_RX_ETHERNET_DMA_DESCRIPTORS ];
#elif defined ( __GNUC__ )
static volatile __attribute__ ((aligned (8))) RX_Stat Rx_Stat[ configNUM_RX_ETHERNET_DMA_DESCRIPTORS ];
#endif
/* Tx descriptors and status array. */
static volatile TX_Desc Tx_Desc[ configNUM_TX_ETHERNET_DMA_DESCRIPTORS ];
static volatile TX_Stat Tx_Stat[ configNUM_TX_ETHERNET_DMA_DESCRIPTORS ];
static unsigned int TxDescIndex = 0;
/* Private Functions ---------------------------------------------------------- */
static void rx_descr_init( void );
static void tx_descr_init( void );
static int32_t write_PHY( uint32_t PhyReg, uint16_t Value );
static int32_t read_PHY( uint32_t PhyReg );
static void setEmacAddr( uint8_t abStationAddr[] );
/*********************************************************************//**
* @brief Initializes the EMAC peripheral according to the specified
* parameters in the EMAC_ConfigStruct.
* @param[in] EMAC_ConfigStruct Pointer to a EMAC_CFG_Type structure
* that contains the configuration information for the
* specified EMAC peripheral.
* @return None
*
* Note: This function will initialize EMAC module according to procedure below:
* - Remove the soft reset condition from the MAC
* - Configure the PHY via the MIIM interface of the MAC
* - Select RMII mode
* - Configure the transmit and receive DMA engines, including the descriptor arrays
* - Configure the host registers (MAC1,MAC2 etc.) in the MAC
* - Enable the receive and transmit data paths
* In default state after initializing, only Rx Done and Tx Done interrupt are enabled,
* all remain interrupts are disabled
* (Ref. from LPC17xx UM)
**********************************************************************/
portBASE_TYPE EMAC_Init(EMAC_CFG_Type *EMAC_ConfigStruct)
{
int32_t id1, id2, regv, phy = 0;
int32_t phy_linkstatus_reg, phy_linkstatus_mask;
uint32_t x;
const uint32_t ulMaxAttempts = 250UL;
portBASE_TYPE xReturn = pdPASS;
/* Enable Ethernet Pins (NGX LPC1830 Xplorer. */
scu_pinmux(0x2 ,0 , (MD_EHS | MD_PLN | MD_EZI | MD_ZI), FUNC7);
scu_pinmux(0x1 ,17 , (MD_EHS | MD_PLN | MD_EZI | MD_ZI), FUNC3);
scu_pinmux(0x1 ,18 , (MD_EHS | MD_PLN | MD_EZI | MD_ZI), FUNC3);
scu_pinmux(0x1 ,20 , (MD_EHS | MD_PLN | MD_EZI | MD_ZI), FUNC3);
scu_pinmux(0x1 ,19 , (MD_EHS | MD_PLN | MD_EZI | MD_ZI), FUNC0);
scu_pinmux(0x0 ,1 , (MD_EHS | MD_PLN | MD_EZI | MD_ZI), FUNC6);
scu_pinmux(0x1 ,15 , (MD_EHS | MD_PLN | MD_EZI | MD_ZI), FUNC3);
scu_pinmux(0x0 ,0 , (MD_EHS | MD_PLN | MD_EZI | MD_ZI), FUNC2);
scu_pinmux(0x1 ,16 , (MD_EHS | MD_PLN | MD_EZI | MD_ZI), FUNC3);
scu_pinmux(0xC ,9 , (MD_EHS | MD_PLN | MD_EZI | MD_ZI), FUNC3);
scu_pinmux(0x1 ,16 , (MD_EHS | MD_PLN | MD_EZI | MD_ZI), FUNC7);
/* Ethernet RESET Pins */
scu_pinmux(0x1 ,0 , MD_PUP, FUNC0);
GPIO_SetDir(0,(1<<4), 1);
GPIO_SetValue(0,(1<<4));
#if MII /* Select MII interface */ // check MUXING for new Eagle...
scu_pinmux(0xC ,6 , (MD_PLN | MD_EZI | MD_ZI), FUNC3); // ENET_RXD2: PC_6 -> FUNC3
scu_pinmux(0xC ,7 , (MD_PLN | MD_EZI | MD_ZI), FUNC3); // ENET_RXD3: PC_7 -> FUNC3
scu_pinmux(0xC ,0 , (MD_PLN | MD_EZI | MD_ZI), FUNC3); // ENET_RXLK: PC_0 -> FUNC3
scu_pinmux(0xC ,2 , (MD_PLN | MD_EZI | MD_ZI), FUNC3); // ENET_TXD2: PC_2 -> FUNC3
scu_pinmux(0xC ,3 , (MD_PLN | MD_EZI | MD_ZI), FUNC3); // ENET_TXD3: PC_3 -> FUNC3
scu_pinmux(0xC ,5 , (MD_PLN | MD_EZI | MD_ZI), FUNC3); // ENET_TX_ER: PC_5 -> FUNC3
scu_pinmux(0x0 ,1 , (MD_PLN | MD_EZI | MD_ZI), FUNC2); // ENET_COL: P0_1 -> FUNC2
#else /* Select RMII interface */
LPC_CREG->CREG6 |= RMII_SELECT;
#endif
RGU_SoftReset( RGU_SIG_ETHERNET );
/* Wait for reset. */
while( !( LPC_RGU->RESET_ACTIVE_STATUS0 & ( 1 << ETHERNET_RST ) ) )
{
vTaskDelay( emacTIMEOUT_DELAY );
}
/* Reset all GMAC Subsystem internal registers and logic. */
LPC_ETHERNET->DMA_BUS_MODE |= DMA_SOFT_RESET;
/* Wait for software reset completion. */
while( LPC_ETHERNET->DMA_BUS_MODE & DMA_SOFT_RESET )
{
vTaskDelay( emacTIMEOUT_DELAY );
}
/* Put the PHY in reset mode */
write_PHY( PHY_REG_BMCR, PHY_BMCR_RESET );
/* Wait for hardware reset to end. */
for( x = 0; x < ulMaxAttempts; x++ )
{
regv = read_PHY (PHY_REG_BMCR);
if( !( regv & PHY_BMCR_RESET ) )
{
/* Reset complete */
break;
}
else
{
vTaskDelay( emacTIMEOUT_DELAY );
}
}
if( x == ulMaxAttempts )
{
xReturn = pdFAIL;
}
/* Check if this is a DP83848C PHY. */
id1 = read_PHY( PHY_REG_IDR1 );
id2 = read_PHY( PHY_REG_IDR2 );
if( ( ( id1 << 16 ) | ( id2 & 0xFFF0 ) ) == DP83848C_ID )
{
phy = DP83848C_ID;
}
else if( ( ( id1 << 16 ) | id2 ) == LAN8720_ID )
{
phy = LAN8720_ID;
}
if( phy != 0 )
{
/* Use autonegotiation about the link speed. */
write_PHY( PHY_REG_BMCR, PHY_AUTO_NEG );
/* Wait to complete Auto_Negotiation. */
for( x = 0; x < ulMaxAttempts; x++ )
{
regv = read_PHY( PHY_REG_BMSR );
if( ( regv & PHY_AUTO_NEG_DONE ) != 0 )
{
/* Auto negotiation Complete. */
break;
}
else
{
vTaskDelay( emacNEGOTIATE_DELAY );
}
}
if( x == ulMaxAttempts )
{
xReturn = pdFAIL;
}
}
else
{
xReturn = pdFAIL;
}
if( xReturn == pdPASS )
{
/* Default to DP83848C. */
phy_linkstatus_reg = PHY_REG_STS;
phy_linkstatus_mask = 0x0001;
if( phy == LAN8720_ID )
{
phy_linkstatus_reg = PHY_REG_BMSR;
phy_linkstatus_mask = 0x0004;
}
/* Check the link status. */
for( x = 0; x < ulMaxAttempts; x++ )
{
regv = read_PHY( phy_linkstatus_reg );
if( ( regv & phy_linkstatus_mask ) != 0 )
{
/* Link is on. */
break;
}
else
{
vTaskDelay( emacNEGOTIATE_DELAY );
}
}
if( x == ulMaxAttempts )
{
xReturn = pdFAIL;
}
regv = read_PHY( PHY_REG_SPCON );
regv &= PHY_REG_HCDSPEED_MASK;
/* Configure 100MBit/10MBit mode and Full/Half Duplex mode. */
switch( regv )
{
case PHY_REG_HCDSPEED_10MB_FULLD:
LPC_ETHERNET->MAC_CONFIG |= MAC_DUPMODE;
break;
case PHY_REG_HCDSPEED_100MB_HALFD:
LPC_ETHERNET->MAC_CONFIG |= MAC_100MPS;
break;
case PHY_REG_HCDSPEED_100MB_FULLD:
LPC_ETHERNET->MAC_CONFIG |= MAC_DUPMODE;
LPC_ETHERNET->MAC_CONFIG |= MAC_100MPS;
break;
default:
break;
}
/* Set the Ethernet MAC Address registers */
setEmacAddr( EMAC_ConfigStruct->pbEMAC_Addr );
/* Initialize Descriptor Lists */
rx_descr_init();
tx_descr_init();
/* Configure Filter
LPC_ETHERNET->MAC_FRAME_FILTER is left at its default value.
MAC_PROMISCUOUS and MAC_RECEIVEALL can be set if required. */
/* Enable Receiver and Transmitter */
LPC_ETHERNET->MAC_CONFIG |= (MAC_TX_ENABLE | MAC_RX_ENABLE);
/* Enable interrupts */
LPC_ETHERNET->DMA_INT_EN = DMA_INT_NOR_SUM | DMA_INT_RECEIVE ;
/* Start Transmission & Receive processes */
LPC_ETHERNET->DMA_OP_MODE |= (DMA_SS_TRANSMIT | DMA_SS_RECEIVE );
}
return xReturn;
}
/*********************************************************************//**
**********************************************************************/
portBASE_TYPE EMAC_CheckTransmitIndex( void )
{
portBASE_TYPE xReturn;
if( ( Tx_Desc[ TxDescIndex ].Status & OWN_BIT ) == 0 )
{
xReturn = pdPASS;
}
else
{
xReturn = pdFAIL;
}
return xReturn;
}
/*********************************************************************//**
* @brief EMAC_SetNextPacketToSend
* @param[in] pucBuffer
* @return None
***********************************************************************/
void EMAC_SetNextPacketToSend( uint8_t * pucBuffer )
{
/* The old packet is now finished with and can be freed. */
vEthernetBufferRelease( ( void * ) Tx_Desc[ TxDescIndex ].Packet );
/* Assign the new packet to the descriptor. */
Tx_Desc[ TxDescIndex ].Packet = ( uint32_t ) pucBuffer;
}
void EMAC_StartTransmitNextBuffer( uint32_t ulLength )
{
Tx_Desc[ TxDescIndex ].Ctrl = ulLength;
Tx_Desc[ TxDescIndex ].Status |= OWN_BIT;
/* Wake Up the DMA if it's in Suspended Mode. */
LPC_ETHERNET->DMA_TRANS_POLL_DEMAND = 1;
TxDescIndex++;
if( TxDescIndex == configNUM_TX_ETHERNET_DMA_DESCRIPTORS )
{
TxDescIndex = 0;
}
}
/*********************************************************************//**
* @brief Get size of current Received data in received buffer (due to
* RxConsumeIndex)
* @param[in] None
* @return Size of received data
**********************************************************************/
uint32_t EMAC_GetReceiveDataSize(void)
{
unsigned short RxLen = 0;
RxLen = ( Rx_Desc[ RxDescIndex ].Status >> 16 ) & 0x03FFF;
return RxLen;
}
/*********************************************************************//**
* @brief Increase the RxConsumeIndex (after reading the Receive buffer
* to release the Receive buffer) and wrap-around the index if
* it reaches the maximum Receive Number
* @param[in] None
* @return None
**********************************************************************/
void EMAC_UpdateRxConsumeIndex( void )
{
Rx_Desc[ RxDescIndex ].Status = OWN_BIT;
RxDescIndex++;
if( RxDescIndex == configNUM_RX_ETHERNET_DMA_DESCRIPTORS )
{
RxDescIndex = 0;
}
}
/*********************************************************************//**
* @brief Check whether if the current RxConsumeIndex is not equal to the
* current RxProduceIndex.
* @param[in] None
* @return TRUE if they're not equal, otherwise return FALSE
*
* Note: In case the RxConsumeIndex is not equal to the RxProduceIndex,
* it means there're available data has been received. They should be read
* out and released the Receive Data Buffer by updating the RxConsumeIndex value.
**********************************************************************/
portBASE_TYPE EMAC_CheckReceiveIndex(void)
{
portBASE_TYPE xReturn;
if( ( Rx_Desc[ RxDescIndex ].Status & OWN_BIT ) == 0 )
{
xReturn = pdPASS;
}
else
{
xReturn = pdFAIL;
}
return xReturn;
}
void EMAC_NextPacketToRead( xNetworkBufferDescriptor_t *pxNetworkBuffer )
{
uint8_t *pucTemp;
/* Swap the buffer in the network buffer with the buffer used by the DMA.
This allows the data to be passed out without having to perform any copies. */
pucTemp = ( uint8_t * ) Rx_Desc[ RxDescIndex ].Packet;
Rx_Desc[ RxDescIndex ].Packet = ( uint32_t ) pxNetworkBuffer->pucEthernetBuffer;
pxNetworkBuffer->pucEthernetBuffer = pucTemp;
/* Only supports frames coming in single buffers. If this frame is split
across multiple buffers then reject it (and if the frame is needed increase
the ipconfigNETWORK_MTU setting). */
if( ( Rx_Desc[ RxDescIndex ].Status & emacEXPECTED_RX_STATUS_MASK ) != emacEXPECTED_RX_STATUS_MASK )
{
pxNetworkBuffer->xDataLength = 0;
}
else
{
pxNetworkBuffer->xDataLength = ( size_t ) EMAC_GetReceiveDataSize() - ( ipETHERNET_CRC_BYTES - 1U );;
}
}
/*********************************************************************//**
* @brief Initializes RX Descriptor
* @param[in] None
* @return None
***********************************************************************/
static void rx_descr_init( void )
{
uint32_t x;
size_t xBufferSize = ipTOTAL_ETHERNET_FRAME_SIZE;
for( x = 0; x < configNUM_RX_ETHERNET_DMA_DESCRIPTORS; x++ )
{
/* Obtain the buffer first, as the size of the buffer might be changed
within the pucEthernetBufferGet() call. */
Rx_Desc[ x ].Packet = ( uint32_t ) pucEthernetBufferGet( &xBufferSize );
Rx_Desc[ x ].Status = OWN_BIT;
Rx_Desc[ x ].Ctrl = xBufferSize;
Rx_Desc[ x ].NextDescripter = ( uint32_t ) &Rx_Desc[ x + 1 ];
configASSERT( ( ( ( uint32_t ) Rx_Desc[x].Packet ) & 0x07 ) == 0 );
}
/* Last Descriptor */
Rx_Desc[ configNUM_RX_ETHERNET_DMA_DESCRIPTORS - 1 ].Ctrl |= RX_END_RING;
RxDescIndex = 0;
/* Set Starting address of RX Descriptor list */
LPC_ETHERNET->DMA_REC_DES_ADDR = ( uint32_t ) Rx_Desc;
}
/*********************************************************************//**
* @brief Initializes TX Descriptor
* @param[in] None
* @return None
***********************************************************************/
static void tx_descr_init( void )
{
/* Initialize Transmit Descriptor and Status array. */
uint32_t x;
for( x = 0; x < configNUM_TX_ETHERNET_DMA_DESCRIPTORS; x++ )
{
Tx_Desc[ x ].Status = TX_LAST_SEGM | TX_FIRST_SEGM;
Tx_Desc[ x ].Ctrl = 0;
Tx_Desc[ x ].NextDescripter = ( uint32_t ) &Tx_Desc[ x + 1 ];
/* Packet is assigned when a Tx is initiated. */
Tx_Desc[ x ].Packet = ( uint32_t )NULL;
}
/* Last Descriptor? */
Tx_Desc[ configNUM_TX_ETHERNET_DMA_DESCRIPTORS-1 ].Status |= TX_END_RING;
/* Set Starting address of TX Descriptor list */
LPC_ETHERNET->DMA_TRANS_DES_ADDR = ( uint32_t ) Tx_Desc;
}
/*********************************************************************//**
* @brief Write value to PHY device
* @param[in] PhyReg: PHY Register address
* @param[in] Value: Value to write
* @return 0 - if success
* 1 - if fail
***********************************************************************/
static int32_t write_PHY (uint32_t PhyReg, uint16_t Value)
{
uint32_t x;
const uint32_t ulMaxAttempts = 250UL;
int32_t lReturn = pdPASS;
/* Write a data 'Value' to PHY register 'PhyReg'. */
x = 0;
while( LPC_ETHERNET->MAC_MII_ADDR & GMII_BUSY )
{
x++;
if( x >= ulMaxAttempts )
{
/* Time out. */
lReturn = pdFAIL;
break;
}
else
{
/* GMII is busy. */
vTaskDelay( emacTIMEOUT_DELAY );
}
}
if( lReturn == pdPASS )
{
LPC_ETHERNET->MAC_MII_ADDR = ( DP83848C_DEF_ADR << 11 ) | ( PhyReg << 6 ) | GMII_WRITE;
LPC_ETHERNET->MAC_MII_DATA = Value;
/* Start PHY Write Cycle. */
LPC_ETHERNET->MAC_MII_ADDR |= GMII_BUSY;
/* Wait untl operation completed. */
for( x = 0; x < ulMaxAttempts; x++ )
{
if( ( LPC_ETHERNET->MAC_MII_ADDR & GMII_BUSY ) == 0 )
{
break;
}
else
{
vTaskDelay( emacTIMEOUT_DELAY );
}
}
if( x == ulMaxAttempts )
{
/* Timeout. */
lReturn = pdFAIL;
}
}
return lReturn;
}
/*********************************************************************//**
* @brief Read value from PHY device
* @param[in] PhyReg: PHY Register address
* @return 0 - if success
* 1 - if fail
***********************************************************************/
static int32_t read_PHY( uint32_t PhyReg )
{
int32_t lValue = 0;
uint32_t x;
const uint32_t ulMaxAttempts = 250UL;
/* Write a data 'Value' to PHY register 'PhyReg'. */
x = 0;
while( LPC_ETHERNET->MAC_MII_ADDR & GMII_BUSY )
{
x++;
if( x >= ulMaxAttempts )
{
/* Time out. */
break;
}
else
{
/* GMII is busy. */
vTaskDelay( emacTIMEOUT_DELAY );
}
}
if( x < ulMaxAttempts )
{
/* Read a PHY register 'PhyReg'. */
LPC_ETHERNET->MAC_MII_ADDR = ( DP83848C_DEF_ADR << 11 ) | ( PhyReg << 6 ) | GMII_READ;
/* Start PHY Read Cycle. */
LPC_ETHERNET->MAC_MII_ADDR |= GMII_BUSY;
/* Wait until operation completed */
for( x = 0; x < ulMaxAttempts; x++ )
{
if( ( LPC_ETHERNET->MAC_MII_ADDR & GMII_BUSY ) == 0 )
{
break;
}
else
{
vTaskDelay( emacTIMEOUT_DELAY );
}
}
configASSERT( x != ulMaxAttempts );
lValue = LPC_ETHERNET->MAC_MII_DATA;
}
return lValue;
}
/*********************************************************************//**
* @brief Set Station MAC address for EMAC module
* @param[in] abStationAddr Pointer to Station address that contains 6-bytes
* of MAC address (should be in order from MAC Address 1 to MAC Address 6)
* @return None
**********************************************************************/
static void setEmacAddr( uint8_t abStationAddr[] )
{
/* Set the Ethernet MAC Address registers */
LPC_ETHERNET->MAC_ADDR0_HIGH = (( uint32_t ) abStationAddr[ 5 ] << 8 ) | ( uint32_t )abStationAddr[ 4 ];
LPC_ETHERNET->MAC_ADDR0_LOW = (( uint32_t )abStationAddr[ 3 ] << 24) | (( uint32_t )abStationAddr[ 2 ] << 16) | (( uint32_t )abStationAddr[ 1 ] << 8 ) | ( uint32_t )abStationAddr[ 0 ];
}

@ -0,0 +1,238 @@
/***********************************************************************//**
* @file lpc17xx_emac.h
* @brief Contains all macro definitions and function prototypes
* support for Ethernet MAC firmware library on LPC17xx
* @version 2.0
* @date 21. May. 2010
* @author NXP MCU SW Application Team
**************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* NXP Semiconductors assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. NXP Semiconductors
* reserves the right to make changes in the software without
* notification. NXP Semiconductors also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
**************************************************************************/
/* Peripheral group ----------------------------------------------------------- */
/** @defgroup EMAC EMAC
* @ingroup LPC1700CMSIS_FwLib_Drivers
* @{
*/
#ifndef LPC18XX_EMAC_H_
#define LPC18XX_EMAC_H_
/* Includes ------------------------------------------------------------------- */
#include "LPC18xx.h"
#ifdef __cplusplus
extern "C"
{
#endif
#include "lpc_types.h"
/* Configuration */
/* Interface Selection */
#define MII 0 // =0 RMII - =1 MII
/* End of Configuration */
/* Descriptors Fields bits */
#define OWN_BIT (1U<<31) /* Own bit in RDES0 & TDES0 */
#define RX_END_RING (1<<15) /* Receive End of Ring bit in RDES1 */
#define RX_NXTDESC_FLAG (1<<14) /* Second Address Chained bit in RDES1 */
#define TX_LAST_SEGM (1<<29) /* Last Segment bit in TDES0 */
#define RX_LAST_SEGM (1<<9)
#define TX_FIRST_SEGM (1<<28) /* First Segment bit in TDES0 */
#define RX_FIRST_SEGM (1<<8) /* First Segment bit in TDES0 */
#define TX_END_RING (1<<21) /* Transmit End of Ring bit in TDES0 */
#define TX_NXTDESC_FLAG (1<<20) /* Second Address Chained bit in TDES0 */
/* EMAC Memory Buffer configuration for 16K Ethernet RAM */
#define EMAC_ETH_MAX_FLEN ipETHERNET_FRAME_SIZE_TO_USE
/* NOTE: EMAC_NUM_RX_FRAG is not used by the example FreeRTOS drivers - use
configNUM_RX_ETHERNET_DMA_DESCRIPTORS. */
#define EMAC_NUM_RX_FRAG 6 /**< Num.of RX Fragments */
/* NOTE: EMAC_NUM_TX_FRAG is not used by the example FreeRTOS drivers - use
configNUM_TX_ETHERNET_DMA_DESCRIPTORS. */
#define EMAC_NUM_TX_FRAG 2 /**< Num.of TX Fragments */
/* EMAC Control and Status bits */
#define MAC_RX_ENABLE (1<<2) /* Receiver Enable in MAC_CONFIG reg */
#define MAC_TX_ENABLE (1<<3) /* Transmitter Enable in MAC_CONFIG reg */
#define MAC_PADCRC_STRIP (1<<7) /* Automatic Pad-CRC Stripping in MAC_CONFIG reg */
#define MAC_DUPMODE (1<<11) /* Duplex Mode in MAC_CONFIG reg */
#define MAC_100MPS (1<<14) /* Speed is 100Mbps in MAC_CONFIG reg */
#define MAC_PROMISCUOUS (1U<<0) /* Promiscuous Mode bit in MAC_FRAME_FILTER reg */
#define MAC_DIS_BROAD (1U<<5) /* Disable Broadcast Frames bit in MAC_FRAME_FILTER reg */
#define MAC_RECEIVEALL (1U<<31) /* Receive All bit in MAC_FRAME_FILTER reg */
#define DMA_SOFT_RESET 0x01 /* Software Reset bit in DMA_BUS_MODE reg */
#define DMA_SS_RECEIVE (1<<1) /* Start/Stop Receive bit in DMA_OP_MODE reg */
#define DMA_SS_TRANSMIT (1<<13) /* Start/Stop Transmission bit in DMA_OP_MODE reg */
#define DMA_INT_TRANSMIT (1<<0) /* Transmit Interrupt Enable bit in DMA_INT_EN reg */
#define DMA_INT_OVERFLOW (1<<4) /* Overflow Interrupt Enable bit in DMA_INT_EN reg */
#define DMA_INT_UNDERFLW (1<<5) /* Underflow Interrupt Enable bit in DMA_INT_EN reg */
#define DMA_INT_RECEIVE (1<<6) /* Receive Interrupt Enable bit in DMA_INT_EN reg */
#define DMA_INT_ABN_SUM (1<<15) /* Abnormal Interrupt Summary Enable bit in DMA_INT_EN reg */
#define DMA_INT_NOR_SUM (1<<16) /* Normal Interrupt Summary Enable bit in DMA_INT_EN reg */
/* MII Management Command Register */
#define GMII_READ (0<<1) /* GMII Read PHY */
#define GMII_WRITE (1<<1) /* GMII Write PHY */
#define GMII_BUSY 0x00000001 /* GMII is Busy / Start Read/Write */
#define MII_WR_TOUT 0x00050000 /* MII Write timeout count */
#define MII_RD_TOUT 0x00050000 /* MII Read timeout count */
/* MII Management Address Register */
#define MADR_PHY_ADR 0x00001F00 /* PHY Address Mask */
/* LAN8720 PHY Registers */
#define PHY_REG_BMCR 0x00 /* Basic Mode Control Register */
#define PHY_REG_BMSR 0x01 /* Basic Mode Status Register */
#define PHY_REG_IDR1 0x02 /* PHY Identifier 1 */
#define PHY_REG_IDR2 0x03 /* PHY Identifier 2 */
#define PHY_REG_ANAR 0x04 /* Auto-Negotiation Advertisement */
#define PHY_REG_ANLPAR 0x05 /* Auto-Neg. Link Partner Abitily */
#define PHY_REG_ANER 0x06 /* Auto-Neg. Expansion Register */
#define PHY_REG_ANNPTR 0x07 /* Auto-Neg. Next Page TX */
/* LAN8720 PHY Speed identify */
#define PHY_REG_SPCON 0x1f /* Speed indication Register */
#define PHY_REG_HCDSPEED_MASK 0x1c /* Speed indication Register mask*/
#define PHY_REG_HCDSPEED_10MB_HALFD 0x04 /* Speed is 10Mbps HALF-duplex */
#define PHY_REG_HCDSPEED_10MB_FULLD 0x14 /* Speed is 10Mbps FULL-duplex */
#define PHY_REG_HCDSPEED_100MB_HALFD 0x08 /* Speed is 100Mbps HALF-duplex */
#define PHY_REG_HCDSPEED_100MB_FULLD 0x18 /* Speed is 100Mbps FULL-duplex */
/* PHY Extended Registers */
#define PHY_REG_STS 0x10 /* Status Register */
#define PHY_REG_MICR 0x11 /* MII Interrupt Control Register */
#define PHY_REG_MISR 0x12 /* MII Interrupt Status Register */
#define PHY_REG_FCSCR 0x14 /* False Carrier Sense Counter */
#define PHY_REG_RECR 0x15 /* Receive Error Counter */
#define PHY_REG_PCSR 0x16 /* PCS Sublayer Config. and Status */
#define PHY_REG_RBR 0x17 /* RMII and Bypass Register */
#define PHY_REG_LEDCR 0x18 /* LED Direct Control Register */
#define PHY_REG_PHYCR 0x19 /* PHY Control Register */
#define PHY_REG_10BTSCR 0x1A /* 10Base-T Status/Control Register */
#define PHY_REG_CDCTRL1 0x1B /* CD Test Control and BIST Extens. */
#define PHY_REG_EDCR 0x1D /* Energy Detect Control Register */
/* PHY Control and Status bits */
#define PHY_FULLD_100M 0x2100 /* Full Duplex 100Mbit */
#define PHY_HALFD_100M 0x2000 /* Half Duplex 100Mbit */
#define PHY_FULLD_10M 0x0100 /* Full Duplex 10Mbit */
#define PHY_HALFD_10M 0x0000 /* Half Duplex 10MBit */
#define PHY_AUTO_NEG 0x1000 /* Select Auto Negotiation */
#define PHY_AUTO_NEG_DONE 0x0020 /* AutoNegotiation Complete in BMSR PHY reg */
#define PHY_BMCR_RESET 0x8000 /* Reset bit at BMCR PHY reg */
#define LINK_VALID_STS 0x0001 /* Link Valid Status at REG_STS PHY reg */
#define FULL_DUP_STS 0x0004 /* Full Duplex Status at REG_STS PHY reg */
#define SPEED_10M_STS 0x0002 /* 10Mbps Status at REG_STS PHY reg */
#define DP83848C_DEF_ADR 0x01 /* Default PHY device address */
#define DP83848C_ID 0x20005C90 /* PHY Identifier (without Rev. info */
#define LAN8720_ID 0x0007C0F1 /* PHY Identifier for SMSC PHY */
/* Misc */
#define ETHERNET_RST 22 /* Reset Output for EMAC at RGU */
#define RMII_SELECT 0x04 /* Select RMII in EMACCFG */
/**
* @brief EMAC configuration structure definition
*/
typedef struct {
uint32_t Mode; /**< Supported EMAC PHY device speed, should be one of the following:
- EMAC_MODE_AUTO
- EMAC_MODE_10M_FULL
- EMAC_MODE_10M_HALF
- EMAC_MODE_100M_FULL
- EMAC_MODE_100M_HALF
*/
uint8_t *pbEMAC_Addr; /**< Pointer to EMAC Station address that contains 6-bytes
of MAC address, it must be sorted in order (bEMAC_Addr[0]..[5])
*/
} EMAC_CFG_Type;
/* Descriptor and status formats ---------------------------------------------- */
/**
* @brief RX Descriptor structure type definition
*/
typedef struct {
uint32_t Status; /**< Receive Status Descriptor */
uint32_t Ctrl; /**< Receive Control Descriptor */
uint32_t Packet; /**< Receive Packet Descriptor */
uint32_t NextDescripter;/**< Receive Next Descriptor Address */
} RX_Desc;
/**
* @brief RX Status structure type definition
*/
typedef struct {
uint32_t Info; /**< Receive Information Status */
uint32_t HashCRC; /**< Receive Hash CRC Status */
} RX_Stat;
/**
* @brief TX Descriptor structure type definition
*/
typedef struct {
uint32_t Status; /**< Transmit Status Descriptor */
uint32_t Ctrl; /**< Transmit Control Descriptor */
uint32_t Packet; /**< Transmit Packet Descriptor */
uint32_t NextDescripter; /**< Transmit Next Descriptor Address */
} TX_Desc;
/**
* @brief TX Status structure type definition
*/
typedef struct {
uint32_t Info; /**< Transmit Information Status */
} TX_Stat;
/**
* @brief TX Data Buffer structure definition
*/
typedef struct {
uint32_t ulDataLen; /**< Data length */
uint32_t *pbDataBuf; /**< A word-align data pointer to data buffer */
} EMAC_PACKETBUF_Type;
/* Prototypes */
portBASE_TYPE EMAC_Init(EMAC_CFG_Type *EMAC_ConfigStruct);
int32_t EMAC_UpdatePHYStatus(void);
uint32_t EMAC_GetReceiveDataSize(void);
void EMAC_StartTransmitNextBuffer( uint32_t ulLength );
void EMAC_SetNextPacketToSend( uint8_t * pucBuffer );
void EMAC_NextPacketToRead( xNetworkBufferDescriptor_t *pxNetworkBuffer );
void EMAC_UpdateRxConsumeIndex(void);
portBASE_TYPE EMAC_CheckReceiveIndex(void);
portBASE_TYPE EMAC_CheckTransmitIndex(void);
#ifdef __cplusplus
}
#endif
#endif /* LPC18XX_EMAC_H_ */
/**
* @}
*/
/* --------------------------------- End Of File ------------------------------ */
Loading…
Cancel
Save