Data Viz Button Code
Fork of lwip-eth by
Revision 32:3534f0b45d38, committed 2016-05-23
- Comitter:
- mbed_official
- Date:
- Mon May 23 09:45:48 2016 +0100
- Parent:
- 31:da93f0f73711
- Child:
- 33:9de8bd8ca1c8
- Commit message:
- Synchronized with git revision 03d8ea8e96051c0fa2d0a081f9f84b9c86d9ffb2
Full URL: https://github.com/mbedmicro/mbed/commit/03d8ea8e96051c0fa2d0a081f9f84b9c86d9ffb2/
Simplify mbed SDK layout
Changed in this revision
--- a/arch/TARGET_Freescale/hardware_init_MK64F12.c Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,88 +0,0 @@ -/* - * Copyright (c) 2013 - 2014, Freescale Semiconductor, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * - * o Redistributions of source code must retain the above copyright notice, this list - * of conditions and the following disclaimer. - * - * o Redistributions in binary form must reproduce the above copyright notice, this - * list of conditions and the following disclaimer in the documentation and/or - * other materials provided with the distribution. - * - * o Neither the name of Freescale Semiconductor, Inc. nor the names of its - * contributors may be used to endorse or promote products derived from this - * software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND - * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED - * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR - * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES - * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON - * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT - * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS - * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ - -#include "fsl_port.h" - -/******************************************************************************* - * Code - ******************************************************************************/ -void k64f_init_eth_hardware(void) -{ - port_pin_config_t configENET = {0}; - - /* Disable MPU. */ - MPU->CESR &= ~MPU_CESR_VLD_MASK; - - CLOCK_EnableClock(kCLOCK_PortC); - /* Affects PORTC_PCR16 register */ - PORT_SetPinMux(PORTC, 16u, kPORT_MuxAlt4); - /* Affects PORTC_PCR17 register */ - PORT_SetPinMux(PORTC, 17u, kPORT_MuxAlt4); - /* Affects PORTC_PCR18 register */ - PORT_SetPinMux(PORTC, 18u, kPORT_MuxAlt4); - /* Affects PORTC_PCR19 register */ - PORT_SetPinMux(PORTC, 19u, kPORT_MuxAlt4); - /* Affects PORTB_PCR1 register */ - PORT_SetPinMux(PORTB, 1u, kPORT_MuxAlt4); - - configENET.openDrainEnable = kPORT_OpenDrainEnable; - configENET.mux = kPORT_MuxAlt4; - configENET.pullSelect = kPORT_PullUp; - /* Ungate the port clock */ - CLOCK_EnableClock(kCLOCK_PortA); - /* Affects PORTB_PCR0 register */ - PORT_SetPinConfig(PORTB, 0u, &configENET); - - /* Affects PORTA_PCR13 register */ - PORT_SetPinMux(PORTA, 13u, kPORT_MuxAlt4); - /* Affects PORTA_PCR12 register */ - PORT_SetPinMux(PORTA, 12u, kPORT_MuxAlt4); - /* Affects PORTA_PCR14 register */ - PORT_SetPinMux(PORTA, 14u, kPORT_MuxAlt4); - /* Affects PORTA_PCR5 register */ - PORT_SetPinMux(PORTA, 5u, kPORT_MuxAlt4); - /* Affects PORTA_PCR16 register */ - PORT_SetPinMux(PORTA, 16u, kPORT_MuxAlt4); - /* Affects PORTA_PCR17 register */ - PORT_SetPinMux(PORTA, 17u, kPORT_MuxAlt4); - /* Affects PORTA_PCR15 register */ - PORT_SetPinMux(PORTA, 15u, kPORT_MuxAlt4); - /* Affects PORTA_PCR28 register */ - PORT_SetPinMux(PORTA, 28u, kPORT_MuxAlt4); - - /* Select the Ethernet timestamp clock source */ - CLOCK_SetEnetTime0Clock(0x2); -} - -/******************************************************************************* - * EOF - ******************************************************************************/ - -
--- a/arch/TARGET_Freescale/k64f_emac.c Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,643 +0,0 @@ -#include "lwip/opt.h" -#include "lwip/sys.h" -#include "lwip/def.h" -#include "lwip/mem.h" -#include "lwip/pbuf.h" -#include "lwip/stats.h" -#include "lwip/snmp.h" -#include "lwip/tcpip.h" -#include "netif/etharp.h" -#include "netif/ppp_oe.h" - -#include "eth_arch.h" -#include "sys_arch.h" - -#include "fsl_phy.h" -#include "k64f_emac_config.h" -#include <ctype.h> -#include <stdio.h> -#include <string.h> -#include <stdlib.h> - -#include "mbed_interface.h" - -enet_handle_t g_handle; -// TX Buffer descriptors -uint8_t *tx_desc_start_addr; -// RX Buffer descriptors -uint8_t *rx_desc_start_addr; -// RX packet buffer pointers -struct pbuf *rx_buff[ENET_RX_RING_LEN]; -// TX packet buffer pointers -struct pbuf *tx_buff[ENET_RX_RING_LEN]; -// RX packet payload pointers -uint32_t *rx_ptr[ENET_RX_RING_LEN]; - -/******************************************************************************** - * Internal data - ********************************************************************************/ -#define ENET_BuffSizeAlign(n) ENET_ALIGN(n, ENET_BUFF_ALIGNMENT) -#define ENET_ALIGN(x,align) ((unsigned int)((x) + ((align)-1)) & (unsigned int)(~(unsigned int)((align)- 1))) -extern void k64f_init_eth_hardware(void); - -/* K64F EMAC driver data structure */ -struct k64f_enetdata { - struct netif *netif; /**< Reference back to LWIP parent netif */ - sys_sem_t RxReadySem; /**< RX packet ready semaphore */ - sys_sem_t TxCleanSem; /**< TX cleanup thread wakeup semaphore */ - sys_mutex_t TXLockMutex; /**< TX critical section mutex */ - sys_sem_t xTXDCountSem; /**< TX free buffer counting semaphore */ - uint8_t tx_consume_index, tx_produce_index; /**< TX buffers ring */ -}; - -static struct k64f_enetdata k64f_enetdata; - -/** \brief Driver transmit and receive thread priorities - * - * Thread priorities for receive thread and TX cleanup thread. Alter - * to prioritize receive or transmit bandwidth. In a heavily loaded - * system or with LEIP_DEBUG enabled, the priorities might be better - * the same. */ -#define RX_PRIORITY (osPriorityNormal) -#define TX_PRIORITY (osPriorityNormal) -#define PHY_PRIORITY (osPriorityNormal) - -/******************************************************************************** - * Buffer management - ********************************************************************************/ -/* - * This function will queue a new receive buffer - */ -static void update_read_buffer(uint8_t *buf) -{ - if (buf != NULL) { - g_handle.rxBdCurrent->buffer = buf; - } - - /* Clears status. */ - g_handle.rxBdCurrent->control &= ENET_BUFFDESCRIPTOR_RX_WRAP_MASK; - - /* Sets the receive buffer descriptor with the empty flag. */ - g_handle.rxBdCurrent->control |= ENET_BUFFDESCRIPTOR_RX_EMPTY_MASK; - - /* Increases the buffer descriptor to the next one. */ - if (g_handle.rxBdCurrent->control & ENET_BUFFDESCRIPTOR_RX_WRAP_MASK) { - g_handle.rxBdCurrent = g_handle.rxBdBase; - g_handle.rxBdDirty = g_handle.rxBdBase; - } else { - g_handle.rxBdCurrent++; - g_handle.rxBdDirty++; - } - - /* Actives the receive buffer descriptor. */ - ENET->RDAR = ENET_RDAR_RDAR_MASK; -} - -/** \brief Free TX buffers that are complete - * - * \param[in] k64f_enet Pointer to driver data structure - */ -static void k64f_tx_reclaim(struct k64f_enetdata *k64f_enet) -{ - uint8_t i = 0 ; - - /* Get exclusive access */ - sys_mutex_lock(&k64f_enet->TXLockMutex); - - i = k64f_enet->tx_consume_index; - // Traverse all descriptors, looking for the ones modified by the uDMA - while((i != k64f_enet->tx_produce_index) && (!(g_handle.txBdDirty->control & ENET_BUFFDESCRIPTOR_TX_READY_MASK))) { - pbuf_free(tx_buff[i]); - if (g_handle.txBdDirty->control & ENET_BUFFDESCRIPTOR_TX_WRAP_MASK) - g_handle.txBdDirty = g_handle.txBdBase; - else - g_handle.txBdDirty++; - - i = (i + 1) % ENET_TX_RING_LEN; - } - - k64f_enet->tx_consume_index = i; - /* Restore access */ - sys_mutex_unlock(&k64f_enet->TXLockMutex); -} - -/** \brief Ethernet receive interrupt handler - * - * This function handles the receive interrupt of K64F. - */ -void enet_mac_rx_isr() -{ - sys_sem_signal(&k64f_enetdata.RxReadySem); -} - -void enet_mac_tx_isr() -{ - sys_sem_signal(&k64f_enetdata.TxCleanSem); -} - -void ethernet_callback(ENET_Type *base, enet_handle_t *handle, enet_event_t event, void *param) -{ - switch (event) - { - case kENET_RxEvent: - enet_mac_rx_isr(); - break; - case kENET_TxEvent: - enet_mac_tx_isr(); - break; - default: - break; - } -} - -/** \brief Low level init of the MAC and PHY. - * - * \param[in] netif Pointer to LWIP netif structure - */ -static err_t low_level_init(struct netif *netif) -{ - struct k64f_enetdata *k64f_enet = netif->state; - uint8_t i; - uint32_t sysClock; - phy_speed_t phy_speed; - phy_duplex_t phy_duplex; - uint32_t phyAddr = 0; - bool link = false; - enet_config_t config; - - // Allocate RX descriptors - rx_desc_start_addr = (uint8_t *)calloc(1, sizeof(enet_rx_bd_struct_t) * ENET_RX_RING_LEN + ENET_BUFF_ALIGNMENT); - if(!rx_desc_start_addr) - return ERR_MEM; - - // Allocate TX descriptors - tx_desc_start_addr = (uint8_t *)calloc(1, sizeof(enet_tx_bd_struct_t) * ENET_TX_RING_LEN + ENET_BUFF_ALIGNMENT); - if(!tx_desc_start_addr) - return ERR_MEM; - - rx_desc_start_addr = (uint8_t *)ENET_ALIGN(rx_desc_start_addr, ENET_BUFF_ALIGNMENT); - tx_desc_start_addr = (uint8_t *)ENET_ALIGN(tx_desc_start_addr, ENET_BUFF_ALIGNMENT); - - /* Create buffers for each receive BD */ - for (i = 0; i < ENET_RX_RING_LEN; i++) { - rx_buff[i] = pbuf_alloc(PBUF_RAW, ENET_ETH_MAX_FLEN + ENET_BUFF_ALIGNMENT, PBUF_RAM); - if (NULL == rx_buff[i]) - return ERR_MEM; - - /* K64F note: the next line ensures that the RX buffer is properly aligned for the K64F - RX descriptors (16 bytes alignment). However, by doing so, we're effectively changing - a data structure which is internal to lwIP. This might not prove to be a good idea - in the long run, but a better fix would probably involve modifying lwIP itself */ - rx_buff[i]->payload = (void*)ENET_ALIGN((uint32_t)rx_buff[i]->payload, ENET_BUFF_ALIGNMENT); - rx_ptr[i] = rx_buff[i]->payload; - } - - k64f_enet->tx_consume_index = k64f_enet->tx_produce_index = 0; - - /* prepare the buffer configuration. */ - enet_buffer_config_t buffCfg = { - ENET_RX_RING_LEN, - ENET_TX_RING_LEN, - ENET_ALIGN(ENET_ETH_MAX_FLEN, ENET_BUFF_ALIGNMENT), - 0, - (volatile enet_rx_bd_struct_t *)rx_desc_start_addr, - (volatile enet_tx_bd_struct_t *)tx_desc_start_addr, - (uint8_t *)&rx_ptr, - NULL, - }; - - k64f_init_eth_hardware(); - - sysClock = CLOCK_GetFreq(kCLOCK_CoreSysClk); - - ENET_GetDefaultConfig(&config); - - PHY_Init(ENET, 0, sysClock); - PHY_GetLinkStatus(ENET, phyAddr, &link); - if (link) - { - /* Get link information from PHY */ - PHY_GetLinkSpeedDuplex(ENET, phyAddr, &phy_speed, &phy_duplex); - /* Change the MII speed and duplex for actual link status. */ - config.miiSpeed = (enet_mii_speed_t)phy_speed; - config.miiDuplex = (enet_mii_duplex_t)phy_duplex; - config.interrupt = kENET_RxFrameInterrupt | kENET_TxFrameInterrupt; - } - config.rxMaxFrameLen = ENET_ETH_MAX_FLEN; - config.macSpecialConfig = kENET_ControlFlowControlEnable; - config.txAccelerConfig = kENET_TxAccelIsShift16Enabled; - config.rxAccelerConfig = kENET_RxAccelisShift16Enabled | kENET_RxAccelMacCheckEnabled; - ENET_Init(ENET, &g_handle, &config, &buffCfg, netif->hwaddr, sysClock); - ENET_SetCallback(&g_handle, ethernet_callback, netif); - ENET_ActiveRead(ENET); - - return ERR_OK; -} - - -/** - * This function is the ethernet packet send function. It calls - * etharp_output after checking link status. - * - * \param[in] netif the lwip network interface structure for this enetif - * \param[in] q Pointer to pbug to send - * \param[in] ipaddr IP address - * \return ERR_OK or error code - */ -err_t k64f_etharp_output(struct netif *netif, struct pbuf *q, ip_addr_t *ipaddr) -{ - /* Only send packet is link is up */ - if (netif->flags & NETIF_FLAG_LINK_UP) - return etharp_output(netif, q, ipaddr); - - return ERR_CONN; -} - -/** \brief Allocates a pbuf and returns the data from the incoming packet. - * - * \param[in] netif the lwip network interface structure - * \param[in] idx index of packet to be read - * \return a pbuf filled with the received packet (including MAC header) - */ -static struct pbuf *k64f_low_level_input(struct netif *netif, int idx) -{ - volatile enet_rx_bd_struct_t *bdPtr = g_handle.rxBdCurrent; - struct pbuf *p = NULL; - struct pbuf *temp_rxbuf = NULL; - u32_t length = 0; - const u16_t err_mask = ENET_BUFFDESCRIPTOR_RX_TRUNC_MASK | ENET_BUFFDESCRIPTOR_RX_CRC_MASK | - ENET_BUFFDESCRIPTOR_RX_NOOCTET_MASK | ENET_BUFFDESCRIPTOR_RX_LENVLIOLATE_MASK; - - -#ifdef LOCK_RX_THREAD - /* Get exclusive access */ - sys_mutex_lock(&k64f_enet->TXLockMutex); -#endif - - /* Determine if a frame has been received */ - if ((bdPtr->control & err_mask) != 0) { -#if LINK_STATS - if ((bdPtr->control & ENET_BUFFDESCRIPTOR_RX_LENVLIOLATE_MASK) != 0) - LINK_STATS_INC(link.lenerr); - else - LINK_STATS_INC(link.chkerr); -#endif - LINK_STATS_INC(link.drop); - /* Re-use the same buffer in case of error */ - update_read_buffer(NULL); - } else { - /* A packet is waiting, get length */ - length = bdPtr->length; - - /* Zero-copy */ - p = rx_buff[idx]; - p->len = length; - - /* Attempt to queue new buffer */ - temp_rxbuf = pbuf_alloc(PBUF_RAW, ENET_ETH_MAX_FLEN + ENET_BUFF_ALIGNMENT, PBUF_RAM); - if (NULL == temp_rxbuf) { - /* Drop frame (out of memory) */ - LINK_STATS_INC(link.drop); - - /* Re-queue the same buffer */ - update_read_buffer(NULL); - - LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE, - ("k64f_low_level_input: Packet index %d dropped for OOM\n", - idx)); -#ifdef LOCK_RX_THREAD - sys_mutex_unlock(&k64f_enet->TXLockMutex); -#endif - - return NULL; - } - - rx_buff[idx] = temp_rxbuf; - /* K64F note: the next line ensures that the RX buffer is properly aligned for the K64F - RX descriptors (16 bytes alignment). However, by doing so, we're effectively changing - a data structure which is internal to lwIP. This might not prove to be a good idea - in the long run, but a better fix would probably involve modifying lwIP itself */ - rx_buff[idx]->payload = (void*)ENET_ALIGN((uint32_t)rx_buff[idx]->payload, ENET_BUFF_ALIGNMENT); - rx_ptr[idx] = rx_buff[idx]->payload; - - update_read_buffer(rx_buff[idx]->payload); - LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE, - ("k64f_low_level_input: Packet received: %p, size %d (index=%d)\n", - p, length, idx)); - - /* Save size */ - p->tot_len = (u16_t) length; - LINK_STATS_INC(link.recv); - } - -#ifdef LOCK_RX_THREAD - sys_mutex_unlock(&k64f_enet->TXLockMutex); -#endif - - return p; -} - -/** \brief Attempt to read a packet from the EMAC interface. - * - * \param[in] netif the lwip network interface structure - * \param[in] idx index of packet to be read - */ -void k64f_enetif_input(struct netif *netif, int idx) -{ - struct eth_hdr *ethhdr; - struct pbuf *p; - - /* move received packet into a new pbuf */ - p = k64f_low_level_input(netif, idx); - if (p == NULL) - return; - - /* points to packet payload, which starts with an Ethernet header */ - ethhdr = (struct eth_hdr*)p->payload; - - switch (htons(ethhdr->type)) { - case ETHTYPE_IP: - case ETHTYPE_ARP: -#if PPPOE_SUPPORT - case ETHTYPE_PPPOEDISC: - case ETHTYPE_PPPOE: -#endif /* PPPOE_SUPPORT */ - /* full packet send to tcpip_thread to process */ - if (netif->input(p, netif) != ERR_OK) { - LWIP_DEBUGF(NETIF_DEBUG, ("k64f_enetif_input: IP input error\n")); - /* Free buffer */ - pbuf_free(p); - } - break; - - default: - /* Return buffer */ - pbuf_free(p); - break; - } -} - -/** \brief Packet reception task - * - * This task is called when a packet is received. It will - * pass the packet to the LWIP core. - * - * \param[in] pvParameters pointer to the interface data - */ -static void packet_rx(void* pvParameters) { - struct k64f_enetdata *k64f_enet = pvParameters; - int idx = 0; - - while (1) { - /* Wait for receive task to wakeup */ - sys_arch_sem_wait(&k64f_enet->RxReadySem, 0); - - while ((g_handle.rxBdCurrent->control & ENET_BUFFDESCRIPTOR_RX_EMPTY_MASK) == 0) { - k64f_enetif_input(k64f_enet->netif, idx); - idx = (idx + 1) % ENET_RX_RING_LEN; - } - } -} - -/** \brief Transmit cleanup task - * - * This task is called when a transmit interrupt occurs and - * reclaims the pbuf and descriptor used for the packet once - * the packet has been transferred. - * - * \param[in] pvParameters pointer to the interface data - */ -static void packet_tx(void* pvParameters) { - struct k64f_enetdata *k64f_enet = pvParameters; - - while (1) { - /* Wait for transmit cleanup task to wakeup */ - sys_arch_sem_wait(&k64f_enet->TxCleanSem, 0); - k64f_tx_reclaim(k64f_enet); - } -} - -/** \brief Low level output of a packet. Never call this from an - * interrupt context, as it may block until TX descriptors - * become available. - * - * \param[in] netif the lwip network interface structure for this netif - * \param[in] p the MAC packet to send (e.g. IP packet including MAC addresses and type) - * \return ERR_OK if the packet could be sent or an err_t value if the packet couldn't be sent - */ -static err_t k64f_low_level_output(struct netif *netif, struct pbuf *p) -{ - struct k64f_enetdata *k64f_enet = netif->state; - struct pbuf *q; - struct pbuf *temp_pbuf; - uint8_t *psend = NULL, *dst; - - - temp_pbuf = pbuf_alloc(PBUF_RAW, p->tot_len + ENET_BUFF_ALIGNMENT, PBUF_RAM); - if (NULL == temp_pbuf) - return ERR_MEM; - - /* K64F note: the next line ensures that the RX buffer is properly aligned for the K64F - RX descriptors (16 bytes alignment). However, by doing so, we're effectively changing - a data structure which is internal to lwIP. This might not prove to be a good idea - in the long run, but a better fix would probably involve modifying lwIP itself */ - psend = (uint8_t *)ENET_ALIGN((uint32_t)temp_pbuf->payload, ENET_BUFF_ALIGNMENT); - - for (q = p, dst = psend; q != NULL; q = q->next) { - MEMCPY(dst, q->payload, q->len); - dst += q->len; - } - - /* Wait until a descriptor is available for the transfer. */ - /* THIS WILL BLOCK UNTIL THERE ARE A DESCRIPTOR AVAILABLE */ - while (g_handle.txBdCurrent->control & ENET_BUFFDESCRIPTOR_TX_READY_MASK) - osSemaphoreWait(k64f_enet->xTXDCountSem.id, osWaitForever); - - /* Get exclusive access */ - sys_mutex_lock(&k64f_enet->TXLockMutex); - - /* Save the buffer so that it can be freed when transmit is done */ - tx_buff[k64f_enet->tx_produce_index] = temp_pbuf; - k64f_enet->tx_produce_index = (k64f_enet->tx_produce_index + 1) % ENET_TX_RING_LEN; - - /* Setup transfers */ - g_handle.txBdCurrent->buffer = psend; - g_handle.txBdCurrent->length = p->tot_len; - g_handle.txBdCurrent->control |= (ENET_BUFFDESCRIPTOR_TX_READY_MASK | ENET_BUFFDESCRIPTOR_TX_LAST_MASK); - - /* Increase the buffer descriptor address. */ - if (g_handle.txBdCurrent->control & ENET_BUFFDESCRIPTOR_TX_WRAP_MASK) - g_handle.txBdCurrent = g_handle.txBdBase; - else - g_handle.txBdCurrent++; - - /* Active the transmit buffer descriptor. */ - ENET->TDAR = ENET_TDAR_TDAR_MASK; - - LINK_STATS_INC(link.xmit); - - /* Restore access */ - sys_mutex_unlock(&k64f_enet->TXLockMutex); - - return ERR_OK; -} - -/******************************************************************************* - * PHY task: monitor link -*******************************************************************************/ - -#define PHY_TASK_PERIOD_MS 200 -#define STATE_UNKNOWN (-1) - -typedef struct { - int connected; - phy_speed_t speed; - phy_duplex_t duplex; -} PHY_STATE; - -int phy_link_status() { - bool connection_status; - uint32_t phyAddr = 0; - - PHY_GetLinkStatus(ENET, phyAddr, &connection_status); - return (int)connection_status; -} - -static void k64f_phy_task(void *data) { - struct netif *netif = (struct netif*)data; - bool connection_status; - PHY_STATE crt_state = {STATE_UNKNOWN, (phy_speed_t)STATE_UNKNOWN, (phy_duplex_t)STATE_UNKNOWN}; - PHY_STATE prev_state; - uint32_t phyAddr = 0; - uint32_t rcr = 0; - - prev_state = crt_state; - while (true) { - // Get current status - PHY_GetLinkStatus(ENET, phyAddr, &connection_status); - crt_state.connected = connection_status ? 1 : 0; - // Get the actual PHY link speed - PHY_GetLinkSpeedDuplex(ENET, phyAddr, &crt_state.speed, &crt_state.duplex); - - // Compare with previous state - if (crt_state.connected != prev_state.connected) { - if (crt_state.connected) - tcpip_callback_with_block((tcpip_callback_fn)netif_set_link_up, (void*) netif, 1); - else - tcpip_callback_with_block((tcpip_callback_fn)netif_set_link_down, (void*) netif, 1); - } - - if (crt_state.speed != prev_state.speed) { - rcr = ENET->RCR; - rcr &= ~ENET_RCR_RMII_10T_MASK; - rcr |= ENET_RCR_RMII_10T(!crt_state.speed); - ENET->RCR = rcr; - } - - prev_state = crt_state; - osDelay(PHY_TASK_PERIOD_MS); - } -} - -/** - * Should be called at the beginning of the program to set up the - * network interface. - * - * This function should be passed as a parameter to netif_add(). - * - * @param[in] netif the lwip network interface structure for this netif - * @return ERR_OK if the loopif is initialized - * ERR_MEM if private data couldn't be allocated - * any other err_t on error - */ -err_t eth_arch_enetif_init(struct netif *netif) -{ - err_t err; - - LWIP_ASSERT("netif != NULL", (netif != NULL)); - - k64f_enetdata.netif = netif; - - /* set MAC hardware address */ -#if (MBED_MAC_ADDRESS_SUM != MBED_MAC_ADDR_INTERFACE) - netif->hwaddr[0] = MBED_MAC_ADDR_0; - netif->hwaddr[1] = MBED_MAC_ADDR_1; - netif->hwaddr[2] = MBED_MAC_ADDR_2; - netif->hwaddr[3] = MBED_MAC_ADDR_3; - netif->hwaddr[4] = MBED_MAC_ADDR_4; - netif->hwaddr[5] = MBED_MAC_ADDR_5; -#else - mbed_mac_address((char *)netif->hwaddr); -#endif - netif->hwaddr_len = ETHARP_HWADDR_LEN; - - /* maximum transfer unit */ - netif->mtu = 1500; - - /* device capabilities */ - // TODOETH: check if the flags are correct below - netif->flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP | NETIF_FLAG_ETHERNET | NETIF_FLAG_IGMP; - - /* Initialize the hardware */ - netif->state = &k64f_enetdata; - err = low_level_init(netif); - if (err != ERR_OK) - return err; - -#if LWIP_NETIF_HOSTNAME - /* Initialize interface hostname */ - netif->hostname = "lwipk64f"; -#endif /* LWIP_NETIF_HOSTNAME */ - - netif->name[0] = 'e'; - netif->name[1] = 'n'; - - netif->output = k64f_etharp_output; - netif->linkoutput = k64f_low_level_output; - - /* CMSIS-RTOS, start tasks */ -#ifdef CMSIS_OS_RTX - memset(k64f_enetdata.xTXDCountSem.data, 0, sizeof(k64f_enetdata.xTXDCountSem.data)); - k64f_enetdata.xTXDCountSem.def.semaphore = k64f_enetdata.xTXDCountSem.data; -#endif - k64f_enetdata.xTXDCountSem.id = osSemaphoreCreate(&k64f_enetdata.xTXDCountSem.def, ENET_TX_RING_LEN); - - LWIP_ASSERT("xTXDCountSem creation error", (k64f_enetdata.xTXDCountSem.id != NULL)); - - err = sys_mutex_new(&k64f_enetdata.TXLockMutex); - LWIP_ASSERT("TXLockMutex creation error", (err == ERR_OK)); - - /* Packet receive task */ - err = sys_sem_new(&k64f_enetdata.RxReadySem, 0); - LWIP_ASSERT("RxReadySem creation error", (err == ERR_OK)); - sys_thread_new("receive_thread", packet_rx, netif->state, DEFAULT_THREAD_STACKSIZE, RX_PRIORITY); - - /* Transmit cleanup task */ - err = sys_sem_new(&k64f_enetdata.TxCleanSem, 0); - LWIP_ASSERT("TxCleanSem creation error", (err == ERR_OK)); - sys_thread_new("txclean_thread", packet_tx, netif->state, DEFAULT_THREAD_STACKSIZE, TX_PRIORITY); - - /* PHY monitoring task */ - sys_thread_new("phy_thread", k64f_phy_task, netif, DEFAULT_THREAD_STACKSIZE, PHY_PRIORITY); - - /* Allow the PHY task to detect the initial link state and set up the proper flags */ - osDelay(10); - - return ERR_OK; -} - -void eth_arch_enable_interrupts(void) { - //NVIC_SetPriority(ENET_Receive_IRQn, 6U); - //NVIC_SetPriority(ENET_Transmit_IRQn, 6U); -} - -void eth_arch_disable_interrupts(void) { - -} - -/** - * @} - */ - -/* --------------------------------- End Of File ------------------------------ */ -
--- a/arch/TARGET_Freescale/k64f_emac_config.h Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,51 +0,0 @@ -/* - * Copyright (c) 2013 - 2014, Freescale Semiconductor, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * - * o Redistributions of source code must retain the above copyright notice, this list - * of conditions and the following disclaimer. - * - * o Redistributions in binary form must reproduce the above copyright notice, this - * list of conditions and the following disclaimer in the documentation and/or - * other materials provided with the distribution. - * - * o Neither the name of Freescale Semiconductor, Inc. nor the names of its - * contributors may be used to endorse or promote products derived from this - * software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND - * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED - * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR - * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES - * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON - * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT - * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS - * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#ifndef K64F_EMAC_CONFIG_H__ -#define K64F_EMAC_CONFIG_H__ - -#include "fsl_enet.h" - -#define ENET_RX_RING_LEN (16) -#define ENET_TX_RING_LEN (8) - -#define ENET_ETH_MAX_FLEN (1522) // recommended size for a VLAN frame - -#if defined(__cplusplus) -extern "C" { -#endif - -int phy_link_status(void); - -#if defined(__cplusplus) -} -#endif - -#endif // #define K64F_EMAC_CONFIG_H__ -
--- a/arch/TARGET_Freescale/lwipopts_conf.h Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,29 +0,0 @@ -/* Copyright (C) 2012 mbed.org, MIT License - * - * Permission is hereby granted, free of charge, to any person obtaining a copy of this software - * and associated documentation files (the "Software"), to deal in the Software without restriction, - * including without limitation the rights to use, copy, modify, merge, publish, distribute, - * sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in all copies or - * substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - * BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - * DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - */ - -#ifndef LWIPOPTS_CONF_H -#define LWIPOPTS_CONF_H - -#include "k64f_emac_config.h" - -#define LWIP_TRANSPORT_ETHERNET 1 -#define ETH_PAD_SIZE 2 - -#define MEM_SIZE (ENET_RX_RING_LEN * (ENET_ETH_MAX_FLEN + ENET_BUFF_ALIGNMENT) + ENET_TX_RING_LEN * ENET_ETH_MAX_FLEN) - -#endif
--- a/arch/TARGET_NXP/lpc17_emac.c Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,1046 +0,0 @@ -/********************************************************************** -* $Id$ lpc17_emac.c 2011-11-20 -*//** -* @file lpc17_emac.c -* @brief LPC17 ethernet driver for LWIP -* @version 1.0 -* @date 20. Nov. 2011 -* @author NXP MCU SW Application Team -* -* Copyright(C) 2011, NXP Semiconductor -* All rights reserved. -* -*********************************************************************** -* Software that is described herein is for illustrative purposes only -* which provides customers with programming information regarding the -* products. This software is supplied "AS IS" without any warranties. -* NXP Semiconductors assumes no responsibility or liability for the -* use of the software, conveys no license or title under any patent, -* copyright, or mask work right to the product. NXP Semiconductors -* reserves the right to make changes in the software without -* notification. NXP Semiconductors also make no representation or -* warranty that such application will be suitable for the specified -* use without further testing or modification. -**********************************************************************/ - -#include "lwip/opt.h" -#include "lwip/sys.h" -#include "lwip/def.h" -#include "lwip/mem.h" -#include "lwip/pbuf.h" -#include "lwip/stats.h" -#include "lwip/snmp.h" -#include "netif/etharp.h" -#include "netif/ppp_oe.h" - -#include "lpc17xx_emac.h" -#include "eth_arch.h" -#include "lpc_emac_config.h" -#include "lpc_phy.h" -#include "sys_arch.h" - -#include "mbed_interface.h" -#include <string.h> - -#ifndef LPC_EMAC_RMII -#error LPC_EMAC_RMII is not defined! -#endif - -#if LPC_NUM_BUFF_TXDESCS < 2 -#error LPC_NUM_BUFF_TXDESCS must be at least 2 -#endif - -#if LPC_NUM_BUFF_RXDESCS < 3 -#error LPC_NUM_BUFF_RXDESCS must be at least 3 -#endif - -/** @defgroup lwip17xx_emac_DRIVER lpc17 EMAC driver for LWIP - * @ingroup lwip_emac - * - * @{ - */ - -#if NO_SYS == 0 -/** \brief Driver transmit and receive thread priorities - * - * Thread priorities for receive thread and TX cleanup thread. Alter - * to prioritize receive or transmit bandwidth. In a heavily loaded - * system or with LEIP_DEBUG enabled, the priorities might be better - * the same. */ -#define RX_PRIORITY (osPriorityNormal) -#define TX_PRIORITY (osPriorityNormal) - -/** \brief Debug output formatter lock define - * - * When using FreeRTOS and with LWIP_DEBUG enabled, enabling this - * define will allow RX debug messages to not interleave with the - * TX messages (so they are actually readable). Not enabling this - * define when the system is under load will cause the output to - * be unreadable. There is a small tradeoff in performance for this - * so use it only for debug. */ -//#define LOCK_RX_THREAD - -/** \brief Receive group interrupts - */ -#define RXINTGROUP (EMAC_INT_RX_OVERRUN | EMAC_INT_RX_ERR | EMAC_INT_RX_DONE) - -/** \brief Transmit group interrupts - */ -#define TXINTGROUP (EMAC_INT_TX_UNDERRUN | EMAC_INT_TX_ERR | EMAC_INT_TX_DONE) - -/** \brief Signal used for ethernet ISR to signal packet_rx() thread. - */ -#define RX_SIGNAL 1 - -#else -#define RXINTGROUP 0 -#define TXINTGROUP 0 -#endif - - /** \brief Structure of a TX/RX descriptor - */ -typedef struct -{ - volatile u32_t packet; /**< Pointer to buffer */ - volatile u32_t control; /**< Control word */ -} LPC_TXRX_DESC_T; - -/** \brief Structure of a RX status entry - */ -typedef struct -{ - volatile u32_t statusinfo; /**< RX status word */ - volatile u32_t statushashcrc; /**< RX hash CRC */ -} LPC_TXRX_STATUS_T; - -/* LPC EMAC driver data structure */ -struct lpc_enetdata { - /* prxs must be 8 byte aligned! */ - LPC_TXRX_STATUS_T prxs[LPC_NUM_BUFF_RXDESCS]; /**< Pointer to RX statuses */ - struct netif *netif; /**< Reference back to LWIP parent netif */ - LPC_TXRX_DESC_T ptxd[LPC_NUM_BUFF_TXDESCS]; /**< Pointer to TX descriptor list */ - LPC_TXRX_STATUS_T ptxs[LPC_NUM_BUFF_TXDESCS]; /**< Pointer to TX statuses */ - LPC_TXRX_DESC_T prxd[LPC_NUM_BUFF_RXDESCS]; /**< Pointer to RX descriptor list */ - struct pbuf *rxb[LPC_NUM_BUFF_RXDESCS]; /**< RX pbuf pointer list, zero-copy mode */ - u32_t rx_fill_desc_index; /**< RX descriptor next available index */ - volatile u32_t rx_free_descs; /**< Count of free RX descriptors */ - struct pbuf *txb[LPC_NUM_BUFF_TXDESCS]; /**< TX pbuf pointer list, zero-copy mode */ - u32_t lpc_last_tx_idx; /**< TX last descriptor index, zero-copy mode */ -#if NO_SYS == 0 - sys_thread_t RxThread; /**< RX receive thread data object pointer */ - sys_sem_t TxCleanSem; /**< TX cleanup thread wakeup semaphore */ - sys_mutex_t TXLockMutex; /**< TX critical section mutex */ - sys_sem_t xTXDCountSem; /**< TX free buffer counting semaphore */ -#endif -}; - -#if defined(TARGET_LPC4088) || defined(TARGET_LPC4088_DM) -# if defined (__ICCARM__) -# define ETHMEM_SECTION -# elif defined(TOOLCHAIN_GCC_CR) -# define ETHMEM_SECTION __attribute__((section(".data.$RamPeriph32"), aligned)) -# else -# define ETHMEM_SECTION __attribute__((section("AHBSRAM1"),aligned)) -# endif -#elif defined(TARGET_LPC1768) -# if defined(TOOLCHAIN_GCC_ARM) -# define ETHMEM_SECTION __attribute__((section("AHBSRAM1"),aligned)) -# endif -#endif - -#ifndef ETHMEM_SECTION -#define ETHMEM_SECTION ALIGNED(8) -#endif - -/** \brief LPC EMAC driver work data - */ -ETHMEM_SECTION struct lpc_enetdata lpc_enetdata; - -/** \brief Queues a pbuf into the RX descriptor list - * - * \param[in] lpc_enetif Pointer to the drvier data structure - * \param[in] p Pointer to pbuf to queue - */ -static void lpc_rxqueue_pbuf(struct lpc_enetdata *lpc_enetif, struct pbuf *p) -{ - u32_t idx; - - /* Get next free descriptor index */ - idx = lpc_enetif->rx_fill_desc_index; - - /* Setup descriptor and clear statuses */ - lpc_enetif->prxd[idx].control = EMAC_RCTRL_INT | ((u32_t) (p->len - 1)); - lpc_enetif->prxd[idx].packet = (u32_t) p->payload; - lpc_enetif->prxs[idx].statusinfo = 0xFFFFFFFF; - lpc_enetif->prxs[idx].statushashcrc = 0xFFFFFFFF; - - /* Save pbuf pointer for push to network layer later */ - lpc_enetif->rxb[idx] = p; - - /* Wrap at end of descriptor list */ - idx++; - if (idx >= LPC_NUM_BUFF_RXDESCS) - idx = 0; - - /* Queue descriptor(s) */ - lpc_enetif->rx_free_descs -= 1; - lpc_enetif->rx_fill_desc_index = idx; - LPC_EMAC->RxConsumeIndex = idx; - - LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE, - ("lpc_rxqueue_pbuf: pbuf packet queued: %p (free desc=%d)\n", p, - lpc_enetif->rx_free_descs)); -} - -/** \brief Attempt to allocate and requeue a new pbuf for RX - * - * \param[in] netif Pointer to the netif structure - * \returns 1 if a packet was allocated and requeued, otherwise 0 - */ -s32_t lpc_rx_queue(struct netif *netif) -{ - struct lpc_enetdata *lpc_enetif = netif->state; - struct pbuf *p; - s32_t queued = 0; - - /* Attempt to requeue as many packets as possible */ - while (lpc_enetif->rx_free_descs > 0) { - /* Allocate a pbuf from the pool. We need to allocate at the - maximum size as we don't know the size of the yet to be - received packet. */ - p = pbuf_alloc(PBUF_RAW, (u16_t) EMAC_ETH_MAX_FLEN, PBUF_RAM); - if (p == NULL) { - LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE, - ("lpc_rx_queue: could not allocate RX pbuf (free desc=%d)\n", - lpc_enetif->rx_free_descs)); - return queued; - } - - /* pbufs allocated from the RAM pool should be non-chained. */ - LWIP_ASSERT("lpc_rx_queue: pbuf is not contiguous (chained)", - pbuf_clen(p) <= 1); - - /* Queue packet */ - lpc_rxqueue_pbuf(lpc_enetif, p); - - /* Update queued count */ - queued++; - } - - return queued; -} - -/** \brief Sets up the RX descriptor ring buffers. - * - * This function sets up the descriptor list used for receive packets. - * - * \param[in] lpc_enetif Pointer to driver data structure - * \returns Always returns ERR_OK - */ -static err_t lpc_rx_setup(struct lpc_enetdata *lpc_enetif) -{ - /* Setup pointers to RX structures */ - LPC_EMAC->RxDescriptor = (u32_t) &lpc_enetif->prxd[0]; - LPC_EMAC->RxStatus = (u32_t) &lpc_enetif->prxs[0]; - LPC_EMAC->RxDescriptorNumber = LPC_NUM_BUFF_RXDESCS - 1; - - lpc_enetif->rx_free_descs = LPC_NUM_BUFF_RXDESCS; - lpc_enetif->rx_fill_desc_index = 0; - - /* Build RX buffer and descriptors */ - lpc_rx_queue(lpc_enetif->netif); - - return ERR_OK; -} - -/** \brief Allocates a pbuf and returns the data from the incoming packet. - * - * \param[in] netif the lwip network interface structure for this lpc_enetif - * \return a pbuf filled with the received packet (including MAC header) - * NULL on memory error - */ -static struct pbuf *lpc_low_level_input(struct netif *netif) -{ - struct lpc_enetdata *lpc_enetif = netif->state; - struct pbuf *p = NULL; - u32_t idx, length; - u16_t origLength; - -#ifdef LOCK_RX_THREAD -#if NO_SYS == 0 - /* Get exclusive access */ - sys_mutex_lock(&lpc_enetif->TXLockMutex); -#endif -#endif - - /* Monitor RX overrun status. This should never happen unless - (possibly) the internal bus is behing held up by something. - Unless your system is running at a very low clock speed or - there are possibilities that the internal buses may be held - up for a long time, this can probably safely be removed. */ - if (LPC_EMAC->IntStatus & EMAC_INT_RX_OVERRUN) { - LINK_STATS_INC(link.err); - LINK_STATS_INC(link.drop); - - /* Temporarily disable RX */ - LPC_EMAC->MAC1 &= ~EMAC_MAC1_REC_EN; - - /* Reset the RX side */ - LPC_EMAC->MAC1 |= EMAC_MAC1_RES_RX; - LPC_EMAC->IntClear = EMAC_INT_RX_OVERRUN; - - /* De-allocate all queued RX pbufs */ - for (idx = 0; idx < LPC_NUM_BUFF_RXDESCS; idx++) { - if (lpc_enetif->rxb[idx] != NULL) { - pbuf_free(lpc_enetif->rxb[idx]); - lpc_enetif->rxb[idx] = NULL; - } - } - - /* Start RX side again */ - lpc_rx_setup(lpc_enetif); - - /* Re-enable RX */ - LPC_EMAC->MAC1 |= EMAC_MAC1_REC_EN; - -#ifdef LOCK_RX_THREAD -#if NO_SYS == 0 - sys_mutex_unlock(&lpc_enetif->TXLockMutex); -#endif -#endif - - return NULL; - } - - /* Determine if a frame has been received */ - length = 0; - idx = LPC_EMAC->RxConsumeIndex; - if (LPC_EMAC->RxProduceIndex != idx) { - /* Handle errors */ - if (lpc_enetif->prxs[idx].statusinfo & (EMAC_RINFO_CRC_ERR | - EMAC_RINFO_SYM_ERR | EMAC_RINFO_ALIGN_ERR | EMAC_RINFO_LEN_ERR)) { -#if LINK_STATS - if (lpc_enetif->prxs[idx].statusinfo & (EMAC_RINFO_CRC_ERR | - EMAC_RINFO_SYM_ERR | EMAC_RINFO_ALIGN_ERR)) - LINK_STATS_INC(link.chkerr); - if (lpc_enetif->prxs[idx].statusinfo & EMAC_RINFO_LEN_ERR) - LINK_STATS_INC(link.lenerr); -#endif - - /* Drop the frame */ - LINK_STATS_INC(link.drop); - - /* Re-queue the pbuf for receive */ - lpc_enetif->rx_free_descs++; - p = lpc_enetif->rxb[idx]; - lpc_enetif->rxb[idx] = NULL; - lpc_rxqueue_pbuf(lpc_enetif, p); - - LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE, - ("lpc_low_level_input: Packet dropped with errors (0x%x)\n", - lpc_enetif->prxs[idx].statusinfo)); - - p = NULL; - } else { - /* A packet is waiting, get length */ - length = (lpc_enetif->prxs[idx].statusinfo & 0x7FF) + 1; - - /* Zero-copy */ - p = lpc_enetif->rxb[idx]; - origLength = p->len; - p->len = (u16_t) length; - - /* Free pbuf from descriptor */ - lpc_enetif->rxb[idx] = NULL; - lpc_enetif->rx_free_descs++; - - /* Attempt to queue new buffer(s) */ - if (lpc_rx_queue(lpc_enetif->netif) == 0) { - /* Drop the frame due to OOM. */ - LINK_STATS_INC(link.drop); - - /* Re-queue the pbuf for receive */ - p->len = origLength; - lpc_rxqueue_pbuf(lpc_enetif, p); - - LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE, - ("lpc_low_level_input: Packet index %d dropped for OOM\n", - idx)); - -#ifdef LOCK_RX_THREAD -#if NO_SYS == 0 - sys_mutex_unlock(&lpc_enetif->TXLockMutex); -#endif -#endif - - return NULL; - } - - LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE, - ("lpc_low_level_input: Packet received: %p, size %d (index=%d)\n", - p, length, idx)); - - /* Save size */ - p->tot_len = (u16_t) length; - LINK_STATS_INC(link.recv); - } - } - -#ifdef LOCK_RX_THREAD -#if NO_SYS == 0 - sys_mutex_unlock(&lpc_enetif->TXLockMutex); -#endif -#endif - - return p; -} - -/** \brief Attempt to read a packet from the EMAC interface. - * - * \param[in] netif the lwip network interface structure for this lpc_enetif - */ -void lpc_enetif_input(struct netif *netif) -{ - struct eth_hdr *ethhdr; - struct pbuf *p; - - /* move received packet into a new pbuf */ - p = lpc_low_level_input(netif); - if (p == NULL) - return; - - /* points to packet payload, which starts with an Ethernet header */ - ethhdr = p->payload; - - switch (htons(ethhdr->type)) { - case ETHTYPE_IP: - case ETHTYPE_ARP: -#if PPPOE_SUPPORT - case ETHTYPE_PPPOEDISC: - case ETHTYPE_PPPOE: -#endif /* PPPOE_SUPPORT */ - /* full packet send to tcpip_thread to process */ - if (netif->input(p, netif) != ERR_OK) { - LWIP_DEBUGF(NETIF_DEBUG, ("lpc_enetif_input: IP input error\n")); - /* Free buffer */ - pbuf_free(p); - } - break; - - default: - /* Return buffer */ - pbuf_free(p); - break; - } -} - -/** \brief Determine if the passed address is usable for the ethernet - * DMA controller. - * - * \param[in] addr Address of packet to check for DMA safe operation - * \return 1 if the packet address is not safe, otherwise 0 - */ -static s32_t lpc_packet_addr_notsafe(void *addr) { - /* Check for legal address ranges */ -#if defined(TARGET_LPC1768) - if ((((u32_t) addr >= 0x2007C000) && ((u32_t) addr < 0x20083FFF))) { -#elif defined(TARGET_LPC4088) || defined(TARGET_LPC4088_DM) - if ((((u32_t) addr >= 0x20000000) && ((u32_t) addr < 0x20007FFF))) { -#endif - return 0; - } - return 1; -} - -/** \brief Sets up the TX descriptor ring buffers. - * - * This function sets up the descriptor list used for transmit packets. - * - * \param[in] lpc_enetif Pointer to driver data structure - */ -static err_t lpc_tx_setup(struct lpc_enetdata *lpc_enetif) -{ - s32_t idx; - - /* Build TX descriptors for local buffers */ - for (idx = 0; idx < LPC_NUM_BUFF_TXDESCS; idx++) { - lpc_enetif->ptxd[idx].control = 0; - lpc_enetif->ptxs[idx].statusinfo = 0xFFFFFFFF; - } - - /* Setup pointers to TX structures */ - LPC_EMAC->TxDescriptor = (u32_t) &lpc_enetif->ptxd[0]; - LPC_EMAC->TxStatus = (u32_t) &lpc_enetif->ptxs[0]; - LPC_EMAC->TxDescriptorNumber = LPC_NUM_BUFF_TXDESCS - 1; - - lpc_enetif->lpc_last_tx_idx = 0; - - return ERR_OK; -} - -/** \brief Free TX buffers that are complete - * - * \param[in] lpc_enetif Pointer to driver data structure - * \param[in] cidx EMAC current descriptor comsumer index - */ -static void lpc_tx_reclaim_st(struct lpc_enetdata *lpc_enetif, u32_t cidx) -{ -#if NO_SYS == 0 - /* Get exclusive access */ - sys_mutex_lock(&lpc_enetif->TXLockMutex); -#endif - - while (cidx != lpc_enetif->lpc_last_tx_idx) { - if (lpc_enetif->txb[lpc_enetif->lpc_last_tx_idx] != NULL) { - LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE, - ("lpc_tx_reclaim_st: Freeing packet %p (index %d)\n", - lpc_enetif->txb[lpc_enetif->lpc_last_tx_idx], - lpc_enetif->lpc_last_tx_idx)); - pbuf_free(lpc_enetif->txb[lpc_enetif->lpc_last_tx_idx]); - lpc_enetif->txb[lpc_enetif->lpc_last_tx_idx] = NULL; - } - -#if NO_SYS == 0 - osSemaphoreRelease(lpc_enetif->xTXDCountSem.id); -#endif - lpc_enetif->lpc_last_tx_idx++; - if (lpc_enetif->lpc_last_tx_idx >= LPC_NUM_BUFF_TXDESCS) - lpc_enetif->lpc_last_tx_idx = 0; - } - -#if NO_SYS == 0 - /* Restore access */ - sys_mutex_unlock(&lpc_enetif->TXLockMutex); -#endif -} - -/** \brief User call for freeingTX buffers that are complete - * - * \param[in] netif the lwip network interface structure for this lpc_enetif - */ -void lpc_tx_reclaim(struct netif *netif) -{ - lpc_tx_reclaim_st((struct lpc_enetdata *) netif->state, - LPC_EMAC->TxConsumeIndex); -} - - /** \brief Polls if an available TX descriptor is ready. Can be used to - * determine if the low level transmit function will block. - * - * \param[in] netif the lwip network interface structure for this lpc_enetif - * \return 0 if no descriptors are read, or >0 - */ -s32_t lpc_tx_ready(struct netif *netif) -{ - s32_t fb; - u32_t idx, cidx; - - cidx = LPC_EMAC->TxConsumeIndex; - idx = LPC_EMAC->TxProduceIndex; - - /* Determine number of free buffers */ - if (idx == cidx) - fb = LPC_NUM_BUFF_TXDESCS; - else if (cidx > idx) - fb = (LPC_NUM_BUFF_TXDESCS - 1) - - ((idx + LPC_NUM_BUFF_TXDESCS) - cidx); - else - fb = (LPC_NUM_BUFF_TXDESCS - 1) - (cidx - idx); - - return fb; -} - -/** \brief Low level output of a packet. Never call this from an - * interrupt context, as it may block until TX descriptors - * become available. - * - * \param[in] netif the lwip network interface structure for this lpc_enetif - * \param[in] p the MAC packet to send (e.g. IP packet including MAC addresses and type) - * \return ERR_OK if the packet could be sent or an err_t value if the packet couldn't be sent - */ -static err_t lpc_low_level_output(struct netif *netif, struct pbuf *p) -{ - struct lpc_enetdata *lpc_enetif = netif->state; - struct pbuf *q; - u8_t *dst; - u32_t idx, notdmasafe = 0; - struct pbuf *np; - s32_t dn; - - /* Zero-copy TX buffers may be fragmented across mutliple payload - chains. Determine the number of descriptors needed for the - transfer. The pbuf chaining can be a mess! */ - dn = (s32_t) pbuf_clen(p); - - /* Test to make sure packet addresses are DMA safe. A DMA safe - address is once that uses external memory or periphheral RAM. - IRAM and FLASH are not safe! */ - for (q = p; q != NULL; q = q->next) - notdmasafe += lpc_packet_addr_notsafe(q->payload); - -#if LPC_TX_PBUF_BOUNCE_EN==1 - /* If the pbuf is not DMA safe, a new bounce buffer (pbuf) will be - created that will be used instead. This requires an copy from the - non-safe DMA region to the new pbuf */ - if (notdmasafe) { - /* Allocate a pbuf in DMA memory */ - np = pbuf_alloc(PBUF_RAW, p->tot_len, PBUF_RAM); - if (np == NULL) - return ERR_MEM; - - /* This buffer better be contiguous! */ - LWIP_ASSERT("lpc_low_level_output: New transmit pbuf is chained", - (pbuf_clen(np) == 1)); - - /* Copy to DMA safe pbuf */ - dst = (u8_t *) np->payload; - for(q = p; q != NULL; q = q->next) { - /* Copy the buffer to the descriptor's buffer */ - MEMCPY(dst, (u8_t *) q->payload, q->len); - dst += q->len; - } - np->len = p->tot_len; - - LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE, - ("lpc_low_level_output: Switched to DMA safe buffer, old=%p, new=%p\n", - q, np)); - - /* use the new buffer for descrptor queueing. The original pbuf will - be de-allocated outsuide this driver. */ - p = np; - dn = 1; - } -#else - if (notdmasafe) - LWIP_ASSERT("lpc_low_level_output: Not a DMA safe pbuf", - (notdmasafe == 0)); -#endif - - /* Wait until enough descriptors are available for the transfer. */ - /* THIS WILL BLOCK UNTIL THERE ARE ENOUGH DESCRIPTORS AVAILABLE */ - while (dn > lpc_tx_ready(netif)) -#if NO_SYS == 0 - osSemaphoreWait(lpc_enetif->xTXDCountSem.id, osWaitForever); -#else - osDelay(1); -#endif - - /* Get free TX buffer index */ - idx = LPC_EMAC->TxProduceIndex; - -#if NO_SYS == 0 - /* Get exclusive access */ - sys_mutex_lock(&lpc_enetif->TXLockMutex); -#endif - - /* Prevent LWIP from de-allocating this pbuf. The driver will - free it once it's been transmitted. */ - if (!notdmasafe) - pbuf_ref(p); - - /* Setup transfers */ - q = p; - while (dn > 0) { - dn--; - - /* Only save pointer to free on last descriptor */ - if (dn == 0) { - /* Save size of packet and signal it's ready */ - lpc_enetif->ptxd[idx].control = (q->len - 1) | EMAC_TCTRL_INT | - EMAC_TCTRL_LAST; - lpc_enetif->txb[idx] = p; - } - else { - /* Save size of packet, descriptor is not last */ - lpc_enetif->ptxd[idx].control = (q->len - 1) | EMAC_TCTRL_INT; - lpc_enetif->txb[idx] = NULL; - } - - LWIP_DEBUGF(UDP_LPC_EMAC | LWIP_DBG_TRACE, - ("lpc_low_level_output: pbuf packet(%p) sent, chain#=%d," - " size = %d (index=%d)\n", q->payload, dn, q->len, idx)); - - lpc_enetif->ptxd[idx].packet = (u32_t) q->payload; - - q = q->next; - - idx++; - if (idx >= LPC_NUM_BUFF_TXDESCS) - idx = 0; - } - - LPC_EMAC->TxProduceIndex = idx; - - LINK_STATS_INC(link.xmit); - -#if NO_SYS == 0 - /* Restore access */ - sys_mutex_unlock(&lpc_enetif->TXLockMutex); -#endif - - return ERR_OK; -} - -/** \brief LPC EMAC interrupt handler. - * - * This function handles the transmit, receive, and error interrupt of - * the LPC177x_8x. This is meant to be used when NO_SYS=0. - */ -void ENET_IRQHandler(void) -{ -#if NO_SYS == 1 - /* Interrupts are not used without an RTOS */ - NVIC_DisableIRQ(ENET_IRQn); -#else - uint32_t ints; - - /* Interrupts are of 2 groups - transmit or receive. Based on the - interrupt, kick off the receive or transmit (cleanup) task */ - - /* Get pending interrupts */ - ints = LPC_EMAC->IntStatus; - - if (ints & RXINTGROUP) { - /* RX group interrupt(s): Give signal to wakeup RX receive task.*/ - osSignalSet(lpc_enetdata.RxThread->id, RX_SIGNAL); - } - - if (ints & TXINTGROUP) { - /* TX group interrupt(s): Give semaphore to wakeup TX cleanup task. */ - sys_sem_signal(&lpc_enetdata.TxCleanSem); - } - - /* Clear pending interrupts */ - LPC_EMAC->IntClear = ints; -#endif -} - -#if NO_SYS == 0 -/** \brief Packet reception task - * - * This task is called when a packet is received. It will - * pass the packet to the LWIP core. - * - * \param[in] pvParameters Not used yet - */ -static void packet_rx(void* pvParameters) { - struct lpc_enetdata *lpc_enetif = pvParameters; - - while (1) { - /* Wait for receive task to wakeup */ - osSignalWait(RX_SIGNAL, osWaitForever); - - /* Process packets until all empty */ - while (LPC_EMAC->RxConsumeIndex != LPC_EMAC->RxProduceIndex) - lpc_enetif_input(lpc_enetif->netif); - } -} - -/** \brief Transmit cleanup task - * - * This task is called when a transmit interrupt occurs and - * reclaims the pbuf and descriptor used for the packet once - * the packet has been transferred. - * - * \param[in] pvParameters Not used yet - */ -static void packet_tx(void* pvParameters) { - struct lpc_enetdata *lpc_enetif = pvParameters; - s32_t idx; - - while (1) { - /* Wait for transmit cleanup task to wakeup */ - sys_arch_sem_wait(&lpc_enetif->TxCleanSem, 0); - - /* Error handling for TX underruns. This should never happen unless - something is holding the bus or the clocks are going too slow. It - can probably be safely removed. */ - if (LPC_EMAC->IntStatus & EMAC_INT_TX_UNDERRUN) { - LINK_STATS_INC(link.err); - LINK_STATS_INC(link.drop); - -#if NO_SYS == 0 - /* Get exclusive access */ - sys_mutex_lock(&lpc_enetif->TXLockMutex); -#endif - /* Reset the TX side */ - LPC_EMAC->MAC1 |= EMAC_MAC1_RES_TX; - LPC_EMAC->IntClear = EMAC_INT_TX_UNDERRUN; - - /* De-allocate all queued TX pbufs */ - for (idx = 0; idx < LPC_NUM_BUFF_TXDESCS; idx++) { - if (lpc_enetif->txb[idx] != NULL) { - pbuf_free(lpc_enetif->txb[idx]); - lpc_enetif->txb[idx] = NULL; - } - } - -#if NO_SYS == 0 - /* Restore access */ - sys_mutex_unlock(&lpc_enetif->TXLockMutex); -#endif - /* Start TX side again */ - lpc_tx_setup(lpc_enetif); - } else { - /* Free TX buffers that are done sending */ - lpc_tx_reclaim(lpc_enetdata.netif); - } - } -} -#endif - -/** \brief Low level init of the MAC and PHY. - * - * \param[in] netif Pointer to LWIP netif structure - */ -static err_t low_level_init(struct netif *netif) -{ - struct lpc_enetdata *lpc_enetif = netif->state; - err_t err = ERR_OK; - - /* Enable MII clocking */ - LPC_SC->PCONP |= CLKPWR_PCONP_PCENET; - -#if defined(TARGET_LPC1768) - LPC_PINCON->PINSEL2 = 0x50150105; /* Enable P1 Ethernet Pins. */ - LPC_PINCON->PINSEL3 = (LPC_PINCON->PINSEL3 & ~0x0000000F) | 0x00000005; -#elif defined(TARGET_LPC4088) || defined(TARGET_LPC4088_DM) - LPC_IOCON->P1_0 &= ~0x07; /* ENET I/O config */ - LPC_IOCON->P1_0 |= 0x01; /* ENET_TXD0 */ - LPC_IOCON->P1_1 &= ~0x07; - LPC_IOCON->P1_1 |= 0x01; /* ENET_TXD1 */ - LPC_IOCON->P1_4 &= ~0x07; - LPC_IOCON->P1_4 |= 0x01; /* ENET_TXEN */ - LPC_IOCON->P1_8 &= ~0x07; - LPC_IOCON->P1_8 |= 0x01; /* ENET_CRS */ - LPC_IOCON->P1_9 &= ~0x07; - LPC_IOCON->P1_9 |= 0x01; /* ENET_RXD0 */ - LPC_IOCON->P1_10 &= ~0x07; - LPC_IOCON->P1_10 |= 0x01; /* ENET_RXD1 */ - LPC_IOCON->P1_14 &= ~0x07; - LPC_IOCON->P1_14 |= 0x01; /* ENET_RX_ER */ - LPC_IOCON->P1_15 &= ~0x07; - LPC_IOCON->P1_15 |= 0x01; /* ENET_REF_CLK */ - LPC_IOCON->P1_16 &= ~0x07; /* ENET/PHY I/O config */ - LPC_IOCON->P1_16 |= 0x01; /* ENET_MDC */ - LPC_IOCON->P1_17 &= ~0x07; - LPC_IOCON->P1_17 |= 0x01; /* ENET_MDIO */ -#endif - - /* Reset all MAC logic */ - LPC_EMAC->MAC1 = EMAC_MAC1_RES_TX | EMAC_MAC1_RES_MCS_TX | - EMAC_MAC1_RES_RX | EMAC_MAC1_RES_MCS_RX | EMAC_MAC1_SIM_RES | - EMAC_MAC1_SOFT_RES; - LPC_EMAC->Command = EMAC_CR_REG_RES | EMAC_CR_TX_RES | EMAC_CR_RX_RES | - EMAC_CR_PASS_RUNT_FRM; - osDelay(10); - - /* Initial MAC initialization */ - LPC_EMAC->MAC1 = EMAC_MAC1_PASS_ALL; - LPC_EMAC->MAC2 = EMAC_MAC2_CRC_EN | EMAC_MAC2_PAD_EN | - EMAC_MAC2_VLAN_PAD_EN; - LPC_EMAC->MAXF = EMAC_ETH_MAX_FLEN; - - /* Set RMII management clock rate to lowest speed */ - LPC_EMAC->MCFG = EMAC_MCFG_CLK_SEL(11) | EMAC_MCFG_RES_MII; - LPC_EMAC->MCFG &= ~EMAC_MCFG_RES_MII; - - /* Maximum number of retries, 0x37 collision window, gap */ - LPC_EMAC->CLRT = EMAC_CLRT_DEF; - LPC_EMAC->IPGR = EMAC_IPGR_P1_DEF | EMAC_IPGR_P2_DEF; - -#if LPC_EMAC_RMII - /* RMII setup */ - LPC_EMAC->Command = EMAC_CR_PASS_RUNT_FRM | EMAC_CR_RMII; -#else - /* MII setup */ - LPC_EMAC->CR = EMAC_CR_PASS_RUNT_FRM; -#endif - - /* Initialize the PHY and reset */ - err = lpc_phy_init(netif, LPC_EMAC_RMII); - if (err != ERR_OK) - return err; - - /* Save station address */ - LPC_EMAC->SA2 = (u32_t) netif->hwaddr[0] | - (((u32_t) netif->hwaddr[1]) << 8); - LPC_EMAC->SA1 = (u32_t) netif->hwaddr[2] | - (((u32_t) netif->hwaddr[3]) << 8); - LPC_EMAC->SA0 = (u32_t) netif->hwaddr[4] | - (((u32_t) netif->hwaddr[5]) << 8); - - /* Setup transmit and receive descriptors */ - if (lpc_tx_setup(lpc_enetif) != ERR_OK) - return ERR_BUF; - if (lpc_rx_setup(lpc_enetif) != ERR_OK) - return ERR_BUF; - - /* Enable packet reception */ -#if IP_SOF_BROADCAST_RECV - LPC_EMAC->RxFilterCtrl = EMAC_RFC_PERFECT_EN | EMAC_RFC_BCAST_EN | EMAC_RFC_MCAST_EN; -#else - LPC_EMAC->RxFilterCtrl = EMAC_RFC_PERFECT_EN; -#endif - - /* Clear and enable rx/tx interrupts */ - LPC_EMAC->IntClear = 0xFFFF; - LPC_EMAC->IntEnable = RXINTGROUP | TXINTGROUP; - - /* Enable RX and TX */ - LPC_EMAC->Command |= EMAC_CR_RX_EN | EMAC_CR_TX_EN; - LPC_EMAC->MAC1 |= EMAC_MAC1_REC_EN; - - return err; -} - -/* This function provides a method for the PHY to setup the EMAC - for the PHY negotiated duplex mode */ -void lpc_emac_set_duplex(int full_duplex) -{ - if (full_duplex) { - LPC_EMAC->MAC2 |= EMAC_MAC2_FULL_DUP; - LPC_EMAC->Command |= EMAC_CR_FULL_DUP; - LPC_EMAC->IPGT = EMAC_IPGT_FULL_DUP; - } else { - LPC_EMAC->MAC2 &= ~EMAC_MAC2_FULL_DUP; - LPC_EMAC->Command &= ~EMAC_CR_FULL_DUP; - LPC_EMAC->IPGT = EMAC_IPGT_HALF_DUP; - } -} - -/* This function provides a method for the PHY to setup the EMAC - for the PHY negotiated bit rate */ -void lpc_emac_set_speed(int mbs_100) -{ - if (mbs_100) - LPC_EMAC->SUPP = EMAC_SUPP_SPEED; - else - LPC_EMAC->SUPP = 0; -} - -/** - * This function is the ethernet packet send function. It calls - * etharp_output after checking link status. - * - * \param[in] netif the lwip network interface structure for this lpc_enetif - * \param[in] q Pointer to pbug to send - * \param[in] ipaddr IP address - * \return ERR_OK or error code - */ -err_t lpc_etharp_output(struct netif *netif, struct pbuf *q, - ip_addr_t *ipaddr) -{ - /* Only send packet is link is up */ - if (netif->flags & NETIF_FLAG_LINK_UP) - return etharp_output(netif, q, ipaddr); - - return ERR_CONN; -} - -#if NO_SYS == 0 -/* periodic PHY status update */ -void phy_update(void const *nif) { - lpc_phy_sts_sm((struct netif*)nif); -} -osTimerDef(phy_update, phy_update); -#endif - -/** - * Should be called at the beginning of the program to set up the - * network interface. - * - * This function should be passed as a parameter to netif_add(). - * - * @param[in] netif the lwip network interface structure for this lpc_enetif - * @return ERR_OK if the loopif is initialized - * ERR_MEM if private data couldn't be allocated - * any other err_t on error - */ -err_t eth_arch_enetif_init(struct netif *netif) -{ - err_t err; - - LWIP_ASSERT("netif != NULL", (netif != NULL)); - - lpc_enetdata.netif = netif; - - /* set MAC hardware address */ -#if (MBED_MAC_ADDRESS_SUM != MBED_MAC_ADDR_INTERFACE) - netif->hwaddr[0] = MBED_MAC_ADDR_0; - netif->hwaddr[1] = MBED_MAC_ADDR_1; - netif->hwaddr[2] = MBED_MAC_ADDR_2; - netif->hwaddr[3] = MBED_MAC_ADDR_3; - netif->hwaddr[4] = MBED_MAC_ADDR_4; - netif->hwaddr[5] = MBED_MAC_ADDR_5; -#else - mbed_mac_address((char *)netif->hwaddr); -#endif - netif->hwaddr_len = ETHARP_HWADDR_LEN; - - /* maximum transfer unit */ - netif->mtu = 1500; - - /* device capabilities */ - netif->flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP | NETIF_FLAG_ETHERNET | NETIF_FLAG_IGMP; - - /* Initialize the hardware */ - netif->state = &lpc_enetdata; - err = low_level_init(netif); - if (err != ERR_OK) - return err; - -#if LWIP_NETIF_HOSTNAME - /* Initialize interface hostname */ - netif->hostname = "lwiplpc"; -#endif /* LWIP_NETIF_HOSTNAME */ - - netif->name[0] = 'e'; - netif->name[1] = 'n'; - - netif->output = lpc_etharp_output; - netif->linkoutput = lpc_low_level_output; - - /* CMSIS-RTOS, start tasks */ -#if NO_SYS == 0 -#ifdef CMSIS_OS_RTX - memset(lpc_enetdata.xTXDCountSem.data, 0, sizeof(lpc_enetdata.xTXDCountSem.data)); - lpc_enetdata.xTXDCountSem.def.semaphore = lpc_enetdata.xTXDCountSem.data; -#endif - lpc_enetdata.xTXDCountSem.id = osSemaphoreCreate(&lpc_enetdata.xTXDCountSem.def, LPC_NUM_BUFF_TXDESCS); - LWIP_ASSERT("xTXDCountSem creation error", (lpc_enetdata.xTXDCountSem.id != NULL)); - - err = sys_mutex_new(&lpc_enetdata.TXLockMutex); - LWIP_ASSERT("TXLockMutex creation error", (err == ERR_OK)); - - /* Packet receive task */ - lpc_enetdata.RxThread = sys_thread_new("receive_thread", packet_rx, netif->state, DEFAULT_THREAD_STACKSIZE, RX_PRIORITY); - LWIP_ASSERT("RxThread creation error", (lpc_enetdata.RxThread)); - - /* Transmit cleanup task */ - err = sys_sem_new(&lpc_enetdata.TxCleanSem, 0); - LWIP_ASSERT("TxCleanSem creation error", (err == ERR_OK)); - sys_thread_new("txclean_thread", packet_tx, netif->state, DEFAULT_THREAD_STACKSIZE, TX_PRIORITY); - - /* periodic PHY status update */ - osTimerId phy_timer = osTimerCreate(osTimer(phy_update), osTimerPeriodic, (void *)netif); - osTimerStart(phy_timer, 250); -#endif - - return ERR_OK; -} - -void eth_arch_enable_interrupts(void) { - NVIC_SetPriority(ENET_IRQn, ((0x01 << 3) | 0x01)); - NVIC_EnableIRQ(ENET_IRQn); -} - -void eth_arch_disable_interrupts(void) { - NVIC_DisableIRQ(ENET_IRQn); -} - -/** - * @} - */ - -/* --------------------------------- End Of File ------------------------------ */
--- a/arch/TARGET_NXP/lpc17xx_emac.h Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,661 +0,0 @@ -/********************************************************************** -* $Id$ lpc17xx_emac.h 2010-05-21 -*//** -* @file lpc17xx_emac.h -* @brief Contains all macro definitions and function prototypes -* support for Ethernet MAC firmware library on LPC17xx -* @version 2.0 -* @date 21. May. 2010 -* @author NXP MCU SW Application Team -* -* Copyright(C) 2010, NXP Semiconductor -* All rights reserved. -* -*********************************************************************** -* Software that is described herein is for illustrative purposes only -* which provides customers with programming information regarding the -* products. This software is supplied "AS IS" without any warranties. -* NXP Semiconductors assumes no responsibility or liability for the -* use of the software, conveys no license or title under any patent, -* copyright, or mask work right to the product. NXP Semiconductors -* reserves the right to make changes in the software without -* notification. NXP Semiconductors also make no representation or -* warranty that such application will be suitable for the specified -* use without further testing or modification. -**********************************************************************/ - -/* Peripheral group ----------------------------------------------------------- */ -/** @defgroup EMAC EMAC (Ethernet Media Access Controller) - * @ingroup LPC1700CMSIS_FwLib_Drivers - * @{ - */ - -#ifndef LPC17XX_EMAC_H_ -#define LPC17XX_EMAC_H_ - -/* Includes ------------------------------------------------------------------- */ -#include "cmsis.h" - -#ifdef __cplusplus -extern "C" -{ -#endif - -#define MCB_LPC_1768 -//#define IAR_LPC_1768 - -/* Public Macros -------------------------------------------------------------- */ -/** @defgroup EMAC_Public_Macros EMAC Public Macros - * @{ - */ - - -/* EMAC PHY status type definitions */ -#define EMAC_PHY_STAT_LINK (0) /**< Link Status */ -#define EMAC_PHY_STAT_SPEED (1) /**< Speed Status */ -#define EMAC_PHY_STAT_DUP (2) /**< Duplex Status */ - -/* EMAC PHY device Speed definitions */ -#define EMAC_MODE_AUTO (0) /**< Auto-negotiation mode */ -#define EMAC_MODE_10M_FULL (1) /**< 10Mbps FullDuplex mode */ -#define EMAC_MODE_10M_HALF (2) /**< 10Mbps HalfDuplex mode */ -#define EMAC_MODE_100M_FULL (3) /**< 100Mbps FullDuplex mode */ -#define EMAC_MODE_100M_HALF (4) /**< 100Mbps HalfDuplex mode */ - -/** - * @} - */ -/* Private Macros ------------------------------------------------------------- */ -/** @defgroup EMAC_Private_Macros EMAC Private Macros - * @{ - */ - - -/* EMAC Memory Buffer configuration for 16K Ethernet RAM */ -#define EMAC_NUM_RX_FRAG 4 /**< Num.of RX Fragments 4*1536= 6.0kB */ -#define EMAC_NUM_TX_FRAG 3 /**< Num.of TX Fragments 3*1536= 4.6kB */ -#define EMAC_ETH_MAX_FLEN 1536 /**< Max. Ethernet Frame Size */ -#define EMAC_TX_FRAME_TOUT 0x00100000 /**< Frame Transmit timeout count */ - -/* --------------------- BIT DEFINITIONS -------------------------------------- */ -/*********************************************************************//** - * Macro defines for MAC Configuration Register 1 - **********************************************************************/ -#define EMAC_MAC1_REC_EN 0x00000001 /**< Receive Enable */ -#define EMAC_MAC1_PASS_ALL 0x00000002 /**< Pass All Receive Frames */ -#define EMAC_MAC1_RX_FLOWC 0x00000004 /**< RX Flow Control */ -#define EMAC_MAC1_TX_FLOWC 0x00000008 /**< TX Flow Control */ -#define EMAC_MAC1_LOOPB 0x00000010 /**< Loop Back Mode */ -#define EMAC_MAC1_RES_TX 0x00000100 /**< Reset TX Logic */ -#define EMAC_MAC1_RES_MCS_TX 0x00000200 /**< Reset MAC TX Control Sublayer */ -#define EMAC_MAC1_RES_RX 0x00000400 /**< Reset RX Logic */ -#define EMAC_MAC1_RES_MCS_RX 0x00000800 /**< Reset MAC RX Control Sublayer */ -#define EMAC_MAC1_SIM_RES 0x00004000 /**< Simulation Reset */ -#define EMAC_MAC1_SOFT_RES 0x00008000 /**< Soft Reset MAC */ - -/*********************************************************************//** - * Macro defines for MAC Configuration Register 2 - **********************************************************************/ -#define EMAC_MAC2_FULL_DUP 0x00000001 /**< Full-Duplex Mode */ -#define EMAC_MAC2_FRM_LEN_CHK 0x00000002 /**< Frame Length Checking */ -#define EMAC_MAC2_HUGE_FRM_EN 0x00000004 /**< Huge Frame Enable */ -#define EMAC_MAC2_DLY_CRC 0x00000008 /**< Delayed CRC Mode */ -#define EMAC_MAC2_CRC_EN 0x00000010 /**< Append CRC to every Frame */ -#define EMAC_MAC2_PAD_EN 0x00000020 /**< Pad all Short Frames */ -#define EMAC_MAC2_VLAN_PAD_EN 0x00000040 /**< VLAN Pad Enable */ -#define EMAC_MAC2_ADET_PAD_EN 0x00000080 /**< Auto Detect Pad Enable */ -#define EMAC_MAC2_PPREAM_ENF 0x00000100 /**< Pure Preamble Enforcement */ -#define EMAC_MAC2_LPREAM_ENF 0x00000200 /**< Long Preamble Enforcement */ -#define EMAC_MAC2_NO_BACKOFF 0x00001000 /**< No Backoff Algorithm */ -#define EMAC_MAC2_BACK_PRESSURE 0x00002000 /**< Backoff Presurre / No Backoff */ -#define EMAC_MAC2_EXCESS_DEF 0x00004000 /**< Excess Defer */ - -/*********************************************************************//** - * Macro defines for Back-to-Back Inter-Packet-Gap Register - **********************************************************************/ -/** Programmable field representing the nibble time offset of the minimum possible period - * between the end of any transmitted packet to the beginning of the next */ -#define EMAC_IPGT_BBIPG(n) (n&0x7F) -/** Recommended value for Full Duplex of Programmable field representing the nibble time - * offset of the minimum possible period between the end of any transmitted packet to the - * beginning of the next */ -#define EMAC_IPGT_FULL_DUP (EMAC_IPGT_BBIPG(0x15)) -/** Recommended value for Half Duplex of Programmable field representing the nibble time - * offset of the minimum possible period between the end of any transmitted packet to the - * beginning of the next */ -#define EMAC_IPGT_HALF_DUP (EMAC_IPGT_BBIPG(0x12)) - -/*********************************************************************//** - * Macro defines for Non Back-to-Back Inter-Packet-Gap Register - **********************************************************************/ -/** Programmable field representing the Non-Back-to-Back Inter-Packet-Gap */ -#define EMAC_IPGR_NBBIPG_P2(n) (n&0x7F) -/** Recommended value for Programmable field representing the Non-Back-to-Back Inter-Packet-Gap Part 1 */ -#define EMAC_IPGR_P2_DEF (EMAC_IPGR_NBBIPG_P2(0x12)) -/** Programmable field representing the optional carrierSense window referenced in - * IEEE 802.3/4.2.3.2.1 'Carrier Deference' */ -#define EMAC_IPGR_NBBIPG_P1(n) ((n&0x7F)<<8) -/** Recommended value for Programmable field representing the Non-Back-to-Back Inter-Packet-Gap Part 2 */ -#define EMAC_IPGR_P1_DEF EMAC_IPGR_NBBIPG_P1(0x0C) - -/*********************************************************************//** - * Macro defines for Collision Window/Retry Register - **********************************************************************/ -/** Programmable field specifying the number of retransmission attempts following a collision before - * aborting the packet due to excessive collisions */ -#define EMAC_CLRT_MAX_RETX(n) (n&0x0F) -/** Programmable field representing the slot time or collision window during which collisions occur - * in properly configured networks */ -#define EMAC_CLRT_COLL(n) ((n&0x3F)<<8) -/** Default value for Collision Window / Retry register */ -#define EMAC_CLRT_DEF ((EMAC_CLRT_MAX_RETX(0x0F))|(EMAC_CLRT_COLL(0x37))) - -/*********************************************************************//** - * Macro defines for Maximum Frame Register - **********************************************************************/ -/** Represents a maximum receive frame of 1536 octets */ -#define EMAC_MAXF_MAXFRMLEN(n) (n&0xFFFF) - -/*********************************************************************//** - * Macro defines for PHY Support Register - **********************************************************************/ -#define EMAC_SUPP_SPEED 0x00000100 /**< Reduced MII Logic Current Speed */ -#define EMAC_SUPP_RES_RMII 0x00000800 /**< Reset Reduced MII Logic */ - -/*********************************************************************//** - * Macro defines for Test Register - **********************************************************************/ -#define EMAC_TEST_SHCUT_PQUANTA 0x00000001 /**< Shortcut Pause Quanta */ -#define EMAC_TEST_TST_PAUSE 0x00000002 /**< Test Pause */ -#define EMAC_TEST_TST_BACKP 0x00000004 /**< Test Back Pressure */ - -/*********************************************************************//** - * Macro defines for MII Management Configuration Register - **********************************************************************/ -#define EMAC_MCFG_SCAN_INC 0x00000001 /**< Scan Increment PHY Address */ -#define EMAC_MCFG_SUPP_PREAM 0x00000002 /**< Suppress Preamble */ -#define EMAC_MCFG_CLK_SEL(n) ((n&0x0F)<<2) /**< Clock Select Field */ -#define EMAC_MCFG_RES_MII 0x00008000 /**< Reset MII Management Hardware */ -#define EMAC_MCFG_MII_MAXCLK 2500000UL /**< MII Clock max */ - -/*********************************************************************//** - * Macro defines for MII Management Command Register - **********************************************************************/ -#define EMAC_MCMD_READ 0x00000001 /**< MII Read */ -#define EMAC_MCMD_SCAN 0x00000002 /**< MII Scan continuously */ - -#define EMAC_MII_WR_TOUT 0x00050000 /**< MII Write timeout count */ -#define EMAC_MII_RD_TOUT 0x00050000 /**< MII Read timeout count */ - -/*********************************************************************//** - * Macro defines for MII Management Address Register - **********************************************************************/ -#define EMAC_MADR_REG_ADR(n) (n&0x1F) /**< MII Register Address field */ -#define EMAC_MADR_PHY_ADR(n) ((n&0x1F)<<8) /**< PHY Address Field */ - -/*********************************************************************//** - * Macro defines for MII Management Write Data Register - **********************************************************************/ -#define EMAC_MWTD_DATA(n) (n&0xFFFF) /**< Data field for MMI Management Write Data register */ - -/*********************************************************************//** - * Macro defines for MII Management Read Data Register - **********************************************************************/ -#define EMAC_MRDD_DATA(n) (n&0xFFFF) /**< Data field for MMI Management Read Data register */ - -/*********************************************************************//** - * Macro defines for MII Management Indicators Register - **********************************************************************/ -#define EMAC_MIND_BUSY 0x00000001 /**< MII is Busy */ -#define EMAC_MIND_SCAN 0x00000002 /**< MII Scanning in Progress */ -#define EMAC_MIND_NOT_VAL 0x00000004 /**< MII Read Data not valid */ -#define EMAC_MIND_MII_LINK_FAIL 0x00000008 /**< MII Link Failed */ - -/* Station Address 0 Register */ -/* Station Address 1 Register */ -/* Station Address 2 Register */ - - -/* Control register definitions --------------------------------------------------------------------------- */ -/*********************************************************************//** - * Macro defines for Command Register - **********************************************************************/ -#define EMAC_CR_RX_EN 0x00000001 /**< Enable Receive */ -#define EMAC_CR_TX_EN 0x00000002 /**< Enable Transmit */ -#define EMAC_CR_REG_RES 0x00000008 /**< Reset Host Registers */ -#define EMAC_CR_TX_RES 0x00000010 /**< Reset Transmit Datapath */ -#define EMAC_CR_RX_RES 0x00000020 /**< Reset Receive Datapath */ -#define EMAC_CR_PASS_RUNT_FRM 0x00000040 /**< Pass Runt Frames */ -#define EMAC_CR_PASS_RX_FILT 0x00000080 /**< Pass RX Filter */ -#define EMAC_CR_TX_FLOW_CTRL 0x00000100 /**< TX Flow Control */ -#define EMAC_CR_RMII 0x00000200 /**< Reduced MII Interface */ -#define EMAC_CR_FULL_DUP 0x00000400 /**< Full Duplex */ - -/*********************************************************************//** - * Macro defines for Status Register - **********************************************************************/ -#define EMAC_SR_RX_EN 0x00000001 /**< Enable Receive */ -#define EMAC_SR_TX_EN 0x00000002 /**< Enable Transmit */ - -/*********************************************************************//** - * Macro defines for Transmit Status Vector 0 Register - **********************************************************************/ -#define EMAC_TSV0_CRC_ERR 0x00000001 /**< CRC error */ -#define EMAC_TSV0_LEN_CHKERR 0x00000002 /**< Length Check Error */ -#define EMAC_TSV0_LEN_OUTRNG 0x00000004 /**< Length Out of Range */ -#define EMAC_TSV0_DONE 0x00000008 /**< Tramsmission Completed */ -#define EMAC_TSV0_MCAST 0x00000010 /**< Multicast Destination */ -#define EMAC_TSV0_BCAST 0x00000020 /**< Broadcast Destination */ -#define EMAC_TSV0_PKT_DEFER 0x00000040 /**< Packet Deferred */ -#define EMAC_TSV0_EXC_DEFER 0x00000080 /**< Excessive Packet Deferral */ -#define EMAC_TSV0_EXC_COLL 0x00000100 /**< Excessive Collision */ -#define EMAC_TSV0_LATE_COLL 0x00000200 /**< Late Collision Occured */ -#define EMAC_TSV0_GIANT 0x00000400 /**< Giant Frame */ -#define EMAC_TSV0_UNDERRUN 0x00000800 /**< Buffer Underrun */ -#define EMAC_TSV0_BYTES 0x0FFFF000 /**< Total Bytes Transferred */ -#define EMAC_TSV0_CTRL_FRAME 0x10000000 /**< Control Frame */ -#define EMAC_TSV0_PAUSE 0x20000000 /**< Pause Frame */ -#define EMAC_TSV0_BACK_PRESS 0x40000000 /**< Backpressure Method Applied */ -#define EMAC_TSV0_VLAN 0x80000000 /**< VLAN Frame */ - -/*********************************************************************//** - * Macro defines for Transmit Status Vector 1 Register - **********************************************************************/ -#define EMAC_TSV1_BYTE_CNT 0x0000FFFF /**< Transmit Byte Count */ -#define EMAC_TSV1_COLL_CNT 0x000F0000 /**< Transmit Collision Count */ - -/*********************************************************************//** - * Macro defines for Receive Status Vector Register - **********************************************************************/ -#define EMAC_RSV_BYTE_CNT 0x0000FFFF /**< Receive Byte Count */ -#define EMAC_RSV_PKT_IGNORED 0x00010000 /**< Packet Previously Ignored */ -#define EMAC_RSV_RXDV_SEEN 0x00020000 /**< RXDV Event Previously Seen */ -#define EMAC_RSV_CARR_SEEN 0x00040000 /**< Carrier Event Previously Seen */ -#define EMAC_RSV_REC_CODEV 0x00080000 /**< Receive Code Violation */ -#define EMAC_RSV_CRC_ERR 0x00100000 /**< CRC Error */ -#define EMAC_RSV_LEN_CHKERR 0x00200000 /**< Length Check Error */ -#define EMAC_RSV_LEN_OUTRNG 0x00400000 /**< Length Out of Range */ -#define EMAC_RSV_REC_OK 0x00800000 /**< Frame Received OK */ -#define EMAC_RSV_MCAST 0x01000000 /**< Multicast Frame */ -#define EMAC_RSV_BCAST 0x02000000 /**< Broadcast Frame */ -#define EMAC_RSV_DRIB_NIBB 0x04000000 /**< Dribble Nibble */ -#define EMAC_RSV_CTRL_FRAME 0x08000000 /**< Control Frame */ -#define EMAC_RSV_PAUSE 0x10000000 /**< Pause Frame */ -#define EMAC_RSV_UNSUPP_OPC 0x20000000 /**< Unsupported Opcode */ -#define EMAC_RSV_VLAN 0x40000000 /**< VLAN Frame */ - -/*********************************************************************//** - * Macro defines for Flow Control Counter Register - **********************************************************************/ -#define EMAC_FCC_MIRR_CNT(n) (n&0xFFFF) /**< Mirror Counter */ -#define EMAC_FCC_PAUSE_TIM(n) ((n&0xFFFF)<<16) /**< Pause Timer */ - -/*********************************************************************//** - * Macro defines for Flow Control Status Register - **********************************************************************/ -#define EMAC_FCS_MIRR_CNT(n) (n&0xFFFF) /**< Mirror Counter Current */ - - -/* Receive filter register definitions -------------------------------------------------------- */ -/*********************************************************************//** - * Macro defines for Receive Filter Control Register - **********************************************************************/ -#define EMAC_RFC_UCAST_EN 0x00000001 /**< Accept Unicast Frames Enable */ -#define EMAC_RFC_BCAST_EN 0x00000002 /**< Accept Broadcast Frames Enable */ -#define EMAC_RFC_MCAST_EN 0x00000004 /**< Accept Multicast Frames Enable */ -#define EMAC_RFC_UCAST_HASH_EN 0x00000008 /**< Accept Unicast Hash Filter Frames */ -#define EMAC_RFC_MCAST_HASH_EN 0x00000010 /**< Accept Multicast Hash Filter Fram.*/ -#define EMAC_RFC_PERFECT_EN 0x00000020 /**< Accept Perfect Match Enable */ -#define EMAC_RFC_MAGP_WOL_EN 0x00001000 /**< Magic Packet Filter WoL Enable */ -#define EMAC_RFC_PFILT_WOL_EN 0x00002000 /**< Perfect Filter WoL Enable */ - -/*********************************************************************//** - * Macro defines for Receive Filter WoL Status/Clear Registers - **********************************************************************/ -#define EMAC_WOL_UCAST 0x00000001 /**< Unicast Frame caused WoL */ -#define EMAC_WOL_BCAST 0x00000002 /**< Broadcast Frame caused WoL */ -#define EMAC_WOL_MCAST 0x00000004 /**< Multicast Frame caused WoL */ -#define EMAC_WOL_UCAST_HASH 0x00000008 /**< Unicast Hash Filter Frame WoL */ -#define EMAC_WOL_MCAST_HASH 0x00000010 /**< Multicast Hash Filter Frame WoL */ -#define EMAC_WOL_PERFECT 0x00000020 /**< Perfect Filter WoL */ -#define EMAC_WOL_RX_FILTER 0x00000080 /**< RX Filter caused WoL */ -#define EMAC_WOL_MAG_PACKET 0x00000100 /**< Magic Packet Filter caused WoL */ -#define EMAC_WOL_BITMASK 0x01BF /**< Receive Filter WoL Status/Clear bitmasl value */ - - -/* Module control register definitions ---------------------------------------------------- */ -/*********************************************************************//** - * Macro defines for Interrupt Status/Enable/Clear/Set Registers - **********************************************************************/ -#define EMAC_INT_RX_OVERRUN 0x00000001 /**< Overrun Error in RX Queue */ -#define EMAC_INT_RX_ERR 0x00000002 /**< Receive Error */ -#define EMAC_INT_RX_FIN 0x00000004 /**< RX Finished Process Descriptors */ -#define EMAC_INT_RX_DONE 0x00000008 /**< Receive Done */ -#define EMAC_INT_TX_UNDERRUN 0x00000010 /**< Transmit Underrun */ -#define EMAC_INT_TX_ERR 0x00000020 /**< Transmit Error */ -#define EMAC_INT_TX_FIN 0x00000040 /**< TX Finished Process Descriptors */ -#define EMAC_INT_TX_DONE 0x00000080 /**< Transmit Done */ -#define EMAC_INT_SOFT_INT 0x00001000 /**< Software Triggered Interrupt */ -#define EMAC_INT_WAKEUP 0x00002000 /**< Wakeup Event Interrupt */ - -/*********************************************************************//** - * Macro defines for Power Down Register - **********************************************************************/ -#define EMAC_PD_POWER_DOWN 0x80000000 /**< Power Down MAC */ - -/* Descriptor and status formats ---------------------------------------------------- */ -/*********************************************************************//** - * Macro defines for RX Descriptor Control Word - **********************************************************************/ -#define EMAC_RCTRL_SIZE(n) (n&0x7FF) /**< Buffer size field */ -#define EMAC_RCTRL_INT 0x80000000 /**< Generate RxDone Interrupt */ - -/*********************************************************************//** - * Macro defines for RX Status Hash CRC Word - **********************************************************************/ -#define EMAC_RHASH_SA 0x000001FF /**< Hash CRC for Source Address */ -#define EMAC_RHASH_DA 0x001FF000 /**< Hash CRC for Destination Address */ - -/*********************************************************************//** - * Macro defines for RX Status Information Word - **********************************************************************/ -#define EMAC_RINFO_SIZE 0x000007FF /**< Data size in bytes */ -#define EMAC_RINFO_CTRL_FRAME 0x00040000 /**< Control Frame */ -#define EMAC_RINFO_VLAN 0x00080000 /**< VLAN Frame */ -#define EMAC_RINFO_FAIL_FILT 0x00100000 /**< RX Filter Failed */ -#define EMAC_RINFO_MCAST 0x00200000 /**< Multicast Frame */ -#define EMAC_RINFO_BCAST 0x00400000 /**< Broadcast Frame */ -#define EMAC_RINFO_CRC_ERR 0x00800000 /**< CRC Error in Frame */ -#define EMAC_RINFO_SYM_ERR 0x01000000 /**< Symbol Error from PHY */ -#define EMAC_RINFO_LEN_ERR 0x02000000 /**< Length Error */ -#define EMAC_RINFO_RANGE_ERR 0x04000000 /**< Range Error (exceeded max. size) */ -#define EMAC_RINFO_ALIGN_ERR 0x08000000 /**< Alignment Error */ -#define EMAC_RINFO_OVERRUN 0x10000000 /**< Receive overrun */ -#define EMAC_RINFO_NO_DESCR 0x20000000 /**< No new Descriptor available */ -#define EMAC_RINFO_LAST_FLAG 0x40000000 /**< Last Fragment in Frame */ -#define EMAC_RINFO_ERR 0x80000000 /**< Error Occured (OR of all errors) */ -#define EMAC_RINFO_ERR_MASK (EMAC_RINFO_FAIL_FILT | EMAC_RINFO_CRC_ERR | EMAC_RINFO_SYM_ERR | \ -EMAC_RINFO_LEN_ERR | EMAC_RINFO_ALIGN_ERR | EMAC_RINFO_OVERRUN) - -/*********************************************************************//** - * Macro defines for TX Descriptor Control Word - **********************************************************************/ -#define EMAC_TCTRL_SIZE 0x000007FF /**< Size of data buffer in bytes */ -#define EMAC_TCTRL_OVERRIDE 0x04000000 /**< Override Default MAC Registers */ -#define EMAC_TCTRL_HUGE 0x08000000 /**< Enable Huge Frame */ -#define EMAC_TCTRL_PAD 0x10000000 /**< Pad short Frames to 64 bytes */ -#define EMAC_TCTRL_CRC 0x20000000 /**< Append a hardware CRC to Frame */ -#define EMAC_TCTRL_LAST 0x40000000 /**< Last Descriptor for TX Frame */ -#define EMAC_TCTRL_INT 0x80000000 /**< Generate TxDone Interrupt */ - -/*********************************************************************//** - * Macro defines for TX Status Information Word - **********************************************************************/ -#define EMAC_TINFO_COL_CNT 0x01E00000 /**< Collision Count */ -#define EMAC_TINFO_DEFER 0x02000000 /**< Packet Deferred (not an error) */ -#define EMAC_TINFO_EXCESS_DEF 0x04000000 /**< Excessive Deferral */ -#define EMAC_TINFO_EXCESS_COL 0x08000000 /**< Excessive Collision */ -#define EMAC_TINFO_LATE_COL 0x10000000 /**< Late Collision Occured */ -#define EMAC_TINFO_UNDERRUN 0x20000000 /**< Transmit Underrun */ -#define EMAC_TINFO_NO_DESCR 0x40000000 /**< No new Descriptor available */ -#define EMAC_TINFO_ERR 0x80000000 /**< Error Occured (OR of all errors) */ - -#ifdef MCB_LPC_1768 -/* DP83848C PHY definition ------------------------------------------------------------ */ - -/** PHY device reset time out definition */ -#define EMAC_PHY_RESP_TOUT 0x100000UL - -/* ENET Device Revision ID */ -#define EMAC_OLD_EMAC_MODULE_ID 0x39022000 /**< Rev. ID for first rev '-' */ - -/*********************************************************************//** - * Macro defines for DP83848C PHY Registers - **********************************************************************/ -#define EMAC_PHY_REG_BMCR 0x00 /**< Basic Mode Control Register */ -#define EMAC_PHY_REG_BMSR 0x01 /**< Basic Mode Status Register */ -#define EMAC_PHY_REG_IDR1 0x02 /**< PHY Identifier 1 */ -#define EMAC_PHY_REG_IDR2 0x03 /**< PHY Identifier 2 */ -#define EMAC_PHY_REG_ANAR 0x04 /**< Auto-Negotiation Advertisement */ -#define EMAC_PHY_REG_ANLPAR 0x05 /**< Auto-Neg. Link Partner Abitily */ -#define EMAC_PHY_REG_ANER 0x06 /**< Auto-Neg. Expansion Register */ -#define EMAC_PHY_REG_ANNPTR 0x07 /**< Auto-Neg. Next Page TX */ -#define EMAC_PHY_REG_LPNPA 0x08 - -/*********************************************************************//** - * Macro defines for PHY Extended Registers - **********************************************************************/ -#define EMAC_PHY_REG_STS 0x10 /**< Status Register */ -#define EMAC_PHY_REG_MICR 0x11 /**< MII Interrupt Control Register */ -#define EMAC_PHY_REG_MISR 0x12 /**< MII Interrupt Status Register */ -#define EMAC_PHY_REG_FCSCR 0x14 /**< False Carrier Sense Counter */ -#define EMAC_PHY_REG_RECR 0x15 /**< Receive Error Counter */ -#define EMAC_PHY_REG_PCSR 0x16 /**< PCS Sublayer Config. and Status */ -#define EMAC_PHY_REG_RBR 0x17 /**< RMII and Bypass Register */ -#define EMAC_PHY_REG_LEDCR 0x18 /**< LED Direct Control Register */ -#define EMAC_PHY_REG_PHYCR 0x19 /**< PHY Control Register */ -#define EMAC_PHY_REG_10BTSCR 0x1A /**< 10Base-T Status/Control Register */ -#define EMAC_PHY_REG_CDCTRL1 0x1B /**< CD Test Control and BIST Extens. */ -#define EMAC_PHY_REG_EDCR 0x1D /**< Energy Detect Control Register */ - -/*********************************************************************//** - * Macro defines for PHY Basic Mode Control Register - **********************************************************************/ -#define EMAC_PHY_BMCR_RESET (1<<15) /**< Reset bit */ -#define EMAC_PHY_BMCR_LOOPBACK (1<<14) /**< Loop back */ -#define EMAC_PHY_BMCR_SPEED_SEL (1<<13) /**< Speed selection */ -#define EMAC_PHY_BMCR_AN (1<<12) /**< Auto Negotiation */ -#define EMAC_PHY_BMCR_POWERDOWN (1<<11) /**< Power down mode */ -#define EMAC_PHY_BMCR_ISOLATE (1<<10) /**< Isolate */ -#define EMAC_PHY_BMCR_RE_AN (1<<9) /**< Restart auto negotiation */ -#define EMAC_PHY_BMCR_DUPLEX (1<<8) /**< Duplex mode */ - -/*********************************************************************//** - * Macro defines for PHY Basic Mode Status Status Register - **********************************************************************/ -#define EMAC_PHY_BMSR_100BE_T4 (1<<15) /**< 100 base T4 */ -#define EMAC_PHY_BMSR_100TX_FULL (1<<14) /**< 100 base full duplex */ -#define EMAC_PHY_BMSR_100TX_HALF (1<<13) /**< 100 base half duplex */ -#define EMAC_PHY_BMSR_10BE_FULL (1<<12) /**< 10 base T full duplex */ -#define EMAC_PHY_BMSR_10BE_HALF (1<<11) /**< 10 base T half duplex */ -#define EMAC_PHY_BMSR_NOPREAM (1<<6) /**< MF Preamable Supress */ -#define EMAC_PHY_BMSR_AUTO_DONE (1<<5) /**< Auto negotiation complete */ -#define EMAC_PHY_BMSR_REMOTE_FAULT (1<<4) /**< Remote fault */ -#define EMAC_PHY_BMSR_NO_AUTO (1<<3) /**< Auto Negotiation ability */ -#define EMAC_PHY_BMSR_LINK_ESTABLISHED (1<<2) /**< Link status */ - -/*********************************************************************//** - * Macro defines for PHY Status Register - **********************************************************************/ -#define EMAC_PHY_SR_REMOTE_FAULT (1<<6) /**< Remote Fault */ -#define EMAC_PHY_SR_JABBER (1<<5) /**< Jabber detect */ -#define EMAC_PHY_SR_AUTO_DONE (1<<4) /**< Auto Negotiation complete */ -#define EMAC_PHY_SR_LOOPBACK (1<<3) /**< Loop back status */ -#define EMAC_PHY_SR_DUP (1<<2) /**< Duplex status */ -#define EMAC_PHY_SR_SPEED (1<<1) /**< Speed status */ -#define EMAC_PHY_SR_LINK (1<<0) /**< Link Status */ - -#define EMAC_PHY_FULLD_100M 0x2100 /**< Full Duplex 100Mbit */ -#define EMAC_PHY_HALFD_100M 0x2000 /**< Half Duplex 100Mbit */ -#define EMAC_PHY_FULLD_10M 0x0100 /**< Full Duplex 10Mbit */ -#define EMAC_PHY_HALFD_10M 0x0000 /**< Half Duplex 10MBit */ -#define EMAC_PHY_AUTO_NEG 0x3000 /**< Select Auto Negotiation */ - -#define EMAC_DEF_ADR 0x0100 /**< Default PHY device address */ -#define EMAC_DP83848C_ID 0x20005C90 /**< PHY Identifier */ - -#define EMAC_PHY_SR_100_SPEED ((1<<14)|(1<<13)) -#define EMAC_PHY_SR_FULL_DUP ((1<<14)|(1<<12)) -#define EMAC_PHY_BMSR_LINK_STATUS (1<<2) /**< Link status */ - -#elif defined(IAR_LPC_1768) -/* KSZ8721BL PHY definition ------------------------------------------------------------ */ -/** PHY device reset time out definition */ -#define EMAC_PHY_RESP_TOUT 0x100000UL - -/* ENET Device Revision ID */ -#define EMAC_OLD_EMAC_MODULE_ID 0x39022000 /**< Rev. ID for first rev '-' */ - -/*********************************************************************//** - * Macro defines for KSZ8721BL PHY Registers - **********************************************************************/ -#define EMAC_PHY_REG_BMCR 0x00 /**< Basic Mode Control Register */ -#define EMAC_PHY_REG_BMSR 0x01 /**< Basic Mode Status Register */ -#define EMAC_PHY_REG_IDR1 0x02 /**< PHY Identifier 1 */ -#define EMAC_PHY_REG_IDR2 0x03 /**< PHY Identifier 2 */ -#define EMAC_PHY_REG_ANAR 0x04 /**< Auto-Negotiation Advertisement */ -#define EMAC_PHY_REG_ANLPAR 0x05 /**< Auto-Neg. Link Partner Abitily */ -#define EMAC_PHY_REG_ANER 0x06 /**< Auto-Neg. Expansion Register */ -#define EMAC_PHY_REG_ANNPTR 0x07 /**< Auto-Neg. Next Page TX */ -#define EMAC_PHY_REG_LPNPA 0x08 /**< Link Partner Next Page Ability */ -#define EMAC_PHY_REG_REC 0x15 /**< RXError Counter Register */ -#define EMAC_PHY_REG_ISC 0x1b /**< Interrupt Control/Status Register */ -#define EMAC_PHY_REG_100BASE 0x1f /**< 100BASE-TX PHY Control Register */ - -/*********************************************************************//** - * Macro defines for PHY Basic Mode Control Register - **********************************************************************/ -#define EMAC_PHY_BMCR_RESET (1<<15) /**< Reset bit */ -#define EMAC_PHY_BMCR_LOOPBACK (1<<14) /**< Loop back */ -#define EMAC_PHY_BMCR_SPEED_SEL (1<<13) /**< Speed selection */ -#define EMAC_PHY_BMCR_AN (1<<12) /**< Auto Negotiation */ -#define EMAC_PHY_BMCR_POWERDOWN (1<<11) /**< Power down mode */ -#define EMAC_PHY_BMCR_ISOLATE (1<<10) /**< Isolate */ -#define EMAC_PHY_BMCR_RE_AN (1<<9) /**< Restart auto negotiation */ -#define EMAC_PHY_BMCR_DUPLEX (1<<8) /**< Duplex mode */ -#define EMAC_PHY_BMCR_COLLISION (1<<7) /**< Collision test */ -#define EMAC_PHY_BMCR_TXDIS (1<<0) /**< Disable transmit */ - -/*********************************************************************//** - * Macro defines for PHY Basic Mode Status Register - **********************************************************************/ -#define EMAC_PHY_BMSR_100BE_T4 (1<<15) /**< 100 base T4 */ -#define EMAC_PHY_BMSR_100TX_FULL (1<<14) /**< 100 base full duplex */ -#define EMAC_PHY_BMSR_100TX_HALF (1<<13) /**< 100 base half duplex */ -#define EMAC_PHY_BMSR_10BE_FULL (1<<12) /**< 10 base T full duplex */ -#define EMAC_PHY_BMSR_10BE_HALF (1<<11) /**< 10 base T half duplex */ -#define EMAC_PHY_BMSR_NOPREAM (1<<6) /**< MF Preamable Supress */ -#define EMAC_PHY_BMSR_AUTO_DONE (1<<5) /**< Auto negotiation complete */ -#define EMAC_PHY_BMSR_REMOTE_FAULT (1<<4) /**< Remote fault */ -#define EMAC_PHY_BMSR_NO_AUTO (1<<3) /**< Auto Negotiation ability */ -#define EMAC_PHY_BMSR_LINK_STATUS (1<<2) /**< Link status */ -#define EMAC_PHY_BMSR_JABBER_DETECT (1<<1) /**< Jabber detect */ -#define EMAC_PHY_BMSR_EXTEND (1<<0) /**< Extended support */ - -/*********************************************************************//** - * Macro defines for PHY Identifier - **********************************************************************/ -/* PHY Identifier 1 bitmap definitions */ -#define EMAC_PHY_IDR1(n) (n & 0xFFFF) /**< PHY ID1 Number */ - -/* PHY Identifier 2 bitmap definitions */ -#define EMAC_PHY_IDR2(n) (n & 0xFFFF) /**< PHY ID2 Number */ - -/*********************************************************************//** - * Macro defines for Auto-Negotiation Advertisement - **********************************************************************/ -#define EMAC_PHY_AN_NEXTPAGE (1<<15) /**< Next page capable */ -#define EMAC_PHY_AN_REMOTE_FAULT (1<<13) /**< Remote Fault support */ -#define EMAC_PHY_AN_PAUSE (1<<10) /**< Pause support */ -#define EMAC_PHY_AN_100BASE_T4 (1<<9) /**< T4 capable */ -#define EMAC_PHY_AN_100BASE_TX_FD (1<<8) /**< TX with Full-duplex capable */ -#define EMAC_PHY_AN_100BASE_TX (1<<7) /**< TX capable */ -#define EMAC_PHY_AN_10BASE_T_FD (1<<6) /**< 10Mbps with full-duplex capable */ -#define EMAC_PHY_AN_10BASE_T (1<<5) /**< 10Mbps capable */ -#define EMAC_PHY_AN_FIELD(n) (n & 0x1F) /**< Selector Field */ - -#define EMAC_PHY_FULLD_100M 0x2100 /**< Full Duplex 100Mbit */ -#define EMAC_PHY_HALFD_100M 0x2000 /**< Half Duplex 100Mbit */ -#define EMAC_PHY_FULLD_10M 0x0100 /**< Full Duplex 10Mbit */ -#define EMAC_PHY_HALFD_10M 0x0000 /**< Half Duplex 10MBit */ -#define EMAC_PHY_AUTO_NEG 0x3000 /**< Select Auto Negotiation */ - -#define EMAC_PHY_SR_100_SPEED ((1<<14)|(1<<13)) -#define EMAC_PHY_SR_FULL_DUP ((1<<14)|(1<<12)) - -#define EMAC_DEF_ADR (0x01<<8) /**< Default PHY device address */ -#define EMAC_KSZ8721BL_ID ((0x22 << 16) | 0x1619 ) /**< PHY Identifier */ -#endif - -/** - * @} - */ - - -/* Public Types --------------------------------------------------------------- */ -/** @defgroup EMAC_Public_Types EMAC Public Types - * @{ - */ - -/* Descriptor and status formats ---------------------------------------------- */ - -/** - * @brief RX Descriptor structure type definition - */ -typedef struct { - uint32_t Packet; /**< Receive Packet Descriptor */ - uint32_t Ctrl; /**< Receive Control Descriptor */ -} RX_Desc; - -/** - * @brief RX Status structure type definition - */ -typedef struct { - uint32_t Info; /**< Receive Information Status */ - uint32_t HashCRC; /**< Receive Hash CRC Status */ -} RX_Stat; - -/** - * @brief TX Descriptor structure type definition - */ -typedef struct { - uint32_t Packet; /**< Transmit Packet Descriptor */ - uint32_t Ctrl; /**< Transmit Control Descriptor */ -} TX_Desc; - -/** - * @brief TX Status structure type definition - */ -typedef struct { - uint32_t Info; /**< Transmit Information Status */ -} TX_Stat; - - -/** - * @brief TX Data Buffer structure definition - */ -typedef struct { - uint32_t ulDataLen; /**< Data length */ - uint32_t *pbDataBuf; /**< A word-align data pointer to data buffer */ -} EMAC_PACKETBUF_Type; - -/** - * @brief EMAC configuration structure definition - */ -typedef struct { - uint32_t Mode; /**< Supported EMAC PHY device speed, should be one of the following: - - EMAC_MODE_AUTO - - EMAC_MODE_10M_FULL - - EMAC_MODE_10M_HALF - - EMAC_MODE_100M_FULL - - EMAC_MODE_100M_HALF - */ - uint8_t *pbEMAC_Addr; /**< Pointer to EMAC Station address that contains 6-bytes - of MAC address, it must be sorted in order (bEMAC_Addr[0]..[5]) - */ -} EMAC_CFG_Type; - -/** Ethernet block power/clock control bit*/ -#define CLKPWR_PCONP_PCENET ((uint32_t)(1<<30)) - -#ifdef __cplusplus -} -#endif - -#endif /* LPC17XX_EMAC_H_ */ - -/** - * @} - */ - -/* --------------------------------- End Of File ------------------------------ */
--- a/arch/TARGET_NXP/lpc_emac_config.h Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,111 +0,0 @@ -/********************************************************************** -* $Id$ lpc_emac_config.h 2011-11-20 -*//** -* @file lpc_emac_config.h -* @brief PHY and EMAC configuration file -* @version 1.0 -* @date 20 Nov. 2011 -* @author NXP MCU SW Application Team -* -* Copyright(C) 2011, NXP Semiconductor -* All rights reserved. -* -*********************************************************************** -* Software that is described herein is for illustrative purposes only -* which provides customers with programming information regarding the -* products. This software is supplied "AS IS" without any warranties. -* NXP Semiconductors assumes no responsibility or liability for the -* use of the software, conveys no license or title under any patent, -* copyright, or mask work right to the product. NXP Semiconductors -* reserves the right to make changes in the software without -* notification. NXP Semiconductors also make no representation or -* warranty that such application will be suitable for the specified -* use without further testing or modification. -**********************************************************************/ - -#ifndef __LPC_EMAC_CONFIG_H -#define __LPC_EMAC_CONFIG_H - -#include "lwip/opt.h" - -#ifdef __cplusplus -extern "C" -{ -#endif - -/** @defgroup lwip_phy_config LWIP PHY configuration - * @ingroup lwip_phy - * - * Configuration options for the PHY connected to the LPC EMAC. - * @{ - */ - -/** \brief The PHY address connected the to MII/RMII - */ -#define LPC_PHYDEF_PHYADDR 1 /**< The PHY address on the PHY device. */ - -/** \brief Enable autonegotiation mode. - * If this is enabled, the PHY will attempt to auto-negotiate the - * best link mode if the PHY supports it. If this is not enabled, - * the PHY_USE_FULL_DUPLEX and PHY_USE_100MBS defines will be - * used to select the link mode. Note that auto-negotiation may - * take a few seconds to complete. - */ -#define PHY_USE_AUTONEG 1 /**< Enables auto-negotiation mode. */ - -/** \brief Sets up the PHY interface to either full duplex operation or - * half duplex operation if PHY_USE_AUTONEG is not enabled. - */ -#define PHY_USE_FULL_DUPLEX 1 /**< Sets duplex mode to full. */ - -/** \brief Sets up the PHY interface to either 100MBS operation or 10MBS - * operation if PHY_USE_AUTONEG is not enabled. - */ -#define PHY_USE_100MBS 1 /**< Sets data rate to 100Mbps. */ - -/** - * @} - */ - -/** @defgroup lwip_emac_config LWIP EMAC configuration - * @ingroup lwip_emac - * - * Configuration options for the LPC EMAC. - * @{ - */ - -/** \brief Selects RMII or MII connection type in the EMAC peripheral - */ -#define LPC_EMAC_RMII 1 /**< Use the RMII or MII driver variant .*/ - -/** \brief Defines the number of descriptors used for RX. This - * must be a minimum value of 2. - */ -#define LPC_NUM_BUFF_RXDESCS 3 - -/** \brief Defines the number of descriptors used for TX. Must - * be a minimum value of 2. - */ -#define LPC_NUM_BUFF_TXDESCS (TCP_SND_QUEUELEN + 1) - -/** \brief Set this define to 1 to enable bounce buffers for transmit pbufs - * that cannot be sent via the zero-copy method. Some chained pbufs - * may have a payload address that links to an area of memory that - * cannot be used for transmit DMA operations. If this define is - * set to 1, an extra check will be made with the pbufs. If a buffer - * is determined to be non-usable for zero-copy, a temporary bounce - * buffer will be created and used instead. - */ -#define LPC_TX_PBUF_BOUNCE_EN 1 - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __LPC_EMAC_CONFIG_H */ - -/* --------------------------------- End Of File ------------------------------ */
--- a/arch/TARGET_NXP/lpc_phy.h Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,151 +0,0 @@ -/********************************************************************** -* $Id$ lpc_phy.h 2011-11-20 -*//** -* @file lpc_phy.h -* @brief Common PHY definitions used with all PHYs -* @version 1.0 -* @date 20 Nov. 2011 -* @author NXP MCU SW Application Team -* -* Copyright(C) 2011, NXP Semiconductor -* All rights reserved. -* -*********************************************************************** -* Software that is described herein is for illustrative purposes only -* which provides customers with programming information regarding the -* products. This software is supplied "AS IS" without any warranties. -* NXP Semiconductors assumes no responsibility or liability for the -* use of the software, conveys no license or title under any patent, -* copyright, or mask work right to the product. NXP Semiconductors -* reserves the right to make changes in the software without -* notification. NXP Semiconductors also make no representation or -* warranty that such application will be suitable for the specified -* use without further testing or modification. -**********************************************************************/ - -#ifndef __LPC_PHY_H_ -#define __LPC_PHY_H_ - -#include "lwip/opt.h" -#include "lwip/err.h" -#include "lwip/netif.h" - -#ifdef __cplusplus -extern "C" -{ -#endif - -/* These PHY functions are usually part of the EMAC driver */ - -/** \brief Phy status update state machine - * - * This function provides a state machine for maintaining the PHY - * status without blocking. It must be occasionally called for the - * PHY status to be maintained. - * - * \param[in] netif NETIF structure - */ -s32_t lpc_phy_sts_sm(struct netif *netif); - -/** \brief Initialize the PHY - * - * This function initializes the PHY. It will block until complete. - * This function is called as part of the EMAC driver - * initialization. Configuration of the PHY at startup is - * controlled by setting up configuration defines in lpc_phy.h. - * - * \param[in] netif NETIF structure - * \param[in] rmii If set, configures the PHY for RMII mode - * \return ERR_OK if the setup was successful, otherwise ERR_TIMEOUT - */ -err_t lpc_phy_init(struct netif *netif, int rmii); - -/** \brief Write a value via the MII link (non-blocking) - * - * This function will write a value on the MII link interface to a PHY - * or a connected device. The function will return immediately without - * a status. Status needs to be polled later to determine if the write - * was successful. - * - * \param[in] PhyReg PHY register to write to - * \param[in] Value Value to write - */ -void lpc_mii_write_noblock(u32_t PhyReg, u32_t Value); - -/** \brief Write a value via the MII link (blocking) - * - * This function will write a value on the MII link interface to a PHY - * or a connected device. The function will block until complete. - * - * \param[in] PhyReg PHY register to write to - * \param[in] Value Value to write - * \returns 0 if the write was successful, otherwise !0 - */ -err_t lpc_mii_write(u32_t PhyReg, u32_t Value); - -/** \brief Reads current MII link busy status - * - * This function will return the current MII link busy status and is meant to - * be used with non-blocking functions for monitor PHY status such as - * connection state. - * - * \returns !0 if the MII link is busy, otherwise 0 - */ -u32_t lpc_mii_is_busy(void); - -/** \brief Starts a read operation via the MII link (non-blocking) - * - * This function returns the current value in the MII data register. It is - * meant to be used with the non-blocking oeprations. This value should - * only be read after a non-block read command has been issued and the - * MII status has been determined to be good. - * - * \returns The current value in the MII value register - */ -u32_t lpc_mii_read_data(void); - -/** \brief Starts a read operation via the MII link (non-blocking) - * - * This function will start a read operation on the MII link interface - * from a PHY or a connected device. The function will not block and - * the status mist be polled until complete. Once complete, the data - * can be read. - * - * \param[in] PhyReg PHY register to read from - */ -err_t lpc_mii_read(u32_t PhyReg, u32_t *data); - -/** \brief Read a value via the MII link (blocking) - * - * This function will read a value on the MII link interface from a PHY - * or a connected device. The function will block until complete. - * - * \param[in] PhyReg PHY register to read from - * \param[in] data Pointer to where to save data read via MII - * \returns 0 if the read was successful, otherwise !0 - */ -void lpc_mii_read_noblock(u32_t PhyReg); - -/** - * This function provides a method for the PHY to setup the EMAC - * for the PHY negotiated duplex mode. - * - * @param[in] full_duplex 0 = half duplex, 1 = full duplex - */ -void lpc_emac_set_duplex(int full_duplex); - -/** - * This function provides a method for the PHY to setup the EMAC - * for the PHY negotiated bit rate. - * - * @param[in] mbs_100 0 = 10mbs mode, 1 = 100mbs mode - */ -void lpc_emac_set_speed(int mbs_100); - -#ifdef __cplusplus -} -#endif - -#endif /* __LPC_PHY_H_ */ - -/* --------------------------------- End Of File ------------------------------ */
--- a/arch/TARGET_NXP/lpc_phy_dp83848.c Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,438 +0,0 @@ -/********************************************************************** -* $Id$ lpc_phy_dp83848.c 2011-11-20 -*//** -* @file lpc_phy_dp83848.c -* @brief DP83848C PHY status and control. -* @version 1.0 -* @date 20 Nov. 2011 -* @author NXP MCU SW Application Team -* -* Copyright(C) 2011, NXP Semiconductor -* All rights reserved. -* -*********************************************************************** -* Software that is described herein is for illustrative purposes only -* which provides customers with programming information regarding the -* products. This software is supplied "AS IS" without any warranties. -* NXP Semiconductors assumes no responsibility or liability for the -* use of the software, conveys no license or title under any patent, -* copyright, or mask work right to the product. NXP Semiconductors -* reserves the right to make changes in the software without -* notification. NXP Semiconductors also make no representation or -* warranty that such application will be suitable for the specified -* use without further testing or modification. -**********************************************************************/ - -#include "lwip/opt.h" -#include "lwip/err.h" -#include "lwip/tcpip.h" -#include "lwip/snmp.h" -#include "lpc_emac_config.h" -#include "lpc_phy.h" -#include "lpc17xx_emac.h" - -/** @defgroup dp83848_phy PHY status and control for the DP83848. - * @ingroup lwip_phy - * - * Various functions for controlling and monitoring the status of the - * DP83848 PHY. In polled (standalone) systems, the PHY state must be - * monitored as part of the application. In a threaded (RTOS) system, - * the PHY state is monitored by the PHY handler thread. The MAC - * driver will not transmit unless the PHY link is active. - * @{ - */ - -/** \brief DP83848 PHY register offsets */ -#define DP8_BMCR_REG 0x0 /**< Basic Mode Control Register */ -#define DP8_BMSR_REG 0x1 /**< Basic Mode Status Reg */ -#define DP8_IDR1_REG 0x2 /**< Basic Mode Status Reg */ -#define DP8_IDR2_REG 0x3 /**< Basic Mode Status Reg */ -#define DP8_ANADV_REG 0x4 /**< Auto_Neg Advt Reg */ -#define DP8_ANLPA_REG 0x5 /**< Auto_neg Link Partner Ability Reg */ -#define DP8_ANEEXP_REG 0x6 /**< Auto-neg Expansion Reg */ -#define DP8_PHY_STAT_REG 0x10 /**< PHY Status Register */ -#define DP8_PHY_INT_CTL_REG 0x11 /**< PHY Interrupt Control Register */ -#define DP8_PHY_RBR_REG 0x17 /**< PHY RMII and Bypass Register */ -#define DP8_PHY_STS_REG 0x19 /**< PHY Status Register */ - -#define DP8_PHY_SCSR_REG 0x1f /**< PHY Special Control/Status Register (LAN8720) */ - -/** \brief DP83848 Control register definitions */ -#define DP8_RESET (1 << 15) /**< 1= S/W Reset */ -#define DP8_LOOPBACK (1 << 14) /**< 1=loopback Enabled */ -#define DP8_SPEED_SELECT (1 << 13) /**< 1=Select 100MBps */ -#define DP8_AUTONEG (1 << 12) /**< 1=Enable auto-negotiation */ -#define DP8_POWER_DOWN (1 << 11) /**< 1=Power down PHY */ -#define DP8_ISOLATE (1 << 10) /**< 1=Isolate PHY */ -#define DP8_RESTART_AUTONEG (1 << 9) /**< 1=Restart auto-negoatiation */ -#define DP8_DUPLEX_MODE (1 << 8) /**< 1=Full duplex mode */ -#define DP8_COLLISION_TEST (1 << 7) /**< 1=Perform collsion test */ - -/** \brief DP83848 Status register definitions */ -#define DP8_100BASE_T4 (1 << 15) /**< T4 mode */ -#define DP8_100BASE_TX_FD (1 << 14) /**< 100MBps full duplex */ -#define DP8_100BASE_TX_HD (1 << 13) /**< 100MBps half duplex */ -#define DP8_10BASE_T_FD (1 << 12) /**< 100Bps full duplex */ -#define DP8_10BASE_T_HD (1 << 11) /**< 10MBps half duplex */ -#define DP8_MF_PREAMB_SUPPR (1 << 6) /**< Preamble suppress */ -#define DP8_AUTONEG_COMP (1 << 5) /**< Auto-negotation complete */ -#define DP8_RMT_FAULT (1 << 4) /**< Fault */ -#define DP8_AUTONEG_ABILITY (1 << 3) /**< Auto-negotation supported */ -#define DP8_LINK_STATUS (1 << 2) /**< 1=Link active */ -#define DP8_JABBER_DETECT (1 << 1) /**< Jabber detect */ -#define DP8_EXTEND_CAPAB (1 << 0) /**< Supports extended capabilities */ - -/** \brief DP83848 PHY RBR MII dode definitions */ -#define DP8_RBR_RMII_MODE (1 << 5) /**< Use RMII mode */ - -/** \brief DP83848 PHY status definitions */ -#define DP8_REMOTEFAULT (1 << 6) /**< Remote fault */ -#define DP8_FULLDUPLEX (1 << 2) /**< 1=full duplex */ -#define DP8_SPEED10MBPS (1 << 1) /**< 1=10MBps speed */ -#define DP8_VALID_LINK (1 << 0) /**< 1=Link active */ - -/** \brief DP83848 PHY ID register definitions */ -#define DP8_PHYID1_OUI 0x2000 /**< Expected PHY ID1 */ -#define DP8_PHYID2_OUI 0x5c90 /**< Expected PHY ID2 */ - -/** \brief LAN8720 PHY Special Control/Status Register */ -#define PHY_SCSR_100MBIT 0x0008 /**< Speed: 1=100 MBit, 0=10Mbit */ -#define PHY_SCSR_DUPLEX 0x0010 /**< PHY Duplex Mask */ - -/** \brief Link status bits */ -#define LNK_STAT_VALID 0x01 -#define LNK_STAT_FULLDUPLEX 0x02 -#define LNK_STAT_SPEED10MPS 0x04 - -/** \brief PHY ID definitions */ -#define DP83848C_ID 0x20005C90 /**< PHY Identifier - DP83848C */ -#define LAN8720_ID 0x0007C0F0 /**< PHY Identifier - LAN8720 */ - -/** \brief PHY status structure used to indicate current status of PHY. - */ -typedef struct { - u32_t phy_speed_100mbs:1; /**< 10/100 MBS connection speed flag. */ - u32_t phy_full_duplex:1; /**< Half/full duplex connection speed flag. */ - u32_t phy_link_active:1; /**< Phy link active flag. */ -} PHY_STATUS_TYPE; - -/** \brief PHY update flags */ -static PHY_STATUS_TYPE physts; - -/** \brief Last PHY update flags, used for determing if something has changed */ -static PHY_STATUS_TYPE olddphysts; - -/** \brief PHY update counter for state machine */ -static s32_t phyustate; - -/** \brief Holds the PHY ID */ -static u32_t phy_id; - -/** \brief Temporary holder of link status for LAN7420 */ -static u32_t phy_lan7420_sts_tmp; - -/* Write a value via the MII link (non-blocking) */ -void lpc_mii_write_noblock(u32_t PhyReg, u32_t Value) -{ - /* Write value at PHY address and register */ - LPC_EMAC->MADR = (LPC_PHYDEF_PHYADDR << 8) | PhyReg; - LPC_EMAC->MWTD = Value; -} - -/* Write a value via the MII link (blocking) */ -err_t lpc_mii_write(u32_t PhyReg, u32_t Value) -{ - u32_t mst = 250; - err_t sts = ERR_OK; - - /* Write value at PHY address and register */ - lpc_mii_write_noblock(PhyReg, Value); - - /* Wait for unbusy status */ - while (mst > 0) { - sts = LPC_EMAC->MIND; - if ((sts & EMAC_MIND_BUSY) == 0) - mst = 0; - else { - mst--; - osDelay(1); - } - } - - if (sts != 0) - sts = ERR_TIMEOUT; - - return sts; -} - -/* Reads current MII link busy status */ -u32_t lpc_mii_is_busy(void) -{ - return (u32_t) (LPC_EMAC->MIND & EMAC_MIND_BUSY); -} - -/* Starts a read operation via the MII link (non-blocking) */ -u32_t lpc_mii_read_data(void) -{ - u32_t data = LPC_EMAC->MRDD; - LPC_EMAC->MCMD = 0; - - return data; -} - -/* Starts a read operation via the MII link (non-blocking) */ -void lpc_mii_read_noblock(u32_t PhyReg) -{ - /* Read value at PHY address and register */ - LPC_EMAC->MADR = (LPC_PHYDEF_PHYADDR << 8) | PhyReg; - LPC_EMAC->MCMD = EMAC_MCMD_READ; -} - -/* Read a value via the MII link (blocking) */ -err_t lpc_mii_read(u32_t PhyReg, u32_t *data) -{ - u32_t mst = 250; - err_t sts = ERR_OK; - - /* Read value at PHY address and register */ - lpc_mii_read_noblock(PhyReg); - - /* Wait for unbusy status */ - while (mst > 0) { - sts = LPC_EMAC->MIND & ~EMAC_MIND_MII_LINK_FAIL; - if ((sts & EMAC_MIND_BUSY) == 0) { - mst = 0; - *data = LPC_EMAC->MRDD; - } else { - mst--; - osDelay(1); - } - } - - LPC_EMAC->MCMD = 0; - - if (sts != 0) - sts = ERR_TIMEOUT; - - return sts; -} - - - -/** \brief Update PHY status from passed value - * - * This function updates the current PHY status based on the - * passed PHY status word. The PHY status indicate if the link - * is active, the connection speed, and duplex. - * - * \param[in] netif NETIF structure - * \param[in] linksts Status word from PHY - * \return 1 if the status has changed, otherwise 0 - */ -static s32_t lpc_update_phy_sts(struct netif *netif, u32_t linksts) -{ - s32_t changed = 0; - - /* Update link active status */ - if (linksts & LNK_STAT_VALID) - physts.phy_link_active = 1; - else - physts.phy_link_active = 0; - - /* Full or half duplex */ - if (linksts & LNK_STAT_FULLDUPLEX) - physts.phy_full_duplex = 1; - else - physts.phy_full_duplex = 0; - - /* Configure 100MBit/10MBit mode. */ - if (linksts & LNK_STAT_SPEED10MPS) - physts.phy_speed_100mbs = 0; - else - physts.phy_speed_100mbs = 1; - - if (physts.phy_speed_100mbs != olddphysts.phy_speed_100mbs) { - changed = 1; - if (physts.phy_speed_100mbs) { - /* 100MBit mode. */ - lpc_emac_set_speed(1); - - NETIF_INIT_SNMP(netif, snmp_ifType_ethernet_csmacd, 100000000); - } - else { - /* 10MBit mode. */ - lpc_emac_set_speed(0); - - NETIF_INIT_SNMP(netif, snmp_ifType_ethernet_csmacd, 10000000); - } - - olddphysts.phy_speed_100mbs = physts.phy_speed_100mbs; - } - - if (physts.phy_full_duplex != olddphysts.phy_full_duplex) { - changed = 1; - if (physts.phy_full_duplex) - lpc_emac_set_duplex(1); - else - lpc_emac_set_duplex(0); - - olddphysts.phy_full_duplex = physts.phy_full_duplex; - } - - if (physts.phy_link_active != olddphysts.phy_link_active) { - changed = 1; -#if NO_SYS == 1 - if (physts.phy_link_active) - netif_set_link_up(netif); - else - netif_set_link_down(netif); -#else - if (physts.phy_link_active) - tcpip_callback_with_block((tcpip_callback_fn) netif_set_link_up, - (void*) netif, 1); - else - tcpip_callback_with_block((tcpip_callback_fn) netif_set_link_down, - (void*) netif, 1); -#endif - - olddphysts.phy_link_active = physts.phy_link_active; - } - - return changed; -} - -/** \brief Initialize the DP83848 PHY. - * - * This function initializes the DP83848 PHY. It will block until - * complete. This function is called as part of the EMAC driver - * initialization. Configuration of the PHY at startup is - * controlled by setting up configuration defines in lpc_phy.h. - * - * \param[in] netif NETIF structure - * \param[in] rmii If set, configures the PHY for RMII mode - * \return ERR_OK if the setup was successful, otherwise ERR_TIMEOUT - */ -err_t lpc_phy_init(struct netif *netif, int rmii) -{ - u32_t tmp; - s32_t i; - - physts.phy_speed_100mbs = olddphysts.phy_speed_100mbs = 0; - physts.phy_full_duplex = olddphysts.phy_full_duplex = 0; - physts.phy_link_active = olddphysts.phy_link_active = 0; - phyustate = 0; - - /* Only first read and write are checked for failure */ - /* Put the DP83848C in reset mode and wait for completion */ - if (lpc_mii_write(DP8_BMCR_REG, DP8_RESET) != 0) - return ERR_TIMEOUT; - i = 400; - while (i > 0) { - osDelay(1); /* 1 ms */ - if (lpc_mii_read(DP8_BMCR_REG, &tmp) != 0) - return ERR_TIMEOUT; - - if (!(tmp & (DP8_RESET | DP8_POWER_DOWN))) - i = -1; - else - i--; - } - /* Timeout? */ - if (i == 0) - return ERR_TIMEOUT; - - // read PHY ID - lpc_mii_read(DP8_IDR1_REG, &tmp); - phy_id = (tmp << 16); - lpc_mii_read(DP8_IDR2_REG, &tmp); - phy_id |= (tmp & 0XFFF0); - - /* Setup link based on configuration options */ -#if PHY_USE_AUTONEG==1 - tmp = DP8_AUTONEG; -#else - tmp = 0; -#endif -#if PHY_USE_100MBS==1 - tmp |= DP8_SPEED_SELECT; -#endif -#if PHY_USE_FULL_DUPLEX==1 - tmp |= DP8_DUPLEX_MODE; -#endif - lpc_mii_write(DP8_BMCR_REG, tmp); - - /* Enable RMII mode for PHY */ - if (rmii) - lpc_mii_write(DP8_PHY_RBR_REG, DP8_RBR_RMII_MODE); - - /* The link is not set active at this point, but will be detected - later */ - - return ERR_OK; -} - -/* Phy status update state machine */ -s32_t lpc_phy_sts_sm(struct netif *netif) -{ - s32_t changed = 0; - u32_t data = 0; - u32_t tmp; - - switch (phyustate) { - default: - case 0: - if (phy_id == DP83848C_ID) { - lpc_mii_read_noblock(DP8_PHY_STAT_REG); - phyustate = 2; - } - else if (phy_id == LAN8720_ID) { - lpc_mii_read_noblock(DP8_PHY_SCSR_REG); - phyustate = 1; - } - break; - - case 1: - if (phy_id == LAN8720_ID) { - tmp = lpc_mii_read_data(); - // we get speed and duplex here. - phy_lan7420_sts_tmp = (tmp & PHY_SCSR_DUPLEX) ? LNK_STAT_FULLDUPLEX : 0; - phy_lan7420_sts_tmp |= (tmp & PHY_SCSR_100MBIT) ? 0 : LNK_STAT_SPEED10MPS; - - //read the status register to get link status - lpc_mii_read_noblock(DP8_BMSR_REG); - phyustate = 2; - } - break; - - case 2: - /* Wait for read status state */ - if (!lpc_mii_is_busy()) { - /* Update PHY status */ - tmp = lpc_mii_read_data(); - - if (phy_id == DP83848C_ID) { - // STS register contains all needed status bits - data = (tmp & DP8_VALID_LINK) ? LNK_STAT_VALID : 0; - data |= (tmp & DP8_FULLDUPLEX) ? LNK_STAT_FULLDUPLEX : 0; - data |= (tmp & DP8_SPEED10MBPS) ? LNK_STAT_SPEED10MPS : 0; - } - else if (phy_id == LAN8720_ID) { - // we only get the link status here. - phy_lan7420_sts_tmp |= (tmp & DP8_LINK_STATUS) ? LNK_STAT_VALID : 0; - data = phy_lan7420_sts_tmp; - } - - changed = lpc_update_phy_sts(netif, data); - phyustate = 0; - } - break; - } - - return changed; -} - -/** - * @} - */ - -/* --------------------------------- End Of File ------------------------------ */
--- a/arch/TARGET_NXP/lwipopts_conf.h Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,30 +0,0 @@ -/* Copyright (C) 2012 mbed.org, MIT License - * - * Permission is hereby granted, free of charge, to any person obtaining a copy of this software - * and associated documentation files (the "Software"), to deal in the Software without restriction, - * including without limitation the rights to use, copy, modify, merge, publish, distribute, - * sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in all copies or - * substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - * BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - * DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - */ - -#ifndef LWIPOPTS_CONF_H -#define LWIPOPTS_CONF_H - -#define LWIP_TRANSPORT_ETHERNET 1 - -#if defined(TARGET_LPC4088) || defined(TARGET_LPC4088_DM) -#define MEM_SIZE 15360 -#elif defined(TARGET_LPC1768) -#define MEM_SIZE 16362 -#endif - -#endif
--- a/arch/TARGET_RZ_A1H/lwipopts_conf.h Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,26 +0,0 @@ -/* Copyright (C) 2012 mbed.org, MIT License - * - * Permission is hereby granted, free of charge, to any person obtaining a copy of this software - * and associated documentation files (the "Software"), to deal in the Software without restriction, - * including without limitation the rights to use, copy, modify, merge, publish, distribute, - * sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in all copies or - * substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - * BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - * DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - */ - -#ifndef LWIPOPTS_CONF_H -#define LWIPOPTS_CONF_H - -#define LWIP_TRANSPORT_ETHERNET 1 - -#define MEM_SIZE (1600 * 16) - -#endif
--- a/arch/TARGET_RZ_A1H/rza1_emac.c Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,194 +0,0 @@ -#include "lwip/opt.h" -#include "lwip/tcpip.h" -#include "netif/etharp.h" -#include "mbed_interface.h" -#include "ethernet_api.h" -#include "ethernetext_api.h" - -#define RECV_TASK_PRI (osPriorityNormal) -#define PHY_TASK_PRI (osPriorityNormal) -#define PHY_TASK_WAIT (200) - -/* memory */ -static sys_sem_t recv_ready_sem; /* receive ready semaphore */ - -/* function */ -static void rza1_recv_task(void *arg); -static void rza1_phy_task(void *arg); -static err_t rza1_etharp_output(struct netif *netif, struct pbuf *q, ip_addr_t *ipaddr); -static err_t rza1_low_level_output(struct netif *netif, struct pbuf *p); -static void rza1_recv_callback(void); - -static void rza1_recv_task(void *arg) { - struct netif *netif = (struct netif*)arg; - struct eth_hdr *ethhdr; - u16_t recv_size; - struct pbuf *p; - int cnt; - - while (1) { - sys_arch_sem_wait(&recv_ready_sem, 0); - for (cnt = 0; cnt < 16; cnt++) { - recv_size = ethernet_receive(); - if (recv_size != 0) { - p = pbuf_alloc(PBUF_RAW, recv_size, PBUF_RAM); - if (p != NULL) { - (void)ethernet_read((char *)p->payload, p->len); - ethhdr = p->payload; - switch (htons(ethhdr->type)) { - case ETHTYPE_IP: - case ETHTYPE_ARP: -#if PPPOE_SUPPORT - case ETHTYPE_PPPOEDISC: - case ETHTYPE_PPPOE: -#endif /* PPPOE_SUPPORT */ - /* full packet send to tcpip_thread to process */ - if (netif->input(p, netif) != ERR_OK) { - /* Free buffer */ - pbuf_free(p); - } - break; - default: - /* Return buffer */ - pbuf_free(p); - break; - } - } - } else { - break; - } - } - } -} - -static void rza1_phy_task(void *arg) { - struct netif *netif = (struct netif*)arg; - s32_t connect_sts = 0; /* 0: disconnect, 1:connect */ - s32_t link_sts; - s32_t link_mode_new = NEGO_FAIL; - s32_t link_mode_old = NEGO_FAIL; - - while (1) { - link_sts = ethernet_link(); - if (link_sts == 1) { - link_mode_new = ethernetext_chk_link_mode(); - if (link_mode_new != link_mode_old) { - if (connect_sts == 1) { - tcpip_callback_with_block((tcpip_callback_fn)netif_set_link_down, (void*) netif, 1); - } - if (link_mode_new != NEGO_FAIL) { - ethernetext_set_link_mode(link_mode_new); - tcpip_callback_with_block((tcpip_callback_fn)netif_set_link_up, (void*) netif, 1); - connect_sts = 1; - } - } - } else { - if (connect_sts != 0) { - tcpip_callback_with_block((tcpip_callback_fn)netif_set_link_down, (void*) netif, 1); - link_mode_new = NEGO_FAIL; - connect_sts = 0; - } - } - link_mode_old = link_mode_new; - osDelay(PHY_TASK_WAIT); - } -} - -static err_t rza1_etharp_output(struct netif *netif, struct pbuf *q, ip_addr_t *ipaddr) { - /* Only send packet is link is up */ - if (netif->flags & NETIF_FLAG_LINK_UP) { - return etharp_output(netif, q, ipaddr); - } - - return ERR_CONN; -} - -static err_t rza1_low_level_output(struct netif *netif, struct pbuf *p) { - struct pbuf *q; - s32_t cnt; - err_t err = ERR_MEM; - s32_t write_size = 0; - - if ((p->payload != NULL) && (p->len != 0)) { - /* If the first data can't be written, transmit descriptor is full. */ - for (cnt = 0; cnt < 100; cnt++) { - write_size = ethernet_write((char *)p->payload, p->len); - if (write_size != 0) { - break; - } - osDelay(1); - } - if (write_size != 0) { - for (q = p->next; q != NULL; q = q->next) { - (void)ethernet_write((char *)q->payload, q->len); - } - if (ethernet_send() == 1) { - err = ERR_OK; - } - } - } - - return err; -} - -static void rza1_recv_callback(void) { - sys_sem_signal(&recv_ready_sem); -} - -err_t eth_arch_enetif_init(struct netif *netif) -{ - ethernet_cfg_t ethcfg; - - /* set MAC hardware address */ -#if (MBED_MAC_ADDRESS_SUM != MBED_MAC_ADDR_INTERFACE) - netif->hwaddr[0] = MBED_MAC_ADDR_0; - netif->hwaddr[1] = MBED_MAC_ADDR_1; - netif->hwaddr[2] = MBED_MAC_ADDR_2; - netif->hwaddr[3] = MBED_MAC_ADDR_3; - netif->hwaddr[4] = MBED_MAC_ADDR_4; - netif->hwaddr[5] = MBED_MAC_ADDR_5; -#else - mbed_mac_address((char *)netif->hwaddr); -#endif - netif->hwaddr_len = ETHARP_HWADDR_LEN; - - /* maximum transfer unit */ - netif->mtu = 1500; - - /* device capabilities */ - netif->flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP | NETIF_FLAG_ETHERNET | NETIF_FLAG_IGMP; - -#if LWIP_NETIF_HOSTNAME - /* Initialize interface hostname */ - netif->hostname = "lwiprza1"; -#endif /* LWIP_NETIF_HOSTNAME */ - - netif->name[0] = 'e'; - netif->name[1] = 'n'; - - netif->output = rza1_etharp_output; - netif->linkoutput = rza1_low_level_output; - - /* Initialize the hardware */ - ethcfg.int_priority = 6; - ethcfg.recv_cb = &rza1_recv_callback; - ethcfg.ether_mac = (char *)netif->hwaddr; - ethernetext_init(ðcfg); - - /* semaphore */ - sys_sem_new(&recv_ready_sem, 0); - - /* task */ - sys_thread_new("rza1_recv_task", rza1_recv_task, netif, DEFAULT_THREAD_STACKSIZE, RECV_TASK_PRI); - sys_thread_new("rza1_phy_task", rza1_phy_task, netif, DEFAULT_THREAD_STACKSIZE, PHY_TASK_PRI); - - return ERR_OK; -} - -void eth_arch_enable_interrupts(void) { - ethernetext_start_stop(1); -} - -void eth_arch_disable_interrupts(void) { - ethernetext_start_stop(0); -}
--- a/arch/TARGET_STM/lwipopts_conf.h Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,26 +0,0 @@ -/* Copyright (C) 2015 mbed.org, MIT License - * - * Permission is hereby granted, free of charge, to any person obtaining a copy of this software - * and associated documentation files (the "Software"), to deal in the Software without restriction, - * including without limitation the rights to use, copy, modify, merge, publish, distribute, - * sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in all copies or - * substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - * BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - * DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - */ - -#ifndef LWIPOPTS_CONF_H -#define LWIPOPTS_CONF_H - -#define LWIP_TRANSPORT_ETHERNET 1 - -#define MEM_SIZE (1600 * 16) - -#endif
--- a/arch/TARGET_STM/stm32f4_emac.c Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,560 +0,0 @@ - -#include "stm32f4xx_hal.h" -#include "lwip/opt.h" - -#include "lwip/timers.h" -#include "netif/etharp.h" -#include "lwip/tcpip.h" -#include <string.h> -#include "cmsis_os.h" -#include "mbed_interface.h" - -/** @defgroup lwipstm32f4xx_emac_DRIVER stm32f4 EMAC driver for LWIP - * @ingroup lwip_emac - * - * @{ - */ - -#define RECV_TASK_PRI (osPriorityHigh) -#define PHY_TASK_PRI (osPriorityLow) -#define PHY_TASK_WAIT (200) - - -#if defined (__ICCARM__) /*!< IAR Compiler */ - #pragma data_alignment=4 -#endif -__ALIGN_BEGIN ETH_DMADescTypeDef DMARxDscrTab[ETH_RXBUFNB] __ALIGN_END; /* Ethernet Rx MA Descriptor */ - -#if defined (__ICCARM__) /*!< IAR Compiler */ - #pragma data_alignment=4 -#endif -__ALIGN_BEGIN ETH_DMADescTypeDef DMATxDscrTab[ETH_TXBUFNB] __ALIGN_END; /* Ethernet Tx DMA Descriptor */ - -#if defined (__ICCARM__) /*!< IAR Compiler */ - #pragma data_alignment=4 -#endif -__ALIGN_BEGIN uint8_t Rx_Buff[ETH_RXBUFNB][ETH_RX_BUF_SIZE] __ALIGN_END; /* Ethernet Receive Buffer */ - -#if defined (__ICCARM__) /*!< IAR Compiler */ - #pragma data_alignment=4 -#endif -__ALIGN_BEGIN uint8_t Tx_Buff[ETH_TXBUFNB][ETH_TX_BUF_SIZE] __ALIGN_END; /* Ethernet Transmit Buffer */ - - -ETH_HandleTypeDef heth; - -static sys_sem_t rx_ready_sem; /* receive ready semaphore */ -static sys_mutex_t tx_lock_mutex; - -/* function */ -static void stm32f4_rx_task(void *arg); -static void stm32f4_phy_task(void *arg); -static err_t stm32f4_etharp_output(struct netif *netif, struct pbuf *q, ip_addr_t *ipaddr); -static err_t stm32f4_low_level_output(struct netif *netif, struct pbuf *p); - -/** - * Override HAL Eth Init function - */ -void HAL_ETH_MspInit(ETH_HandleTypeDef* heth) -{ - GPIO_InitTypeDef GPIO_InitStruct; - if (heth->Instance == ETH) { - /* Peripheral clock enable */ - __ETH_CLK_ENABLE(); - - __GPIOA_CLK_ENABLE(); - __GPIOB_CLK_ENABLE(); - __GPIOC_CLK_ENABLE(); - - /**ETH GPIO Configuration - PC1 ------> ETH_MDC - PA1 ------> ETH_REF_CLK - PA2 ------> ETH_MDIO - PA7 ------> ETH_CRS_DV - PC4 ------> ETH_RXD0 - PC5 ------> ETH_RXD1 - PB11 ------> ETH_TX_EN - PB12 ------> ETH_TXD0 - PB13 ------> ETH_TXD1 - */ - GPIO_InitStruct.Pin = GPIO_PIN_1 | GPIO_PIN_4 | GPIO_PIN_5; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF11_ETH; - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = GPIO_PIN_1 | GPIO_PIN_2 | GPIO_PIN_7; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF11_ETH; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF11_ETH; - HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); - - /* Peripheral interrupt init*/ - /* Sets the priority grouping field */ - HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); - HAL_NVIC_SetPriority(ETH_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(ETH_IRQn); - } -} - -/** - * Override HAL Eth DeInit function - */ -void HAL_ETH_MspDeInit(ETH_HandleTypeDef* heth) -{ - if (heth->Instance == ETH) { - /* Peripheral clock disable */ - __ETH_CLK_DISABLE(); - - /**ETH GPIO Configuration - PC1 ------> ETH_MDC - PA1 ------> ETH_REF_CLK - PA2 ------> ETH_MDIO - PA7 ------> ETH_CRS_DV - PC4 ------> ETH_RXD0 - PC5 ------> ETH_RXD1 - PB11 ------> ETH_TX_EN - PB12 ------> ETH_TXD0 - PB13 ------> ETH_TXD1 - */ - HAL_GPIO_DeInit(GPIOC, GPIO_PIN_1 | GPIO_PIN_4 | GPIO_PIN_5); - - HAL_GPIO_DeInit(GPIOA, GPIO_PIN_1 | GPIO_PIN_2 | GPIO_PIN_7); - - HAL_GPIO_DeInit(GPIOB, GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13); - - /* Peripheral interrupt Deinit*/ - HAL_NVIC_DisableIRQ(ETH_IRQn); - } -} - -/** - * Ethernet Rx Transfer completed callback - * - * @param heth: ETH handle - * @retval None - */ -void HAL_ETH_RxCpltCallback(ETH_HandleTypeDef *heth) -{ - - sys_sem_signal(&rx_ready_sem); -} - - -/** - * Ethernet IRQ Handler - * - * @param None - * @retval None - */ -void ETH_IRQHandler(void) -{ - HAL_ETH_IRQHandler(&heth); -} - - - -/** - * In this function, the hardware should be initialized. - * Called from eth_arch_enetif_init(). - * - * @param netif the already initialized lwip network interface structure - * for this ethernetif - */ -static void stm32f4_low_level_init(struct netif *netif) -{ - uint32_t regvalue = 0; - HAL_StatusTypeDef hal_eth_init_status; - - /* Init ETH */ - uint8_t MACAddr[6]; - heth.Instance = ETH; - heth.Init.AutoNegotiation = ETH_AUTONEGOTIATION_ENABLE; - heth.Init.Speed = ETH_SPEED_10M; - heth.Init.DuplexMode = ETH_MODE_FULLDUPLEX; - heth.Init.PhyAddress = 1; -#if (MBED_MAC_ADDRESS_SUM != MBED_MAC_ADDR_INTERFACE) - MACAddr[0] = MBED_MAC_ADDR_0; - MACAddr[1] = MBED_MAC_ADDR_1; - MACAddr[2] = MBED_MAC_ADDR_2; - MACAddr[3] = MBED_MAC_ADDR_3; - MACAddr[4] = MBED_MAC_ADDR_4; - MACAddr[5] = MBED_MAC_ADDR_5; -#else - mbed_mac_address((char *)MACAddr); -#endif - heth.Init.MACAddr = &MACAddr[0]; - heth.Init.RxMode = ETH_RXINTERRUPT_MODE; - heth.Init.ChecksumMode = ETH_CHECKSUM_BY_HARDWARE; - heth.Init.MediaInterface = ETH_MEDIA_INTERFACE_RMII; - hal_eth_init_status = HAL_ETH_Init(&heth); - - if (hal_eth_init_status == HAL_OK) { - /* Set netif link flag */ - netif->flags |= NETIF_FLAG_LINK_UP; - } - - /* Initialize Tx Descriptors list: Chain Mode */ - HAL_ETH_DMATxDescListInit(&heth, DMATxDscrTab, &Tx_Buff[0][0], ETH_TXBUFNB); - - /* Initialize Rx Descriptors list: Chain Mode */ - HAL_ETH_DMARxDescListInit(&heth, DMARxDscrTab, &Rx_Buff[0][0], ETH_RXBUFNB); - - #if LWIP_ARP || LWIP_ETHERNET - /* set MAC hardware address length */ - netif->hwaddr_len = ETHARP_HWADDR_LEN; - - /* set MAC hardware address */ - netif->hwaddr[0] = heth.Init.MACAddr[0]; - netif->hwaddr[1] = heth.Init.MACAddr[1]; - netif->hwaddr[2] = heth.Init.MACAddr[2]; - netif->hwaddr[3] = heth.Init.MACAddr[3]; - netif->hwaddr[4] = heth.Init.MACAddr[4]; - netif->hwaddr[5] = heth.Init.MACAddr[5]; - - /* maximum transfer unit */ - netif->mtu = 1500; - - /* device capabilities */ - /* don't set NETIF_FLAG_ETHARP if this device is not an ethernet one */ - netif->flags |= NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP; - - /* Enable MAC and DMA transmission and reception */ - HAL_ETH_Start(&heth); - - /**** Configure PHY to generate an interrupt when Eth Link state changes ****/ - /* Read Register Configuration */ - HAL_ETH_ReadPHYRegister(&heth, PHY_MICR, ®value); - - regvalue |= (PHY_MICR_INT_EN | PHY_MICR_INT_OE); - - /* Enable Interrupts */ - HAL_ETH_WritePHYRegister(&heth, PHY_MICR, regvalue); - - /* Read Register Configuration */ - HAL_ETH_ReadPHYRegister(&heth, PHY_MISR, ®value); - - regvalue |= PHY_MISR_LINK_INT_EN; - - /* Enable Interrupt on change of link status */ - HAL_ETH_WritePHYRegister(&heth, PHY_MISR, regvalue); -#endif -} - -/** - * This function should do the actual transmission of the packet. The packet is - * contained in the pbuf that is passed to the function. This pbuf - * might be chained. - * - * @param netif the lwip network interface structure for this ethernetif - * @param p the MAC packet to send (e.g. IP packet including MAC addresses and type) - * @return ERR_OK if the packet could be sent - * an err_t value if the packet couldn't be sent - * - * @note Returning ERR_MEM here if a DMA queue of your MAC is full can lead to - * strange results. You might consider waiting for space in the DMA queue - * to become availale since the stack doesn't retry to send a packet - * dropped because of memory failure (except for the TCP timers). - */ - -static err_t stm32f4_low_level_output(struct netif *netif, struct pbuf *p) -{ - err_t errval; - struct pbuf *q; - uint8_t *buffer = (uint8_t*)(heth.TxDesc->Buffer1Addr); - __IO ETH_DMADescTypeDef *DmaTxDesc; - uint32_t framelength = 0; - uint32_t bufferoffset = 0; - uint32_t byteslefttocopy = 0; - uint32_t payloadoffset = 0; - DmaTxDesc = heth.TxDesc; - bufferoffset = 0; - - - sys_mutex_lock(&tx_lock_mutex); - - /* copy frame from pbufs to driver buffers */ - for (q = p; q != NULL; q = q->next) { - /* Is this buffer available? If not, goto error */ - if ((DmaTxDesc->Status & ETH_DMATXDESC_OWN) != (uint32_t)RESET) { - errval = ERR_USE; - goto error; - } - - /* Get bytes in current lwIP buffer */ - byteslefttocopy = q->len; - payloadoffset = 0; - - /* Check if the length of data to copy is bigger than Tx buffer size*/ - while ((byteslefttocopy + bufferoffset) > ETH_TX_BUF_SIZE) { - /* Copy data to Tx buffer*/ - memcpy((uint8_t*)((uint8_t*)buffer + bufferoffset), (uint8_t*)((uint8_t*)q->payload + payloadoffset), (ETH_TX_BUF_SIZE - bufferoffset)); - - /* Point to next descriptor */ - DmaTxDesc = (ETH_DMADescTypeDef*)(DmaTxDesc->Buffer2NextDescAddr); - - /* Check if the buffer is available */ - if ((DmaTxDesc->Status & ETH_DMATXDESC_OWN) != (uint32_t)RESET) { - errval = ERR_USE; - goto error; - } - - buffer = (uint8_t*)(DmaTxDesc->Buffer1Addr); - - byteslefttocopy = byteslefttocopy - (ETH_TX_BUF_SIZE - bufferoffset); - payloadoffset = payloadoffset + (ETH_TX_BUF_SIZE - bufferoffset); - framelength = framelength + (ETH_TX_BUF_SIZE - bufferoffset); - bufferoffset = 0; - } - - /* Copy the remaining bytes */ - memcpy((uint8_t*)((uint8_t*)buffer + bufferoffset), (uint8_t*)((uint8_t*)q->payload + payloadoffset), byteslefttocopy); - bufferoffset = bufferoffset + byteslefttocopy; - framelength = framelength + byteslefttocopy; - } - - /* Prepare transmit descriptors to give to DMA */ - HAL_ETH_TransmitFrame(&heth, framelength); - - errval = ERR_OK; - -error: - - /* When Transmit Underflow flag is set, clear it and issue a Transmit Poll Demand to resume transmission */ - if ((heth.Instance->DMASR & ETH_DMASR_TUS) != (uint32_t)RESET) { - /* Clear TUS ETHERNET DMA flag */ - heth.Instance->DMASR = ETH_DMASR_TUS; - - /* Resume DMA transmission*/ - heth.Instance->DMATPDR = 0; - } - - sys_mutex_unlock(&tx_lock_mutex); - - return errval; -} - - -/** - * Should allocate a pbuf and transfer the bytes of the incoming - * packet from the interface into the pbuf. - * - * @param netif the lwip network interface structure for this ethernetif - * @return a pbuf filled with the received packet (including MAC header) - * NULL on memory error - */ -static struct pbuf * stm32f4_low_level_input(struct netif *netif) -{ - struct pbuf *p = NULL; - struct pbuf *q; - uint16_t len = 0; - uint8_t *buffer; - __IO ETH_DMADescTypeDef *dmarxdesc; - uint32_t bufferoffset = 0; - uint32_t payloadoffset = 0; - uint32_t byteslefttocopy = 0; - uint32_t i = 0; - - - /* get received frame */ - if (HAL_ETH_GetReceivedFrame(&heth) != HAL_OK) - return NULL; - - /* Obtain the size of the packet and put it into the "len" variable. */ - len = heth.RxFrameInfos.length; - buffer = (uint8_t*)heth.RxFrameInfos.buffer; - - if (len > 0) { - /* We allocate a pbuf chain of pbufs from the Lwip buffer pool */ - p = pbuf_alloc(PBUF_RAW, len, PBUF_POOL); - } - - if (p != NULL) { - dmarxdesc = heth.RxFrameInfos.FSRxDesc; - bufferoffset = 0; - for (q = p; q != NULL; q = q->next) { - byteslefttocopy = q->len; - payloadoffset = 0; - - /* Check if the length of bytes to copy in current pbuf is bigger than Rx buffer size*/ - while ((byteslefttocopy + bufferoffset) > ETH_RX_BUF_SIZE) { - /* Copy data to pbuf */ - memcpy((uint8_t*)((uint8_t*)q->payload + payloadoffset), (uint8_t*)((uint8_t*)buffer + bufferoffset), (ETH_RX_BUF_SIZE - bufferoffset)); - - /* Point to next descriptor */ - dmarxdesc = (ETH_DMADescTypeDef*)(dmarxdesc->Buffer2NextDescAddr); - buffer = (uint8_t*)(dmarxdesc->Buffer1Addr); - - byteslefttocopy = byteslefttocopy - (ETH_RX_BUF_SIZE - bufferoffset); - payloadoffset = payloadoffset + (ETH_RX_BUF_SIZE - bufferoffset); - bufferoffset = 0; - } - /* Copy remaining data in pbuf */ - memcpy((uint8_t*)((uint8_t*)q->payload + payloadoffset), (uint8_t*)((uint8_t*)buffer + bufferoffset), byteslefttocopy); - bufferoffset = bufferoffset + byteslefttocopy; - } - - /* Release descriptors to DMA */ - /* Point to first descriptor */ - dmarxdesc = heth.RxFrameInfos.FSRxDesc; - /* Set Own bit in Rx descriptors: gives the buffers back to DMA */ - for (i = 0; i < heth.RxFrameInfos.SegCount; i++) { - dmarxdesc->Status |= ETH_DMARXDESC_OWN; - dmarxdesc = (ETH_DMADescTypeDef*)(dmarxdesc->Buffer2NextDescAddr); - } - - /* Clear Segment_Count */ - heth.RxFrameInfos.SegCount = 0; - } - - /* When Rx Buffer unavailable flag is set: clear it and resume reception */ - if ((heth.Instance->DMASR & ETH_DMASR_RBUS) != (uint32_t)RESET) { - /* Clear RBUS ETHERNET DMA flag */ - heth.Instance->DMASR = ETH_DMASR_RBUS; - /* Resume DMA reception */ - heth.Instance->DMARPDR = 0; - } - return p; -} - -/** - * This task receives input data - * - * \param[in] netif the lwip network interface structure - */ -static void stm32f4_rx_task(void *arg) -{ - struct netif *netif = (struct netif*)arg; - struct pbuf *p; - - while (1) { - sys_arch_sem_wait(&rx_ready_sem, 0); - p = stm32f4_low_level_input(netif); - if (p != NULL) { - if (netif->input(p, netif) != ERR_OK) { - pbuf_free(p); - p = NULL; - } - } - } -} - -/** - * This task checks phy link status and updates net status - * - * \param[in] netif the lwip network interface structure - */ -static void stm32f4_phy_task(void *arg) -{ - struct netif *netif = (struct netif*)arg; - uint32_t phy_status = 0; - - while (1) { - uint32_t status; - if (HAL_ETH_ReadPHYRegister(&heth, PHY_SR, &status) == HAL_OK) { - if ((status & PHY_LINK_STATUS) && !(phy_status & PHY_LINK_STATUS)) { - tcpip_callback_with_block((tcpip_callback_fn)netif_set_link_up, (void*) netif, 1); - } else if (!(status & PHY_LINK_STATUS) && (phy_status & PHY_LINK_STATUS)) { - tcpip_callback_with_block((tcpip_callback_fn)netif_set_link_down, (void*) netif, 1); - } - - phy_status = status; - } - - osDelay(PHY_TASK_WAIT); - } -} - -/** - * This function is the ethernet packet send function. It calls - * etharp_output after checking link status. - * - * \param[in] netif the lwip network interface structure for this lpc_enetif - * \param[in] q Pointer to pbug to send - * \param[in] ipaddr IP address - * \return ERR_OK or error code - */ -static err_t stm32f4_etharp_output(struct netif *netif, struct pbuf *q, ip_addr_t *ipaddr) -{ - /* Only send packet is link is up */ - if (netif->flags & NETIF_FLAG_LINK_UP) { - return etharp_output(netif, q, ipaddr); - } - - return ERR_CONN; -} - -/** - * Should be called at the beginning of the program to set up the - * network interface. - * - * This function should be passed as a parameter to netif_add(). - * - * @param[in] netif the lwip network interface structure for this lpc_enetif - * @return ERR_OK if the loopif is initialized - * ERR_MEM if private data couldn't be allocated - * any other err_t on error - */ -err_t eth_arch_enetif_init(struct netif *netif) -{ - /* set MAC hardware address */ - netif->hwaddr_len = ETHARP_HWADDR_LEN; - - /* maximum transfer unit */ - netif->mtu = 1500; - - /* device capabilities */ - netif->flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP | NETIF_FLAG_ETHERNET | NETIF_FLAG_IGMP; - -#if LWIP_NETIF_HOSTNAME - /* Initialize interface hostname */ - netif->hostname = "lwipstm32f4"; -#endif /* LWIP_NETIF_HOSTNAME */ - - netif->name[0] = 'e'; - netif->name[1] = 'n'; - - netif->output = stm32f4_etharp_output; - netif->linkoutput = stm32f4_low_level_output; - - /* semaphore */ - sys_sem_new(&rx_ready_sem, 0); - - sys_mutex_new(&tx_lock_mutex); - - /* task */ - sys_thread_new("stm32f4_recv_task", stm32f4_rx_task, netif, DEFAULT_THREAD_STACKSIZE, RECV_TASK_PRI); - sys_thread_new("stm32f4_phy_task", stm32f4_phy_task, netif, DEFAULT_THREAD_STACKSIZE, PHY_TASK_PRI); - - /* initialize the hardware */ - stm32f4_low_level_init(netif); - - return ERR_OK; -} - -void eth_arch_enable_interrupts(void) -{ - HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); - HAL_NVIC_SetPriority(ETH_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(ETH_IRQn); -} - -void eth_arch_disable_interrupts(void) -{ - NVIC_DisableIRQ(ETH_IRQn); -} - -/** - * @} - */ - -/* --------------------------------- End Of File ------------------------------ */
--- a/arch/TARGET_VK_RZ_A1H/lwipopts_conf.h Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,26 +0,0 @@ -/* Copyright (C) 2012 mbed.org, MIT License - * - * Permission is hereby granted, free of charge, to any person obtaining a copy of this software - * and associated documentation files (the "Software"), to deal in the Software without restriction, - * including without limitation the rights to use, copy, modify, merge, publish, distribute, - * sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in all copies or - * substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - * BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - * DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - */ - -#ifndef LWIPOPTS_CONF_H -#define LWIPOPTS_CONF_H - -#define LWIP_TRANSPORT_ETHERNET 1 - -#define MEM_SIZE (1600 * 16) - -#endif
--- a/arch/TARGET_VK_RZ_A1H/rza1_emac.c Tue May 03 00:16:23 2016 +0100 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,194 +0,0 @@ -#include "lwip/opt.h" -#include "lwip/tcpip.h" -#include "netif/etharp.h" -#include "mbed_interface.h" -#include "ethernet_api.h" -#include "ethernetext_api.h" - -#define RECV_TASK_PRI (osPriorityNormal) -#define PHY_TASK_PRI (osPriorityNormal) -#define PHY_TASK_WAIT (200) - -/* memory */ -static sys_sem_t recv_ready_sem; /* receive ready semaphore */ - -/* function */ -static void rza1_recv_task(void *arg); -static void rza1_phy_task(void *arg); -static err_t rza1_etharp_output(struct netif *netif, struct pbuf *q, ip_addr_t *ipaddr); -static err_t rza1_low_level_output(struct netif *netif, struct pbuf *p); -static void rza1_recv_callback(void); - -static void rza1_recv_task(void *arg) { - struct netif *netif = (struct netif*)arg; - struct eth_hdr *ethhdr; - u16_t recv_size; - struct pbuf *p; - int cnt; - - while (1) { - sys_arch_sem_wait(&recv_ready_sem, 0); - for (cnt = 0; cnt < 16; cnt++) { - recv_size = ethernet_receive(); - if (recv_size != 0) { - p = pbuf_alloc(PBUF_RAW, recv_size, PBUF_RAM); - if (p != NULL) { - (void)ethernet_read((char *)p->payload, p->len); - ethhdr = p->payload; - switch (htons(ethhdr->type)) { - case ETHTYPE_IP: - case ETHTYPE_ARP: -#if PPPOE_SUPPORT - case ETHTYPE_PPPOEDISC: - case ETHTYPE_PPPOE: -#endif /* PPPOE_SUPPORT */ - /* full packet send to tcpip_thread to process */ - if (netif->input(p, netif) != ERR_OK) { - /* Free buffer */ - pbuf_free(p); - } - break; - default: - /* Return buffer */ - pbuf_free(p); - break; - } - } - } else { - break; - } - } - } -} - -static void rza1_phy_task(void *arg) { - struct netif *netif = (struct netif*)arg; - s32_t connect_sts = 0; /* 0: disconnect, 1:connect */ - s32_t link_sts; - s32_t link_mode_new = NEGO_FAIL; - s32_t link_mode_old = NEGO_FAIL; - - while (1) { - link_sts = ethernet_link(); - if (link_sts == 1) { - link_mode_new = ethernetext_chk_link_mode(); - if (link_mode_new != link_mode_old) { - if (connect_sts == 1) { - tcpip_callback_with_block((tcpip_callback_fn)netif_set_link_down, (void*) netif, 1); - } - if (link_mode_new != NEGO_FAIL) { - ethernetext_set_link_mode(link_mode_new); - tcpip_callback_with_block((tcpip_callback_fn)netif_set_link_up, (void*) netif, 1); - connect_sts = 1; - } - } - } else { - if (connect_sts != 0) { - tcpip_callback_with_block((tcpip_callback_fn)netif_set_link_down, (void*) netif, 1); - link_mode_new = NEGO_FAIL; - connect_sts = 0; - } - } - link_mode_old = link_mode_new; - osDelay(PHY_TASK_WAIT); - } -} - -static err_t rza1_etharp_output(struct netif *netif, struct pbuf *q, ip_addr_t *ipaddr) { - /* Only send packet is link is up */ - if (netif->flags & NETIF_FLAG_LINK_UP) { - return etharp_output(netif, q, ipaddr); - } - - return ERR_CONN; -} - -static err_t rza1_low_level_output(struct netif *netif, struct pbuf *p) { - struct pbuf *q; - s32_t cnt; - err_t err = ERR_MEM; - s32_t write_size = 0; - - if ((p->payload != NULL) && (p->len != 0)) { - /* If the first data can't be written, transmit descriptor is full. */ - for (cnt = 0; cnt < 100; cnt++) { - write_size = ethernet_write((char *)p->payload, p->len); - if (write_size != 0) { - break; - } - osDelay(1); - } - if (write_size != 0) { - for (q = p->next; q != NULL; q = q->next) { - (void)ethernet_write((char *)q->payload, q->len); - } - if (ethernet_send() == 1) { - err = ERR_OK; - } - } - } - - return err; -} - -static void rza1_recv_callback(void) { - sys_sem_signal(&recv_ready_sem); -} - -err_t eth_arch_enetif_init(struct netif *netif) -{ - ethernet_cfg_t ethcfg; - - /* set MAC hardware address */ -#if (MBED_MAC_ADDRESS_SUM != MBED_MAC_ADDR_INTERFACE) - netif->hwaddr[0] = MBED_MAC_ADDR_0; - netif->hwaddr[1] = MBED_MAC_ADDR_1; - netif->hwaddr[2] = MBED_MAC_ADDR_2; - netif->hwaddr[3] = MBED_MAC_ADDR_3; - netif->hwaddr[4] = MBED_MAC_ADDR_4; - netif->hwaddr[5] = MBED_MAC_ADDR_5; -#else - mbed_mac_address((char *)netif->hwaddr); -#endif - netif->hwaddr_len = ETHARP_HWADDR_LEN; - - /* maximum transfer unit */ - netif->mtu = 1500; - - /* device capabilities */ - netif->flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP | NETIF_FLAG_ETHERNET | NETIF_FLAG_IGMP; - -#if LWIP_NETIF_HOSTNAME - /* Initialize interface hostname */ - netif->hostname = "lwiprza1"; -#endif /* LWIP_NETIF_HOSTNAME */ - - netif->name[0] = 'e'; - netif->name[1] = 'n'; - - netif->output = rza1_etharp_output; - netif->linkoutput = rza1_low_level_output; - - /* Initialize the hardware */ - ethcfg.int_priority = 6; - ethcfg.recv_cb = &rza1_recv_callback; - ethcfg.ether_mac = (char *)netif->hwaddr; - ethernetext_init(ðcfg); - - /* semaphore */ - sys_sem_new(&recv_ready_sem, 0); - - /* task */ - sys_thread_new("rza1_recv_task", rza1_recv_task, netif, DEFAULT_THREAD_STACKSIZE, RECV_TASK_PRI); - sys_thread_new("rza1_phy_task", rza1_phy_task, netif, DEFAULT_THREAD_STACKSIZE, PHY_TASK_PRI); - - return ERR_OK; -} - -void eth_arch_enable_interrupts(void) { - ethernetext_start_stop(1); -} - -void eth_arch_disable_interrupts(void) { - ethernetext_start_stop(0); -}