Adapted to Lora Semtech + Nucleo

Dependencies:   DebugLib

Dependents:   LoRaWAN-lmic-app LoRaWAN-lmic-app LoRaWAN-test-10secs LoRaPersonalizedDeviceForEverynet ... more

Fork of lwip_ppp_ethernet by Donatien Garnier

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