Control a robot over the internet using UDP and a Ethernet interface.

Dependencies:   EthernetInterface Motor TextLCD mbed-rtos mbed Socket lwip-eth lwip-sys lwip

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