From 12c6b1bd8823b14262ebc83e73f6cb378bcd2beb Mon Sep 17 00:00:00 2001 From: Mahesh Mahadevan Date: Mon, 7 May 2018 12:20:56 -0500 Subject: [PATCH] MIMXRT1050EVK: Add ENET support Signed-off-by: Mahesh Mahadevan --- features/lwipstack/mbed_lib.json | 5 +- .../TARGET_MIMXRT1050_EVK/hardware_init.c | 226 +++++++ .../TARGET_NXP_EMAC/TARGET_IMX/imx_emac.cpp | 593 ++++++++++++++++++ .../TARGET_NXP_EMAC/TARGET_IMX/imx_emac.h | 170 +++++ .../TARGET_IMX/imx_emac_config.h | 48 ++ .../TARGET_NXP_EMAC/TARGET_IMX/mbed_lib.json | 7 + .../TARGET_MIMXRT1050/TARGET_EVK/device.h | 1 + .../TARGET_MIMXRT1050/TARGET_EVK/fsl_phy.c | 70 ++- .../TARGET_MIMXRT1050/TARGET_EVK/fsl_phy.h | 10 + .../TARGET_MIMXRT1050/drivers/fsl_enet.c | 51 +- .../TARGET_MIMXRT1050/drivers/fsl_enet.h | 8 +- targets/targets.json | 13 +- 12 files changed, 1138 insertions(+), 64 deletions(-) create mode 100644 features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/TARGET_MIMXRT1050_EVK/hardware_init.c create mode 100644 features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/imx_emac.cpp create mode 100644 features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/imx_emac.h create mode 100644 features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/imx_emac_config.h create mode 100644 features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/mbed_lib.json diff --git a/features/lwipstack/mbed_lib.json b/features/lwipstack/mbed_lib.json index 47b462732e..0307c00d27 100644 --- a/features/lwipstack/mbed_lib.json +++ b/features/lwipstack/mbed_lib.json @@ -140,7 +140,7 @@ }, "ARCH_PRO": { "mem-size": 16362 - }, + }, "LPC546XX": { "mem-size": 36496 }, @@ -157,6 +157,9 @@ "tcp-wnd": "(TCP_MSS * 8)", "pbuf-pool-size": 16, "mem-size": 51200 + }, + "MIMXRT1050_EVK": { + "mem-size": 36560 } } } diff --git a/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/TARGET_MIMXRT1050_EVK/hardware_init.c b/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/TARGET_MIMXRT1050_EVK/hardware_init.c new file mode 100644 index 0000000000..a48c7ce637 --- /dev/null +++ b/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/TARGET_MIMXRT1050_EVK/hardware_init.c @@ -0,0 +1,226 @@ +/* + * 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_gpio.h" +#include "fsl_iomuxc.h" +#include "fsl_clock.h" +#include "mbed_wait_api.h" + +/******************************************************************************* + * Code + ******************************************************************************/ +static void BOARD_InitModuleClock(void) +{ + const clock_enet_pll_config_t config = {true, false, 1}; + CLOCK_InitEnetPll(&config); +} + +void kinetis_init_eth_hardware(void) +{ + gpio_pin_config_t gpio_config = {kGPIO_DigitalOutput, 0, kGPIO_NoIntmode}; + + CLOCK_EnableClock(kCLOCK_Iomuxc); /* iomuxc clock (iomuxc_clk_enable): 0x03u */ + + IOMUXC_SetPinMux( + IOMUXC_GPIO_AD_B0_09_GPIO1_IO09, /* GPIO_AD_B0_09 is configured as GPIO1_IO09 */ + 0U); /* Software Input On Field: Input Path is determined by functionality */ + IOMUXC_SetPinMux( + IOMUXC_GPIO_AD_B0_10_GPIO1_IO10, /* GPIO_AD_B0_10 is configured as GPIO1_IO10 */ + 0U); /* Software Input On Field: Input Path is determined by functionality */ + IOMUXC_SetPinMux( + IOMUXC_GPIO_B1_04_ENET_RX_DATA00, /* GPIO_B1_04 is configured as ENET_RX_DATA00 */ + 0U); /* Software Input On Field: Input Path is determined by functionality */ + IOMUXC_SetPinMux( + IOMUXC_GPIO_B1_05_ENET_RX_DATA01, /* GPIO_B1_05 is configured as ENET_RX_DATA01 */ + 0U); /* Software Input On Field: Input Path is determined by functionality */ + IOMUXC_SetPinMux( + IOMUXC_GPIO_B1_06_ENET_RX_EN, /* GPIO_B1_06 is configured as ENET_RX_EN */ + 0U); /* Software Input On Field: Input Path is determined by functionality */ + IOMUXC_SetPinMux( + IOMUXC_GPIO_B1_07_ENET_TX_DATA00, /* GPIO_B1_07 is configured as ENET_TX_DATA00 */ + 0U); /* Software Input On Field: Input Path is determined by functionality */ + IOMUXC_SetPinMux( + IOMUXC_GPIO_B1_08_ENET_TX_DATA01, /* GPIO_B1_08 is configured as ENET_TX_DATA01 */ + 0U); /* Software Input On Field: Input Path is determined by functionality */ + IOMUXC_SetPinMux( + IOMUXC_GPIO_B1_09_ENET_TX_EN, /* GPIO_B1_09 is configured as ENET_TX_EN */ + 0U); /* Software Input On Field: Input Path is determined by functionality */ + IOMUXC_SetPinMux( + IOMUXC_GPIO_B1_10_ENET_REF_CLK, /* GPIO_B1_10 is configured as ENET_REF_CLK */ + 1U); /* Software Input On Field: Force input path of pad GPIO_B1_10 */ + IOMUXC_SetPinMux( + IOMUXC_GPIO_B1_11_ENET_RX_ER, /* GPIO_B1_11 is configured as ENET_RX_ER */ + 0U); /* Software Input On Field: Input Path is determined by functionality */ + IOMUXC_SetPinMux( + IOMUXC_GPIO_EMC_40_ENET_MDC, /* GPIO_EMC_40 is configured as ENET_MDC */ + 0U); /* Software Input On Field: Input Path is determined by functionality */ + IOMUXC_SetPinMux( + IOMUXC_GPIO_EMC_41_ENET_MDIO, /* GPIO_EMC_41 is configured as ENET_MDIO */ + 0U); /* Software Input On Field: Input Path is determined by functionality */ + IOMUXC_SetPinConfig( + IOMUXC_GPIO_AD_B0_09_GPIO1_IO09, /* GPIO_AD_B0_09 PAD functional properties : */ + 0xB0A9u); /* Slew Rate Field: Fast Slew Rate + Drive Strength Field: R0/5 + Speed Field: medium(100MHz) + Open Drain Enable Field: Open Drain Disabled + Pull / Keep Enable Field: Pull/Keeper Enabled + Pull / Keep Select Field: Pull + Pull Up / Down Config. Field: 100K Ohm Pull Up + Hyst. Enable Field: Hysteresis Disabled */ + IOMUXC_SetPinConfig( + IOMUXC_GPIO_AD_B0_10_GPIO1_IO10, /* GPIO_AD_B0_10 PAD functional properties : */ + 0xB0A9u); /* Slew Rate Field: Fast Slew Rate + Drive Strength Field: R0/5 + Speed Field: medium(100MHz) + Open Drain Enable Field: Open Drain Disabled + Pull / Keep Enable Field: Pull/Keeper Enabled + Pull / Keep Select Field: Pull + Pull Up / Down Config. Field: 100K Ohm Pull Up + Hyst. Enable Field: Hysteresis Disabled */ + IOMUXC_SetPinConfig( + IOMUXC_GPIO_B1_04_ENET_RX_DATA00, /* GPIO_B1_04 PAD functional properties : */ + 0xB0E9u); /* Slew Rate Field: Fast Slew Rate + Drive Strength Field: R0/5 + Speed Field: max(200MHz) + Open Drain Enable Field: Open Drain Disabled + Pull / Keep Enable Field: Pull/Keeper Enabled + Pull / Keep Select Field: Pull + Pull Up / Down Config. Field: 100K Ohm Pull Up + Hyst. Enable Field: Hysteresis Disabled */ + IOMUXC_SetPinConfig( + IOMUXC_GPIO_B1_05_ENET_RX_DATA01, /* GPIO_B1_05 PAD functional properties : */ + 0xB0E9u); /* Slew Rate Field: Fast Slew Rate + Drive Strength Field: R0/5 + Speed Field: max(200MHz) + Open Drain Enable Field: Open Drain Disabled + Pull / Keep Enable Field: Pull/Keeper Enabled + Pull / Keep Select Field: Pull + Pull Up / Down Config. Field: 100K Ohm Pull Up + Hyst. Enable Field: Hysteresis Disabled */ + IOMUXC_SetPinConfig( + IOMUXC_GPIO_B1_06_ENET_RX_EN, /* GPIO_B1_06 PAD functional properties : */ + 0xB0E9u); /* Slew Rate Field: Fast Slew Rate + Drive Strength Field: R0/5 + Speed Field: max(200MHz) + Open Drain Enable Field: Open Drain Disabled + Pull / Keep Enable Field: Pull/Keeper Enabled + Pull / Keep Select Field: Pull + Pull Up / Down Config. Field: 100K Ohm Pull Up + Hyst. Enable Field: Hysteresis Disabled */ + IOMUXC_SetPinConfig( + IOMUXC_GPIO_B1_07_ENET_TX_DATA00, /* GPIO_B1_07 PAD functional properties : */ + 0xB0E9u); /* Slew Rate Field: Fast Slew Rate + Drive Strength Field: R0/5 + Speed Field: max(200MHz) + Open Drain Enable Field: Open Drain Disabled + Pull / Keep Enable Field: Pull/Keeper Enabled + Pull / Keep Select Field: Pull + Pull Up / Down Config. Field: 100K Ohm Pull Up + Hyst. Enable Field: Hysteresis Disabled */ + IOMUXC_SetPinConfig( + IOMUXC_GPIO_B1_08_ENET_TX_DATA01, /* GPIO_B1_08 PAD functional properties : */ + 0xB0E9u); /* Slew Rate Field: Fast Slew Rate + Drive Strength Field: R0/5 + Speed Field: max(200MHz) + Open Drain Enable Field: Open Drain Disabled + Pull / Keep Enable Field: Pull/Keeper Enabled + Pull / Keep Select Field: Pull + Pull Up / Down Config. Field: 100K Ohm Pull Up + Hyst. Enable Field: Hysteresis Disabled */ + IOMUXC_SetPinConfig( + IOMUXC_GPIO_B1_09_ENET_TX_EN, /* GPIO_B1_09 PAD functional properties : */ + 0xB0E9u); /* Slew Rate Field: Fast Slew Rate + Drive Strength Field: R0/5 + Speed Field: max(200MHz) + Open Drain Enable Field: Open Drain Disabled + Pull / Keep Enable Field: Pull/Keeper Enabled + Pull / Keep Select Field: Pull + Pull Up / Down Config. Field: 100K Ohm Pull Up + Hyst. Enable Field: Hysteresis Disabled */ + IOMUXC_SetPinConfig( + IOMUXC_GPIO_B1_10_ENET_REF_CLK, /* GPIO_B1_10 PAD functional properties : */ + 0x31u); /* Slew Rate Field: Fast Slew Rate + Drive Strength Field: R0/6 + Speed Field: low(50MHz) + Open Drain Enable Field: Open Drain Disabled + Pull / Keep Enable Field: Pull/Keeper Disabled + Pull / Keep Select Field: Keeper + Pull Up / Down Config. Field: 100K Ohm Pull Down + Hyst. Enable Field: Hysteresis Disabled */ + IOMUXC_SetPinConfig( + IOMUXC_GPIO_B1_11_ENET_RX_ER, /* GPIO_B1_11 PAD functional properties : */ + 0xB0E9u); /* Slew Rate Field: Fast Slew Rate + Drive Strength Field: R0/5 + Speed Field: max(200MHz) + Open Drain Enable Field: Open Drain Disabled + Pull / Keep Enable Field: Pull/Keeper Enabled + Pull / Keep Select Field: Pull + Pull Up / Down Config. Field: 100K Ohm Pull Up + Hyst. Enable Field: Hysteresis Disabled */ + IOMUXC_SetPinConfig( + IOMUXC_GPIO_EMC_40_ENET_MDC, /* GPIO_EMC_40 PAD functional properties : */ + 0xB0E9u); /* Slew Rate Field: Fast Slew Rate + Drive Strength Field: R0/5 + Speed Field: max(200MHz) + Open Drain Enable Field: Open Drain Disabled + Pull / Keep Enable Field: Pull/Keeper Enabled + Pull / Keep Select Field: Pull + Pull Up / Down Config. Field: 100K Ohm Pull Up + Hyst. Enable Field: Hysteresis Disabled */ + IOMUXC_SetPinConfig( + IOMUXC_GPIO_EMC_41_ENET_MDIO, /* GPIO_EMC_41 PAD functional properties : */ + 0xB829u); /* Slew Rate Field: Fast Slew Rate + Drive Strength Field: R0/5 + Speed Field: low(50MHz) + Open Drain Enable Field: Open Drain Enabled + Pull / Keep Enable Field: Pull/Keeper Enabled + Pull / Keep Select Field: Pull + Pull Up / Down Config. Field: 100K Ohm Pull Up + Hyst. Enable Field: Hysteresis Disabled */ + + + BOARD_InitModuleClock(); + + IOMUXC_EnableMode(IOMUXC_GPR, kIOMUXC_GPR_ENET1TxClkOutputDir, true); + + GPIO_PinInit(GPIO1, 9, &gpio_config); + GPIO_PinInit(GPIO1, 10, &gpio_config); + /* pull up the ENET_INT before RESET. */ + GPIO_WritePinOutput(GPIO1, 10, 1); + GPIO_WritePinOutput(GPIO1, 9, 0); + wait_ms(1); + GPIO_WritePinOutput(GPIO1, 9, 1); +} + +/******************************************************************************* + * EOF + ******************************************************************************/ + + diff --git a/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/imx_emac.cpp b/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/imx_emac.cpp new file mode 100644 index 0000000000..bf8bf35d0e --- /dev/null +++ b/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/imx_emac.cpp @@ -0,0 +1,593 @@ +/* + * Copyright (c) 2013 - 2014, Freescale Semiconductor, Inc. + * Copyright (c) 2017 ARM Limited + * + * 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 +#include +#include +#include + +#include "cmsis_os.h" + +#include "mbed_interface.h" +#include "mbed_assert.h" +#include "netsocket/nsapi_types.h" +#include "mbed_shared_queues.h" + +#include "fsl_phy.h" + +#include "imx_emac_config.h" +#include "imx_emac.h" + +enet_handle_t g_handle; +// RX packet buffer pointers +emac_mem_buf_t *rx_buff[ENET_RX_RING_LEN]; +// TX packet buffer pointers +emac_mem_buf_t *tx_buff[ENET_TX_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 "C" void kinetis_init_eth_hardware(void); + +/* \brief Flags for worker thread */ +#define FLAG_TX 1 +#define FLAG_RX 2 + +/** \brief Driver thread priority */ +#define THREAD_PRIORITY (osPriorityNormal) + +#define PHY_TASK_PERIOD_MS 200 + +Kinetis_EMAC::Kinetis_EMAC() : xTXDCountSem(ENET_TX_RING_LEN, ENET_TX_RING_LEN), hwaddr() +{ +} + +static osThreadId_t create_new_thread(const char *threadName, void (*thread)(void *arg), void *arg, int stacksize, osPriority_t priority, mbed_rtos_storage_thread_t *thread_cb) +{ + osThreadAttr_t attr = {0}; + attr.name = threadName; + attr.stack_mem = malloc(stacksize); + attr.cb_mem = thread_cb; + attr.stack_size = stacksize; + attr.cb_size = sizeof(mbed_rtos_storage_thread_t); + attr.priority = priority; + return osThreadNew(thread, arg, &attr); +} +/******************************************************************************** + * Buffer management + ********************************************************************************/ +/* + * This function will queue a new receive buffer + */ +static void update_read_buffer(uint8_t *buf) +{ + if (buf != NULL) { + g_handle.rxBdCurrent[0]->buffer = buf; + } + + /* Clears status. */ + g_handle.rxBdCurrent[0]->control &= ENET_BUFFDESCRIPTOR_RX_WRAP_MASK; + + /* Sets the receive buffer descriptor with the empty flag. */ + g_handle.rxBdCurrent[0]->control |= ENET_BUFFDESCRIPTOR_RX_EMPTY_MASK; + + /* Increases the buffer descriptor to the next one. */ + if (g_handle.rxBdCurrent[0]->control & ENET_BUFFDESCRIPTOR_RX_WRAP_MASK) { + g_handle.rxBdCurrent[0] = g_handle.rxBdBase[0]; + } else { + g_handle.rxBdCurrent[0]++; + } + + /* Actives the receive buffer descriptor. */ + ENET->RDAR = ENET_RDAR_RDAR_MASK; +} + +/** \brief Free TX buffers that are complete + */ +void Kinetis_EMAC::tx_reclaim() +{ + /* Get exclusive access */ + TXLockMutex.lock(); + + // Traverse all descriptors, looking for the ones modified by the uDMA + while((tx_consume_index != tx_produce_index) && + (!(g_handle.txBdDirty[0]->control & ENET_BUFFDESCRIPTOR_TX_READY_MASK))) { + memory_manager->free(tx_buff[tx_consume_index % ENET_TX_RING_LEN]); + if (g_handle.txBdDirty[0]->control & ENET_BUFFDESCRIPTOR_TX_WRAP_MASK) + g_handle.txBdDirty[0] = g_handle.txBdBase[0]; + else + g_handle.txBdDirty[0]++; + + tx_consume_index += 1; + xTXDCountSem.release(); + } + + /* Restore access */ + TXLockMutex.unlock(); +} + +/** \brief Ethernet receive interrupt handler + * + * This function handles the receive interrupt. + */ +void Kinetis_EMAC::rx_isr() +{ + if (thread) { + osThreadFlagsSet(thread, FLAG_RX); + } +} + +void Kinetis_EMAC::tx_isr() +{ + osThreadFlagsSet(thread, FLAG_TX); +} + +void Kinetis_EMAC::ethernet_callback(ENET_Type *base, enet_handle_t *handle, enet_event_t event, void *param) +{ + Kinetis_EMAC *enet = static_cast(param); + switch (event) + { + case kENET_RxEvent: + enet->rx_isr(); + break; + case kENET_TxEvent: + enet->tx_isr(); + break; + default: + break; + } +} + + +/** \brief Low level init of the MAC and PHY. + */ +bool Kinetis_EMAC::low_level_init_successful() +{ + uint8_t i; + uint32_t sysClock; + phy_speed_t phy_speed; + phy_duplex_t phy_duplex; + uint32_t phyAddr = 0; + enet_config_t config; + + AT_NONCACHEABLE_SECTION_ALIGN(static enet_rx_bd_struct_t rx_desc_start_addr[ENET_RX_RING_LEN], ENET_BUFF_ALIGNMENT); + AT_NONCACHEABLE_SECTION_ALIGN(static enet_tx_bd_struct_t tx_desc_start_addr[ENET_TX_RING_LEN], ENET_BUFF_ALIGNMENT); + + /* Create buffers for each receive BD */ + for (i = 0; i < ENET_RX_RING_LEN; i++) { + rx_buff[i] = memory_manager->alloc_heap(ENET_ETH_MAX_FLEN, ENET_BUFF_ALIGNMENT); + if (NULL == rx_buff[i]) + return false; + + rx_ptr[i] = (uint32_t*)memory_manager->get_ptr(rx_buff[i]); + } + + tx_consume_index = 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, + }; + + kinetis_init_eth_hardware(); + + sysClock = CLOCK_GetFreq(kCLOCK_CoreSysClk); + + ENET_GetDefaultConfig(&config); + + if (PHY_Init(ENET, phyAddr, sysClock) != kStatus_Success) { + return false; + } + + /* 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 = 0; + config.rxAccelerConfig = kENET_RxAccelMacCheckEnabled; + ENET_Init(ENET, &g_handle, &config, &buffCfg, hwaddr, sysClock); + +#if defined(TOOLCHAIN_ARM) +#if defined(__OPTIMISE_TIME) && (__ARMCC_VERSION < 5060750) + /* Add multicast groups + work around for https://github.com/ARMmbed/mbed-os/issues/4372 */ + ENET->GAUR = 0xFFFFFFFFu; + ENET->GALR = 0xFFFFFFFFu; +#endif +#endif + + ENET_SetCallback(&g_handle, &Kinetis_EMAC::ethernet_callback, this); + ENET_ActiveRead(ENET); + + return true; +} + +/** \brief Allocates a emac_mem_buf_t and returns the data from the incoming packet. + * + * \param[in] idx index of packet to be read + * \return a emac_mem_buf_t filled with the received packet (including MAC header) + */ +emac_mem_buf_t *Kinetis_EMAC::low_level_input(int idx) +{ + volatile enet_rx_bd_struct_t *bdPtr = g_handle.rxBdCurrent[0]; + emac_mem_buf_t *p = NULL; + emac_mem_buf_t *temp_rxbuf = NULL; + uint32_t length = 0; + const uint16_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 */ + TXLockMutex.lock(); +#endif + + /* Determine if a frame has been received */ + if ((bdPtr->control & err_mask) != 0) { + /* 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]; + memory_manager->set_len(p, length); + + /* Attempt to queue new buffer */ + temp_rxbuf = memory_manager->alloc_heap(ENET_ETH_MAX_FLEN, ENET_BUFF_ALIGNMENT); + if (NULL == temp_rxbuf) { + /* Re-queue the same buffer */ + update_read_buffer(NULL); + +#ifdef LOCK_RX_THREAD + TXLockMutex.unlock(); +#endif + + return NULL; + } + + rx_buff[idx] = temp_rxbuf; + rx_ptr[idx] = (uint32_t*)memory_manager->get_ptr(rx_buff[idx]); + + update_read_buffer((uint8_t*)rx_ptr[idx]); + } + +#ifdef LOCK_RX_THREAD + osMutexRelease(TXLockMutex); +#endif + + return p; +} + +/** \brief Attempt to read a packet from the EMAC interface. + * + * \param[in] idx index of packet to be read + */ +void Kinetis_EMAC::input(int idx) +{ + emac_mem_buf_t *p; + + /* move received packet into a new buf */ + p = low_level_input(idx); + if (p == NULL) { + return; + } + + emac_link_input_cb(p); +} + +/** \brief Worker thread. + * + * Woken by thread flags to receive packets or clean up transmit + * + * \param[in] pvParameters pointer to the interface data + */ +void Kinetis_EMAC::thread_function(void* pvParameters) +{ + struct Kinetis_EMAC *kinetis_enet = static_cast(pvParameters); + + for (;;) { + uint32_t flags = osThreadFlagsWait(FLAG_RX|FLAG_TX, osFlagsWaitAny, osWaitForever); + + MBED_ASSERT(!(flags & osFlagsError)); + + if (flags & FLAG_RX) { + kinetis_enet->packet_rx(); + } + + if (flags & FLAG_TX) { + kinetis_enet->packet_tx(); + } + } +} + +/** \brief Packet reception task + * + * This task is called when a packet is received. It will + * pass the packet to the LWIP core. + */ +void Kinetis_EMAC::packet_rx() +{ + static int idx = 0; + + while ((g_handle.rxBdCurrent[0]->control & ENET_BUFFDESCRIPTOR_RX_EMPTY_MASK) == 0) { + input(idx); + idx = (idx + 1) % ENET_RX_RING_LEN; + } +} + +/** \brief Transmit cleanup task + * + * This task is called when a transmit interrupt occurs and + * reclaims the buffer and descriptor used for the packet once + * the packet has been transferred. + */ +void Kinetis_EMAC::packet_tx() +{ + tx_reclaim(); +} + +/** \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] buf 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 + */ +bool Kinetis_EMAC::link_out(emac_mem_buf_t *buf) +{ + // If buffer is chained or not aligned then make a contiguous aligned copy of it + if (memory_manager->get_next(buf) || + reinterpret_cast(memory_manager->get_ptr(buf)) % ENET_BUFF_ALIGNMENT) { + emac_mem_buf_t *copy_buf; + copy_buf = memory_manager->alloc_heap(memory_manager->get_total_len(buf), ENET_BUFF_ALIGNMENT); + if (NULL == copy_buf) { + memory_manager->free(buf); + return false; + } + + // Copy to new buffer and free original + memory_manager->copy(copy_buf, buf); + memory_manager->free(buf); + buf = copy_buf; + } + + /* Check if a descriptor is available for the transfer (wait 10ms before dropping the buffer) */ + if (xTXDCountSem.wait(10) == 0) { + memory_manager->free(buf); + return false; + } + + /* Get exclusive access */ + TXLockMutex.lock(); + + /* Save the buffer so that it can be freed when transmit is done */ + tx_buff[tx_produce_index % ENET_TX_RING_LEN] = buf; + tx_produce_index += 1; + + /* Setup transfers */ + g_handle.txBdCurrent[0]->buffer = static_cast(memory_manager->get_ptr(buf)); + g_handle.txBdCurrent[0]->length = memory_manager->get_len(buf); + g_handle.txBdCurrent[0]->control |= (ENET_BUFFDESCRIPTOR_TX_READY_MASK | ENET_BUFFDESCRIPTOR_TX_LAST_MASK); + + /* Increase the buffer descriptor address. */ + if (g_handle.txBdCurrent[0]->control & ENET_BUFFDESCRIPTOR_TX_WRAP_MASK) { + g_handle.txBdCurrent[0] = g_handle.txBdBase[0]; + } else { + g_handle.txBdCurrent[0]++; + } + + /* Active the transmit buffer descriptor. */ + ENET->TDAR = ENET_TDAR_TDAR_MASK; + + /* Restore access */ + TXLockMutex.unlock(); + + return true; +} + +/******************************************************************************* + * PHY task: monitor link +*******************************************************************************/ + +#define STATE_UNKNOWN (-1) +#define STATE_LINK_DOWN (0) +#define STATE_LINK_UP (1) + +void Kinetis_EMAC::phy_task() +{ + uint32_t phyAddr = BOARD_ENET_PHY_ADDR; + + // Get current status + PHY_STATE crt_state; + bool connection_status; + PHY_GetLinkStatus(ENET, phyAddr, &connection_status); + + if (connection_status) { + crt_state.connected = STATE_LINK_UP; + } else { + crt_state.connected = STATE_LINK_DOWN; + } + + if (crt_state.connected == STATE_LINK_UP) { + if (prev_state.connected != STATE_LINK_UP) { + PHY_AutoNegotiation(ENET, phyAddr); + } + + PHY_GetLinkSpeedDuplex(ENET, phyAddr, &crt_state.speed, &crt_state.duplex); + + if (prev_state.connected != STATE_LINK_UP || crt_state.speed != prev_state.speed) { + /* Poke the registers*/ + ENET_SetMII(ENET, (enet_mii_speed_t)crt_state.speed, (enet_mii_duplex_t)crt_state.duplex); + } + } + + // Compare with previous state + if (crt_state.connected != prev_state.connected && emac_link_state_cb) { + emac_link_state_cb(crt_state.connected); + } + + prev_state = crt_state; +} + +bool Kinetis_EMAC::power_up() +{ + /* Initialize the hardware */ + if (!low_level_init_successful()) { + return false; + } + + /* Worker thread */ + thread = create_new_thread("Kinetis_EMAC_thread", &Kinetis_EMAC::thread_function, this, THREAD_STACKSIZE, THREAD_PRIORITY, &thread_cb); + + /* Trigger thread to deal with any RX packets that arrived before thread was started */ + rx_isr(); + + /* PHY monitoring task */ + prev_state.connected = STATE_LINK_DOWN; + prev_state.speed = (phy_speed_t)STATE_UNKNOWN; + prev_state.duplex = (phy_duplex_t)STATE_UNKNOWN; + + mbed::mbed_event_queue()->call(mbed::callback(this, &Kinetis_EMAC::phy_task)); + + /* Allow the PHY task to detect the initial link state and set up the proper flags */ + osDelay(10); + + phy_task_handle = mbed::mbed_event_queue()->call_every(PHY_TASK_PERIOD_MS, mbed::callback(this, &Kinetis_EMAC::phy_task)); + + return true; +} + +uint32_t Kinetis_EMAC::get_mtu_size() const +{ + return KINETIS_ETH_MTU_SIZE; +} + +uint32_t Kinetis_EMAC::get_align_preference() const +{ + return ENET_BUFF_ALIGNMENT; +} + +void Kinetis_EMAC::get_ifname(char *name, uint8_t size) const +{ + memcpy(name, KINETIS_ETH_IF_NAME, (size < sizeof(KINETIS_ETH_IF_NAME)) ? size : sizeof(KINETIS_ETH_IF_NAME)); +} + +uint8_t Kinetis_EMAC::get_hwaddr_size() const +{ + return KINETIS_HWADDR_SIZE; +} + +bool Kinetis_EMAC::get_hwaddr(uint8_t *addr) const +{ + return false; +} + +void Kinetis_EMAC::set_hwaddr(const uint8_t *addr) +{ + memcpy(hwaddr, addr, sizeof hwaddr); + ENET_SetMacAddr(ENET, const_cast(addr)); +} + +void Kinetis_EMAC::set_link_input_cb(emac_link_input_cb_t input_cb) +{ + emac_link_input_cb = input_cb; +} + +void Kinetis_EMAC::set_link_state_cb(emac_link_state_change_cb_t state_cb) +{ + emac_link_state_cb = state_cb; +} + +void Kinetis_EMAC::add_multicast_group(const uint8_t *addr) +{ + ENET_AddMulticastGroup(ENET, const_cast(addr)); +} + +void Kinetis_EMAC::remove_multicast_group(const uint8_t *addr) +{ + // ENET HAL doesn't reference count - ENET_LeaveMulticastGroup just maps + // address to filter bit, and clears that bit, even if shared by other + // addresses. So don't attempt anything for now. +} + +void Kinetis_EMAC::set_all_multicast(bool all) +{ + if (all) { + ENET->GAUR = 0xFFFFFFFFu; + ENET->GALR = 0xFFFFFFFFu; + } +} + +void Kinetis_EMAC::power_down() +{ + /* No-op at this stage */ +} + +void Kinetis_EMAC::set_memory_manager(EMACMemoryManager &mem_mngr) +{ + memory_manager = &mem_mngr; +} + + +Kinetis_EMAC &Kinetis_EMAC::get_instance() { + static Kinetis_EMAC emac; + return emac; +} + +// Weak so a module can override +MBED_WEAK EMAC &EMAC::get_default_instance() { + return Kinetis_EMAC::get_instance(); +} + +/** + * @} + */ + +/* --------------------------------- End Of File ------------------------------ */ + diff --git a/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/imx_emac.h b/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/imx_emac.h new file mode 100644 index 0000000000..f6138efa3b --- /dev/null +++ b/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/imx_emac.h @@ -0,0 +1,170 @@ +/* + * Copyright (c) 2017 ARM Limited. All rights reserved. + */ + +#ifndef KINETIS_EMAC_H_ +#define KINETIS_EMAC_H_ + +#include "EMAC.h" +#include "rtos/Semaphore.h" +#include "rtos/Mutex.h" + +class Kinetis_EMAC : public EMAC { +public: + Kinetis_EMAC(); + + static Kinetis_EMAC &get_instance(); + + /** + * Return maximum transmission unit + * + * @return MTU in bytes + */ + virtual uint32_t get_mtu_size() const; + + /** + * Gets memory buffer alignment preference + * + * Gets preferred memory buffer alignment of the Emac device. IP stack may or may not + * align link out memory buffer chains using the alignment. + * + * @return Memory alignment requirement in bytes + */ + virtual uint32_t get_align_preference() const; + + /** + * Return interface name + * + * @param name Pointer to where the name should be written + * @param size Maximum number of character to copy + */ + virtual void get_ifname(char *name, uint8_t size) const; + + /** + * Returns size of the underlying interface HW address size. + * + * @return HW address size in bytes + */ + virtual uint8_t get_hwaddr_size() const; + + /** + * Return interface-supplied HW address + * + * Copies HW address to provided memory, @param addr has to be of correct size see @a get_hwaddr_size + * + * HW address need not be provided if this interface does not have its own HW + * address configuration; stack will choose address from central system + * configuration if the function returns false and does not write to addr. + * + * @param addr HW address for underlying interface + * @return true if HW address is available + */ + virtual bool get_hwaddr(uint8_t *addr) const; + + /** + * Set HW address for interface + * + * Provided address has to be of correct size, see @a get_hwaddr_size + * + * Called to set the MAC address to actually use - if @a get_hwaddr is provided + * the stack would normally use that, but it could be overridden, eg for test + * purposes. + * + * @param addr Address to be set + */ + virtual void set_hwaddr(const uint8_t *addr); + + /** + * Sends the packet over the link + * + * That can not be called from an interrupt context. + * + * @param buf Packet to be send + * @return True if the packet was send successfully, False otherwise + */ + virtual bool link_out(emac_mem_buf_t *buf); + + /** + * Initializes the HW + * + * @return True on success, False in case of an error. + */ + virtual bool power_up(); + + /** + * Deinitializes the HW + * + */ + virtual void power_down(); + + /** + * Sets a callback that needs to be called for packets received for that interface + * + * @param input_cb Function to be register as a callback + */ + virtual void set_link_input_cb(emac_link_input_cb_t input_cb); + + /** + * Sets a callback that needs to be called on link status changes for given interface + * + * @param state_cb Function to be register as a callback + */ + virtual void set_link_state_cb(emac_link_state_change_cb_t state_cb); + + /** Add device to a multicast group + * + * @param address A multicast group hardware address + */ + virtual void add_multicast_group(const uint8_t *address); + + /** Remove device from a multicast group + * + * @param address A multicast group hardware address + */ + virtual void remove_multicast_group(const uint8_t *address); + + /** Request reception of all multicast packets + * + * @param all True to receive all multicasts + * False to receive only multicasts addressed to specified groups + */ + virtual void set_all_multicast(bool all); + + /** Sets memory manager that is used to handle memory buffers + * + * @param mem_mngr Pointer to memory manager + */ + virtual void set_memory_manager(EMACMemoryManager &mem_mngr); + +private: + bool low_level_init_successful(); + void rx_isr(); + void tx_isr(); + void packet_rx(); + void packet_tx(); + void tx_reclaim(); + void input(int idx); + emac_mem_buf_t *low_level_input(int idx); + static void thread_function(void* pvParameters); + void phy_task(); + static void ethernet_callback(ENET_Type *base, enet_handle_t *handle, enet_event_t event, void *param); + + mbed_rtos_storage_thread_t thread_cb; + osThreadId_t thread; /**< Processing thread */ + rtos::Mutex TXLockMutex;/**< TX critical section mutex */ + rtos::Semaphore xTXDCountSem; /**< TX free buffer counting semaphore */ + uint8_t tx_consume_index, tx_produce_index; /**< TX buffers ring */ + emac_link_input_cb_t emac_link_input_cb; /**< Callback for incoming data */ + emac_link_state_change_cb_t emac_link_state_cb; /**< Link state change callback */ + EMACMemoryManager *memory_manager; /**< Memory manager */ + int phy_task_handle; /**< Handle for phy task event */ + struct PHY_STATE { + int connected; + phy_speed_t speed; + phy_duplex_t duplex; + }; + PHY_STATE prev_state; + uint8_t hwaddr[KINETIS_HWADDR_SIZE]; +}; + +#endif /* KINETIS_EMAC_H_ */ diff --git a/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/imx_emac_config.h b/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/imx_emac_config.h new file mode 100644 index 0000000000..a56fe41942 --- /dev/null +++ b/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/imx_emac_config.h @@ -0,0 +1,48 @@ +/* + * 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 KINETIS_EMAC_CONFIG_H__ +#define KINETIS_EMAC_CONFIG_H__ + +#include "fsl_enet.h" + +#define ENET_RX_RING_LEN MBED_CONF_KINETIS_EMAC_RX_RING_LEN +#define ENET_TX_RING_LEN MBED_CONF_KINETIS_EMAC_TX_RING_LEN + +#define ENET_ETH_MAX_FLEN (1522) // recommended size for a VLAN frame + +#define KINETIS_HWADDR_SIZE (6) + +#define KINETIS_ETH_MTU_SIZE 1500 +#define KINETIS_ETH_IF_NAME "en" + +#define THREAD_STACKSIZE 512 + +#endif // #define KINETIS_EMAC_CONFIG_H__ + diff --git a/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/mbed_lib.json b/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/mbed_lib.json new file mode 100644 index 0000000000..2e1ef2e320 --- /dev/null +++ b/features/netsocket/emac-drivers/TARGET_NXP_EMAC/TARGET_IMX/mbed_lib.json @@ -0,0 +1,7 @@ +{ + "name": "kinetis-emac", + "config": { + "rx-ring-len": 16, + "tx-ring-len": 8 + } +} diff --git a/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/TARGET_EVK/device.h b/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/TARGET_EVK/device.h index c6a2cc471f..1ef61d14a3 100644 --- a/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/TARGET_EVK/device.h +++ b/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/TARGET_EVK/device.h @@ -20,6 +20,7 @@ #define DEVICE_ID_LENGTH 24 #define BOARD_FLASH_SIZE (0x4000000U) +#define BOARD_ENET_PHY_ADDR (2) #include "objects.h" diff --git a/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/TARGET_EVK/fsl_phy.c b/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/TARGET_EVK/fsl_phy.c index 79b79138af..bbf37d8459 100644 --- a/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/TARGET_EVK/fsl_phy.c +++ b/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/TARGET_EVK/fsl_phy.c @@ -3,7 +3,7 @@ * Copyright (c) 2015, Freescale Semiconductor, Inc. * Copyright 2016-2017 NXP * All rights reserved. - * + * * Redistribution and use in source and binary forms, with or without modification, * are permitted (subject to the limitations in the disclaimer below) provided * that the following conditions are met: @@ -67,13 +67,10 @@ extern clock_ip_name_t s_enetClock[FSL_FEATURE_SOC_ENET_COUNT]; status_t PHY_Init(ENET_Type *base, uint32_t phyAddr, uint32_t srcClock_Hz) { - uint32_t bssReg; uint32_t counter = PHY_TIMEOUT_COUNT; uint32_t idReg = 0; status_t result = kStatus_Success; uint32_t instance = ENET_GetInstance(base); - uint32_t timeDelay; - uint32_t ctlReg = 0; #if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) /* Set SMI first. */ @@ -85,7 +82,7 @@ status_t PHY_Init(ENET_Type *base, uint32_t phyAddr, uint32_t srcClock_Hz) while ((idReg != PHY_CONTROL_ID1) && (counter != 0)) { PHY_Read(base, phyAddr, PHY_ID1_REG, &idReg); - counter --; + counter --; } if (!counter) @@ -94,7 +91,6 @@ status_t PHY_Init(ENET_Type *base, uint32_t phyAddr, uint32_t srcClock_Hz) } /* Reset PHY. */ - counter = PHY_TIMEOUT_COUNT; result = PHY_Write(base, phyAddr, PHY_BASICCONTROL_REG, PHY_BCTL_RESET_MASK); if (result == kStatus_Success) { @@ -111,40 +107,50 @@ status_t PHY_Init(ENET_Type *base, uint32_t phyAddr, uint32_t srcClock_Hz) { return result; } -#endif /* FSL_FEATURE_PHYKSZ8081_USE_RMII50M_MODE */ - - /* Set the negotiation. */ - result = PHY_Write(base, phyAddr, PHY_AUTONEG_ADVERTISE_REG, - (PHY_100BASETX_FULLDUPLEX_MASK | PHY_100BASETX_HALFDUPLEX_MASK | - PHY_10BASETX_FULLDUPLEX_MASK | PHY_10BASETX_HALFDUPLEX_MASK | 0x1U)); +#endif /* FSL_FEATURE_PHYKSZ8081_USE_RMII50M_MODE */ + } + return result; +} + +status_t PHY_AutoNegotiation(ENET_Type *base, uint32_t phyAddr) +{ + status_t result = kStatus_Success; + uint32_t bssReg; + uint32_t counter = PHY_TIMEOUT_COUNT; + uint32_t timeDelay; + uint32_t ctlReg = 0; + + /* Set the negotiation. */ + result = PHY_Write(base, phyAddr, PHY_AUTONEG_ADVERTISE_REG, + (PHY_100BASETX_FULLDUPLEX_MASK | PHY_100BASETX_HALFDUPLEX_MASK | + PHY_10BASETX_FULLDUPLEX_MASK | PHY_10BASETX_HALFDUPLEX_MASK | 0x1U)); + if (result == kStatus_Success) + { + result = PHY_Write(base, phyAddr, PHY_BASICCONTROL_REG, + (PHY_BCTL_AUTONEG_MASK | PHY_BCTL_RESTART_AUTONEG_MASK)); if (result == kStatus_Success) { - result = PHY_Write(base, phyAddr, PHY_BASICCONTROL_REG, - (PHY_BCTL_AUTONEG_MASK | PHY_BCTL_RESTART_AUTONEG_MASK)); - if (result == kStatus_Success) + /* Check auto negotiation complete. */ + while (counter --) { - /* Check auto negotiation complete. */ - while (counter --) + result = PHY_Read(base, phyAddr, PHY_BASICSTATUS_REG, &bssReg); + if ( result == kStatus_Success) { - result = PHY_Read(base, phyAddr, PHY_BASICSTATUS_REG, &bssReg); - if ( result == kStatus_Success) + PHY_Read(base, phyAddr, PHY_CONTROL1_REG, &ctlReg); + if (((bssReg & PHY_BSTATUS_AUTONEGCOMP_MASK) != 0) && (ctlReg & PHY_LINK_READY_MASK)) { - PHY_Read(base, phyAddr, PHY_CONTROL1_REG, &ctlReg); - if (((bssReg & PHY_BSTATUS_AUTONEGCOMP_MASK) != 0) && (ctlReg & PHY_LINK_READY_MASK)) + /* Wait a moment for Phy status stable. */ + for (timeDelay = 0; timeDelay < PHY_TIMEOUT_COUNT; timeDelay ++) { - /* Wait a moment for Phy status stable. */ - for (timeDelay = 0; timeDelay < PHY_TIMEOUT_COUNT; timeDelay ++) - { - __ASM("nop"); - } - break; + __ASM("nop"); } + break; } + } - if (!counter) - { - return kStatus_PHY_AutoNegotiateFail; - } + if (!counter) + { + return kStatus_PHY_AutoNegotiateFail; } } } @@ -236,7 +242,7 @@ status_t PHY_EnableLoopback(ENET_Type *base, uint32_t phyAddr, phy_loop_t mode, } else { - data = PHY_BCTL_DUPLEX_MASK | PHY_BCTL_LOOP_MASK; + data = PHY_BCTL_DUPLEX_MASK | PHY_BCTL_LOOP_MASK; } return PHY_Write(base, phyAddr, PHY_BASICCONTROL_REG, data); } diff --git a/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/TARGET_EVK/fsl_phy.h b/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/TARGET_EVK/fsl_phy.h index f5d9e6c3f1..027a345366 100644 --- a/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/TARGET_EVK/fsl_phy.h +++ b/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/TARGET_EVK/fsl_phy.h @@ -149,6 +149,16 @@ extern "C" { */ status_t PHY_Init(ENET_Type *base, uint32_t phyAddr, uint32_t srcClock_Hz); +/*! + * @brief Initiates auto negotiation. + * + * @param base ENET peripheral base address. + * @param phyAddr The PHY address. + * @retval kStatus_Success PHY auto negotiation success + * @retval kStatus_PHY_AutoNegotiateFail PHY auto negotiate fail + */ +status_t PHY_AutoNegotiation(ENET_Type *base, uint32_t phyAddr); + /*! * @brief PHY Write function. This function write data over the SMI to * the specified PHY register. This function is called by all PHY interfaces. diff --git a/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/drivers/fsl_enet.c b/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/drivers/fsl_enet.c index d44b73eb94..5161963c55 100644 --- a/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/drivers/fsl_enet.c +++ b/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/drivers/fsl_enet.c @@ -3,7 +3,7 @@ * Copyright (c) 2015 - 2016, Freescale Semiconductor, Inc. * Copyright 2016-2017 NXP * All rights reserved. - * + * * Redistribution and use in source and binary forms, with or without modification, * are permitted (subject to the limitations in the disclaimer below) provided * that the following conditions are met: @@ -347,12 +347,12 @@ void ENET_GetDefaultConfig(enet_config_t *config) memset(config, 0, sizeof(enet_config_t)); /* Sets MII mode, full duplex, 100Mbps for MAC and PHY data interface. */ -#if defined(FSL_FEATURE_ENET_HAS_AVB) && FSL_FEATURE_ENET_HAS_AVB +#if defined(FSL_FEATURE_ENET_HAS_AVB) && FSL_FEATURE_ENET_HAS_AVB config->miiMode = kENET_RgmiiMode; #else config->miiMode = kENET_RmiiMode; #endif - config->miiSpeed = kENET_MiiSpeed100M; + config->miiSpeed = kENET_MiiSpeed100M; config->miiDuplex = kENET_MiiFullDuplex; config->ringNum = 1; @@ -443,6 +443,7 @@ static void ENET_SetHandler(ENET_Type *base, handle->rxBuffSizeAlign[count] = buffCfg->rxBuffSizeAlign; handle->txBdBase[count] = buffCfg->txBdStartAddrAlign; handle->txBdCurrent[count] = buffCfg->txBdStartAddrAlign; + handle->txBdDirty[count] = buffCfg->txBdStartAddrAlign; handle->txBuffSizeAlign[count] = buffCfg->txBuffSizeAlign; buffCfg++; } @@ -513,7 +514,7 @@ static void ENET_SetMacController(ENET_Type *base, ((macSpecialConfig & kENET_ControlRxPadRemoveEnable) ? ENET_RCR_PADEN_MASK : 0) | ((macSpecialConfig & kENET_ControlRxBroadCastRejectEnable) ? ENET_RCR_BC_REJ_MASK : 0) | ((macSpecialConfig & kENET_ControlPromiscuousEnable) ? ENET_RCR_PROM_MASK : 0) | - ENET_RCR_MAX_FL(maxFrameLen) | ENET_RCR_CRCFWD_MASK; + ENET_RCR_MAX_FL(maxFrameLen) | ENET_RCR_CRCFWD_MASK; /* Set the RGMII or RMII, MII mode and control register. */ #if defined(FSL_FEATURE_ENET_HAS_AVB) && FSL_FEATURE_ENET_HAS_AVB @@ -609,11 +610,11 @@ static void ENET_SetMacController(ENET_Type *base, /* Initializes the ring 0. */ #if defined(FSL_FEATURE_MEMORY_HAS_ADDRESS_OFFSET) && FSL_FEATURE_MEMORY_HAS_ADDRESS_OFFSET base->TDSR = MEMORY_ConvertMemoryMapAddress((uint32_t)bufferConfig->txBdStartAddrAlign, kMEMORY_Local2DMA); - base->RDSR = MEMORY_ConvertMemoryMapAddress((uint32_t)bufferConfig->rxBdStartAddrAlign, kMEMORY_Local2DMA); + base->RDSR = MEMORY_ConvertMemoryMapAddress((uint32_t)bufferConfig->rxBdStartAddrAlign, kMEMORY_Local2DMA); #else base->TDSR = (uint32_t)bufferConfig->txBdStartAddrAlign; base->RDSR = (uint32_t)bufferConfig->rxBdStartAddrAlign; -#endif +#endif base->MRBR = bufferConfig->rxBuffSizeAlign; #if defined(FSL_FEATURE_ENET_HAS_AVB) && FSL_FEATURE_ENET_HAS_AVB @@ -628,7 +629,7 @@ static void ENET_SetMacController(ENET_Type *base, base->RDSR1 = MEMORY_ConvertMemoryMapAddress((uint32_t)buffCfg->rxBdStartAddrAlign, kMEMORY_Local2DMA); #else base->TDSR1 = (uint32_t)buffCfg->txBdStartAddrAlign; - base->RDSR1 = (uint32_t)buffCfg->rxBdStartAddrAlign; + base->RDSR1 = (uint32_t)buffCfg->rxBdStartAddrAlign; #endif base->MRBR1 = buffCfg->rxBuffSizeAlign; /* Enable the DMAC for ring 1 and with no rx classification set. */ @@ -725,7 +726,7 @@ static void ENET_SetTxBufferDescriptors(enet_handle_t *handle, const enet_config /* Check the input parameters. */ for (ringNum = 0; ringNum < config->ringNum; ringNum++) { - if ((buffCfg->txBdStartAddrAlign > 0) && (buffCfg->txBufferAlign > 0)) + if (buffCfg->txBdStartAddrAlign > 0) { volatile enet_tx_bd_struct_t *curBuffDescrip = buffCfg->txBdStartAddrAlign; txBuffSizeAlign = buffCfg->txBuffSizeAlign; @@ -814,7 +815,7 @@ static void ENET_SetRxBufferDescriptors(enet_handle_t *handle, const enet_config for (count = 0; count < buffCfg->rxBdNumber; count++) { /* Set data buffer and the length. */ - curBuffDescrip->buffer = (uint8_t *)((uint32_t)&rxBuffer[count * rxBuffSizeAlign]); + curBuffDescrip->buffer = (uint8_t *)(*((uint32_t *)(rxBuffer + count * 4))); curBuffDescrip->length = 0; /* Initializes the buffer descriptors with empty bit. */ @@ -1194,14 +1195,14 @@ status_t ENET_ReadFrame(ENET_Type *base, enet_handle_t *handle, uint8_t *data, u address = MEMORY_ConvertMemoryMapAddress((uint32_t)curBuffDescrip->buffer,kMEMORY_DMA2Local); #else address = (uint32_t)curBuffDescrip->buffer; -#endif /* FSL_FEATURE_MEMORY_HAS_ADDRESS_OFFSET */ +#endif /* FSL_FEATURE_MEMORY_HAS_ADDRESS_OFFSET */ #if defined(FSL_SDK_ENABLE_DRIVER_CACHE_CONTROL) && FSL_SDK_ENABLE_DRIVER_CACHE_CONTROL /* Add the cache invalidate maintain. */ DCACHE_InvalidateByRange(address, handle->rxBuffSizeAlign[0]); -#endif /* FSL_SDK_ENABLE_DRIVER_CACHE_CONTROL */ +#endif /* FSL_SDK_ENABLE_DRIVER_CACHE_CONTROL */ #ifdef ENET_ENHANCEDBUFFERDESCRIPTOR_MODE enet_ptp_time_data_t ptpTimestamp; - bool isPtpEventMessage = false; + bool isPtpEventMessage = false; /* Parse the PTP message according to the header message. */ isPtpEventMessage = ENET_Ptp1588ParseFrame((uint8_t *)address, &ptpTimestamp, false); #endif /* ENET_ENHANCEDBUFFERDESCRIPTOR_MODE */ @@ -1262,8 +1263,8 @@ status_t ENET_ReadFrame(ENET_Type *base, enet_handle_t *handle, uint8_t *data, u address = MEMORY_ConvertMemoryMapAddress((uint32_t)curBuffDescrip->buffer,kMEMORY_DMA2Local); #else address = (uint32_t)curBuffDescrip->buffer; -#endif /* FSL_FEATURE_MEMORY_HAS_ADDRESS_OFFSET */ -#if defined(FSL_SDK_ENABLE_DRIVER_CACHE_CONTROL) && FSL_SDK_ENABLE_DRIVER_CACHE_CONTROL +#endif /* FSL_FEATURE_MEMORY_HAS_ADDRESS_OFFSET */ +#if defined(FSL_SDK_ENABLE_DRIVER_CACHE_CONTROL) && FSL_SDK_ENABLE_DRIVER_CACHE_CONTROL DCACHE_InvalidateByRange(address, handle->rxBuffSizeAlign[0]); #endif /* FSL_SDK_ENABLE_DRIVER_CACHE_CONTROL */ } @@ -1414,7 +1415,7 @@ status_t ENET_SendFrame(ENET_Type *base, enet_handle_t *handle, const uint8_t *d address = MEMORY_ConvertMemoryMapAddress((uint32_t)curBuffDescrip->buffer,kMEMORY_DMA2Local); #else address = (uint32_t)curBuffDescrip->buffer; -#endif /* FSL_FEATURE_MEMORY_HAS_ADDRESS_OFFSET */ +#endif /* FSL_FEATURE_MEMORY_HAS_ADDRESS_OFFSET */ if (sizeleft > handle->txBuffSizeAlign[0]) { /* Data copy. */ @@ -1439,10 +1440,10 @@ status_t ENET_SendFrame(ENET_Type *base, enet_handle_t *handle, const uint8_t *d #if defined(FSL_SDK_ENABLE_DRIVER_CACHE_CONTROL) && FSL_SDK_ENABLE_DRIVER_CACHE_CONTROL /* Add the cache clean maintain. */ DCACHE_CleanByRange(address, sizeleft); -#endif /* FSL_SDK_ENABLE_DRIVER_CACHE_CONTROL */ +#endif /* FSL_SDK_ENABLE_DRIVER_CACHE_CONTROL */ curBuffDescrip->length = sizeleft; /* Set Last buffer wrap flag. */ - curBuffDescrip->control |= ENET_BUFFDESCRIPTOR_TX_READY_MASK | ENET_BUFFDESCRIPTOR_TX_LAST_MASK; + curBuffDescrip->control |= ENET_BUFFDESCRIPTOR_TX_READY_MASK | ENET_BUFFDESCRIPTOR_TX_LAST_MASK; /* Active the transmit buffer descriptor. */ ENET_ActiveSend(base, 0); @@ -1560,7 +1561,7 @@ status_t ENET_GetRxFrameSizeMultiRing(enet_handle_t *handle, uint32_t *length, u if ((!(curBuffDescrip->control & ENET_BUFFDESCRIPTOR_RX_EMPTY_MASK)) && (!curBuffDescrip->length)) { return kStatus_ENET_RxFrameError; - } + } /* Find the last buffer descriptor. */ if ((curBuffDescrip->control & validLastMask) == ENET_BUFFDESCRIPTOR_RX_LAST_MASK) { @@ -2011,7 +2012,7 @@ status_t ENET_GetTxErrAfterSendFrame(enet_handle_t *handle, enet_data_error_stat return kStatus_ENET_TxFrameFail; } -#if FSL_FEATURE_ENET_QUEUE > 1 +#if FSL_FEATURE_ENET_QUEUE > 1 status_t ENET_GetTxErrAfterSendFrameMultiRing(enet_handle_t *handle, enet_data_error_stats_t *eErrorStatic, uint32_t ringId) { @@ -2103,7 +2104,7 @@ static bool ENET_Ptp1588ParseFrame(const uint8_t *data, enet_ptp_time_data_t *pt #if defined(FSL_FEATUR_ENET_HAS_AVB) && FSL_FEATURE_HAS_AVB if (*(uint16_t *)(buffer + ENET_PTP1588_ETHL2_PACKETTYPE_OFFSET) == ENET_HTONS(ENET_8021QVLAN) { - buffer += ENET_FRAME_VLAN_TAGLEN; + buffer += ENET_FRAME_VLAN_TAGLEN; } #endif /* FSL_FEATURE_ENET_HAS_AVB */ } @@ -2445,7 +2446,7 @@ static status_t ENET_StoreTxFrameTime(ENET_Type *base, enet_handle_t *handle, ui isPtpEventMessage = ENET_Ptp1588ParseFrame((uint8_t *)address, &ptpTimeData, false); if (isPtpEventMessage) { - /* Only store tx timestamp for ptp event message. */ + /* Only store tx timestamp for ptp event message. */ do { /* Increase current buffer descriptor to the next one. */ @@ -2512,7 +2513,7 @@ static status_t ENET_StoreTxFrameTime(ENET_Type *base, enet_handle_t *handle, ui else { handle->txBdDirtyTime[ringId]++; - } + } } return kStatus_Success; } @@ -2874,7 +2875,7 @@ void ENET_DriverIRQHandler(void) exception return operation might vector to incorrect interrupt */ #if defined __CORTEX_M && (__CORTEX_M == 4U) __DSB(); -#endif +#endif /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping exception return operation might vector to incorrect interrupt */ #if defined __CORTEX_M && (__CORTEX_M == 4U) @@ -2885,7 +2886,7 @@ void ENET_DriverIRQHandler(void) #endif -#if defined(ENET1) +#if defined(ENET1) void ENET1_DriverIRQHandler(void) { ENET_CommonFrame0IRQHandler(ENET1); @@ -2910,7 +2911,7 @@ void ENET2_DriverIRQHandler(void) #endif -#if defined(CONNECTIVITY__ENET0) +#if defined(CONNECTIVITY__ENET0) void CONNECTIVITY_ENET0_FRAME0_EVENT_INT_DriverIRQHandler(void) { ENET_CommonFrame0IRQHandler(CONNECTIVITY__ENET0); diff --git a/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/drivers/fsl_enet.h b/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/drivers/fsl_enet.h index 3538bca2f2..b0c9adafe4 100644 --- a/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/drivers/fsl_enet.h +++ b/targets/TARGET_NXP/TARGET_MCUXpresso_MCUS/TARGET_MIMXRT1050/drivers/fsl_enet.h @@ -648,6 +648,8 @@ struct _enet_handle *txBdBase[FSL_FEATURE_ENET_QUEUE]; /*!< Transmit buffer descriptor base address pointer. */ volatile enet_tx_bd_struct_t *txBdCurrent[FSL_FEATURE_ENET_QUEUE]; /*!< The current available transmit buffer descriptor pointer. */ + volatile enet_tx_bd_struct_t + *txBdDirty[FSL_FEATURE_ENET_QUEUE]; /*!< The dirty transmit buffer descriptor needed to be updated from. */ uint32_t rxBuffSizeAlign[FSL_FEATURE_ENET_QUEUE]; /*!< Receive buffer size alignment. */ uint32_t txBuffSizeAlign[FSL_FEATURE_ENET_QUEUE]; /*!< Transmit buffer size alignment. */ uint8_t ringNum; /*!< Number of used rings. */ @@ -707,9 +709,9 @@ void ENET_GetDefaultConfig(enet_config_t *config); * The buffer configuration should be prepared for ENET Initialization. * It is the start address of "ringNum" enet_buffer_config structures. * To support added multi-ring features in some soc and compatible with the previous - * enet driver version. For single ring supported, this bufferConfig is a buffer - * configure structure pointer, for multi-ring supported and used case, this bufferConfig - * pointer should be a buffer configure structure array pointer. + * enet driver version. For single ring supported, this bufferConfig is a buffer + * configure structure pointer, for multi-ring supported and used case, this bufferConfig + * pointer should be a buffer configure structure array pointer. * @param macAddr ENET mac address of Ethernet device. This MAC address should be * provided. * @param srcClock_Hz The internal module clock source for MII clock. diff --git a/targets/targets.json b/targets/targets.json index faf3a22b9e..d670365587 100644 --- a/targets/targets.json +++ b/targets/targets.json @@ -1738,7 +1738,7 @@ "supported_form_factors": ["ARDUINO"], "core": "Cortex-M7FD", "supported_toolchains": ["ARM", "GCC_ARM", "IAR"], - "extra_labels": ["NXP", "MCUXpresso_MCUS", "EVK", "MIMXRT1050", "IMX"], + "extra_labels": ["NXP", "MCUXpresso_MCUS", "EVK", "MIMXRT1050", "IMX", "NXP_EMAC"], "is_disk_virtual": true, "macros": [ "CPU_MIMXRT1052DVL6B", @@ -1746,7 +1746,9 @@ "XIP_BOOT_HEADER_ENABLE=1", "XIP_EXTERNAL_FLASH=1", "XIP_BOOT_HEADER_DCD_ENABLE=1", - "SKIP_SYSCLK_INIT" + "SKIP_SYSCLK_INIT", + "FSL_FEATURE_PHYKSZ8081_USE_RMII50M_MODE", + "SDRAM_IS_SHAREABLE" ], "inherits": ["Target"], "detect_code": ["0227"], @@ -1756,6 +1758,7 @@ "USTICKER", "LPTICKER", "ANALOGIN", + "EMAC", "I2C", "I2CSLAVE", "ERROR_RED", @@ -1770,7 +1773,11 @@ "STDIO_MESSAGES" ], "release_versions": ["2", "5"], - "device_name": "MIMXRT1052" + "features": ["LWIP"], + "device_name": "MIMXRT1052", + "overrides": { + "network-default-interface-type": "ETHERNET" + } }, "LPC54114": { "supported_form_factors": ["ARDUINO"],