Modify changes to test TCP socket.

Dependents:   EthernetInterface

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