Skovbrynet / Mbed 2 deprecated TankCounter

Dependencies:   EthernetInterface NTPClient SDFileSystem TextLCD WebSocketClient mbed-rtos mbed Socket lwip-eth lwip-sys lwip FATFileSystem

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers lpc17_emac.c Source File

lpc17_emac.c

Go to the documentation of this file.
00001 /**********************************************************************
00002 * $Id$        lpc17_emac.c            2011-11-20
00003 *//**
00004 * @file        lpc17_emac.c
00005 * @brief    LPC17 ethernet driver for LWIP
00006 * @version    1.0
00007 * @date        20. Nov. 2011
00008 * @author    NXP MCU SW Application Team
00009 * 
00010 * Copyright(C) 2011, NXP Semiconductor
00011 * All rights reserved.
00012 *
00013 ***********************************************************************
00014 * Software that is described herein is for illustrative purposes only
00015 * which provides customers with programming information regarding the
00016 * products. This software is supplied "AS IS" without any warranties.
00017 * NXP Semiconductors assumes no responsibility or liability for the
00018 * use of the software, conveys no license or title under any patent,
00019 * copyright, or mask work right to the product. NXP Semiconductors
00020 * reserves the right to make changes in the software without
00021 * notification. NXP Semiconductors also make no representation or
00022 * warranty that such application will be suitable for the specified
00023 * use without further testing or modification.
00024 **********************************************************************/
00025 
00026 #include "lwip/opt.h"
00027 #include "lwip/sys.h"
00028 #include "lwip/def.h"
00029 #include "lwip/mem.h"
00030 #include "lwip/pbuf.h"
00031 #include "lwip/stats.h"
00032 #include "lwip/snmp.h"
00033 #include "netif/etharp.h"
00034 #include "netif/ppp_oe.h"
00035 
00036 #include "lpc17xx_emac.h"
00037 #include "lpc17_emac.h"
00038 #include "lpc_emac_config.h"
00039 #include "lpc_phy.h"
00040 #include "sys_arch.h"
00041 
00042 #include "mbed_interface.h"
00043 #include <string.h>
00044 
00045 #ifndef LPC_EMAC_RMII
00046 #error LPC_EMAC_RMII is not defined!
00047 #endif
00048 
00049 #if LPC_NUM_BUFF_TXDESCS < 2
00050 #error LPC_NUM_BUFF_TXDESCS must be at least 2
00051 #endif
00052 
00053 #if LPC_NUM_BUFF_RXDESCS < 3
00054 #error LPC_NUM_BUFF_RXDESCS must be at least 3
00055 #endif
00056 
00057 /** @defgroup lwip17xx_emac_DRIVER    lpc17 EMAC driver for LWIP
00058  * @ingroup lwip_emac
00059  *
00060  * @{
00061  */
00062 
00063 #if NO_SYS == 0
00064 /** \brief  Driver transmit and receive thread priorities
00065  * 
00066  * Thread priorities for receive thread and TX cleanup thread. Alter
00067  * to prioritize receive or transmit bandwidth. In a heavily loaded
00068  * system or with LEIP_DEBUG enabled, the priorities might be better
00069  * the same. */
00070 #define RX_PRIORITY   (osPriorityNormal)
00071 #define TX_PRIORITY   (osPriorityNormal)
00072 
00073 /** \brief  Debug output formatter lock define
00074  * 
00075  * When using FreeRTOS and with LWIP_DEBUG enabled, enabling this
00076  * define will allow RX debug messages to not interleave with the
00077  * TX messages (so they are actually readable). Not enabling this
00078  * define when the system is under load will cause the output to
00079  * be unreadable. There is a small tradeoff in performance for this
00080  * so use it only for debug. */
00081 //#define LOCK_RX_THREAD
00082 
00083 /** \brief  Receive group interrupts
00084  */
00085 #define RXINTGROUP (EMAC_INT_RX_OVERRUN | EMAC_INT_RX_ERR | EMAC_INT_RX_DONE)
00086 
00087 /** \brief  Transmit group interrupts
00088  */
00089 #define TXINTGROUP (EMAC_INT_TX_UNDERRUN | EMAC_INT_TX_ERR | EMAC_INT_TX_DONE)
00090 
00091 #else
00092 #define RXINTGROUP 0
00093 #define TXINTGROUP 0
00094 #endif
00095 
00096  /** \brief  Structure of a TX/RX descriptor
00097  */
00098 typedef struct
00099 {
00100     volatile u32_t packet;        /**< Pointer to buffer */
00101     volatile u32_t control;       /**< Control word */
00102 } LPC_TXRX_DESC_T;
00103 
00104 /** \brief  Structure of a RX status entry
00105  */
00106 typedef struct
00107 {
00108     volatile u32_t statusinfo;   /**< RX status word */
00109     volatile u32_t statushashcrc; /**< RX hash CRC */
00110 } LPC_TXRX_STATUS_T;
00111 
00112 /* LPC EMAC driver data structure */
00113 struct lpc_enetdata {
00114     /* prxs must be 8 byte aligned! */
00115     LPC_TXRX_STATUS_T prxs[LPC_NUM_BUFF_RXDESCS]; /**< Pointer to RX statuses */
00116     struct netif *netif;        /**< Reference back to LWIP parent netif */
00117     LPC_TXRX_DESC_T ptxd[LPC_NUM_BUFF_TXDESCS];   /**< Pointer to TX descriptor list */
00118     LPC_TXRX_STATUS_T ptxs[LPC_NUM_BUFF_TXDESCS]; /**< Pointer to TX statuses */
00119     LPC_TXRX_DESC_T prxd[LPC_NUM_BUFF_RXDESCS];   /**< Pointer to RX descriptor list */
00120     struct pbuf *rxb[LPC_NUM_BUFF_RXDESCS]; /**< RX pbuf pointer list, zero-copy mode */
00121     u32_t rx_fill_desc_index; /**< RX descriptor next available index */
00122     volatile u32_t rx_free_descs; /**< Count of free RX descriptors */
00123     struct pbuf *txb[LPC_NUM_BUFF_TXDESCS]; /**< TX pbuf pointer list, zero-copy mode */
00124     u32_t lpc_last_tx_idx; /**< TX last descriptor index, zero-copy mode */
00125 #if NO_SYS == 0
00126     sys_sem_t RxSem; /**< RX receive thread wakeup semaphore */
00127     sys_sem_t TxCleanSem; /**< TX cleanup thread wakeup semaphore */
00128     sys_mutex_t TXLockMutex; /**< TX critical section mutex */
00129     sys_sem_t xTXDCountSem; /**< TX free buffer counting semaphore */
00130 #endif
00131 };
00132 
00133 /** \brief  LPC EMAC driver work data
00134  */
00135 ALIGNED(8) struct lpc_enetdata lpc_enetdata;
00136 
00137 /* Write a value via the MII link (non-blocking) */
00138 void lpc_mii_write_noblock(u32_t PhyReg, u32_t Value)
00139 {
00140     /* Write value at PHY address and register */
00141     LPC_EMAC->MADR = (LPC_PHYDEF_PHYADDR << 8) | PhyReg;
00142     LPC_EMAC->MWTD = Value;
00143 }
00144 
00145 /* Write a value via the MII link (blocking) */
00146 err_t lpc_mii_write(u32_t PhyReg, u32_t Value)
00147 {
00148     u32_t mst = 250;
00149     err_t sts = ERR_OK;
00150 
00151     /* Write value at PHY address and register */
00152     lpc_mii_write_noblock(PhyReg, Value);
00153 
00154     /* Wait for unbusy status */
00155     while (mst > 0) {
00156         sts = LPC_EMAC->MIND;
00157         if ((sts & EMAC_MIND_BUSY) == 0)
00158             mst = 0;
00159         else {
00160             mst--;
00161             osDelay(1);
00162         }
00163     }
00164 
00165     if (sts != 0)
00166         sts = ERR_TIMEOUT;
00167 
00168     return sts;
00169 }
00170 
00171 /* Reads current MII link busy status */
00172 u32_t lpc_mii_is_busy(void)
00173 {
00174     return (u32_t) (LPC_EMAC->MIND & EMAC_MIND_BUSY);
00175 }
00176 
00177 /* Starts a read operation via the MII link (non-blocking) */
00178 u32_t lpc_mii_read_data(void)
00179 {
00180     u32_t data = LPC_EMAC->MRDD;
00181     LPC_EMAC->MCMD = 0;
00182 
00183     return data;
00184 }
00185 
00186 /* Starts a read operation via the MII link (non-blocking) */
00187 void lpc_mii_read_noblock(u32_t PhyReg) 
00188 {
00189     /* Read value at PHY address and register */
00190     LPC_EMAC->MADR = (LPC_PHYDEF_PHYADDR << 8) | PhyReg;
00191     LPC_EMAC->MCMD = EMAC_MCMD_READ;
00192 }
00193 
00194 /* Read a value via the MII link (blocking) */
00195 err_t lpc_mii_read(u32_t PhyReg, u32_t *data) 
00196 {
00197     u32_t mst = 250;
00198     err_t sts = ERR_OK;
00199 
00200     /* Read value at PHY address and register */
00201     lpc_mii_read_noblock(PhyReg);
00202 
00203     /* Wait for unbusy status */
00204     while (mst > 0) {
00205         sts = LPC_EMAC->MIND & ~EMAC_MIND_MII_LINK_FAIL;
00206         if ((sts & EMAC_MIND_BUSY) == 0) {
00207             mst = 0;
00208             *data = LPC_EMAC->MRDD;
00209         } else {
00210             mst--;
00211             osDelay(1);
00212         }
00213     }
00214 
00215     LPC_EMAC->MCMD = 0;
00216 
00217     if (sts != 0)
00218         sts = ERR_TIMEOUT;
00219 
00220     return sts;
00221 }
00222 
00223 /** \brief  Queues a pbuf into the RX descriptor list
00224  *
00225  *  \param[in] lpc_enetif Pointer to the drvier data structure
00226  *  \param[in] p            Pointer to pbuf to queue
00227  */
00228 static void lpc_rxqueue_pbuf(struct lpc_enetdata *lpc_enetif, struct pbuf *p)
00229 {
00230     u32_t idx;
00231 
00232     /* Get next free descriptor index */
00233     idx = lpc_enetif->rx_fill_desc_index;
00234 
00235     /* Setup descriptor and clear statuses */
00236     lpc_enetif->prxd[idx].control = EMAC_RCTRL_INT | ((u32_t) (p->len - 1));
00237     lpc_enetif->prxd[idx].packet = (u32_t) p->payload;
00238     lpc_enetif->prxs[idx].statusinfo = 0xFFFFFFFF;
00239     lpc_enetif->prxs[idx].statushashcrc = 0xFFFFFFFF;
00240 
00241     /* Save pbuf pointer for push to network layer later */
00242     lpc_enetif->rxb[idx] = p;
00243 
00244     /* Wrap at end of descriptor list */
00245     idx++;
00246     if (idx >= LPC_NUM_BUFF_RXDESCS)
00247         idx = 0;
00248 
00249     /* Queue descriptor(s) */
00250     lpc_enetif->rx_free_descs -= 1;
00251     lpc_enetif->rx_fill_desc_index = idx;
00252     LPC_EMAC->RxConsumeIndex = idx;
00253 
00254     LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE,
00255         ("lpc_rxqueue_pbuf: pbuf packet queued: %p (free desc=%d)\n", p,
00256             lpc_enetif->rx_free_descs));
00257 }
00258 
00259 /** \brief  Attempt to allocate and requeue a new pbuf for RX
00260  *
00261  *  \param[in]     netif Pointer to the netif structure
00262  *  \returns         1 if a packet was allocated and requeued, otherwise 0
00263  */
00264 s32_t lpc_rx_queue(struct netif *netif)
00265 {
00266     struct lpc_enetdata *lpc_enetif = netif->state;
00267     struct pbuf *p;
00268     s32_t queued = 0;
00269 
00270     /* Attempt to requeue as many packets as possible */
00271     while (lpc_enetif->rx_free_descs > 0) {
00272         /* Allocate a pbuf from the pool. We need to allocate at the
00273            maximum size as we don't know the size of the yet to be
00274            received packet. */
00275         p = pbuf_alloc(PBUF_RAW, (u16_t) EMAC_ETH_MAX_FLEN, PBUF_RAM);
00276         if (p == NULL) {
00277             LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE,
00278                 ("lpc_rx_queue: could not allocate RX pbuf (free desc=%d)\n",
00279                 lpc_enetif->rx_free_descs));
00280             return queued;
00281         }
00282 
00283         /* pbufs allocated from the RAM pool should be non-chained. */
00284         LWIP_ASSERT("lpc_rx_queue: pbuf is not contiguous (chained)",
00285             pbuf_clen(p) <= 1);
00286 
00287         /* Queue packet */
00288         lpc_rxqueue_pbuf(lpc_enetif, p);
00289 
00290         /* Update queued count */
00291         queued++;
00292     }
00293 
00294     return queued;
00295 }
00296 
00297 /** \brief  Sets up the RX descriptor ring buffers.
00298  * 
00299  *  This function sets up the descriptor list used for receive packets.
00300  *
00301  *  \param[in]  lpc_enetif  Pointer to driver data structure
00302  *  \returns                   Always returns ERR_OK
00303  */
00304 static err_t lpc_rx_setup(struct lpc_enetdata *lpc_enetif)
00305 {
00306     /* Setup pointers to RX structures */
00307     LPC_EMAC->RxDescriptor = (u32_t) &lpc_enetif->prxd[0];
00308     LPC_EMAC->RxStatus = (u32_t) &lpc_enetif->prxs[0];
00309     LPC_EMAC->RxDescriptorNumber = LPC_NUM_BUFF_RXDESCS - 1;
00310 
00311     lpc_enetif->rx_free_descs = LPC_NUM_BUFF_RXDESCS;
00312     lpc_enetif->rx_fill_desc_index = 0;
00313 
00314     /* Build RX buffer and descriptors */
00315     lpc_rx_queue(lpc_enetif->netif);
00316 
00317     return ERR_OK;
00318 }
00319 
00320 /** \brief  Allocates a pbuf and returns the data from the incoming packet.
00321  *
00322  *  \param[in] netif the lwip network interface structure for this lpc_enetif
00323  *  \return a pbuf filled with the received packet (including MAC header)
00324  *         NULL on memory error
00325  */
00326 static struct pbuf *lpc_low_level_input(struct netif *netif)
00327 {
00328     struct lpc_enetdata *lpc_enetif = netif->state;
00329     struct pbuf *p = NULL;
00330     u32_t idx, length;
00331 
00332 #ifdef LOCK_RX_THREAD
00333 #if NO_SYS == 0
00334     /* Get exclusive access */
00335     sys_mutex_lock(&lpc_enetif->TXLockMutex);
00336 #endif
00337 #endif
00338 
00339     /* Monitor RX overrun status. This should never happen unless
00340        (possibly) the internal bus is behing held up by something.
00341        Unless your system is running at a very low clock speed or
00342        there are possibilities that the internal buses may be held
00343        up for a long time, this can probably safely be removed. */
00344     if (LPC_EMAC->IntStatus & EMAC_INT_RX_OVERRUN) {
00345         LINK_STATS_INC(link.err);
00346         LINK_STATS_INC(link.drop);
00347 
00348         /* Temporarily disable RX */
00349         LPC_EMAC->MAC1 &= ~EMAC_MAC1_REC_EN;
00350 
00351         /* Reset the RX side */
00352         LPC_EMAC->MAC1 |= EMAC_MAC1_RES_RX;
00353         LPC_EMAC->IntClear = EMAC_INT_RX_OVERRUN;
00354 
00355         /* De-allocate all queued RX pbufs */
00356         for (idx = 0; idx < LPC_NUM_BUFF_RXDESCS; idx++) {
00357             if (lpc_enetif->rxb[idx] != NULL) {
00358                 pbuf_free(lpc_enetif->rxb[idx]);
00359                 lpc_enetif->rxb[idx] = NULL;
00360             }
00361         }
00362 
00363         /* Start RX side again */
00364         lpc_rx_setup(lpc_enetif);
00365 
00366         /* Re-enable RX */
00367         LPC_EMAC->MAC1 |= EMAC_MAC1_REC_EN;
00368 
00369 #ifdef LOCK_RX_THREAD
00370 #if NO_SYS == 0
00371         sys_mutex_unlock(&lpc_enetif->TXLockMutex);
00372 #endif
00373 #endif
00374 
00375         return NULL;
00376     }
00377 
00378     /* Determine if a frame has been received */
00379     length = 0;
00380     idx = LPC_EMAC->RxConsumeIndex;
00381     if (LPC_EMAC->RxProduceIndex != idx) {
00382         /* Handle errors */
00383         if (lpc_enetif->prxs[idx].statusinfo & (EMAC_RINFO_CRC_ERR |
00384             EMAC_RINFO_SYM_ERR | EMAC_RINFO_ALIGN_ERR | EMAC_RINFO_LEN_ERR)) {
00385 #if LINK_STATS
00386             if (lpc_enetif->prxs[idx].statusinfo & (EMAC_RINFO_CRC_ERR |
00387                 EMAC_RINFO_SYM_ERR | EMAC_RINFO_ALIGN_ERR))
00388                 LINK_STATS_INC(link.chkerr);
00389             if (lpc_enetif->prxs[idx].statusinfo & EMAC_RINFO_LEN_ERR)
00390                 LINK_STATS_INC(link.lenerr);
00391 #endif
00392 
00393             /* Drop the frame */
00394             LINK_STATS_INC(link.drop);
00395 
00396             /* Re-queue the pbuf for receive */
00397             lpc_enetif->rx_free_descs++;
00398             p = lpc_enetif->rxb[idx];
00399             lpc_enetif->rxb[idx] = NULL;
00400             lpc_rxqueue_pbuf(lpc_enetif, p);
00401 
00402             LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE,
00403                 ("lpc_low_level_input: Packet dropped with errors (0x%x)\n",
00404                 lpc_enetif->prxs[idx].statusinfo));
00405             
00406             p = NULL;
00407         } else {
00408             /* A packet is waiting, get length */
00409             length = (lpc_enetif->prxs[idx].statusinfo & 0x7FF) + 1;
00410 
00411             /* Zero-copy */
00412             p = lpc_enetif->rxb[idx];
00413             p->len = (u16_t) length;
00414 
00415             /* Free pbuf from desriptor */
00416             lpc_enetif->rxb[idx] = NULL;
00417             lpc_enetif->rx_free_descs++;
00418 
00419             LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE,
00420                 ("lpc_low_level_input: Packet received: %p, size %d (index=%d)\n",
00421                 p, length, idx));
00422 
00423             /* Save size */
00424             p->tot_len = (u16_t) length;
00425             LINK_STATS_INC(link.recv);
00426 
00427             /* Queue new buffer(s) */
00428             lpc_rx_queue(lpc_enetif->netif);
00429         }
00430     }
00431 
00432 #ifdef LOCK_RX_THREAD
00433 #if NO_SYS == 0
00434     sys_mutex_unlock(&lpc_enetif->TXLockMutex);
00435 #endif
00436 #endif
00437 
00438     return p;  
00439 }
00440 
00441 /** \brief  Attempt to read a packet from the EMAC interface.
00442  *
00443  *  \param[in] netif the lwip network interface structure for this lpc_enetif
00444  */
00445 void lpc_enetif_input(struct netif *netif)
00446 {
00447     struct eth_hdr *ethhdr;
00448     struct pbuf *p;
00449 
00450     /* move received packet into a new pbuf */
00451     p = lpc_low_level_input(netif);
00452     if (p == NULL)
00453         return;
00454 
00455     /* points to packet payload, which starts with an Ethernet header */
00456     ethhdr = p->payload;
00457 
00458     switch (htons(ethhdr->type)) {
00459         case ETHTYPE_IP:
00460         case ETHTYPE_ARP:
00461 #if PPPOE_SUPPORT
00462         case ETHTYPE_PPPOEDISC:
00463         case ETHTYPE_PPPOE:
00464 #endif /* PPPOE_SUPPORT */
00465             /* full packet send to tcpip_thread to process */
00466             if (netif->input(p, netif) != ERR_OK) {
00467                 LWIP_DEBUGF(NETIF_DEBUG, ("lpc_enetif_input: IP input error\n"));
00468                 /* Free buffer */
00469                 pbuf_free(p);
00470             }
00471             break;
00472 
00473         default:
00474             /* Return buffer */
00475             pbuf_free(p);
00476             break;
00477     }
00478 }
00479 
00480 /** \brief  Determine if the passed address is usable for the ethernet
00481  *          DMA controller.
00482  *
00483  *  \param[in] addr Address of packet to check for DMA safe operation
00484  *  \return          1 if the packet address is not safe, otherwise 0
00485  */
00486 static s32_t lpc_packet_addr_notsafe(void *addr) {
00487     /* Check for legal address ranges */
00488     if ((((u32_t) addr >= 0x2007C000) && ((u32_t) addr < 0x20083FFF))) {
00489         return 0;
00490     }
00491     return 1;
00492 }
00493 
00494 /** \brief  Sets up the TX descriptor ring buffers.
00495  *
00496  *  This function sets up the descriptor list used for transmit packets.
00497  *
00498  *  \param[in]      lpc_enetif  Pointer to driver data structure
00499  */
00500 static err_t lpc_tx_setup(struct lpc_enetdata *lpc_enetif)
00501 {
00502     s32_t idx;
00503 
00504     /* Build TX descriptors for local buffers */
00505     for (idx = 0; idx < LPC_NUM_BUFF_TXDESCS; idx++) {
00506         lpc_enetif->ptxd[idx].control = 0;
00507         lpc_enetif->ptxs[idx].statusinfo = 0xFFFFFFFF;
00508     }
00509 
00510     /* Setup pointers to TX structures */
00511     LPC_EMAC->TxDescriptor = (u32_t) &lpc_enetif->ptxd[0];
00512     LPC_EMAC->TxStatus = (u32_t) &lpc_enetif->ptxs[0];
00513     LPC_EMAC->TxDescriptorNumber = LPC_NUM_BUFF_TXDESCS - 1;
00514 
00515     lpc_enetif->lpc_last_tx_idx = 0;
00516 
00517     return ERR_OK;
00518 }
00519 
00520 /** \brief  Free TX buffers that are complete
00521  *
00522  *  \param[in] lpc_enetif  Pointer to driver data structure
00523  *  \param[in] cidx  EMAC current descriptor comsumer index
00524  */
00525 static void lpc_tx_reclaim_st(struct lpc_enetdata *lpc_enetif, u32_t cidx)
00526 {
00527 #if NO_SYS == 0
00528     /* Get exclusive access */
00529     sys_mutex_lock(&lpc_enetif->TXLockMutex);
00530 #endif
00531 
00532     while (cidx != lpc_enetif->lpc_last_tx_idx) {
00533         if (lpc_enetif->txb[lpc_enetif->lpc_last_tx_idx] != NULL) {
00534             LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE,
00535                 ("lpc_tx_reclaim_st: Freeing packet %p (index %d)\n",
00536                 lpc_enetif->txb[lpc_enetif->lpc_last_tx_idx],
00537                 lpc_enetif->lpc_last_tx_idx));
00538             pbuf_free(lpc_enetif->txb[lpc_enetif->lpc_last_tx_idx]);
00539              lpc_enetif->txb[lpc_enetif->lpc_last_tx_idx] = NULL;
00540         }
00541 
00542 #if NO_SYS == 0
00543         osSemaphoreRelease(lpc_enetif->xTXDCountSem.id);
00544 #endif
00545         lpc_enetif->lpc_last_tx_idx++;
00546         if (lpc_enetif->lpc_last_tx_idx >= LPC_NUM_BUFF_TXDESCS)
00547             lpc_enetif->lpc_last_tx_idx = 0;
00548     }
00549 
00550 #if NO_SYS == 0
00551     /* Restore access */
00552     sys_mutex_unlock(&lpc_enetif->TXLockMutex);
00553 #endif
00554 }
00555 
00556 /** \brief  User call for freeingTX buffers that are complete
00557  *
00558  *  \param[in] netif the lwip network interface structure for this lpc_enetif
00559  */
00560 void lpc_tx_reclaim(struct netif *netif)
00561 {
00562     lpc_tx_reclaim_st((struct lpc_enetdata *) netif->state,
00563         LPC_EMAC->TxConsumeIndex);
00564 }
00565 
00566  /** \brief  Polls if an available TX descriptor is ready. Can be used to
00567  *           determine if the low level transmit function will block.
00568  *
00569  *  \param[in] netif the lwip network interface structure for this lpc_enetif
00570  *  \return 0 if no descriptors are read, or >0
00571  */
00572 s32_t lpc_tx_ready(struct netif *netif)
00573 {
00574     s32_t fb;
00575     u32_t idx, cidx;
00576 
00577     cidx = LPC_EMAC->TxConsumeIndex;
00578     idx = LPC_EMAC->TxProduceIndex;
00579 
00580     /* Determine number of free buffers */
00581     if (idx == cidx)
00582         fb = LPC_NUM_BUFF_TXDESCS;
00583     else if (cidx > idx)
00584         fb = (LPC_NUM_BUFF_TXDESCS - 1) -
00585             ((idx + LPC_NUM_BUFF_TXDESCS) - cidx);
00586     else
00587         fb = (LPC_NUM_BUFF_TXDESCS - 1) - (cidx - idx);
00588 
00589     return fb;
00590 }
00591 
00592 /** \brief  Low level output of a packet. Never call this from an
00593  *          interrupt context, as it may block until TX descriptors
00594  *          become available.
00595  *
00596  *  \param[in] netif the lwip network interface structure for this lpc_enetif
00597  *  \param[in] p the MAC packet to send (e.g. IP packet including MAC addresses and type)
00598  *  \return ERR_OK if the packet could be sent or an err_t value if the packet couldn't be sent
00599  */
00600 static err_t lpc_low_level_output(struct netif *netif, struct pbuf *p)
00601 {
00602     struct lpc_enetdata *lpc_enetif = netif->state;
00603     struct pbuf *q;
00604     u8_t *dst;
00605     u32_t idx;
00606     struct pbuf *np;
00607     u32_t dn, notdmasafe = 0;
00608 
00609     /* Zero-copy TX buffers may be fragmented across mutliple payload
00610        chains. Determine the number of descriptors needed for the
00611        transfer. The pbuf chaining can be a mess! */
00612     dn = (u32_t) pbuf_clen(p);
00613 
00614     /* Test to make sure packet addresses are DMA safe. A DMA safe
00615        address is once that uses external memory or periphheral RAM.
00616        IRAM and FLASH are not safe! */
00617     for (q = p; q != NULL; q = q->next)
00618         notdmasafe += lpc_packet_addr_notsafe(q->payload);
00619 
00620 #if LPC_TX_PBUF_BOUNCE_EN==1
00621     /* If the pbuf is not DMA safe, a new bounce buffer (pbuf) will be
00622        created that will be used instead. This requires an copy from the
00623        non-safe DMA region to the new pbuf */
00624     if (notdmasafe) {
00625         /* Allocate a pbuf in DMA memory */
00626         np = pbuf_alloc(PBUF_RAW, p->tot_len, PBUF_RAM);
00627         if (np == NULL)
00628             return ERR_MEM;    
00629 
00630         /* This buffer better be contiguous! */
00631         LWIP_ASSERT("lpc_low_level_output: New transmit pbuf is chained",
00632             (pbuf_clen(np) == 1));
00633 
00634         /* Copy to DMA safe pbuf */
00635         dst = (u8_t *) np->payload;
00636          for(q = p; q != NULL; q = q->next) {
00637             /* Copy the buffer to the descriptor's buffer */
00638               MEMCPY(dst, (u8_t *) q->payload, q->len);
00639           dst += q->len;
00640         }
00641         np->len = p->tot_len; 
00642 
00643         LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE,
00644             ("lpc_low_level_output: Switched to DMA safe buffer, old=%p, new=%p\n",
00645             q, np));
00646 
00647         /* use the new buffer for descrptor queueing. The original pbuf will
00648            be de-allocated outsuide this driver. */
00649         p = np;
00650         dn = 1;
00651     }
00652 #else
00653     if (notdmasafe)
00654         LWIP_ASSERT("lpc_low_level_output: Not a DMA safe pbuf",
00655             (notdmasafe == 0));
00656 #endif
00657 
00658     /* Wait until enough descriptors are available for the transfer. */
00659     /* THIS WILL BLOCK UNTIL THERE ARE ENOUGH DESCRIPTORS AVAILABLE */
00660     while (dn > lpc_tx_ready(netif))
00661 #if NO_SYS == 0
00662         osSemaphoreWait(lpc_enetif->xTXDCountSem.id, osWaitForever);
00663 #else
00664         osDelay(1);
00665 #endif
00666 
00667     /* Get free TX buffer index */
00668     idx = LPC_EMAC->TxProduceIndex;
00669 
00670 #if NO_SYS == 0
00671     /* Get exclusive access */
00672     sys_mutex_lock(&lpc_enetif->TXLockMutex);
00673 #endif
00674 
00675     /* Prevent LWIP from de-allocating this pbuf. The driver will
00676        free it once it's been transmitted. */
00677     if (!notdmasafe)
00678         pbuf_ref(p);
00679 
00680     /* Setup transfers */
00681     q = p;
00682     while (dn > 0) {
00683         dn--;
00684 
00685         /* Only save pointer to free on last descriptor */
00686         if (dn == 0) {
00687             /* Save size of packet and signal it's ready */
00688             lpc_enetif->ptxd[idx].control = (q->len - 1) | EMAC_TCTRL_INT |
00689                 EMAC_TCTRL_LAST;
00690             lpc_enetif->txb[idx] = p;
00691         }
00692         else {
00693             /* Save size of packet, descriptor is not last */
00694             lpc_enetif->ptxd[idx].control = (q->len - 1) | EMAC_TCTRL_INT;
00695             lpc_enetif->txb[idx] = NULL;
00696         }
00697 
00698         LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE,
00699             ("lpc_low_level_output: pbuf packet(%p) sent, chain#=%d,"
00700             " size = %d (index=%d)\n", q->payload, dn, q->len, idx));
00701 
00702         lpc_enetif->ptxd[idx].packet = (u32_t) q->payload;
00703 
00704         q = q->next;
00705 
00706         idx++;
00707         if (idx >= LPC_NUM_BUFF_TXDESCS)
00708             idx = 0;
00709     }
00710 
00711     LPC_EMAC->TxProduceIndex = idx;
00712 
00713     LINK_STATS_INC(link.xmit);
00714 
00715 #if NO_SYS == 0
00716     /* Restore access */
00717     sys_mutex_unlock(&lpc_enetif->TXLockMutex);
00718 #endif
00719 
00720     return ERR_OK;
00721 }
00722 
00723 /** \brief  LPC EMAC interrupt handler.
00724  *
00725  *  This function handles the transmit, receive, and error interrupt of
00726  *  the LPC177x_8x. This is meant to be used when NO_SYS=0.
00727  */
00728 void ENET_IRQHandler(void)
00729 {
00730 #if NO_SYS == 1
00731     /* Interrupts are not used without an RTOS */
00732     NVIC_DisableIRQ(ENET_IRQn);
00733 #else
00734     uint32_t ints;
00735 
00736     /* Interrupts are of 2 groups - transmit or receive. Based on the
00737        interrupt, kick off the receive or transmit (cleanup) task */
00738 
00739     /* Get pending interrupts */
00740     ints = LPC_EMAC->IntStatus;
00741 
00742     if (ints & RXINTGROUP) {
00743         /* RX group interrupt(s): Give semaphore to wakeup RX receive task.*/
00744         sys_sem_signal(&lpc_enetdata.RxSem);
00745     }
00746     
00747     if (ints & TXINTGROUP) {
00748         /* TX group interrupt(s): Give semaphore to wakeup TX cleanup task. */
00749         sys_sem_signal(&lpc_enetdata.TxCleanSem);
00750     }
00751     
00752     /* Clear pending interrupts */
00753     LPC_EMAC->IntClear = ints;
00754 #endif
00755 }
00756 
00757 #if NO_SYS == 0
00758 /** \brief  Packet reception task
00759  *
00760  * This task is called when a packet is received. It will
00761  * pass the packet to the LWIP core.
00762  *
00763  *  \param[in] pvParameters Not used yet
00764  */
00765 static void packet_rx(void* pvParameters) {
00766     struct lpc_enetdata *lpc_enetif = pvParameters;
00767     
00768     while (1) {
00769         /* Wait for receive task to wakeup */
00770         sys_arch_sem_wait(&lpc_enetif->RxSem, 0);
00771         
00772         /* Process packets until all empty */
00773         while (LPC_EMAC->RxConsumeIndex != LPC_EMAC->RxProduceIndex)
00774             lpc_enetif_input(lpc_enetif->netif);
00775     }
00776 }
00777 
00778 /** \brief  Transmit cleanup task
00779  *
00780  * This task is called when a transmit interrupt occurs and
00781  * reclaims the pbuf and descriptor used for the packet once
00782  * the packet has been transferred.
00783  *
00784  *  \param[in] pvParameters Not used yet
00785  */
00786 static void packet_tx(void* pvParameters) {
00787     struct lpc_enetdata *lpc_enetif = pvParameters;
00788     s32_t idx;
00789     
00790     while (1) {
00791         /* Wait for transmit cleanup task to wakeup */
00792         sys_arch_sem_wait(&lpc_enetif->TxCleanSem, 0);
00793         
00794         /* Error handling for TX underruns. This should never happen unless
00795            something is holding the bus or the clocks are going too slow. It
00796             can probably be safely removed. */
00797         if (LPC_EMAC->IntStatus & EMAC_INT_TX_UNDERRUN) {
00798             LINK_STATS_INC(link.err);
00799             LINK_STATS_INC(link.drop);
00800             
00801 #if NO_SYS == 0
00802             /* Get exclusive access */
00803             sys_mutex_lock(&lpc_enetif->TXLockMutex);
00804 #endif
00805             /* Reset the TX side */
00806             LPC_EMAC->MAC1 |= EMAC_MAC1_RES_TX;
00807             LPC_EMAC->IntClear = EMAC_INT_TX_UNDERRUN;
00808             
00809             /* De-allocate all queued TX pbufs */
00810             for (idx = 0; idx < LPC_NUM_BUFF_RXDESCS; idx++) {
00811                 if (lpc_enetif->txb[idx] != NULL) {
00812                     pbuf_free(lpc_enetif->txb[idx]);
00813                     lpc_enetif->txb[idx] = NULL;
00814                 }
00815             }
00816             
00817 #if NO_SYS == 0
00818             /* Restore access */
00819             sys_mutex_unlock(&lpc_enetif->TXLockMutex);
00820 #endif
00821             /* Start TX side again */
00822             lpc_tx_setup(lpc_enetif);
00823         } else {
00824             /* Free TX buffers that are done sending */
00825             lpc_tx_reclaim(lpc_enetdata.netif);
00826         }
00827     }
00828 }
00829 #endif
00830 
00831 /** \brief  Low level init of the MAC and PHY.
00832  *
00833  *  \param[in]      netif  Pointer to LWIP netif structure
00834  */
00835 static err_t low_level_init(struct netif *netif)
00836 {
00837     struct lpc_enetdata *lpc_enetif = netif->state;
00838     err_t err = ERR_OK;
00839 
00840     /* Enable MII clocking */
00841     LPC_SC->PCONP |= CLKPWR_PCONP_PCENET;
00842     
00843     LPC_PINCON->PINSEL2 = 0x50150105;                  /* Enable P1 Ethernet Pins. */
00844     LPC_PINCON->PINSEL3 = (LPC_PINCON->PINSEL3 & ~0x0000000F) | 0x00000005;
00845     
00846     /* Reset all MAC logic */
00847     LPC_EMAC->MAC1 = EMAC_MAC1_RES_TX | EMAC_MAC1_RES_MCS_TX |
00848         EMAC_MAC1_RES_RX | EMAC_MAC1_RES_MCS_RX | EMAC_MAC1_SIM_RES |
00849         EMAC_MAC1_SOFT_RES;
00850     LPC_EMAC->Command = EMAC_CR_REG_RES | EMAC_CR_TX_RES | EMAC_CR_RX_RES |
00851         EMAC_CR_PASS_RUNT_FRM;
00852     osDelay(10);
00853     
00854     /* Initial MAC initialization */
00855     LPC_EMAC->MAC1 = EMAC_MAC1_PASS_ALL;
00856     LPC_EMAC->MAC2 = EMAC_MAC2_CRC_EN | EMAC_MAC2_PAD_EN |
00857         EMAC_MAC2_VLAN_PAD_EN;
00858     LPC_EMAC->MAXF = EMAC_ETH_MAX_FLEN;
00859 
00860     /* Set RMII management clock rate to lowest speed */
00861     LPC_EMAC->MCFG = EMAC_MCFG_CLK_SEL(11) | EMAC_MCFG_RES_MII;
00862     LPC_EMAC->MCFG &= ~EMAC_MCFG_RES_MII;
00863 
00864     /* Maximum number of retries, 0x37 collision window, gap */
00865     LPC_EMAC->CLRT = EMAC_CLRT_DEF;
00866     LPC_EMAC->IPGR = EMAC_IPGR_P1_DEF | EMAC_IPGR_P2_DEF;
00867 
00868 #if LPC_EMAC_RMII
00869     /* RMII setup */
00870     LPC_EMAC->Command = EMAC_CR_PASS_RUNT_FRM | EMAC_CR_RMII;
00871 #else
00872     /* MII setup */
00873     LPC_EMAC->CR = EMAC_CR_PASS_RUNT_FRM;
00874 #endif
00875 
00876     /* Initialize the PHY and reset */
00877     err = lpc_phy_init(netif, LPC_EMAC_RMII);
00878     if (err != ERR_OK)
00879          return err;
00880 
00881     /* Save station address */
00882     LPC_EMAC->SA2 = (u32_t) netif->hwaddr[0] |
00883         (((u32_t) netif->hwaddr[1]) << 8);
00884     LPC_EMAC->SA1 = (u32_t) netif->hwaddr[2] |
00885         (((u32_t) netif->hwaddr[3]) << 8);
00886     LPC_EMAC->SA0 = (u32_t) netif->hwaddr[4] |
00887         (((u32_t) netif->hwaddr[5]) << 8);
00888 
00889     /* Setup transmit and receive descriptors */
00890     if (lpc_tx_setup(lpc_enetif) != ERR_OK)
00891         return ERR_BUF;
00892     if (lpc_rx_setup(lpc_enetif) != ERR_OK)
00893         return ERR_BUF;
00894 
00895     /* Enable packet reception */
00896 #if IP_SOF_BROADCAST_RECV
00897     LPC_EMAC->RxFilterCtrl = EMAC_RFC_PERFECT_EN | EMAC_RFC_BCAST_EN;
00898 #else
00899     LPC_EMAC->RxFilterCtrl = EMAC_RFC_PERFECT_EN;
00900 #endif
00901 
00902     /* Clear and enable rx/tx interrupts */
00903     LPC_EMAC->IntClear = 0xFFFF;
00904     LPC_EMAC->IntEnable = RXINTGROUP | TXINTGROUP;
00905 
00906     /* Enable RX and TX */
00907     LPC_EMAC->Command |= EMAC_CR_RX_EN | EMAC_CR_TX_EN;
00908     LPC_EMAC->MAC1 |= EMAC_MAC1_REC_EN;
00909 
00910     return err;
00911 }
00912 
00913 /* This function provides a method for the PHY to setup the EMAC
00914    for the PHY negotiated duplex mode */
00915 void lpc_emac_set_duplex(int full_duplex)
00916 {
00917     if (full_duplex) {
00918         LPC_EMAC->MAC2    |= EMAC_MAC2_FULL_DUP;
00919         LPC_EMAC->Command |= EMAC_CR_FULL_DUP;
00920         LPC_EMAC->IPGT     = EMAC_IPGT_FULL_DUP;
00921     } else {
00922         LPC_EMAC->MAC2    &= ~EMAC_MAC2_FULL_DUP;
00923         LPC_EMAC->Command &= ~EMAC_CR_FULL_DUP;
00924         LPC_EMAC->IPGT = EMAC_IPGT_HALF_DUP;
00925     }
00926 }
00927 
00928 /* This function provides a method for the PHY to setup the EMAC
00929    for the PHY negotiated bit rate */
00930 void lpc_emac_set_speed(int mbs_100)
00931 {
00932     if (mbs_100)
00933         LPC_EMAC->SUPP = EMAC_SUPP_SPEED;
00934     else
00935         LPC_EMAC->SUPP = 0;
00936 }
00937 
00938 /**
00939  * This function is the ethernet packet send function. It calls
00940  * etharp_output after checking link status.
00941  *
00942  * \param[in] netif the lwip network interface structure for this lpc_enetif
00943  * \param[in] q Pointer to pbug to send
00944  * \param[in] ipaddr IP address 
00945  * \return ERR_OK or error code
00946  */
00947 err_t lpc_etharp_output(struct netif *netif, struct pbuf *q,
00948     ip_addr_t *ipaddr)
00949 {
00950     /* Only send packet is link is up */
00951     if (netif->flags & NETIF_FLAG_LINK_UP)
00952         return etharp_output(netif, q, ipaddr);
00953 
00954     return ERR_CONN;
00955 }
00956 
00957 #if NO_SYS == 0
00958 /* periodic PHY status update */
00959 void phy_update(void const *nif) {
00960     lpc_phy_sts_sm((struct netif*)nif);
00961 }
00962 osTimerDef(phy_update, phy_update);
00963 #endif
00964 
00965 /**
00966  * Should be called at the beginning of the program to set up the
00967  * network interface.
00968  *
00969  * This function should be passed as a parameter to netif_add().
00970  *
00971  * @param[in] netif the lwip network interface structure for this lpc_enetif
00972  * @return ERR_OK if the loopif is initialized
00973  *         ERR_MEM if private data couldn't be allocated
00974  *         any other err_t on error
00975  */
00976 err_t lpc_enetif_init(struct netif *netif)
00977 {
00978     err_t err;
00979 
00980     LWIP_ASSERT("netif != NULL", (netif != NULL));
00981     
00982     lpc_enetdata.netif = netif;
00983 
00984     /* set MAC hardware address */
00985     mbed_mac_address((char *)netif->hwaddr);
00986     netif->hwaddr_len = ETHARP_HWADDR_LEN;
00987 
00988      /* maximum transfer unit */
00989     netif->mtu = 1500;
00990 
00991     /* device capabilities */
00992     netif->flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP | NETIF_FLAG_ETHERNET;
00993 
00994     /* Initialize the hardware */
00995     netif->state = &lpc_enetdata;
00996     err = low_level_init(netif);
00997     if (err != ERR_OK)
00998         return err;
00999 
01000 #if LWIP_NETIF_HOSTNAME
01001     /* Initialize interface hostname */
01002     netif->hostname = "lwiplpc";
01003 #endif /* LWIP_NETIF_HOSTNAME */
01004 
01005     netif->name[0] = 'e';
01006     netif->name[1] = 'n';
01007 
01008     netif->output = lpc_etharp_output;
01009     netif->linkoutput = lpc_low_level_output;
01010 
01011     /* CMSIS-RTOS, start tasks */
01012 #if NO_SYS == 0
01013 #ifdef CMSIS_OS_RTX
01014     memset(lpc_enetdata.xTXDCountSem.data, 0, sizeof(lpc_enetdata.xTXDCountSem.data));
01015     lpc_enetdata.xTXDCountSem.def.semaphore = lpc_enetdata.xTXDCountSem.data;
01016 #endif
01017     lpc_enetdata.xTXDCountSem.id = osSemaphoreCreate(&lpc_enetdata.xTXDCountSem.def, LPC_NUM_BUFF_TXDESCS);
01018     LWIP_ASSERT("xTXDCountSem creation error", (lpc_enetdata.xTXDCountSem.id != NULL));
01019 
01020     err = sys_mutex_new(&lpc_enetdata.TXLockMutex);
01021     LWIP_ASSERT("TXLockMutex creation error", (err == ERR_OK));
01022 
01023     /* Packet receive task */
01024     err = sys_sem_new(&lpc_enetdata.RxSem, 0);
01025     LWIP_ASSERT("RxSem creation error", (err == ERR_OK));
01026     sys_thread_new("receive_thread", packet_rx, netif->state, DEFAULT_THREAD_STACKSIZE, RX_PRIORITY);
01027 
01028     /* Transmit cleanup task */
01029     err = sys_sem_new(&lpc_enetdata.TxCleanSem, 0);
01030     LWIP_ASSERT("TxCleanSem creation error", (err == ERR_OK));
01031     sys_thread_new("txclean_thread", packet_tx, netif->state, DEFAULT_THREAD_STACKSIZE, TX_PRIORITY);
01032     
01033     /* periodic PHY status update */
01034     osTimerId phy_timer = osTimerCreate(osTimer(phy_update), osTimerPeriodic, (void *)netif);
01035     osTimerStart(phy_timer, 250);
01036 #endif
01037     
01038     return ERR_OK;
01039 }
01040 
01041 /**
01042  * @}
01043  */
01044 
01045 /* --------------------------------- End Of File ------------------------------ */