NXP LPC1768 Ethernet driver for lwip and CMSIS-RTOS

Dependents:   EthernetInterface EthernetInterface EthernetInterface_RSF EthernetInterface ... more

Legacy Networking Libraries

This is an mbed 2 networking library. For mbed 5, the networking libraries have been revised to better support additional network stacks and thread safety here.

This library is based on the code of the NXP LPC port of the Lightweight TCP/IP Stack

Copyright(C) 2011, NXP Semiconductor
All rights reserved.

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.

Files at this revision

API Documentation at this revision

Comitter:
mbed_official
Date:
Fri Jun 22 09:32:29 2012 +0000
Child:
1:0c9d93e2f51c
Commit message:
Initial import from NXP lwip_lpc: http://sw.lpcware.com/index.php?p=lwip_lpc.git&a=snapshot&h=7b84446afe97af955acad1d720696a0de73ab7cf&fmt=zip

Changed in this revision

arch/lpc17_emac.c Show annotated file Show diff for this revision Revisions of this file
arch/lpc17_emac.h Show annotated file Show diff for this revision Revisions of this file
arch/lpc_emac_config.h Show annotated file Show diff for this revision Revisions of this file
arch/lpc_phy.h Show annotated file Show diff for this revision Revisions of this file
arch/lpc_phy_dp83848.c Show annotated file Show diff for this revision Revisions of this file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/arch/lpc17_emac.c	Fri Jun 22 09:32:29 2012 +0000
@@ -0,0 +1,1040 @@
+/**********************************************************************
+* $Id$        lpc17_emac.c            2011-11-20
+*//**
+* @file        lpc17_emac.c
+* @brief    LPC17 ethernet driver for LWIP
+* @version    1.0
+* @date        20. Nov. 2011
+* @author    NXP MCU SW Application Team
+* 
+* Copyright(C) 2011, NXP Semiconductor
+* All rights reserved.
+*
+***********************************************************************
+* 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.
+**********************************************************************/
+
+#include "lwip/opt.h"
+#include "lwip/sys.h"
+#include "lwip/def.h"
+#include "lwip/mem.h"
+#include "lwip/pbuf.h"
+#include "lwip/stats.h"
+#include "lwip/snmp.h"
+#include "netif/etharp.h"
+#include "netif/ppp_oe.h"
+
+#include "lpc177x_8x_emac.h"
+#include "lpc177x_8x_clkpwr.h"
+#include "lpc17_emac.h"
+#include "lpc_emac_config.h"
+#include "lpc_phy.h"
+
+#ifndef LPC_EMAC_RMII
+#error LPC_EMAC_RMII is not defined!
+#endif
+
+#if LPC_NUM_BUFF_TXDESCS < 2
+#error LPC_NUM_BUFF_TXDESCS must be at least 2
+#endif
+
+#if LPC_NUM_BUFF_RXDESCS < 3
+#error LPC_NUM_BUFF_RXDESCS must be at least 3
+#endif
+
+/** @defgroup lwip17xx_emac_DRIVER    lpc17 EMAC driver for LWIP
+ * @ingroup lwip_emac
+ *
+ * @{
+ */
+
+#if NO_SYS == 0
+/** \brief  Driver transmit and receive thread priorities
+ * 
+ * Thread priorities for receive thread and TX cleanup thread. Alter
+ * to prioritize receive or transmit bandwidth. In a heavily loaded
+ * system or with LEIP_DEBUG enabled, the priorities might be better
+ * the same. */
+#define tskRECPKT_PRIORITY   (DEFAULT_THREAD_PRIO + 4)
+#define tskTXCLEAN_PRIORITY  (DEFAULT_THREAD_PRIO + 5)
+
+/** \brief  Debug output formatter lock define
+ * 
+ * When using FreeRTOS and with LWIP_DEBUG enabled, enabling this
+ * define will allow RX debug messages to not interleave with the
+ * TX messages (so they are actually readable). Not enabling this
+ * define when the system is under load will cause the output to
+ * be unreadable. There is a small tradeoff in performance for this
+ * so use it only for debug. */
+//#define LOCK_RX_THREAD
+
+/** \brief  Receive group interrupts
+ */
+#define RXINTGROUP (EMAC_INT_RX_OVERRUN | EMAC_INT_RX_ERR | EMAC_INT_RX_DONE)
+
+/** \brief  Transmit group interrupts
+ */
+#define TXINTGROUP (EMAC_INT_TX_UNDERRUN | EMAC_INT_TX_ERR | EMAC_INT_TX_DONE)
+#else
+#define RXINTGROUP 0
+#define TXINTGROUP 0
+#endif
+
+ /** \brief  Structure of a TX/RX descriptor
+ */
+typedef struct
+{
+    volatile u32_t packet;        /**< Pointer to buffer */
+    volatile u32_t control;       /**< Control word */
+} LPC_TXRX_DESC_T;
+
+/** \brief  Structure of a RX status entry
+ */
+typedef struct
+{
+    volatile u32_t statusinfo;   /**< RX status word */
+    volatile u32_t statushashcrc; /**< RX hash CRC */
+} LPC_TXRX_STATUS_T;
+
+/* LPC EMAC driver data structure */
+struct lpc_enetdata {
+    /* prxs must be 8 byte aligned! */
+    LPC_TXRX_STATUS_T prxs[LPC_NUM_BUFF_RXDESCS]; /**< Pointer to RX statuses */
+    struct netif *netif;        /**< Reference back to LWIP parent netif */
+    LPC_TXRX_DESC_T ptxd[LPC_NUM_BUFF_TXDESCS];   /**< Pointer to TX descriptor list */
+    LPC_TXRX_STATUS_T ptxs[LPC_NUM_BUFF_TXDESCS]; /**< Pointer to TX statuses */
+    LPC_TXRX_DESC_T prxd[LPC_NUM_BUFF_RXDESCS];   /**< Pointer to RX descriptor list */
+    struct pbuf *rxb[LPC_NUM_BUFF_RXDESCS]; /**< RX pbuf pointer list, zero-copy mode */
+    u32_t rx_fill_desc_index; /**< RX descriptor next available index */
+    volatile u32_t rx_free_descs; /**< Count of free RX descriptors */
+    struct pbuf *txb[LPC_NUM_BUFF_TXDESCS]; /**< TX pbuf pointer list, zero-copy mode */
+    u32_t lpc_last_tx_idx; /**< TX last descriptor index, zero-copy mode */
+#if NO_SYS == 0
+    sys_sem_t RxSem; /**< RX receive thread wakeup semaphore */
+    sys_sem_t TxCleanSem; /**< TX cleanup thread wakeup semaphore */
+    sys_mutex_t TXLockMutex; /**< TX critical section mutex */
+    xSemaphoreHandle xTXDCountSem; /**< TX free buffer counting semaphore */
+#endif
+};
+
+/** \brief  LPC EMAC driver work data
+ */
+ALIGNED(8) struct lpc_enetdata lpc_enetdata;
+
+/* Write a value via the MII link (non-blocking) */
+void lpc_mii_write_noblock(u32_t PhyReg, u32_t Value)
+{
+    /* Write value at PHY address and register */
+    LPC_EMAC->MADR = (LPC_PHYDEF_PHYADDR << 8) | PhyReg;
+    LPC_EMAC->MWTD = Value;
+}
+
+/* Write a value via the MII link (blocking) */
+err_t lpc_mii_write(u32_t PhyReg, u32_t Value)
+{
+    u32_t mst = 250;
+    err_t sts = ERR_OK;
+
+    /* Write value at PHY address and register */
+    lpc_mii_write_noblock(PhyReg, Value);
+
+    /* Wait for unbusy status */
+    while (mst > 0) {
+        sts = LPC_EMAC->MIND;
+        if ((sts & EMAC_MIND_BUSY) == 0)
+            mst = 0;
+        else {
+            mst--;
+            msDelay(1);
+        }
+    }
+
+    if (sts != 0)
+        sts = ERR_TIMEOUT;
+
+    return sts;
+}
+
+/* Reads current MII link busy status */
+u32_t lpc_mii_is_busy(void)
+{
+    return (u32_t) (LPC_EMAC->MIND & EMAC_MIND_BUSY);
+}
+
+/* Starts a read operation via the MII link (non-blocking) */
+u32_t lpc_mii_read_data(void)
+{
+    u32_t data = LPC_EMAC->MRDD;
+    LPC_EMAC->MCMD = 0;
+
+    return data;
+}
+
+/* Starts a read operation via the MII link (non-blocking) */
+void lpc_mii_read_noblock(u32_t PhyReg) 
+{
+    /* Read value at PHY address and register */
+    LPC_EMAC->MADR = (LPC_PHYDEF_PHYADDR << 8) | PhyReg;
+    LPC_EMAC->MCMD = EMAC_MCMD_READ;
+}
+
+/* Read a value via the MII link (blocking) */
+err_t lpc_mii_read(u32_t PhyReg, u32_t *data) 
+{
+    u32_t mst = 250;
+    err_t sts = ERR_OK;
+
+    /* Read value at PHY address and register */
+    lpc_mii_read_noblock(PhyReg);
+
+    /* Wait for unbusy status */
+    while (mst > 0) {
+        sts = LPC_EMAC->MIND & ~EMAC_MIND_MII_LINK_FAIL;
+        if ((sts & EMAC_MIND_BUSY) == 0) {
+            mst = 0;
+            *data = LPC_EMAC->MRDD;
+        } else {
+            mst--;
+            msDelay(1);
+        }
+    }
+
+    LPC_EMAC->MCMD = 0;
+
+    if (sts != 0)
+        sts = ERR_TIMEOUT;
+
+    return sts;
+}
+
+/** \brief  Queues a pbuf into the RX descriptor list
+ *
+ *  \param[in] lpc_enetif Pointer to the drvier data structure
+ *  \param[in] p            Pointer to pbuf to queue
+ */
+static void lpc_rxqueue_pbuf(struct lpc_enetdata *lpc_enetif, struct pbuf *p)
+{
+    u32_t idx;
+
+    /* Get next free descriptor index */
+    idx = lpc_enetif->rx_fill_desc_index;
+
+    /* Setup descriptor and clear statuses */
+    lpc_enetif->prxd[idx].control = EMAC_RCTRL_INT | ((u32_t) (p->len - 1));
+    lpc_enetif->prxd[idx].packet = (u32_t) p->payload;
+    lpc_enetif->prxs[idx].statusinfo = 0xFFFFFFFF;
+    lpc_enetif->prxs[idx].statushashcrc = 0xFFFFFFFF;
+
+    /* Save pbuf pointer for push to network layer later */
+    lpc_enetif->rxb[idx] = p;
+
+    /* Wrap at end of descriptor list */
+    idx++;
+    if (idx >= LPC_NUM_BUFF_RXDESCS)
+        idx = 0;
+
+    /* Queue descriptor(s) */
+    lpc_enetif->rx_free_descs -= 1;
+    lpc_enetif->rx_fill_desc_index = idx;
+    LPC_EMAC->RxConsumeIndex = idx;
+
+    LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE,
+        ("lpc_rxqueue_pbuf: pbuf packet queued: %p (free desc=%d)\n", p,
+            lpc_enetif->rx_free_descs));
+}
+
+/** \brief  Attempt to allocate and requeue a new pbuf for RX
+ *
+ *  \param[in]     netif Pointer to the netif structure
+ *  \returns         1 if a packet was allocated and requeued, otherwise 0
+ */
+s32_t lpc_rx_queue(struct netif *netif)
+{
+    struct lpc_enetdata *lpc_enetif = netif->state;
+    struct pbuf *p;
+    s32_t queued = 0;
+
+    /* Attempt to requeue as many packets as possible */
+    while (lpc_enetif->rx_free_descs > 0) {
+        /* Allocate a pbuf from the pool. We need to allocate at the
+           maximum size as we don't know the size of the yet to be
+           received packet. */
+        p = pbuf_alloc(PBUF_RAW, (u16_t) EMAC_ETH_MAX_FLEN, PBUF_RAM);
+        if (p == NULL) {
+            LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE,
+                ("lpc_rx_queue: could not allocate RX pbuf (free desc=%d)\n",
+                lpc_enetif->rx_free_descs));
+            return queued;
+        }
+
+        /* pbufs allocated from the RAM pool should be non-chained. */
+        LWIP_ASSERT("lpc_rx_queue: pbuf is not contiguous (chained)",
+            pbuf_clen(p) <= 1);
+
+        /* Queue packet */
+        lpc_rxqueue_pbuf(lpc_enetif, p);
+
+        /* Update queued count */
+        queued++;
+    }
+
+    return queued;
+}
+
+/** \brief  Sets up the RX descriptor ring buffers.
+ * 
+ *  This function sets up the descriptor list used for receive packets.
+ *
+ *  \param[in]  lpc_enetif  Pointer to driver data structure
+ *  \returns                   Always returns ERR_OK
+ */
+static err_t lpc_rx_setup(struct lpc_enetdata *lpc_enetif)
+{
+    s32_t idx;
+
+    /* Setup pointers to RX structures */
+    LPC_EMAC->RxDescriptor = (u32_t) &lpc_enetif->prxd[0];
+    LPC_EMAC->RxStatus = (u32_t) &lpc_enetif->prxs[0];
+    LPC_EMAC->RxDescriptorNumber = LPC_NUM_BUFF_RXDESCS - 1;
+
+    lpc_enetif->rx_free_descs = LPC_NUM_BUFF_RXDESCS;
+    lpc_enetif->rx_fill_desc_index = 0;
+
+    /* Build RX buffer and descriptors */
+    lpc_rx_queue(lpc_enetif->netif);
+
+    return ERR_OK;
+}
+
+/** \brief  Allocates a pbuf and returns the data from the incoming packet.
+ *
+ *  \param[in] netif the lwip network interface structure for this lpc_enetif
+ *  \return a pbuf filled with the received packet (including MAC header)
+ *         NULL on memory error
+ */
+static struct pbuf *lpc_low_level_input(struct netif *netif)
+{
+    struct lpc_enetdata *lpc_enetif = netif->state;
+    struct pbuf *p = NULL, *q;
+    u32_t idx, length;
+    u8_t *src;
+
+#ifdef LOCK_RX_THREAD
+#if NO_SYS == 0
+    /* Get exclusive access */
+    sys_mutex_lock(&lpc_enetif->TXLockMutex);
+#endif
+#endif
+
+    /* Monitor RX overrun status. This should never happen unless
+       (possibly) the internal bus is behing held up by something.
+       Unless your system is running at a very low clock speed or
+       there are possibilities that the internal buses may be held
+       up for a long time, this can probably safely be removed. */
+    if (LPC_EMAC->IntStatus & EMAC_INT_RX_OVERRUN) {
+        LINK_STATS_INC(link.err);
+        LINK_STATS_INC(link.drop);
+
+        /* Temporarily disable RX */
+        LPC_EMAC->MAC1 &= ~EMAC_MAC1_REC_EN;
+
+        /* Reset the RX side */
+        LPC_EMAC->MAC1 |= EMAC_MAC1_RES_RX;
+        LPC_EMAC->IntClear = EMAC_INT_RX_OVERRUN;
+
+        /* De-allocate all queued RX pbufs */
+        for (idx = 0; idx < LPC_NUM_BUFF_RXDESCS; idx++) {
+            if (lpc_enetif->rxb[idx] != NULL) {
+                pbuf_free(lpc_enetif->rxb[idx]);
+                lpc_enetif->rxb[idx] = NULL;
+            }
+        }
+
+        /* Start RX side again */
+        lpc_rx_setup(lpc_enetif);
+
+        /* Re-enable RX */
+        LPC_EMAC->MAC1 |= EMAC_MAC1_REC_EN;
+
+#ifdef LOCK_RX_THREAD
+#if NO_SYS == 0
+        sys_mutex_unlock(&lpc_enetif->TXLockMutex);
+#endif
+#endif
+
+        return NULL;
+    }
+
+    /* Determine if a frame has been received */
+    length = 0;
+    idx = LPC_EMAC->RxConsumeIndex;
+    if (LPC_EMAC->RxProduceIndex != idx) {
+        /* Handle errors */
+        if (lpc_enetif->prxs[idx].statusinfo & (EMAC_RINFO_CRC_ERR |
+            EMAC_RINFO_SYM_ERR | EMAC_RINFO_ALIGN_ERR | EMAC_RINFO_LEN_ERR)) {
+#if LINK_STATS
+            if (lpc_enetif->prxs[idx].statusinfo & (EMAC_RINFO_CRC_ERR |
+                EMAC_RINFO_SYM_ERR | EMAC_RINFO_ALIGN_ERR))
+                LINK_STATS_INC(link.chkerr);
+            if (lpc_enetif->prxs[idx].statusinfo & EMAC_RINFO_LEN_ERR)
+                LINK_STATS_INC(link.lenerr);
+#endif
+
+            /* Drop the frame */
+            LINK_STATS_INC(link.drop);
+
+            /* Re-queue the pbuf for receive */
+            lpc_enetif->rx_free_descs++;
+            p = lpc_enetif->rxb[idx];
+            lpc_enetif->rxb[idx] = NULL;
+            lpc_rxqueue_pbuf(lpc_enetif, p);
+
+            LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE,
+                ("lpc_low_level_input: Packet dropped with errors (0x%x)\n",
+                lpc_enetif->prxs[idx].statusinfo));
+        } else {
+            /* A packet is waiting, get length */
+            length = (lpc_enetif->prxs[idx].statusinfo & 0x7FF) + 1;
+
+            /* Zero-copy */
+            p = lpc_enetif->rxb[idx];
+            p->len = (u16_t) length;
+
+            /* Free pbuf from desriptor */
+            lpc_enetif->rxb[idx] = NULL;
+            lpc_enetif->rx_free_descs++;
+
+            LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE,
+                ("lpc_low_level_input: Packet received: %p, size %d (index=%d)\n",
+                p, length, idx));
+
+            /* Save size */
+            p->tot_len = (u16_t) length;
+            LINK_STATS_INC(link.recv);
+
+            /* Queue new buffer(s) */
+            lpc_rx_queue(lpc_enetif->netif);
+        }
+    }
+
+#ifdef LOCK_RX_THREAD
+#if NO_SYS == 0
+    sys_mutex_unlock(&lpc_enetif->TXLockMutex);
+#endif
+#endif
+
+    return p;  
+}
+
+/** \brief  Attempt to read a packet from the EMAC interface.
+ *
+ *  \param[in] netif the lwip network interface structure for this lpc_enetif
+ */
+void lpc_enetif_input(struct netif *netif)
+{
+    struct eth_hdr *ethhdr;
+    struct pbuf *p;
+
+    /* move received packet into a new pbuf */
+    p = lpc_low_level_input(netif);
+    if (p == NULL)
+        return;
+
+    /* points to packet payload, which starts with an Ethernet header */
+    ethhdr = p->payload;
+
+    switch (htons(ethhdr->type)) {
+        case ETHTYPE_IP:
+        case ETHTYPE_ARP:
+#if PPPOE_SUPPORT
+        case ETHTYPE_PPPOEDISC:
+        case ETHTYPE_PPPOE:
+#endif /* PPPOE_SUPPORT */
+            /* full packet send to tcpip_thread to process */
+            if (netif->input(p, netif) != ERR_OK) {
+                LWIP_DEBUGF(NETIF_DEBUG, ("lpc_enetif_input: IP input error\n"));
+                /* Free buffer */
+                pbuf_free(p);
+            }
+            break;
+
+        default:
+            /* Return buffer */
+            pbuf_free(p);
+            break;
+    }
+}
+
+/** \brief  Determine if the passed address is usable for the ethernet
+ *          DMA controller.
+ *
+ *  \param[in] addr Address of packet to check for DMA safe operation
+ *  \return          1 if the packet address is not safe, otherwise 0
+ */
+static s32_t lpc_packet_addr_notsafe(void *addr) {
+    /* Check for legal address ranges */
+    if ((((u32_t) addr >= 0x20000000) && ((u32_t) addr < 0x20008000)) ||
+        (((u32_t) addr >= 0x80000000) && ((u32_t) addr < 0xF0000000)))
+        return 0;
+
+    return 1;
+}
+
+/** \brief  Sets up the TX descriptor ring buffers.
+ *
+ *  This function sets up the descriptor list used for transmit packets.
+ *
+ *  \param[in]      lpc_enetif  Pointer to driver data structure
+ */
+static err_t lpc_tx_setup(struct lpc_enetdata *lpc_enetif)
+{
+    s32_t idx;
+
+    /* Build TX descriptors for local buffers */
+    for (idx = 0; idx < LPC_NUM_BUFF_TXDESCS; idx++) {
+        lpc_enetif->ptxd[idx].control = 0;
+        lpc_enetif->ptxs[idx].statusinfo = 0xFFFFFFFF;
+    }
+
+    /* Setup pointers to TX structures */
+    LPC_EMAC->TxDescriptor = (u32_t) &lpc_enetif->ptxd[0];
+    LPC_EMAC->TxStatus = (u32_t) &lpc_enetif->ptxs[0];
+    LPC_EMAC->TxDescriptorNumber = LPC_NUM_BUFF_TXDESCS - 1;
+
+    lpc_enetif->lpc_last_tx_idx = 0;
+
+    return ERR_OK;
+}
+
+/** \brief  Free TX buffers that are complete
+ *
+ *  \param[in] lpc_enetif  Pointer to driver data structure
+ *  \param[in] cidx  EMAC current descriptor comsumer index
+ */
+static void lpc_tx_reclaim_st(struct lpc_enetdata *lpc_enetif, u32_t cidx)
+{
+#if NO_SYS == 0
+    /* Get exclusive access */
+    sys_mutex_lock(&lpc_enetif->TXLockMutex);
+#endif
+
+    while (cidx != lpc_enetif->lpc_last_tx_idx) {
+        if (lpc_enetif->txb[lpc_enetif->lpc_last_tx_idx] != NULL) {
+            LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE,
+                ("lpc_tx_reclaim_st: Freeing packet %p (index %d)\n",
+                lpc_enetif->txb[lpc_enetif->lpc_last_tx_idx],
+                lpc_enetif->lpc_last_tx_idx));
+            pbuf_free(lpc_enetif->txb[lpc_enetif->lpc_last_tx_idx]);
+             lpc_enetif->txb[lpc_enetif->lpc_last_tx_idx] = NULL;
+        }
+
+#if NO_SYS == 0
+        xSemaphoreGive(lpc_enetif->xTXDCountSem);
+#endif
+        lpc_enetif->lpc_last_tx_idx++;
+        if (lpc_enetif->lpc_last_tx_idx >= LPC_NUM_BUFF_TXDESCS)
+            lpc_enetif->lpc_last_tx_idx = 0;
+    }
+
+#if NO_SYS == 0
+    /* Restore access */
+    sys_mutex_unlock(&lpc_enetif->TXLockMutex);
+#endif
+}
+
+/** \brief  User call for freeingTX buffers that are complete
+ *
+ *  \param[in] netif the lwip network interface structure for this lpc_enetif
+ */
+void lpc_tx_reclaim(struct netif *netif)
+{
+    lpc_tx_reclaim_st((struct lpc_enetdata *) netif->state,
+        LPC_EMAC->TxConsumeIndex);
+}
+
+ /** \brief  Polls if an available TX descriptor is ready. Can be used to
+ *           determine if the low level transmit function will block.
+ *
+ *  \param[in] netif the lwip network interface structure for this lpc_enetif
+ *  \return 0 if no descriptors are read, or >0
+ */
+s32_t lpc_tx_ready(struct netif *netif)
+{
+    s32_t fb;
+    u32_t idx, cidx;
+
+    cidx = LPC_EMAC->TxConsumeIndex;
+    idx = LPC_EMAC->TxProduceIndex;
+
+    /* Determine number of free buffers */
+    if (idx == cidx)
+        fb = LPC_NUM_BUFF_TXDESCS;
+    else if (cidx > idx)
+        fb = (LPC_NUM_BUFF_TXDESCS - 1) -
+            ((idx + LPC_NUM_BUFF_TXDESCS) - cidx);
+    else
+        fb = (LPC_NUM_BUFF_TXDESCS - 1) - (cidx - idx);
+
+    return fb;
+}
+
+/** \brief  Low level output of a packet. Never call this from an
+ *          interrupt context, as it may block until TX descriptors
+ *          become available.
+ *
+ *  \param[in] netif the lwip network interface structure for this lpc_enetif
+ *  \param[in] p the MAC packet to send (e.g. IP packet including MAC addresses and type)
+ *  \return ERR_OK if the packet could be sent or an err_t value if the packet couldn't be sent
+ */
+static err_t lpc_low_level_output(struct netif *netif, struct pbuf *p)
+{
+    struct lpc_enetdata *lpc_enetif = netif->state;
+    struct pbuf *q;
+    u8_t *dst;
+    u32_t idx, sz = 0;
+    err_t err = ERR_OK;
+    struct pbuf *np;
+    u32_t dn, notdmasafe = 0;
+
+    /* Zero-copy TX buffers may be fragmented across mutliple payload
+       chains. Determine the number of descriptors needed for the
+       transfer. The pbuf chaining can be a mess! */
+    dn = (u32_t) pbuf_clen(p);
+
+    /* Test to make sure packet addresses are DMA safe. A DMA safe
+       address is once that uses external memory or periphheral RAM.
+       IRAM and FLASH are not safe! */
+    for (q = p; q != NULL; q = q->next)
+        notdmasafe += lpc_packet_addr_notsafe(q->payload);
+
+#if LPC_TX_PBUF_BOUNCE_EN==1
+    /* If the pbuf is not DMA safe, a new bounce buffer (pbuf) will be
+       created that will be used instead. This requires an copy from the
+       non-safe DMA region to the new pbuf */
+    if (notdmasafe) {
+        /* Allocate a pbuf in DMA memory */
+        np = pbuf_alloc(PBUF_RAW, p->tot_len, PBUF_RAM);
+        if (np == NULL)
+            return ERR_MEM;    
+
+        /* This buffer better be contiguous! */
+        LWIP_ASSERT("lpc_low_level_output: New transmit pbuf is chained",
+            (pbuf_clen(np) == 1));
+
+        /* Copy to DMA safe pbuf */
+        dst = (u8_t *) np->payload;
+         for(q = p; q != NULL; q = q->next) {
+            /* Copy the buffer to the descriptor's buffer */
+              MEMCPY(dst, (u8_t *) q->payload, q->len);
+          dst += q->len;
+        }
+        np->len = p->tot_len; 
+
+        LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE,
+            ("lpc_low_level_output: Switched to DMA safe buffer, old=%p, new=%p\n",
+            q, np));
+
+        /* use the new buffer for descrptor queueing. The original pbuf will
+           be de-allocated outsuide this driver. */
+        p = np;
+        dn = 1;
+    }
+#else
+    if (notdmasafe)
+        LWIP_ASSERT("lpc_low_level_output: Not a DMA safe pbuf",
+            (notdmasafe == 0));
+#endif
+
+    /* Wait until enough descriptors are available for the transfer. */
+    /* THIS WILL BLOCK UNTIL THERE ARE ENOUGH DESCRIPTORS AVAILABLE */
+    while (dn > lpc_tx_ready(netif))
+#if NO_SYS == 0
+        xSemaphoreTake(lpc_enetif->xTXDCountSem, 0);
+#else
+        msDelay(1);
+#endif
+
+    /* Get free TX buffer index */
+    idx = LPC_EMAC->TxProduceIndex;
+
+#if NO_SYS == 0
+    /* Get exclusive access */
+    sys_mutex_lock(&lpc_enetif->TXLockMutex);
+#endif
+
+    /* Prevent LWIP from de-allocating this pbuf. The driver will
+       free it once it's been transmitted. */
+    if (!notdmasafe)
+        pbuf_ref(p);
+
+    /* Setup transfers */
+    q = p;
+    while (dn > 0) {
+        dn--;
+
+        /* Only save pointer to free on last descriptor */
+        if (dn == 0) {
+            /* Save size of packet and signal it's ready */
+            lpc_enetif->ptxd[idx].control = (q->len - 1) | EMAC_TCTRL_INT |
+                EMAC_TCTRL_LAST;
+            lpc_enetif->txb[idx] = p;
+        }
+        else {
+            /* Save size of packet, descriptor is not last */
+            lpc_enetif->ptxd[idx].control = (q->len - 1) | EMAC_TCTRL_INT;
+            lpc_enetif->txb[idx] = NULL;
+        }
+
+        LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE,
+            ("lpc_low_level_output: pbuf packet(%p) sent, chain#=%d,"
+            " size = %d (index=%d)\n", q->payload, dn, q->len, idx));
+
+        lpc_enetif->ptxd[idx].packet = (u32_t) q->payload;
+
+        q = q->next;
+
+        idx++;
+        if (idx >= LPC_NUM_BUFF_TXDESCS)
+            idx = 0;
+    }
+
+    LPC_EMAC->TxProduceIndex = idx;
+
+    LINK_STATS_INC(link.xmit);
+
+#if NO_SYS == 0
+    /* Restore access */
+    sys_mutex_unlock(&lpc_enetif->TXLockMutex);
+#endif
+
+    return ERR_OK;
+}
+
+/** \brief  LPC EMAC interrupt handler.
+ *
+ *  This function handles the transmit, receive, and error interrupt of
+ *  the LPC177x_8x. This is meant to be used when NO_SYS=0.
+ */
+void ENET_IRQHandler(void)
+{
+#if NO_SYS == 1
+    /* Interrupts are not used without an RTOS */
+    NVIC_DisableIRQ(ENET_IRQn);
+#else
+    signed portBASE_TYPE xRecTaskWoken = pdFALSE, XTXTaskWoken = pdFALSE;
+    uint32_t ints;
+
+    /* Interrupts are of 2 groups - transmit or receive. Based on the
+       interrupt, kick off the receive or transmit (cleanup) task */
+
+    /* Get pending interrupts */
+    ints = LPC_EMAC->IntStatus;
+
+    if (ints & RXINTGROUP) {
+        /* RX group interrupt(s) */
+        /* Give semaphore to wakeup RX receive task. Note the FreeRTOS
+           method is used instead of the LWIP arch method. */
+        xSemaphoreGiveFromISR(lpc_enetdata.RxSem, &xRecTaskWoken);
+    }
+
+    if (ints & TXINTGROUP) {
+        /* TX group interrupt(s) */
+        /* Give semaphore to wakeup TX cleanup task. Note the FreeRTOS
+           method is used instead of the LWIP arch method. */
+        xSemaphoreGiveFromISR(lpc_enetdata.TxCleanSem, &XTXTaskWoken);
+    }
+
+    /* Clear pending interrupts */
+    LPC_EMAC->IntClear = ints;
+
+    /* Context switch needed? */
+    portEND_SWITCHING_ISR( xRecTaskWoken || XTXTaskWoken );
+#endif
+}
+
+#if NO_SYS == 0
+/** \brief  Packet reception task
+ *
+ * This task is called when a packet is received. It will
+ * pass the packet to the LWIP core.
+ *
+ *  \param[in] pvParameters Not used yet
+ */
+static portTASK_FUNCTION( vPacketReceiveTask, pvParameters )
+{
+    struct lpc_enetdata *lpc_enetif = pvParameters;
+
+    while (1) {
+        /* Wait for receive task to wakeup */
+        sys_arch_sem_wait(&lpc_enetif->RxSem, 0);
+
+        /* Process packets until all empty */
+        while (LPC_EMAC->RxConsumeIndex != LPC_EMAC->RxProduceIndex)
+            lpc_enetif_input(lpc_enetif->netif);
+    }
+}
+
+/** \brief  Transmit cleanup task
+ *
+ * This task is called when a transmit interrupt occurs and
+ * reclaims the pbuf and descriptor used for the packet once
+ * the packet has been transferred.
+ *
+ *  \param[in] pvParameters Not used yet
+ */
+static portTASK_FUNCTION( vTransmitCleanupTask, pvParameters )
+{
+    struct lpc_enetdata *lpc_enetif = pvParameters;
+    s32_t idx;
+
+    while (1) {
+        /* Wait for transmit cleanup task to wakeup */
+        sys_arch_sem_wait(&lpc_enetif->TxCleanSem, 0);
+
+        /* Error handling for TX underruns. This should never happen unless
+           something is holding the bus or the clocks are going too slow. It
+           can probably be safely removed. */
+         if (LPC_EMAC->IntStatus & EMAC_INT_TX_UNDERRUN) {
+            LINK_STATS_INC(link.err);
+            LINK_STATS_INC(link.drop);
+
+#if NO_SYS == 0
+            /* Get exclusive access */
+            sys_mutex_lock(&lpc_enetif->TXLockMutex);
+#endif
+            /* Reset the TX side */
+            LPC_EMAC->MAC1 |= EMAC_MAC1_RES_TX;
+            LPC_EMAC->IntClear = EMAC_INT_TX_UNDERRUN;
+
+            /* De-allocate all queued TX pbufs */
+            for (idx = 0; idx < LPC_NUM_BUFF_RXDESCS; idx++) {
+                if (lpc_enetif->txb[idx] != NULL) {
+                    pbuf_free(lpc_enetif->txb[idx]);
+                    lpc_enetif->txb[idx] = NULL;
+                }
+            }
+
+#if NO_SYS == 0
+            /* Restore access */
+            sys_mutex_unlock(&lpc_enetif->TXLockMutex);
+#endif
+            /* Start TX side again */
+            lpc_tx_setup(lpc_enetif);
+        } else {
+            /* Free TX buffers that are done sending */
+            lpc_tx_reclaim(lpc_enetdata.netif);
+        }
+    }
+}
+#endif
+
+/** \brief  Low level init of the MAC and PHY.
+ *
+ *  \param[in]      netif  Pointer to LWIP netif structure
+ */
+static err_t low_level_init(struct netif *netif)
+{
+    struct lpc_enetdata *lpc_enetif = netif->state;
+    err_t err = ERR_OK;
+
+    /* Enable MII clocking */
+    CLKPWR_ConfigPPWR(CLKPWR_PCONP_PCENET, ENABLE);
+
+    /* Reset all MAC logic */
+    LPC_EMAC->MAC1 = EMAC_MAC1_RES_TX | EMAC_MAC1_RES_MCS_TX |
+        EMAC_MAC1_RES_RX | EMAC_MAC1_RES_MCS_RX | EMAC_MAC1_SIM_RES |
+        EMAC_MAC1_SOFT_RES;
+    LPC_EMAC->Command = EMAC_CR_REG_RES | EMAC_CR_TX_RES | EMAC_CR_RX_RES |
+        EMAC_CR_PASS_RUNT_FRM;
+    msDelay(10);
+
+    /* Initial MAC initialization */
+    LPC_EMAC->MAC1 = EMAC_MAC1_PASS_ALL;
+    LPC_EMAC->MAC2 = EMAC_MAC2_CRC_EN | EMAC_MAC2_PAD_EN |
+        EMAC_MAC2_VLAN_PAD_EN;
+    LPC_EMAC->MAXF = EMAC_ETH_MAX_FLEN;
+
+    /* Set RMII management clock rate to lowest speed */
+    LPC_EMAC->MCFG = EMAC_MCFG_CLK_SEL(11) | EMAC_MCFG_RES_MII;
+    LPC_EMAC->MCFG &= ~EMAC_MCFG_RES_MII;
+
+    /* Maximum number of retries, 0x37 collision window, gap */
+    LPC_EMAC->CLRT = EMAC_CLRT_DEF;
+    LPC_EMAC->IPGR = EMAC_IPGR_P1_DEF | EMAC_IPGR_P2_DEF;
+
+#if LPC_EMAC_RMII
+    /* RMII setup */
+    LPC_EMAC->Command = EMAC_CR_PASS_RUNT_FRM | EMAC_CR_RMII;
+#else
+    /* MII setup */
+    LPC_EMAC->CR = EMAC_CR_PASS_RUNT_FRM;
+#endif
+
+    /* Initialize the PHY and reset */
+    err = lpc_phy_init(netif, LPC_EMAC_RMII);
+    if (err != ERR_OK)
+         return err;
+
+    /* Save station address */
+    LPC_EMAC->SA2 = (u32_t) netif->hwaddr[0] |
+        (((u32_t) netif->hwaddr[1]) << 8);
+    LPC_EMAC->SA1 = (u32_t) netif->hwaddr[2] |
+        (((u32_t) netif->hwaddr[3]) << 8);
+    LPC_EMAC->SA0 = (u32_t) netif->hwaddr[4] |
+        (((u32_t) netif->hwaddr[5]) << 8);
+
+    /* Setup transmit and receive descriptors */
+    if (lpc_tx_setup(lpc_enetif) != ERR_OK)
+        return ERR_BUF;
+    if (lpc_rx_setup(lpc_enetif) != ERR_OK)
+        return ERR_BUF;
+
+    /* Enable packet reception */
+#if IP_SOF_BROADCAST_RECV
+    LPC_EMAC->RxFilterCtrl = EMAC_RFC_PERFECT_EN | EMAC_RFC_BCAST_EN;
+#else
+    LPC_EMAC->RxFilterCtrl = EMAC_RFC_PERFECT_EN;
+#endif
+
+    /* Clear and enable rx/tx interrupts */
+    LPC_EMAC->IntClear = 0xFFFF;
+    LPC_EMAC->IntEnable = RXINTGROUP | TXINTGROUP;
+
+    /* Enable RX and TX */
+    LPC_EMAC->Command |= EMAC_CR_RX_EN | EMAC_CR_TX_EN;
+    LPC_EMAC->MAC1 |= EMAC_MAC1_REC_EN;
+
+    return err;
+}
+
+/* This function provides a method for the PHY to setup the EMAC
+   for the PHY negotiated duplex mode */
+void lpc_emac_set_duplex(int full_duplex)
+{
+    if (full_duplex) {
+        LPC_EMAC->MAC2    |= EMAC_MAC2_FULL_DUP;
+        LPC_EMAC->Command |= EMAC_CR_FULL_DUP;
+        LPC_EMAC->IPGT     = EMAC_IPGT_FULL_DUP;
+    } else {
+        LPC_EMAC->MAC2    &= ~EMAC_MAC2_FULL_DUP;
+        LPC_EMAC->Command &= ~EMAC_CR_FULL_DUP;
+        LPC_EMAC->IPGT = EMAC_IPGT_HALF_DUP;
+    }
+}
+
+/* This function provides a method for the PHY to setup the EMAC
+   for the PHY negotiated bit rate */
+void lpc_emac_set_speed(int mbs_100)
+{
+    if (mbs_100)
+        LPC_EMAC->SUPP = EMAC_SUPP_SPEED;
+    else
+        LPC_EMAC->SUPP = 0;
+}
+
+/**
+ * This function is the ethernet packet send function. It calls
+ * etharp_output after checking link status.
+ *
+ * \param[in] netif the lwip network interface structure for this lpc_enetif
+ * \param[in] q Pointer to pbug to send
+ * \param[in] ipaddr IP address 
+ * \return ERR_OK or error code
+ */
+err_t lpc_etharp_output(struct netif *netif, struct pbuf *q,
+    ip_addr_t *ipaddr)
+{
+    /* Only send packet is link is up */
+    if (netif->flags & NETIF_FLAG_LINK_UP)
+        return etharp_output(netif, q, ipaddr);
+
+    return ERR_CONN;
+}
+
+/**
+ * Should be called at the beginning of the program to set up the
+ * network interface.
+ *
+ * This function should be passed as a parameter to netif_add().
+ *
+ * @param[in] netif the lwip network interface structure for this lpc_enetif
+ * @return ERR_OK if the loopif is initialized
+ *         ERR_MEM if private data couldn't be allocated
+ *         any other err_t on error
+ */
+err_t lpc_enetif_init(struct netif *netif)
+{
+    err_t err;
+
+    LWIP_ASSERT("netif != NULL", (netif != NULL));
+    
+    lpc_enetdata.netif = netif;
+
+    /* set MAC hardware address */
+    board_get_macaddr(netif->hwaddr);
+    netif->hwaddr_len = ETHARP_HWADDR_LEN;
+
+     /* maximum transfer unit */
+    netif->mtu = 1500;
+
+    /* device capabilities */
+    netif->flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP | NETIF_FLAG_UP |
+        NETIF_FLAG_ETHERNET;
+
+    /* Initialize the hardware */
+    netif->state = &lpc_enetdata;
+    err = low_level_init(netif);
+    if (err != ERR_OK)
+        return err;
+
+#if LWIP_NETIF_HOSTNAME
+    /* Initialize interface hostname */
+    netif->hostname = "lwiplpc";
+#endif /* LWIP_NETIF_HOSTNAME */
+
+    netif->name[0] = 'e';
+    netif->name[1] = 'n';
+
+    netif->output = lpc_etharp_output;
+    netif->linkoutput = lpc_low_level_output;
+
+    /* For FreeRTOS, start tasks */
+#if NO_SYS == 0
+    lpc_enetdata.xTXDCountSem = xSemaphoreCreateCounting(LPC_NUM_BUFF_TXDESCS,
+        LPC_NUM_BUFF_TXDESCS);
+    LWIP_ASSERT("xTXDCountSem creation error",
+        (lpc_enetdata.xTXDCountSem != NULL));
+
+    err = sys_mutex_new(&lpc_enetdata.TXLockMutex);
+    LWIP_ASSERT("TXLockMutex creation error", (err == ERR_OK));
+
+    /* Packet receive task */
+    err = sys_sem_new(&lpc_enetdata.RxSem, 0);
+    LWIP_ASSERT("RxSem creation error", (err == ERR_OK));
+    sys_thread_new("receive_thread", vPacketReceiveTask, netif->state,
+        DEFAULT_THREAD_STACKSIZE, tskRECPKT_PRIORITY);
+
+    /* Transmit cleanup task */
+    err = sys_sem_new(&lpc_enetdata.TxCleanSem, 0);
+    LWIP_ASSERT("TxCleanSem creation error", (err == ERR_OK));
+    sys_thread_new("txclean_thread", vTransmitCleanupTask, netif->state,
+        DEFAULT_THREAD_STACKSIZE, tskTXCLEAN_PRIORITY);
+#endif
+
+    return ERR_OK;
+}
+
+/**
+ * @}
+ */
+
+/* --------------------------------- End Of File ------------------------------ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/arch/lpc17_emac.h	Fri Jun 22 09:32:29 2012 +0000
@@ -0,0 +1,51 @@
+/**********************************************************************
+* $Id$        lpc17_emac.h            2011-11-20
+*//**
+* @file        lpc17_emac.h
+* @brief    LPC17 ethernet driver header file for LWIP
+* @version    1.0
+* @date        20. Nov. 2011
+* @author    NXP MCU SW Application Team
+* 
+* Copyright(C) 2011, NXP Semiconductor
+* All rights reserved.
+*
+***********************************************************************
+* 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.
+**********************************************************************/
+
+#ifndef __LPC17_EMAC_H
+#define __LPC17_EMAC_H
+
+#include "lwip/opt.h"
+#include "lwip/netif.h"
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/* These functions are only visible when not using an RTOS */ 
+#if NO_SYS == 1
+void lpc_enetif_input(struct netif *netif);
+s32_t lpc_tx_ready(struct netif *netif);
+s32_t lpc_rx_queue(struct netif *netif);
+void lpc_tx_reclaim(struct netif *netif);
+#endif
+
+err_t lpc_enetif_init(struct netif *netif);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __LPC17_EMAC_H */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/arch/lpc_emac_config.h	Fri Jun 22 09:32:29 2012 +0000
@@ -0,0 +1,111 @@
+/**********************************************************************
+* $Id$        lpc_emac_config.h            2011-11-20
+*//**
+* @file        lpc_emac_config.h
+* @brief    PHY and EMAC configuration file
+* @version    1.0
+* @date        20 Nov. 2011
+* @author    NXP MCU SW Application Team
+* 
+* Copyright(C) 2011, NXP Semiconductor
+* All rights reserved.
+*
+***********************************************************************
+* 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.
+**********************************************************************/
+
+#ifndef __LPC_EMAC_CONFIG_H
+#define __LPC_EMAC_CONFIG_H
+
+#include "lwip/opt.h"
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/** @defgroup lwip_phy_config    LWIP PHY configuration
+ * @ingroup lwip_phy
+ *
+ * Configuration options for the PHY connected to the LPC EMAC.
+ * @{
+ */
+
+/** \brief  The PHY address connected the to MII/RMII
+ */
+#define LPC_PHYDEF_PHYADDR 1    /**< The PHY address on the PHY device. */
+
+/** \brief  Enable autonegotiation mode.
+ *          If this is enabled, the PHY will attempt to auto-negotiate the
+ *          best link mode if the PHY supports it. If this is not enabled,
+ *          the PHY_USE_FULL_DUPLEX and PHY_USE_100MBS defines will be
+ *          used to select the link mode. Note that auto-negotiation may
+ *          take a few seconds to complete.
+ */
+#define PHY_USE_AUTONEG 1 /**< Enables auto-negotiation mode. */
+
+/** \brief  Sets up the PHY interface to either full duplex operation or
+ *          half duplex operation if PHY_USE_AUTONEG is not enabled.
+ */
+#define PHY_USE_FULL_DUPLEX 1 /**< Sets duplex mode to full. */
+
+/** \brief  Sets up the PHY interface to either 100MBS operation or 10MBS
+ *          operation if PHY_USE_AUTONEG is not enabled.
+ */
+#define PHY_USE_100MBS 1 /**< Sets data rate to 100Mbps. */
+
+/**          
+ * @}
+ */
+
+/** @defgroup lwip_emac_config    LWIP EMAC configuration
+ * @ingroup lwip_emac
+ *
+ * Configuration options for the LPC EMAC.
+ * @{
+ */
+
+/** \brief  Selects RMII or MII connection type in the EMAC peripheral
+ */
+#define LPC_EMAC_RMII 1         /**< Use the RMII or MII driver variant .*/
+
+/** \brief  Defines the number of descriptors used for RX. This
+ *          must be a minimum value of 2.
+ */
+#define LPC_NUM_BUFF_RXDESCS 3
+
+/** \brief  Defines the number of descriptors used for TX. Must
+ *          be a minimum value of 2.
+ */
+#define LPC_NUM_BUFF_TXDESCS 3
+
+/** \brief  Set this define to 1 to enable bounce buffers for transmit pbufs
+ *          that cannot be sent via the zero-copy method. Some chained pbufs
+ *          may have a payload address that links to an area of memory that
+ *          cannot be used for transmit DMA operations. If this define is
+ *          set to 1, an extra check will be made with the pbufs. If a buffer
+ *          is determined to be non-usable for zero-copy, a temporary bounce
+ *          buffer will be created and used instead.
+ */
+#define LPC_TX_PBUF_BOUNCE_EN 0
+
+/**          
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __LPC_EMAC_CONFIG_H */
+
+/* --------------------------------- End Of File ------------------------------ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/arch/lpc_phy.h	Fri Jun 22 09:32:29 2012 +0000
@@ -0,0 +1,151 @@
+/**********************************************************************
+* $Id$        lpc_phy.h            2011-11-20
+*//**
+* @file        lpc_phy.h
+* @brief    Common PHY definitions used with all PHYs
+* @version    1.0
+* @date        20 Nov. 2011
+* @author    NXP MCU SW Application Team
+* 
+* Copyright(C) 2011, NXP Semiconductor
+* All rights reserved.
+*
+***********************************************************************
+* 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.
+**********************************************************************/
+
+#ifndef __LPC_PHY_H_
+#define __LPC_PHY_H_
+
+#include "lwip/opt.h"
+#include "lwip/err.h"
+#include "lwip/netif.h"
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/* These PHY functions are usually part of the EMAC driver */
+
+/** \brief  Phy status update state machine
+ *
+ *  This function provides a state machine for maintaining the PHY
+ *  status without blocking. It must be occasionally called for the
+ *  PHY status to be maintained.
+ *
+ *  \param[in]     netif   NETIF structure
+ */
+s32_t lpc_phy_sts_sm(struct netif *netif);
+
+/** \brief  Initialize the PHY
+ *
+ *  This function initializes the PHY. It will block until complete.
+ *  This function is called as part of the EMAC driver
+ *  initialization. Configuration of the PHY at startup is
+ *  controlled by setting up configuration defines in lpc_phy.h.
+ *
+ *  \param[in]     netif   NETIF structure
+ *  \param[in]     rmii    If set, configures the PHY for RMII mode
+ *  \return        ERR_OK if the setup was successful, otherwise ERR_TIMEOUT
+ */
+err_t lpc_phy_init(struct netif *netif, int rmii);
+
+/** \brief  Write a value via the MII link (non-blocking)
+ *
+ *  This function will write a value on the MII link interface to a PHY
+ *  or a connected device. The function will return immediately without
+ *  a status. Status needs to be polled later to determine if the write
+ *  was successful.
+ *
+ *  \param[in]      PhyReg  PHY register to write to
+ *  \param[in]      Value   Value to write
+ */
+void lpc_mii_write_noblock(u32_t PhyReg, u32_t Value);
+
+/** \brief  Write a value via the MII link (blocking)
+ *
+ *  This function will write a value on the MII link interface to a PHY
+ *  or a connected device. The function will block until complete.
+ *
+ *  \param[in]      PhyReg  PHY register to write to
+ *  \param[in]      Value   Value to write
+ * \returns         0 if the write was successful, otherwise !0
+ */
+err_t lpc_mii_write(u32_t PhyReg, u32_t Value);
+
+/** \brief  Reads current MII link busy status
+ *
+ *  This function will return the current MII link busy status and is meant to
+ *  be used with non-blocking functions for monitor PHY status such as
+ *  connection state.
+ *
+ *  \returns         !0 if the MII link is busy, otherwise 0
+ */
+u32_t lpc_mii_is_busy(void);
+
+/** \brief  Starts a read operation via the MII link (non-blocking)
+ *
+ *  This function returns the current value in the MII data register. It is
+ *  meant to be used with the non-blocking oeprations. This value should
+ *  only be read after a non-block read command has been issued and the
+ *  MII status has been determined to be good.
+ *
+ *  \returns          The current value in the MII value register
+ */
+u32_t lpc_mii_read_data(void);
+
+/** \brief  Starts a read operation via the MII link (non-blocking)
+ *
+ *  This function will start a read operation on the MII link interface
+ *  from a PHY or a connected device. The function will not block and
+ *  the status mist be polled until complete. Once complete, the data
+ *  can be read.
+ *
+ *  \param[in]      PhyReg  PHY register to read from
+ */
+err_t lpc_mii_read(u32_t PhyReg, u32_t *data);
+
+/** \brief  Read a value via the MII link (blocking)
+ *
+ *  This function will read a value on the MII link interface from a PHY
+ *  or a connected device. The function will block until complete.
+ * 
+ *  \param[in]      PhyReg  PHY register to read from
+ *  \param[in]      data    Pointer to where to save data read via MII
+ *  \returns         0 if the read was successful, otherwise !0
+ */
+void lpc_mii_read_noblock(u32_t PhyReg);
+
+/**
+ * This function provides a method for the PHY to setup the EMAC
+ * for the PHY negotiated duplex mode.
+ *
+ * @param[in] full_duplex 0 = half duplex, 1 = full duplex
+ */
+void lpc_emac_set_duplex(int full_duplex);
+
+/**
+ * This function provides a method for the PHY to setup the EMAC
+ * for the PHY negotiated bit rate.
+ *
+ * @param[in] mbs_100     0 = 10mbs mode, 1 = 100mbs mode
+ */
+void lpc_emac_set_speed(int mbs_100);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __LPC_PHY_H_ */
+
+/* --------------------------------- End Of File ------------------------------ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/arch/lpc_phy_dp83848.c	Fri Jun 22 09:32:29 2012 +0000
@@ -0,0 +1,287 @@
+/**********************************************************************
+* $Id$        lpc_phy_dp83848.c            2011-11-20
+*//**
+* @file        lpc_phy_dp83848.c
+* @brief    DP83848C PHY status and control.
+* @version    1.0
+* @date        20 Nov. 2011
+* @author    NXP MCU SW Application Team
+*
+* Copyright(C) 2011, NXP Semiconductor
+* All rights reserved.
+*
+***********************************************************************
+* 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.
+**********************************************************************/
+
+#include "lwip/opt.h"
+#include "lwip/err.h"
+#include "lwip/tcpip.h"
+#include "lwip/snmp.h"
+#include "lpc_emac_config.h"
+#include "lpc_phy.h"
+
+/** @defgroup dp83848_phy    PHY status and control for the DP83848.
+ * @ingroup lwip_phy
+ *
+ * Various functions for controlling and monitoring the status of the
+ * DP83848 PHY. In polled (standalone) systems, the PHY state must be
+ * monitored as part of the application. In a threaded (RTOS) system,
+ * the PHY state is monitored by the PHY handler thread. The MAC
+ * driver will not transmit unless the PHY link is active.
+ * @{
+ */
+
+/** \brief  DP83848 PHY register offsets */
+#define DP8_BMCR_REG        0x0  /**< Basic Mode Control Register */
+#define DP8_BMSR_REG        0x1  /**< Basic Mode Status Reg */
+#define DP8_ANADV_REG       0x4  /**< Auto_Neg Advt Reg  */
+#define DP8_ANLPA_REG       0x5  /**< Auto_neg Link Partner Ability Reg */
+#define DP8_ANEEXP_REG      0x6  /**< Auto-neg Expansion Reg  */
+#define DP8_PHY_STAT_REG    0x10 /**< PHY Status Register  */
+#define DP8_PHY_INT_CTL_REG 0x11 /**< PHY Interrupt Control Register */
+#define DP8_PHY_RBR_REG     0x17 /**< PHY RMII and Bypass Register  */
+#define DP8_PHY_STS_REG     0x19 /**< PHY Status Register  */
+
+/** \brief DP83848 Control register definitions */
+#define DP8_RESET          (1 << 15)  /**< 1= S/W Reset */
+#define DP8_LOOPBACK       (1 << 14)  /**< 1=loopback Enabled */
+#define DP8_SPEED_SELECT   (1 << 13)  /**< 1=Select 100MBps */
+#define DP8_AUTONEG        (1 << 12)  /**< 1=Enable auto-negotiation */
+#define DP8_POWER_DOWN     (1 << 11)  /**< 1=Power down PHY */
+#define DP8_ISOLATE        (1 << 10)  /**< 1=Isolate PHY */
+#define DP8_RESTART_AUTONEG (1 << 9)  /**< 1=Restart auto-negoatiation */
+#define DP8_DUPLEX_MODE    (1 << 8)   /**< 1=Full duplex mode */
+#define DP8_COLLISION_TEST (1 << 7)   /**< 1=Perform collsion test */
+
+/** \brief DP83848 Status register definitions */
+#define DP8_100BASE_T4     (1 << 15)  /**< T4 mode */
+#define DP8_100BASE_TX_FD  (1 << 14)  /**< 100MBps full duplex */
+#define DP8_100BASE_TX_HD  (1 << 13)  /**< 100MBps half duplex */
+#define DP8_10BASE_T_FD    (1 << 12)  /**< 100Bps full duplex */
+#define DP8_10BASE_T_HD    (1 << 11)  /**< 10MBps half duplex */
+#define DP8_MF_PREAMB_SUPPR (1 << 6)  /**< Preamble suppress */
+#define DP8_AUTONEG_COMP   (1 << 5)   /**< Auto-negotation complete */
+#define DP8_RMT_FAULT      (1 << 4)   /**< Fault */
+#define DP8_AUTONEG_ABILITY (1 << 3)  /**< Auto-negotation supported */
+#define DP8_LINK_STATUS    (1 << 2)   /**< 1=Link active */
+#define DP8_JABBER_DETECT  (1 << 1)   /**< Jabber detect */
+#define DP8_EXTEND_CAPAB   (1 << 0)   /**< Supports extended capabilities */
+
+/** \brief DP83848 PHY RBR MII dode definitions */
+#define DP8_RBR_RMII_MODE  (1 << 5)   /**< Use RMII mode */
+
+/** \brief DP83848 PHY status definitions */
+#define DP8_REMOTEFAULT    (1 << 6)   /**< Remote fault */
+#define DP8_FULLDUPLEX     (1 << 2)   /**< 1=full duplex */
+#define DP8_SPEED10MBPS    (1 << 1)   /**< 1=10MBps speed */
+#define DP8_VALID_LINK     (1 << 0)   /**< 1=Link active */
+
+/** \brief DP83848 PHY ID register definitions */
+#define DP8_PHYID1_OUI     0x2000     /**< Expected PHY ID1 */
+#define DP8_PHYID2_OUI     0x5c90     /**< Expected PHY ID2 */
+
+/** \brief PHY status structure used to indicate current status of PHY.
+ */
+typedef struct {
+    u32_t     phy_speed_100mbs:1; /**< 10/100 MBS connection speed flag. */
+    u32_t     phy_full_duplex:1;  /**< Half/full duplex connection speed flag. */
+    u32_t     phy_link_active:1;  /**< Phy link active flag. */
+} PHY_STATUS_TYPE;
+
+/** \brief  PHY update flags */
+static PHY_STATUS_TYPE physts;
+
+/** \brief  Last PHY update flags, used for determing if something has changed */
+static PHY_STATUS_TYPE olddphysts;
+
+/** \brief  PHY update counter for state machine */
+static s32_t phyustate;
+
+/** \brief  Update PHY status from passed value
+ *
+ *  This function updates the current PHY status based on the
+ *  passed PHY status word. The PHY status indicate if the link
+ *  is active, the connection speed, and duplex.
+ *
+ *  \param[in]    netif   NETIF structure
+ *  \param[in]    linksts Status word from PHY
+ *  \return        1 if the status has changed, otherwise 0
+ */
+static s32_t lpc_update_phy_sts(struct netif *netif, u32_t linksts)
+{
+    s32_t changed = 0;
+
+    /* Update link active status */
+    if (linksts & DP8_VALID_LINK)
+        physts.phy_link_active = 1;
+    else
+        physts.phy_link_active = 0;
+
+    /* Full or half duplex */
+    if (linksts & DP8_FULLDUPLEX)
+        physts.phy_full_duplex = 1;
+    else
+        physts.phy_full_duplex = 0;
+
+    /* Configure 100MBit/10MBit mode. */
+    if (linksts & DP8_SPEED10MBPS)
+        physts.phy_speed_100mbs = 0;
+    else
+        physts.phy_speed_100mbs = 1;
+
+    if (physts.phy_speed_100mbs != olddphysts.phy_speed_100mbs) {
+        changed = 1;
+        if (physts.phy_speed_100mbs) {
+            /* 100MBit mode. */
+            lpc_emac_set_speed(1);
+
+            NETIF_INIT_SNMP(netif, snmp_ifType_ethernet_csmacd, 100000000);
+        }
+        else {
+            /* 10MBit mode. */
+            lpc_emac_set_speed(0);
+
+            NETIF_INIT_SNMP(netif, snmp_ifType_ethernet_csmacd, 10000000);
+        }
+
+        olddphysts.phy_speed_100mbs = physts.phy_speed_100mbs;
+    }
+
+    if (physts.phy_full_duplex != olddphysts.phy_full_duplex) {
+        changed = 1;
+        if (physts.phy_full_duplex)
+            lpc_emac_set_duplex(1);
+        else
+            lpc_emac_set_duplex(0);
+
+        olddphysts.phy_full_duplex = physts.phy_full_duplex;
+    }
+
+    if (physts.phy_link_active != olddphysts.phy_link_active) {
+        changed = 1;
+#if NO_SYS == 1
+        if (physts.phy_link_active)
+            netif_set_link_up(netif);
+        else
+            netif_set_link_down(netif);
+#else
+        if (physts.phy_link_active)
+            tcpip_callback_with_block((tcpip_callback_fn) netif_set_link_up,
+                (void*) netif, 1);
+         else
+            tcpip_callback_with_block((tcpip_callback_fn) netif_set_link_down,
+                (void*) netif, 1);
+#endif
+
+        olddphysts.phy_link_active = physts.phy_link_active;
+    }
+
+    return changed;
+}
+
+/** \brief  Initialize the DP83848 PHY.
+ *
+ *  This function initializes the DP83848 PHY. It will block until
+ *  complete. This function is called as part of the EMAC driver
+ *  initialization. Configuration of the PHY at startup is
+ *  controlled by setting up configuration defines in lpc_phy.h.
+ *
+ *  \param[in]     netif   NETIF structure
+ *  \param[in]     rmii    If set, configures the PHY for RMII mode
+ *  \return        ERR_OK if the setup was successful, otherwise ERR_TIMEOUT
+ */
+err_t lpc_phy_init(struct netif *netif, int rmii)
+{
+    u32_t tmp;
+    s32_t i;
+
+    physts.phy_speed_100mbs = olddphysts.phy_speed_100mbs = 2;
+    physts.phy_full_duplex = olddphysts.phy_full_duplex = 2;
+    physts.phy_link_active = olddphysts.phy_link_active = 2;
+    phyustate = 0;
+
+    /* Only first read and write are checked for failure */
+    /* Put the DP83848C in reset mode and wait for completion */
+    if (lpc_mii_write(DP8_BMCR_REG, DP8_RESET) != 0)
+        return ERR_TIMEOUT;
+    i = 400;
+    while (i > 0) {
+        msDelay(1);   /* 1 ms */
+        if (lpc_mii_read(DP8_BMCR_REG, &tmp) != 0)
+            return ERR_TIMEOUT;
+
+        if (!(tmp & (DP8_RESET | DP8_POWER_DOWN)))
+            i = -1;
+        else
+            i--;
+    }
+    /* Timeout? */
+    if (i == 0)
+        return ERR_TIMEOUT;
+
+    /* Setup link based on configuration options */
+#if PHY_USE_AUTONEG==1
+    tmp = DP8_AUTONEG;
+#else
+    tmp = 0;
+#endif
+#if PHY_USE_100MBS==1
+    tmp |= DP8_SPEED_SELECT;
+#endif
+#if PHY_USE_FULL_DUPLEX==1
+    tmp |= DP8_DUPLEX_MODE;
+#endif
+
+    lpc_mii_write(DP8_BMCR_REG, tmp);
+
+    /* Enable RMII mode for PHY */
+    if (rmii)
+        lpc_mii_write(DP8_PHY_RBR_REG, DP8_RBR_RMII_MODE);
+
+    /* The link is not set active at this point, but will be detected
+       later */
+
+    return ERR_OK;
+}
+
+/* Phy status update state machine */
+s32_t lpc_phy_sts_sm(struct netif *netif)
+{
+    s32_t changed = 0;
+
+    switch (phyustate) {
+        default:
+        case 0:
+            /* Read BMSR to clear faults */
+            lpc_mii_read_noblock(DP8_PHY_STAT_REG);
+            phyustate = 1;
+            break;
+
+        case 1:
+            /* Wait for read status state */
+            if (!lpc_mii_is_busy()) {
+                /* Update PHY status */
+                changed = lpc_update_phy_sts(netif, lpc_mii_read_data());
+                phyustate = 0;
+            }
+            break;
+    }
+
+    return changed;
+}
+
+/**
+ * @}
+ */
+
+/* --------------------------------- End Of File ------------------------------ */