KEIS

Dependents:   EthernetInterface_t

Fork of lwip-eth by mbed official

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