Browse Source

[bsp] add enet driver for k64 FRDM

tanek liang 7 năm trước cách đây
mục cha
commit
a2d56fb5d9

+ 13 - 2
bsp/frdm-k64f/board/SConscript

@@ -3,8 +3,19 @@ Import('rtconfig')
 from building import *
 
 cwd     = os.path.join(str(Dir('#')), 'board')
-src	= Glob('*.c')
-src	+= Glob('*.s')
+
+# add the general drivers.
+src = Split("""
+board.c
+clock_config.c
+drv_uart.c
+led.c
+""")
+
+# add Ethernet drivers.
+if GetDepend('RT_USING_LWIP'):
+    src += ['drv_emac.c', 'fsl_phy.c']
+
 CPPPATH = [cwd]
 
 group = DefineGroup('Board', src, depend = [''], CPPPATH = CPPPATH)

+ 3 - 1
bsp/frdm-k64f/board/board.c

@@ -18,7 +18,7 @@
 #include "board.h"
 
 #include "drv_uart.h"
-
+#include "clock_config.h"
 
 /**
  * @addtogroup K64
@@ -73,6 +73,8 @@ void rt_hw_board_init()
 {
     /* NVIC Configuration */
     NVIC_Configuration();
+    
+    BOARD_BootClockRUN();
 
     /* Configure the SysTick */
     SysTick_Configuration();

+ 311 - 0
bsp/frdm-k64f/board/clock_config.c

@@ -0,0 +1,311 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ *
+ * 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 the copyright holder 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.
+ */
+
+/*
+ * How to setup clock using clock driver functions:
+ *
+ * 1. CLOCK_SetSimSafeDivs, to make sure core clock, bus clock, flexbus clock
+ *    and flash clock are in allowed range during clock mode switch.
+ *
+ * 2. Call CLOCK_Osc0Init to setup OSC clock, if it is used in target mode.
+ *
+ * 3. Set MCG configuration, MCG includes three parts: FLL clock, PLL clock and
+ *    internal reference clock(MCGIRCLK). Follow the steps to setup:
+ *
+ *    1). Call CLOCK_BootToXxxMode to set MCG to target mode.
+ *
+ *    2). If target mode is FBI/BLPI/PBI mode, the MCGIRCLK has been configured
+ *        correctly. For other modes, need to call CLOCK_SetInternalRefClkConfig
+ *        explicitly to setup MCGIRCLK.
+ *
+ *    3). Don't need to configure FLL explicitly, because if target mode is FLL
+ *        mode, then FLL has been configured by the function CLOCK_BootToXxxMode,
+ *        if the target mode is not FLL mode, the FLL is disabled.
+ *
+ *    4). If target mode is PEE/PBE/PEI/PBI mode, then the related PLL has been
+ *        setup by CLOCK_BootToXxxMode. In FBE/FBI/FEE/FBE mode, the PLL could
+ *        be enabled independently, call CLOCK_EnablePll0 explicitly in this case.
+ *
+ * 4. Call CLOCK_SetSimConfig to set the clock configuration in SIM.
+ */
+
+/* TEXT BELOW IS USED AS SETTING FOR THE CLOCKS TOOL *****************************
+!!ClocksProfile
+product: Clocks v1.0
+processor: MK64FN1M0xxx12
+package_id: MK64FN1M0VLL12
+mcu_data: ksdk2_0
+processor_version: 1.0.1
+board: FRDM-K64F
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR THE CLOCKS TOOL **/
+
+#include "fsl_smc.h"
+#include "clock_config.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+#define MCG_PLL_DISABLE                                   0U  /*!< MCGPLLCLK disabled */
+#define OSC_CAP0P                                         0U  /*!< Oscillator 0pF capacitor load */
+#define OSC_ER_CLK_DISABLE                                0U  /*!< Disable external reference clock */
+#define SIM_OSC32KSEL_RTC32KCLK_CLK                       2U  /*!< OSC32KSEL select: RTC32KCLK clock (32.768kHz) */
+#define SIM_PLLFLLSEL_IRC48MCLK_CLK                       3U  /*!< PLLFLL select: IRC48MCLK clock */
+#define SIM_PLLFLLSEL_MCGPLLCLK_CLK                       1U  /*!< PLLFLL select: MCGPLLCLK clock */
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+/* System clock frequency. */
+extern uint32_t SystemCoreClock;
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+/*FUNCTION**********************************************************************
+ *
+ * Function Name : CLOCK_CONFIG_SetFllExtRefDiv
+ * Description   : Configure FLL external reference divider (FRDIV).
+ * Param frdiv   : The value to set FRDIV.
+ *
+ *END**************************************************************************/
+static void CLOCK_CONFIG_SetFllExtRefDiv(uint8_t frdiv)
+{
+    MCG->C1 = ((MCG->C1 & ~MCG_C1_FRDIV_MASK) | MCG_C1_FRDIV(frdiv));
+}
+
+/*******************************************************************************
+ ********************** Configuration BOARD_BootClockRUN ***********************
+ ******************************************************************************/
+/* TEXT BELOW IS USED AS SETTING FOR THE CLOCKS TOOL *****************************
+!!Configuration
+name: BOARD_BootClockRUN
+outputs:
+- {id: Bus_clock.outFreq, value: 60 MHz}
+- {id: Core_clock.outFreq, value: 120 MHz, locked: true, accuracy: '0.001'}
+- {id: Flash_clock.outFreq, value: 24 MHz}
+- {id: FlexBus_clock.outFreq, value: 40 MHz}
+- {id: LPO_clock.outFreq, value: 1 kHz}
+- {id: MCGFFCLK.outFreq, value: 1.5625 MHz}
+- {id: MCGIRCLK.outFreq, value: 32.768 kHz}
+- {id: OSCERCLK.outFreq, value: 50 MHz}
+- {id: PLLFLLCLK.outFreq, value: 120 MHz}
+- {id: System_clock.outFreq, value: 120 MHz}
+settings:
+- {id: MCGMode, value: PEE}
+- {id: MCG.FCRDIV.scale, value: '1', locked: true}
+- {id: MCG.FRDIV.scale, value: '32'}
+- {id: MCG.IREFS.sel, value: MCG.FRDIV}
+- {id: MCG.PLLS.sel, value: MCG.PLL}
+- {id: MCG.PRDIV.scale, value: '20', locked: true}
+- {id: MCG.VDIV.scale, value: '48', locked: true}
+- {id: MCG_C1_IRCLKEN_CFG, value: Enabled}
+- {id: MCG_C2_RANGE0_CFG, value: Very_high}
+- {id: MCG_C2_RANGE0_FRDIV_CFG, value: Very_high}
+- {id: OSC_CR_ERCLKEN_CFG, value: Enabled}
+- {id: RTCCLKOUTConfig, value: 'yes'}
+- {id: RTC_CR_OSCE_CFG, value: Enabled}
+- {id: RTC_CR_OSC_CAP_LOAD_CFG, value: SC10PF}
+- {id: SIM.OSC32KSEL.sel, value: RTC.RTC32KCLK}
+- {id: SIM.OUTDIV2.scale, value: '2'}
+- {id: SIM.OUTDIV3.scale, value: '3'}
+- {id: SIM.OUTDIV4.scale, value: '5'}
+- {id: SIM.PLLFLLSEL.sel, value: MCG.MCGPLLCLK}
+- {id: SIM.RTCCLKOUTSEL.sel, value: RTC.RTC32KCLK}
+- {id: SIM.SDHCSRCSEL.sel, value: OSC.OSCERCLK}
+- {id: SIM.TIMESRCSEL.sel, value: OSC.OSCERCLK}
+- {id: SIM.USBDIV.scale, value: '5'}
+- {id: SIM.USBFRAC.scale, value: '2'}
+- {id: SIM.USBSRCSEL.sel, value: SIM.USBDIV}
+sources:
+- {id: OSC.OSC.outFreq, value: 50 MHz, enabled: true}
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR THE CLOCKS TOOL **/
+
+/*******************************************************************************
+ * Variables for BOARD_BootClockRUN configuration
+ ******************************************************************************/
+const mcg_config_t mcgConfig_BOARD_BootClockRUN =
+    {
+        .mcgMode = kMCG_ModePEE,                  /* PEE - PLL Engaged External */
+        .irclkEnableMode = kMCG_IrclkEnable,      /* MCGIRCLK enabled, MCGIRCLK disabled in STOP mode */
+        .ircs = kMCG_IrcSlow,                     /* Slow internal reference clock selected */
+        .fcrdiv = 0x0U,                           /* Fast IRC divider: divided by 1 */
+        .frdiv = 0x0U,                            /* FLL reference clock divider: divided by 32 */
+        .drs = kMCG_DrsLow,                       /* Low frequency range */
+        .dmx32 = kMCG_Dmx32Default,               /* DCO has a default range of 25% */
+        .oscsel = kMCG_OscselOsc,                 /* Selects System Oscillator (OSCCLK) */
+        .pll0Config =
+            {
+                .enableMode = MCG_PLL_DISABLE,    /* MCGPLLCLK disabled */
+                .prdiv = 0x13U,                   /* PLL Reference divider: divided by 20 */
+                .vdiv = 0x18U,                    /* VCO divider: multiplied by 48 */
+            },
+    };
+const sim_clock_config_t simConfig_BOARD_BootClockRUN =
+    {
+        .pllFllSel = SIM_PLLFLLSEL_MCGPLLCLK_CLK, /* PLLFLL select: MCGPLLCLK clock */
+        .er32kSrc = SIM_OSC32KSEL_RTC32KCLK_CLK,  /* OSC32KSEL select: RTC32KCLK clock (32.768kHz) */
+        .clkdiv1 = 0x1240000U,                    /* SIM_CLKDIV1 - OUTDIV1: /1, OUTDIV2: /2, OUTDIV3: /3, OUTDIV4: /5 */
+    };
+const osc_config_t oscConfig_BOARD_BootClockRUN =
+    {
+        .freq = 50000000U,                        /* Oscillator frequency: 50000000Hz */
+        .capLoad = (OSC_CAP0P),                   /* Oscillator capacity load: 0pF */
+        .workMode = kOSC_ModeExt,                 /* Use external clock */
+        .oscerConfig =
+            {
+                .enableMode = kOSC_ErClkEnable,   /* Enable external reference clock, disable external reference clock in STOP mode */
+            }
+    };
+
+/*******************************************************************************
+ * Code for BOARD_BootClockRUN configuration
+ ******************************************************************************/
+void BOARD_BootClockRUN(void)
+{
+    /* Set the system clock dividers in SIM to safe value. */
+    CLOCK_SetSimSafeDivs();
+    /* Initializes OSC0 according to board configuration. */
+    CLOCK_InitOsc0(&oscConfig_BOARD_BootClockRUN);
+    CLOCK_SetXtal0Freq(oscConfig_BOARD_BootClockRUN.freq);
+    /* Configure the Internal Reference clock (MCGIRCLK). */
+    CLOCK_SetInternalRefClkConfig(mcgConfig_BOARD_BootClockRUN.irclkEnableMode,
+                                  mcgConfig_BOARD_BootClockRUN.ircs, 
+                                  mcgConfig_BOARD_BootClockRUN.fcrdiv);
+    /* Configure FLL external reference divider (FRDIV). */
+    CLOCK_CONFIG_SetFllExtRefDiv(mcgConfig_BOARD_BootClockRUN.frdiv);
+    /* Set MCG to PEE mode. */
+    CLOCK_BootToPeeMode(mcgConfig_BOARD_BootClockRUN.oscsel,
+                        kMCG_PllClkSelPll0,
+                        &mcgConfig_BOARD_BootClockRUN.pll0Config);
+    /* Set the clock configuration in SIM module. */
+    CLOCK_SetSimConfig(&simConfig_BOARD_BootClockRUN);
+    /* Set SystemCoreClock variable. */
+    SystemCoreClock = BOARD_BOOTCLOCKRUN_CORE_CLOCK;
+}
+
+/*******************************************************************************
+ ********************* Configuration BOARD_BootClockVLPR ***********************
+ ******************************************************************************/
+/* TEXT BELOW IS USED AS SETTING FOR THE CLOCKS TOOL *****************************
+!!Configuration
+name: BOARD_BootClockVLPR
+outputs:
+- {id: Bus_clock.outFreq, value: 4 MHz}
+- {id: Core_clock.outFreq, value: 4 MHz, locked: true, accuracy: '0.001'}
+- {id: Flash_clock.outFreq, value: 800 kHz}
+- {id: FlexBus_clock.outFreq, value: 4 MHz}
+- {id: LPO_clock.outFreq, value: 1 kHz}
+- {id: MCGIRCLK.outFreq, value: 4 MHz}
+- {id: System_clock.outFreq, value: 4 MHz}
+settings:
+- {id: MCGMode, value: BLPI}
+- {id: powerMode, value: VLPR}
+- {id: MCG.CLKS.sel, value: MCG.IRCS}
+- {id: MCG.FCRDIV.scale, value: '1'}
+- {id: MCG.FRDIV.scale, value: '32'}
+- {id: MCG.IRCS.sel, value: MCG.FCRDIV}
+- {id: MCG_C1_IRCLKEN_CFG, value: Enabled}
+- {id: MCG_C2_RANGE0_CFG, value: Very_high}
+- {id: MCG_C2_RANGE0_FRDIV_CFG, value: Very_high}
+- {id: RTC_CR_OSCE_CFG, value: Enabled}
+- {id: RTC_CR_OSC_CAP_LOAD_CFG, value: SC10PF}
+- {id: SIM.OSC32KSEL.sel, value: RTC.RTC32KCLK}
+- {id: SIM.OUTDIV3.scale, value: '1'}
+- {id: SIM.OUTDIV4.scale, value: '5'}
+- {id: SIM.PLLFLLSEL.sel, value: IRC48M.IRC48MCLK}
+- {id: SIM.RTCCLKOUTSEL.sel, value: RTC.RTC32KCLK}
+sources:
+- {id: OSC.OSC.outFreq, value: 50 MHz}
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR THE CLOCKS TOOL **/
+
+/*******************************************************************************
+ * Variables for BOARD_BootClockVLPR configuration
+ ******************************************************************************/
+const mcg_config_t mcgConfig_BOARD_BootClockVLPR =
+    {
+        .mcgMode = kMCG_ModeBLPI,                 /* BLPI - Bypassed Low Power Internal */
+        .irclkEnableMode = kMCG_IrclkEnable,      /* MCGIRCLK enabled, MCGIRCLK disabled in STOP mode */
+        .ircs = kMCG_IrcFast,                     /* Fast internal reference clock selected */
+        .fcrdiv = 0x0U,                           /* Fast IRC divider: divided by 1 */
+        .frdiv = 0x0U,                            /* FLL reference clock divider: divided by 32 */
+        .drs = kMCG_DrsLow,                       /* Low frequency range */
+        .dmx32 = kMCG_Dmx32Default,               /* DCO has a default range of 25% */
+        .oscsel = kMCG_OscselOsc,                 /* Selects System Oscillator (OSCCLK) */
+        .pll0Config =
+            {
+                .enableMode = MCG_PLL_DISABLE,    /* MCGPLLCLK disabled */
+                .prdiv = 0x0U,                    /* PLL Reference divider: divided by 1 */
+                .vdiv = 0x0U,                     /* VCO divider: multiplied by 24 */
+            },
+    };
+const sim_clock_config_t simConfig_BOARD_BootClockVLPR =
+    {
+        .pllFllSel = SIM_PLLFLLSEL_IRC48MCLK_CLK, /* PLLFLL select: IRC48MCLK clock */
+        .er32kSrc = SIM_OSC32KSEL_RTC32KCLK_CLK,  /* OSC32KSEL select: RTC32KCLK clock (32.768kHz) */
+        .clkdiv1 = 0x40000U,                      /* SIM_CLKDIV1 - OUTDIV1: /1, OUTDIV2: /1, OUTDIV3: /1, OUTDIV4: /5 */
+    };
+const osc_config_t oscConfig_BOARD_BootClockVLPR =
+    {
+        .freq = 0U,                               /* Oscillator frequency: 0Hz */
+        .capLoad = (OSC_CAP0P),                   /* Oscillator capacity load: 0pF */
+        .workMode = kOSC_ModeExt,                 /* Use external clock */
+        .oscerConfig =
+            {
+                .enableMode = OSC_ER_CLK_DISABLE, /* Disable external reference clock */
+            }
+    };
+
+/*******************************************************************************
+ * Code for BOARD_BootClockVLPR configuration
+ ******************************************************************************/
+void BOARD_BootClockVLPR(void)
+{
+    /* Set the system clock dividers in SIM to safe value. */
+    CLOCK_SetSimSafeDivs();
+    /* Set MCG to BLPI mode. */
+    CLOCK_BootToBlpiMode(mcgConfig_BOARD_BootClockVLPR.fcrdiv,
+                         mcgConfig_BOARD_BootClockVLPR.ircs,
+                         mcgConfig_BOARD_BootClockVLPR.irclkEnableMode);
+    /* Set the clock configuration in SIM module. */
+    CLOCK_SetSimConfig(&simConfig_BOARD_BootClockVLPR);
+    /* Set VLPR power mode. */
+    SMC_SetPowerModeProtection(SMC, kSMC_AllowPowerModeAll);
+#if (defined(FSL_FEATURE_SMC_HAS_LPWUI) && FSL_FEATURE_SMC_HAS_LPWUI)
+    SMC_SetPowerModeVlpr(SMC, false);
+#else
+    SMC_SetPowerModeVlpr(SMC);
+#endif
+    while (SMC_GetPowerModeState(SMC) != kSMC_PowerStateVlpr)
+    {
+    }
+    /* Set SystemCoreClock variable. */
+    SystemCoreClock = BOARD_BOOTCLOCKVLPR_CORE_CLOCK;
+}
+

+ 112 - 0
bsp/frdm-k64f/board/clock_config.h

@@ -0,0 +1,112 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ *
+ * 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 the copyright holder 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 _CLOCK_CONFIG_H_
+#define _CLOCK_CONFIG_H_
+
+#include "fsl_common.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+#define BOARD_XTAL0_CLK_HZ                         50000000U  /*!< Board xtal0 frequency in Hz */
+
+/*******************************************************************************
+ ********************** Configuration BOARD_BootClockRUN ***********************
+ ******************************************************************************/
+/*******************************************************************************
+ * Definitions for BOARD_BootClockRUN configuration
+ ******************************************************************************/
+#define BOARD_BOOTCLOCKRUN_CORE_CLOCK             120000000U  /*!< Core clock frequency: 120000000Hz */
+
+/*! @brief MCG set for BOARD_BootClockRUN configuration.
+ */
+extern const mcg_config_t mcgConfig_BOARD_BootClockRUN;
+/*! @brief SIM module set for BOARD_BootClockRUN configuration.
+ */
+extern const sim_clock_config_t simConfig_BOARD_BootClockRUN;
+/*! @brief OSC set for BOARD_BootClockRUN configuration.
+ */
+extern const osc_config_t oscConfig_BOARD_BootClockRUN;
+
+/*******************************************************************************
+ * API for BOARD_BootClockRUN configuration
+ ******************************************************************************/
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus*/
+
+/*!
+ * @brief This function executes configuration of clocks.
+ *
+ */
+void BOARD_BootClockRUN(void);
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus*/
+
+/*******************************************************************************
+ ********************* Configuration BOARD_BootClockVLPR ***********************
+ ******************************************************************************/
+/*******************************************************************************
+ * Definitions for BOARD_BootClockVLPR configuration
+ ******************************************************************************/
+#define BOARD_BOOTCLOCKVLPR_CORE_CLOCK              4000000U  /*!< Core clock frequency: 4000000Hz */
+
+/*! @brief MCG set for BOARD_BootClockVLPR configuration.
+ */
+extern const mcg_config_t mcgConfig_BOARD_BootClockVLPR;
+/*! @brief SIM module set for BOARD_BootClockVLPR configuration.
+ */
+extern const sim_clock_config_t simConfig_BOARD_BootClockVLPR;
+/*! @brief OSC set for BOARD_BootClockVLPR configuration.
+ */
+extern const osc_config_t oscConfig_BOARD_BootClockVLPR;
+
+/*******************************************************************************
+ * API for BOARD_BootClockVLPR configuration
+ ******************************************************************************/
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus*/
+
+/*!
+ * @brief This function executes configuration of clocks.
+ *
+ */
+void BOARD_BootClockVLPR(void);
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus*/
+
+#endif /* _CLOCK_CONFIG_H_ */
+

+ 450 - 0
bsp/frdm-k64f/board/drv_emac.c

@@ -0,0 +1,450 @@
+/*
+ * File      : emac_drv.c
+ *             i.MX6 EMAC Ethernet driver
+ * COPYRIGHT (C) 2015, Shanghai Real-Thread Electronic Technology Co.,Ltd
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2015-07-15     Bernard      The first version
+ */
+
+#include <board.h>
+#include <rtthread.h>
+#include "drv_emac.h"
+
+#if defined(RT_USING_LWIP)
+
+#include <finsh.h>
+#include <stdint.h>
+#include <netif/ethernetif.h>
+#include <lwip/opt.h>
+
+#include "MK64F12.h"
+#include "fsl_port.h"
+#include "fsl_enet.h"
+#include "fsl_phy.h"
+
+//#define DRV_EMAC_DEBUG
+//#define DRV_EMAC_RX_DUMP
+//#define DRV_EMAC_TX_DUMP
+
+#ifdef DRV_EMAC_DEBUG
+#define DEBUG_PRINTF(...)          rt_kprintf(__VA_ARGS__)
+#else
+#define DEBUG_PRINTF(...)
+#endif
+
+#define MAX_ADDR_LEN                6    
+#define ENET_RX_RING_LEN            (16)
+#define ENET_TX_RING_LEN            (8)
+
+#define K64_EMAC_DEVICE(eth)        (struct emac_device*)(eth)
+
+#define ENET_ALIGN(x) \
+    ((unsigned int)((x) + ((ENET_BUFF_ALIGNMENT)-1)) & (unsigned int)(~(unsigned int)((ENET_BUFF_ALIGNMENT)-1)))
+
+#define ENET_RXBUFF_SIZE            (ENET_FRAME_MAX_FRAMELEN)
+#define ENET_TXBUFF_SIZE            (ENET_FRAME_MAX_FRAMELEN)
+#define ENET_ETH_MAX_FLEN           (1522) // recommended size for a VLAN frame
+    
+struct emac_device
+{
+    /* inherit from Ethernet device */
+    struct eth_device parent;
+    
+	ALIGN(64) enet_rx_bd_struct_t RxBuffDescrip[ENET_RX_RING_LEN];
+	ALIGN(64) enet_tx_bd_struct_t TxBuffDescrip[ENET_TX_RING_LEN];
+	ALIGN(64) uint8_t RxDataBuff[ENET_RX_RING_LEN * ENET_ALIGN(ENET_RXBUFF_SIZE)];
+	ALIGN(64) uint8_t TxDataBuff[ENET_TX_RING_LEN * ENET_ALIGN(ENET_TXBUFF_SIZE)];
+    
+    enet_handle_t enet_handle;
+    rt_uint8_t  dev_addr[MAX_ADDR_LEN];         /* MAC address  */
+    struct rt_semaphore tx_wait;
+};
+static struct emac_device _emac;
+
+static void setup_k64_io_enet(void)
+{
+    port_pin_config_t configENET = {0};
+
+#ifndef FEATURE_UVISOR
+    /* Disable MPU only when uVisor is not around. */
+    SYSMPU->CESR &= ~SYSMPU_CESR_VLD_MASK;
+#endif/*FEATURE_UVISOR*/
+
+    /* 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);
+}
+
+static void setup_enet_clock_init(void)
+{
+    CLOCK_EnableClock(kCLOCK_PortC);
+    CLOCK_EnableClock(kCLOCK_PortB);
+    
+    /* Select the Ethernet timestamp clock source */
+    CLOCK_SetEnetTime0Clock(0x2);
+}
+
+static void enet_mac_rx_isr(struct emac_device* emac)
+{
+    rt_err_t result;
+    
+    result = eth_device_ready(&(_emac.parent));
+    if( result != RT_EOK )
+    {
+        DEBUG_PRINTF("RX err =%d\n", result );
+    }
+}
+
+static void enet_mac_tx_isr(struct emac_device* emac)
+{
+    rt_sem_release(&emac->tx_wait);
+}
+
+static void ethernet_callback(ENET_Type *base, enet_handle_t *handle, enet_event_t event, void *param)
+{
+    struct emac_device* emac = param;
+    
+    switch (event)
+    {
+      case kENET_RxEvent:
+        enet_mac_rx_isr(emac);
+        break;
+      case kENET_TxEvent:
+        enet_mac_tx_isr(emac);
+        break;
+      default:
+        break;
+    }
+}
+
+static rt_err_t k64_emac_init(rt_device_t dev)
+{
+    struct emac_device* emac = K64_EMAC_DEVICE(dev);
+    enet_handle_t * enet_handle = &emac->enet_handle;
+    
+    bool link = false;
+    uint32_t phyAddr = 0;
+    phy_speed_t phy_speed;
+    phy_duplex_t phy_duplex;
+    uint32_t sysClock;
+    enet_buffer_config_t buffCfg;
+    enet_config_t config;
+
+    /* initialize config according to emac device */
+    setup_enet_clock_init();
+    /* enable iomux and clock */
+    setup_k64_io_enet();
+    
+    /* prepare the buffer configuration. */
+    buffCfg.rxBdNumber = ENET_RX_RING_LEN;                     /* Receive buffer descriptor number. */
+    buffCfg.txBdNumber = ENET_TX_RING_LEN;                     /* Transmit buffer descriptor number. */
+    buffCfg.rxBuffSizeAlign = ENET_ALIGN(ENET_RXBUFF_SIZE); /* Aligned receive data buffer size. */
+    buffCfg.txBuffSizeAlign = ENET_ALIGN(ENET_TXBUFF_SIZE); /* Aligned transmit data buffer size. */
+    buffCfg.rxBdStartAddrAlign = emac->RxBuffDescrip; /* Aligned receive buffer descriptor start address. */
+    buffCfg.txBdStartAddrAlign = emac->TxBuffDescrip; /* Aligned transmit buffer descriptor start address. */
+    buffCfg.rxBufferAlign = emac->RxDataBuff; /* Receive data buffer start address. */
+    buffCfg.txBufferAlign = emac->TxDataBuff; /* Transmit data buffer start address. */
+    
+    sysClock = CLOCK_GetFreq(kCLOCK_CoreSysClk);
+    DEBUG_PRINTF("sysClock: %d\n", sysClock);
+    
+    ENET_GetDefaultConfig(&config);
+    
+    PHY_Init(ENET, 0, CLOCK_GetFreq(kCLOCK_CoreSysClk));
+    if (PHY_GetLinkStatus(ENET, phyAddr, &link) == kStatus_Success)
+    {
+        if (link)
+        {
+            DEBUG_PRINTF("phy link up\n");
+            /* 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;
+        }
+        else
+        {
+            DEBUG_PRINTF("phy link down\n");
+        }
+        config.rxMaxFrameLen = ENET_ETH_MAX_FLEN;
+        config.macSpecialConfig = kENET_ControlFlowControlEnable;
+        config.txAccelerConfig = 0;
+        config.rxAccelerConfig = kENET_RxAccelMacCheckEnabled;
+        
+        ENET_Init(ENET, enet_handle, &config, &buffCfg, emac->dev_addr, sysClock);
+        ENET_SetCallback(enet_handle, ethernet_callback, emac);
+        ENET_ActiveRead(ENET);
+    }
+    else
+    {
+        DEBUG_PRINTF("read phy failed\n");
+    }
+    
+    return RT_EOK;
+}
+
+static rt_err_t k64_emac_open(rt_device_t dev, rt_uint16_t oflag)
+{
+    return RT_EOK;
+}
+
+static rt_err_t k64_emac_close(rt_device_t dev)
+{
+    return RT_EOK;
+}
+
+static rt_size_t k64_emac_read(rt_device_t dev, rt_off_t pos, void* buffer, rt_size_t size)
+{
+    rt_set_errno(-RT_ENOSYS);
+    return 0;
+}
+
+static rt_size_t k64_emac_write (rt_device_t dev, rt_off_t pos, const void* buffer, rt_size_t size)
+{
+    rt_set_errno(-RT_ENOSYS);
+    return 0;
+}
+
+static rt_err_t k64_emac_control(rt_device_t dev, rt_uint8_t cmd, void *args)
+{
+    struct emac_device *emac;
+
+	DEBUG_PRINTF("k64_emac_control\n");
+
+    emac = K64_EMAC_DEVICE(dev);
+    RT_ASSERT(emac != RT_NULL);
+
+    switch(cmd)
+    {
+    case NIOCTL_GADDR:
+        /* get MAC address */
+        if(args) rt_memcpy(args, emac->dev_addr, 6);
+        else return -RT_ERROR;
+        break;
+
+    default :
+        break;
+    }
+
+    return RT_EOK;
+}
+
+static rt_err_t k64_emac_tx(rt_device_t dev, struct pbuf* p)
+{
+    rt_err_t result = RT_EOK;
+
+    struct emac_device *emac = K64_EMAC_DEVICE(dev);
+    enet_handle_t * enet_handle = &emac->enet_handle;
+    
+    RT_ASSERT(p != NULL);
+
+	DEBUG_PRINTF("k64_emac_tx: %d\n", p->len);
+
+    emac = K64_EMAC_DEVICE(dev);
+    RT_ASSERT(emac != RT_NULL);
+    
+#ifdef DRV_EMAC_RX_DUMP
+    {
+        int i;
+        uint8_t * buf;
+        buf = (uint8_t *)p->payload;
+        for (i = 0; i < p->len; i++)
+        {
+            DEBUG_PRINTF("%02X ", buf[i]);
+            if (i % 16 == 15)
+                DEBUG_PRINTF("\n");
+        }
+        DEBUG_PRINTF("\n");
+    }    
+
+#endif
+    
+    do
+    {
+        result = ENET_SendFrame(ENET, enet_handle, p->payload, p->len);
+
+        if (result == kStatus_ENET_TxFrameBusy)
+        {
+            rt_sem_take(&emac->tx_wait, RT_WAITING_FOREVER);
+        }
+
+    } while (result == kStatus_ENET_TxFrameBusy);
+
+    return RT_EOK;
+}
+
+struct pbuf *k64_emac_rx(rt_device_t dev)
+{
+    uint32_t length = 0;
+    status_t status;
+    enet_data_error_stats_t eErrStatic;
+        
+    struct pbuf* p = RT_NULL;
+    struct emac_device *emac = K64_EMAC_DEVICE(dev);
+    enet_handle_t * enet_handle = &emac->enet_handle;
+
+    RT_ASSERT(emac != RT_NULL);
+    DEBUG_PRINTF("k64_emac_rx\n");
+    
+    /* Get the Frame size */
+    status = ENET_GetRxFrameSize(enet_handle, &length);
+    
+    if (status == kStatus_ENET_RxFrameError)
+    {
+        /* Update the received buffer when error happened. */
+        /* Get the error information of the received g_frame. */
+        ENET_GetRxErrBeforeReadFrame(enet_handle, &eErrStatic);
+        /* update the receive buffer. */
+        ENET_ReadFrame(ENET, enet_handle, NULL, 0);
+        
+        DEBUG_PRINTF("receive frame faild\n");
+        
+        return p;
+    }
+    
+    /* Call ENET_ReadFrame when there is a received frame. */
+    if (length != 0)
+    {
+        /* Received valid frame. Deliver the rx buffer with the size equal to length. */
+        p = pbuf_alloc(PBUF_RAW, length, PBUF_POOL);
+    }
+    
+    if (p != NULL)
+    {
+        status = ENET_ReadFrame(ENET, enet_handle, p->payload, length);
+        if (status == kStatus_Success)
+        {
+#ifdef DRV_EMAC_RX_DUMP
+            uint8_t *buf;
+            int i;
+
+            DEBUG_PRINTF(" A frame received. the length:%d\n", p->len);
+            buf = (uint8_t *)p->payload;
+            for (i = 0; i < p->len; i++)
+            {
+                DEBUG_PRINTF("%02X ", buf[i]);
+                if (i % 16 == 15)
+                    DEBUG_PRINTF("\n");
+            }
+            DEBUG_PRINTF("\n");
+#endif
+        }
+        else
+        {
+            DEBUG_PRINTF(" A frame read failed\n");
+            pbuf_free(p);
+        }
+    }
+ 
+    return p;
+}
+
+int drv_emac_hw_init(void)
+{
+    /* use the test MAC address */
+    _emac.dev_addr[0] = 0x00;
+    _emac.dev_addr[1] = 0x04;
+    _emac.dev_addr[2] = 0x9f;
+    _emac.dev_addr[3] = 0xc4;
+    _emac.dev_addr[4] = 0x44;
+    _emac.dev_addr[5] = 0x22;
+
+    _emac.parent.parent.init       = k64_emac_init;
+    _emac.parent.parent.open       = k64_emac_open;
+    _emac.parent.parent.close      = k64_emac_close;
+    _emac.parent.parent.read       = k64_emac_read;
+    _emac.parent.parent.write      = k64_emac_write;
+    _emac.parent.parent.control    = k64_emac_control;
+    _emac.parent.parent.user_data  = RT_NULL;
+
+    _emac.parent.eth_rx     = k64_emac_rx;
+    _emac.parent.eth_tx     = k64_emac_tx;
+
+    /* init tx semaphore */
+    rt_sem_init(&_emac.tx_wait, "tx_wait", ENET_TX_RING_LEN - 1, RT_IPC_FLAG_FIFO);
+    
+    /* register ETH device */
+    eth_device_init(&(_emac.parent), "e0");
+
+    return 0;
+}
+INIT_DEVICE_EXPORT(drv_emac_hw_init);
+
+#ifdef DRV_EMAC_DEBUG
+
+long k64_dump_tx_bd(void)
+{
+	int i;
+
+	enet_tx_bd_struct_t *txbd = _emac.TxBuffDescrip;
+
+	for (i = 0; i < ENET_RX_RING_LEN; i++)
+	{
+		DEBUG_PRINTF("status: %04X,  length: %04X, data: %08X\n", txbd[i].control, txbd[i].length, (uint32_t)txbd[i].buffer);
+	}
+    
+    return 0;
+}
+FINSH_FUNCTION_EXPORT(k64_dump_tx_bd, dump all receive buffer descriptor);
+MSH_CMD_EXPORT(k64_dump_tx_bd, dump all receive buffer descriptor);
+
+long k64_dump_rx_bd(void)
+{
+	int i;
+	enet_rx_bd_struct_t *rxbd = _emac.RxBuffDescrip;
+
+	for (i = 0; i < ENET_RX_RING_LEN; i++)
+	{
+		DEBUG_PRINTF("bd:%08X, ", (void *)&rxbd[i]);
+		//rt_hw_cpu_dcache_ops(RT_HW_CACHE_INVALIDATE, (void *)&rxbd[i], sizeof(enet_rx_bd_struct_t));
+		DEBUG_PRINTF("status:%04X,  length:%04X, data:%08X ", rxbd[i].control, rxbd[i].length, (uint32_t)rxbd[i].buffer);
+#ifdef ENET_ENHANCEDBUFFERDESCRIPTOR_MODE
+		DEBUG_PRINTF("ce:%04X/%04X/%04X ", rxbd[i].controlExtend0, rxbd[i].controlExtend1, rxbd[i].controlExtend2);
+		DEBUG_PRINTF("crc:%04X, len:%04X, type:%04X, ts:%04X", rxbd[i].payloadCheckSum, rxbd[i].headerLength, rxbd[i].protocolTyte, rxbd[i].timestamp);
+#endif
+		DEBUG_PRINTF("\n");
+	}
+    
+    return 0;
+}
+FINSH_FUNCTION_EXPORT(k64_dump_rx_bd, dump all receive buffer descriptor);
+MSH_CMD_EXPORT(k64_dump_rx_bd, dump all receive buffer descriptor);
+#endif
+
+#endif

+ 314 - 0
bsp/frdm-k64f/board/drv_emac.h

@@ -0,0 +1,314 @@
+/*
+ * File      : drv_emac.h
+ *             i.MX6 EMAC Ethernet driver
+ * COPYRIGHT (C) 2015, Shanghai Real-Thread Electronic Technology Co.,Ltd
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2015-07-15     Bernard      The first version
+ */
+
+#ifndef EMAC_DRV_H__
+#define EMAC_DRV_H__
+
+//#define ENHANCED_BD
+
+///* Ethernet standard lengths in bytes*/
+//#define ETH_ADDR_LEN    (6)
+//#define ETH_TYPE_LEN    (2)
+//#define ETH_CRC_LEN     (4)
+//#define ETH_MAX_DATA    (1500)
+//#define ETH_MIN_DATA    (46)
+//#define ETH_HDR_LEN     (ETH_ADDR_LEN * 2 + ETH_TYPE_LEN)
+
+//// 6 * 2 + 2 + 1500 + 4
+
+///* Maximum and Minimum Ethernet Frame Sizes */
+//#define ETH_MAX_FRM     (ETH_HDR_LEN + ETH_MAX_DATA + ETH_CRC_LEN)
+//#define ETH_MIN_FRM     (ETH_HDR_LEN + ETH_MIN_DATA + ETH_CRC_LEN)
+//#define ETH_MTU         (ETH_HDR_LEN + ETH_MAX_DATA)
+
+///********INTERFACE**********/
+//typedef enum
+//{
+//    MAC_MII,
+//    MAC_RMII,
+//} ENET_INTERFACE;
+
+///********AUTONEG**********/
+//typedef enum
+//{
+//    AUTONEG_ON,
+//    AUTONEG_OFF
+//} ENET_AUTONEG;
+
+///********SPEED**********/
+//typedef enum
+//{
+//    MII_10BASET,
+//    MII_100BASET
+//} ENET_SPEED;
+
+///********DUPLEX**********/
+///* MII Duplex Settings */
+//typedef enum
+//{
+//    MII_HDX,        /*!< half-duplex */
+//    MII_FDX         /*!< full-duplex */
+//} ENET_DUPLEX;
+
+///********LOOPBACK**********/
+//typedef enum
+//{
+//    INTERNAL_LOOPBACK,
+//    EXTERNAL_LOOPBACK,
+//    NO_LOOPBACK
+//} ENET_LOOPBACK;
+
+///********EXTERNAL**********/
+//typedef enum
+//{
+//    EXTERNAL_NONE,
+//    EXTERNAL_YES
+//} ENET_EXTERNAL_CONN;
+
+///*
+// * FEC Configuration Parameters
+// */
+//typedef struct
+//{
+//    //ENET_Type*          hw_base;        /* FEC channel       */
+//    ENET_INTERFACE      interface;      /* Transceiver mode  */
+//    ENET_AUTONEG        neg;            /* FEC autoneg */
+//    ENET_SPEED          speed;          /* Ethernet Speed           */
+//    ENET_DUPLEX         duplex;         /* Ethernet Duplex          */
+//    ENET_LOOPBACK       loopback;       /* Loopback Mode */
+//    ENET_EXTERNAL_CONN  external;       /* outside test? */
+//    uint8_t             prom;           /* Promiscuous Mode?        */
+//    uint8_t             mac[6];         /* Ethernet Address         */
+//} ENET_CONFIG;
+
+//// Choose Enhanced Buffer Descriptor or Legacy
+////#define ENHANCED_BD
+
+//// Buffer sizes in bytes (must be divisible by 16)
+//#define RX_BUFFER_SIZE      ETH_MAX_FRM
+//#define TX_BUFFER_SIZE      ETH_MAX_FRM
+
+//// Number of Receive and Transmit Buffers and Buffer Descriptors
+//#define NUM_RXBDS           8
+//#define NUM_TXBDS           4
+
+//// Buffer Descriptor Format
+//typedef struct
+//{
+//    uint16_t status;                /* control and status */
+//    uint16_t length;                /* transfer length */
+//    uint8_t  *data;                 /* buffer address */
+//#ifdef ENHANCED_BD
+//    uint32_t ebd_status;
+//    uint16_t length_proto_type;
+//    uint16_t payload_checksum;
+//    uint32_t bdu;
+//    uint32_t timestamp;
+//    uint32_t reserverd_word1;
+//    uint32_t reserverd_word2;
+//#endif /* ENHANCED_BD */
+//} NBUF;
+
+//// ----------------------------------------------------------------------
+//// TX Buffer Descriptor Bit Definitions
+//// ----------------------------------------------------------------------
+//#define TX_BD_R         0x0080
+//#define TX_BD_TO1       0x0040
+//#define TX_BD_W         0x0020
+//#define TX_BD_TO2       0x0010
+//#define TX_BD_L         0x0008
+//#define TX_BD_TC        0x0004
+//#define TX_BD_ABC       0x0002
+
+//// ----------------------------------------------------------------------
+//// TX Enhanced BD Bit Definitions
+//// ----------------------------------------------------------------------
+//#define TX_BD_INT       0x00000040
+//#define TX_BD_TS        0x00000020
+//#define TX_BD_PINS      0x00000010
+//#define TX_BD_IINS      0x00000008
+//#define TX_BD_TXE       0x00800000
+//#define TX_BD_UE        0x00200000
+//#define TX_BD_EE        0x00100000
+//#define TX_BD_FE        0x00080000
+//#define TX_BD_LCE       0x00040000
+//#define TX_BD_OE        0x00020000
+//#define TX_BD_TSE       0x00010000
+
+//#define TX_BD_BDU       0x00000080
+
+//// ----------------------------------------------------------------------
+//// RX Buffer Descriptor Bit Definitions
+//// ----------------------------------------------------------------------
+
+//// Offset 0 flags - status: Big Endian
+//#define RX_BD_E         0x0080
+//#define RX_BD_R01       0x0040
+//#define RX_BD_W         0x0020
+//#define RX_BD_R02       0x0010
+//#define RX_BD_L         0x0008
+//#define RX_BD_M         0x0001
+//#define RX_BD_BC        0x8000
+//#define RX_BD_MC        0x4000
+//#define RX_BD_LG        0x2000
+//#define RX_BD_NO        0x1000
+//#define RX_BD_CR        0x0400
+//#define RX_BD_OV        0x0200
+//#define RX_BD_TR        0x0100
+
+//// ----------------------------------------------------------------------
+//// RX Enhanced BD Bit Definitions
+//// ----------------------------------------------------------------------
+//#define RX_BD_ME               0x00000080
+//#define RX_BD_PE               0x00000004
+//#define RX_BD_CE               0x00000002
+//#define RX_BD_UC               0x00000001
+
+//#define RX_BD_INT              0x00008000
+
+//#define RX_BD_ICE              0x20000000
+//#define RX_BD_PCR              0x10000000
+//#define RX_BD_VLAN             0x04000000
+//#define RX_BD_IPV6             0x02000000
+//#define RX_BD_FRAG             0x01000000
+
+//#define RX_BD_BDU              0x00000080
+
+///* MII Register Addresses */
+//#define PHY_BMCR                    (0x00)
+//#define PHY_BMSR                    (0x01)
+//#define PHY_PHYIDR1                 (0x02)
+//#define PHY_PHYIDR2                 (0x03)
+//#define PHY_ANAR                    (0x04)
+//#define PHY_ANLPAR                  (0x05)
+//#define PHY_ANLPARNP                (0x05)
+//#define PHY_ANER                    (0x06)
+//#define PHY_ANNPTR                  (0x07)
+//#define PHY_PHYSTS                  (0x10)
+//#define PHY_MICR                    (0x11)
+//#define PHY_MISR                    (0x12)
+//#define PHY_PAGESEL                 (0x13)
+
+///*TSI-EVB definition: National Semiconductor*/
+//#define PHY_PHYCR2                  (0x1C)
+
+///*TWR definition: Micrel*/
+//#define PHY_PHYCTRL1                (0x1E)
+//#define PHY_PHYCTRL2                (0x1F)
+
+///* Bit definitions and macros for PHY_BMCR */
+//#define PHY_BMCR_RESET              (0x8000)
+//#define PHY_BMCR_LOOP               (0x4000)
+//#define PHY_BMCR_SPEED              (0x2000)
+//#define PHY_BMCR_AN_ENABLE          (0x1000)
+//#define PHY_BMCR_POWERDOWN          (0x0800)
+//#define PHY_BMCR_ISOLATE            (0x0400)
+//#define PHY_BMCR_AN_RESTART         (0x0200)
+//#define PHY_BMCR_FDX                (0x0100)
+//#define PHY_BMCR_COL_TEST           (0x0080)
+
+///* Bit definitions and macros for PHY_BMSR */
+//#define PHY_BMSR_100BT4             (0x8000)
+//#define PHY_BMSR_100BTX_FDX         (0x4000)
+//#define PHY_BMSR_100BTX             (0x2000)
+//#define PHY_BMSR_10BT_FDX           (0x1000)
+//#define PHY_BMSR_10BT               (0x0800)
+//#define PHY_BMSR_NO_PREAMBLE        (0x0040)
+//#define PHY_BMSR_AN_COMPLETE        (0x0020)
+//#define PHY_BMSR_REMOTE_FAULT       (0x0010)
+//#define PHY_BMSR_AN_ABILITY         (0x0008)
+//#define PHY_BMSR_LINK               (0x0004)
+//#define PHY_BMSR_JABBER             (0x0002)
+//#define PHY_BMSR_EXTENDED           (0x0001)
+
+///* Bit definitions and macros for PHY_ANAR */
+//#define PHY_ANAR_NEXT_PAGE          (0x8001)
+//#define PHY_ANAR_REM_FAULT          (0x2001)
+//#define PHY_ANAR_PAUSE              (0x0401)
+//#define PHY_ANAR_100BT4             (0x0201)
+//#define PHY_ANAR_100BTX_FDX         (0x0101)
+//#define PHY_ANAR_100BTX             (0x0081)
+//#define PHY_ANAR_10BT_FDX           (0x0041)
+//#define PHY_ANAR_10BT               (0x0021)
+//#define PHY_ANAR_802_3              (0x0001)
+
+///* Bit definitions and macros for PHY_ANLPAR */
+//#define PHY_ANLPAR_NEXT_PAGE        (0x8000)
+//#define PHY_ANLPAR_ACK              (0x4000)
+//#define PHY_ANLPAR_REM_FAULT        (0x2000)
+//#define PHY_ANLPAR_PAUSE            (0x0400)
+//#define PHY_ANLPAR_100BT4           (0x0200)
+//#define PHY_ANLPAR_100BTX_FDX       (0x0100)
+//#define PHY_ANLPAR_100BTX           (0x0080)
+//#define PHY_ANLPAR_10BTX_FDX        (0x0040)
+//#define PHY_ANLPAR_10BT             (0x0020)
+
+
+///* Bit definitions of PHY_PHYSTS: National */
+//#define PHY_PHYSTS_MDIXMODE         (0x4000)
+//#define PHY_PHYSTS_RX_ERR_LATCH     (0x2000)
+//#define PHY_PHYSTS_POL_STATUS       (0x1000)
+//#define PHY_PHYSTS_FALSECARRSENSLAT (0x0800)
+//#define PHY_PHYSTS_SIGNALDETECT     (0x0400)
+//#define PHY_PHYSTS_PAGERECEIVED     (0x0100)
+//#define PHY_PHYSTS_MIIINTERRUPT     (0x0080)
+//#define PHY_PHYSTS_REMOTEFAULT      (0x0040)
+//#define PHY_PHYSTS_JABBERDETECT     (0x0020)
+//#define PHY_PHYSTS_AUTONEGCOMPLETE  (0x0010)
+//#define PHY_PHYSTS_LOOPBACKSTATUS   (0x0008)
+//#define PHY_PHYSTS_DUPLEXSTATUS     (0x0004)
+//#define PHY_PHYSTS_SPEEDSTATUS      (0x0002)
+//#define PHY_PHYSTS_LINKSTATUS       (0x0001)
+
+
+///* Bit definitions of PHY_PHYCR2 */
+//#define PHY_PHYCR2_SYNC_ENET_EN     (0x2000)
+//#define PHY_PHYCR2_CLK_OUT_RXCLK    (0x1000)
+//#define PHY_PHYCR2_BC_WRITE         (0x0800)
+//#define PHY_PHYCR2_PHYTER_COMP      (0x0400)
+//#define PHY_PHYCR2_SOFT_RESET       (0x0200)
+//#define PHY_PHYCR2_CLK_OUT_DIS      (0x0001)
+
+///* Bit definition and macros for PHY_PHYCTRL1 */
+//#define PHY_PHYCTRL1_LED_MASK       (0xC000)
+//#define PHY_PHYCTRL1_POLARITY       (0x2000)
+//#define PHY_PHYCTRL1_MDX_STATE      (0x0800)
+//#define PHY_PHYCTRL1_REMOTE_LOOP    (0x0080)
+
+///* Bit definition and macros for PHY_PHYCTRL2 */
+//#define PHY_PHYCTRL2_HP_MDIX        (0x8000)
+//#define PHY_PHYCTRL2_MDIX_SELECT    (0x4000)
+//#define PHY_PHYCTRL2_PAIRSWAP_DIS   (0x2000)
+//#define PHY_PHYCTRL2_ENERGY_DET     (0x1000)
+//#define PHY_PHYCTRL2_FORCE_LINK     (0x0800)
+//#define PHY_PHYCTRL2_POWER_SAVING   (0x0400)
+//#define PHY_PHYCTRL2_INT_LEVEL      (0x0200)
+//#define PHY_PHYCTRL2_EN_JABBER      (0x0100)
+//#define PHY_PHYCTRL2_AUTONEG_CMPLT  (0x0080)
+//#define PHY_PHYCTRL2_ENABLE_PAUSE   (0x0040)
+//#define PHY_PHYCTRL2_PHY_ISOLATE    (0x0020)
+//#define PHY_PHYCTRL2_OP_MOD_MASK    (0x001C)
+//#define PHY_PHYCTRL2_EN_SQE_TEST    (0x0002)
+//#define PHY_PHYCTRL2_DATA_SCRAM_DIS (0x0001)
+
+///* Bit definitions of PHY_PHYCTRL2_OP_MOD_MASK */
+//#define PHY_PHYCTRL2_OP_MOD_SHIFT             2
+//#define PHY_PHYCTRL2_MODE_OP_MOD_STILL_NEG    0
+//#define PHY_PHYCTRL2_MODE_OP_MOD_10MBPS_HD    1
+//#define PHY_PHYCTRL2_MODE_OP_MOD_100MBPS_HD   2
+//#define PHY_PHYCTRL2_MODE_OP_MOD_10MBPS_FD    5
+//#define PHY_PHYCTRL2_MODE_OP_MOD_100MBPS_FD   6
+
+//#define MII_TIMEOUT         0x1FF
+//#define MII_LINK_TIMEOUT    0x1FF
+
+//int drv_emac_hw_init(void);
+
+#endif

+ 310 - 0
bsp/frdm-k64f/board/fsl_phy.c

@@ -0,0 +1,310 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ *
+ * 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 the copyright holder 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_phy.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @brief Defines the timeout macro. */
+#define PHY_TIMEOUT_COUNT 0xFFFFFU
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+
+/*!
+ * @brief Get the ENET instance from peripheral base address.
+ *
+ * @param base ENET peripheral base address.
+ * @return ENET instance.
+ */
+extern uint32_t ENET_GetInstance(ENET_Type *base);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+/*! @brief Pointers to enet clocks for each instance. */
+extern clock_ip_name_t s_enetClock[FSL_FEATURE_SOC_ENET_COUNT];
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+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);
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+    /* Set SMI first. */
+    CLOCK_EnableClock(s_enetClock[instance]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+    ENET_SetSMI(base, srcClock_Hz, false);
+
+    /* Initialization after PHY stars to work. */
+    while ((idReg != PHY_CONTROL_ID1) && (counter != 0))
+    {
+        PHY_Read(base, phyAddr, PHY_ID1_REG, &idReg);
+        counter --;       
+    }
+
+    if (!counter)
+    {
+        return kStatus_Fail;
+    }
+
+    /* Reset PHY. */
+    counter = PHY_TIMEOUT_COUNT;
+    result = PHY_Write(base, phyAddr, PHY_BASICCONTROL_REG, PHY_BCTL_RESET_MASK);
+    if (result == kStatus_Success)
+    {
+        /* 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)
+            {
+                /* Check auto negotiation complete. */
+                while (counter --)
+                {
+                    result = PHY_Read(base, phyAddr, PHY_BASICSTATUS_REG, &bssReg);
+                    if ( result == kStatus_Success)
+                    {
+                        if ((bssReg & PHY_BSTATUS_AUTONEGCOMP_MASK) != 0)
+                        {
+                            break;
+                        }
+                    }
+
+                    if (!counter)
+                    {
+                        return kStatus_PHY_AutoNegotiateFail;
+                    }
+                }
+            }
+        }
+    }
+
+    return result;
+}
+
+status_t PHY_Write(ENET_Type *base, uint32_t phyAddr, uint32_t phyReg, uint32_t data)
+{
+    uint32_t counter;
+
+    /* Clear the SMI interrupt event. */
+    ENET_ClearInterruptStatus(base, ENET_EIR_MII_MASK);
+
+    /* Starts a SMI write command. */
+    ENET_StartSMIWrite(base, phyAddr, phyReg, kENET_MiiWriteValidFrame, data);
+
+    /* Wait for SMI complete. */
+    for (counter = PHY_TIMEOUT_COUNT; counter > 0; counter--)
+    {
+        if (ENET_GetInterruptStatus(base) & ENET_EIR_MII_MASK)
+        {
+            break;
+        }
+    }
+
+    /* Check for timeout. */
+    if (!counter)
+    {
+        return kStatus_PHY_SMIVisitTimeout;
+    }
+
+    /* Clear MII interrupt event. */
+    ENET_ClearInterruptStatus(base, ENET_EIR_MII_MASK);
+
+    return kStatus_Success;
+}
+
+status_t PHY_Read(ENET_Type *base, uint32_t phyAddr, uint32_t phyReg, uint32_t *dataPtr)
+{
+    assert(dataPtr);
+
+    uint32_t counter;
+
+    /* Clear the MII interrupt event. */
+    ENET_ClearInterruptStatus(base, ENET_EIR_MII_MASK);
+
+    /* Starts a SMI read command operation. */
+    ENET_StartSMIRead(base, phyAddr, phyReg, kENET_MiiReadValidFrame);
+
+    /* Wait for MII complete. */
+    for (counter = PHY_TIMEOUT_COUNT; counter > 0; counter--)
+    {
+        if (ENET_GetInterruptStatus(base) & ENET_EIR_MII_MASK)
+        {
+            break;
+        }
+    }
+
+    /* Check for timeout. */
+    if (!counter)
+    {
+        return kStatus_PHY_SMIVisitTimeout;
+    }
+
+    /* Get data from MII register. */
+    *dataPtr = ENET_ReadSMIData(base);
+
+    /* Clear MII interrupt event. */
+    ENET_ClearInterruptStatus(base, ENET_EIR_MII_MASK);
+
+    return kStatus_Success;
+}
+
+status_t PHY_EnableLoopback(ENET_Type *base, uint32_t phyAddr, phy_loop_t mode, bool enable)
+{
+    status_t result;
+    uint32_t data = 0;
+
+    /* Set the loop mode. */
+    if (enable)
+    {
+        if (mode == kPHY_LocalLoop)
+        {
+            /* First read the current status in control register. */
+            result = PHY_Read(base, phyAddr, PHY_BASICCONTROL_REG, &data);
+            if (result == kStatus_Success)
+            {
+                return PHY_Write(base, phyAddr, PHY_BASICCONTROL_REG, (data | PHY_BCTL_LOOP_MASK));
+            }
+        }
+        else
+        {
+            /* First read the current status in control register. */
+            result = PHY_Read(base, phyAddr, PHY_CONTROL2_REG, &data);
+            if (result == kStatus_Success)
+            {
+                return PHY_Write(base, phyAddr, PHY_CONTROL2_REG, (data | PHY_CTL2_REMOTELOOP_MASK));
+            }
+        }
+    }
+    else
+    {
+        /* Disable the loop mode. */
+        if (mode == kPHY_LocalLoop)
+        {
+            /* First read the current status in the basic control register. */
+            result = PHY_Read(base, phyAddr, PHY_BASICCONTROL_REG, &data);
+            if (result == kStatus_Success)
+            {
+                return PHY_Write(base, phyAddr, PHY_BASICCONTROL_REG, (data & ~PHY_BCTL_LOOP_MASK));
+            }
+        }
+        else
+        {
+            /* First read the current status in control one register. */
+            result = PHY_Read(base, phyAddr, PHY_CONTROL2_REG, &data);
+            if (result == kStatus_Success)
+            {
+                return PHY_Write(base, phyAddr, PHY_CONTROL2_REG, (data & ~PHY_CTL2_REMOTELOOP_MASK));
+            }
+        }
+    }
+    return result;
+}
+
+status_t PHY_GetLinkStatus(ENET_Type *base, uint32_t phyAddr, bool *status)
+{
+    assert(status);
+
+    status_t result = kStatus_Success;
+    uint32_t data;
+
+    /* Read the basic status register. */
+    result = PHY_Read(base, phyAddr, PHY_BASICSTATUS_REG, &data);
+    if (result == kStatus_Success)
+    {
+        if (!(PHY_BSTATUS_LINKSTATUS_MASK & data))
+        {
+            /* link down. */
+            *status = false;
+        }
+        else
+        {
+            /* link up. */
+            *status = true;
+        }
+    }
+    return result;
+}
+
+status_t PHY_GetLinkSpeedDuplex(ENET_Type *base, uint32_t phyAddr, phy_speed_t *speed, phy_duplex_t *duplex)
+{
+    assert(duplex);
+
+    status_t result = kStatus_Success;
+    uint32_t data, ctlReg;
+
+    /* Read the control two register. */
+    result = PHY_Read(base, phyAddr, PHY_CONTROL1_REG, &ctlReg);
+    if (result == kStatus_Success)
+    {
+        data = ctlReg & PHY_CTL1_SPEEDUPLX_MASK;
+        if ((PHY_CTL1_10FULLDUPLEX_MASK == data) || (PHY_CTL1_100FULLDUPLEX_MASK == data))
+        {
+            /* Full duplex. */
+            *duplex = kPHY_FullDuplex;
+        }
+        else
+        {
+            /* Half duplex. */
+            *duplex = kPHY_HalfDuplex;
+        }
+
+        data = ctlReg & PHY_CTL1_SPEEDUPLX_MASK;
+        if ((PHY_CTL1_100HALFDUPLEX_MASK == data) || (PHY_CTL1_100FULLDUPLEX_MASK == data))
+        {
+            /* 100M speed. */
+            *speed = kPHY_Speed100M;
+        }
+        else
+        { /* 10M speed. */
+            *speed = kPHY_Speed10M;
+        }
+    }
+
+    return result;
+}

+ 216 - 0
bsp/frdm-k64f/board/fsl_phy.h

@@ -0,0 +1,216 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ *
+ * 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 the copyright holder 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 _FSL_PHY_H_
+#define _FSL_PHY_H_
+
+#include "fsl_enet.h"
+
+/*!
+ * @addtogroup phy_driver
+ * @{
+ */
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @brief PHY driver version */
+#define FSL_PHY_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0. */
+
+/*! @brief Defines the PHY registers. */
+#define PHY_BASICCONTROL_REG 0x00U      /*!< The PHY basic control register. */
+#define PHY_BASICSTATUS_REG 0x01U       /*!< The PHY basic status register. */
+#define PHY_ID1_REG 0x02U               /*!< The PHY ID one register. */
+#define PHY_ID2_REG 0x03U               /*!< The PHY ID two register. */
+#define PHY_AUTONEG_ADVERTISE_REG 0x04U /*!< The PHY auto-negotiate advertise register. */
+#define PHY_CONTROL1_REG 0x1EU          /*!< The PHY control one register. */
+#define PHY_CONTROL2_REG 0x1FU          /*!< The PHY control two register. */
+
+#define PHY_CONTROL_ID1 0x22U /*!< The PHY ID1*/
+
+/*! @brief Defines the mask flag in basic control register. */
+#define PHY_BCTL_DUPLEX_MASK 0x0100U          /*!< The PHY duplex bit mask. */
+#define PHY_BCTL_RESTART_AUTONEG_MASK 0x0200U /*!< The PHY restart auto negotiation mask. */
+#define PHY_BCTL_AUTONEG_MASK 0x1000U         /*!< The PHY auto negotiation bit mask. */
+#define PHY_BCTL_SPEED_MASK 0x2000U           /*!< The PHY speed bit mask. */
+#define PHY_BCTL_LOOP_MASK 0x4000U            /*!< The PHY loop bit mask. */
+#define PHY_BCTL_RESET_MASK 0x8000U           /*!< The PHY reset bit mask. */
+
+/*!@brief Defines the mask flag of operation mode in control two register*/
+#define PHY_CTL2_REMOTELOOP_MASK 0x0004U    /*!< The PHY remote loopback mask. */
+#define PHY_CTL1_10HALFDUPLEX_MASK 0x0001U  /*!< The PHY 10M half duplex mask. */
+#define PHY_CTL1_100HALFDUPLEX_MASK 0x0002U /*!< The PHY 100M half duplex mask. */
+#define PHY_CTL1_10FULLDUPLEX_MASK 0x0005U  /*!< The PHY 10M full duplex mask. */
+#define PHY_CTL1_100FULLDUPLEX_MASK 0x0006U /*!< The PHY 100M full duplex mask. */
+#define PHY_CTL1_SPEEDUPLX_MASK 0x0007U     /*!< The PHY speed and duplex mask. */
+
+/*! @brief Defines the mask flag in basic status register. */
+#define PHY_BSTATUS_LINKSTATUS_MASK 0x0004U  /*!< The PHY link status mask. */
+#define PHY_BSTATUS_AUTONEGABLE_MASK 0x0008U /*!< The PHY auto-negotiation ability mask. */
+#define PHY_BSTATUS_AUTONEGCOMP_MASK 0x0020U /*!< The PHY auto-negotiation complete mask. */
+
+/*! @brief Defines the mask flag in PHY auto-negotiation advertise register. */
+#define PHY_100BaseT4_ABILITY_MASK 0x200U    /*!< The PHY have the T4 ability. */
+#define PHY_100BASETX_FULLDUPLEX_MASK 0x100U /*!< The PHY has the 100M full duplex ability.*/
+#define PHY_100BASETX_HALFDUPLEX_MASK 0x080U /*!< The PHY has the 100M full duplex ability.*/
+#define PHY_10BASETX_FULLDUPLEX_MASK 0x040U  /*!< The PHY has the 10M full duplex ability.*/
+#define PHY_10BASETX_HALFDUPLEX_MASK 0x020U  /*!< The PHY has the 10M full duplex ability.*/
+
+/*! @brief Defines the PHY status. */
+enum _phy_status
+{
+    kStatus_PHY_SMIVisitTimeout = MAKE_STATUS(kStatusGroup_PHY, 1),  /*!< ENET PHY SMI visit timeout. */
+    kStatus_PHY_AutoNegotiateFail = MAKE_STATUS(kStatusGroup_PHY, 2) /*!< ENET PHY AutoNegotiate Fail. */
+};
+
+/*! @brief Defines the PHY link speed. This is align with the speed for ENET MAC. */
+typedef enum _phy_speed
+{
+    kPHY_Speed10M = 0U, /*!< ENET PHY 10M speed. */
+    kPHY_Speed100M      /*!< ENET PHY 100M speed. */
+} phy_speed_t;
+
+/*! @brief Defines the PHY link duplex. */
+typedef enum _phy_duplex
+{
+    kPHY_HalfDuplex = 0U, /*!< ENET PHY half duplex. */
+    kPHY_FullDuplex       /*!< ENET PHY full duplex. */
+} phy_duplex_t;
+
+/*! @brief Defines the PHY loopback mode. */
+typedef enum _phy_loop
+{
+    kPHY_LocalLoop = 0U, /*!< ENET PHY local loopback. */
+    kPHY_RemoteLoop      /*!< ENET PHY remote loopback. */
+} phy_loop_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+  * @name PHY Driver
+  * @{
+  */
+
+/*!
+ * @brief Initializes PHY.
+ *
+ *  This function initialize the SMI interface and initialize PHY.
+ *  The SMI is the MII management interface between PHY and MAC, which should be
+ *  firstly initialized before any other operation for PHY.
+ *
+ * @param base       ENET peripheral base address.
+ * @param phyAddr    The PHY address.
+ * @param srcClock_Hz  The module clock frequency - system clock for MII management interface - SMI.
+ * @retval kStatus_Success  PHY initialize success
+ * @retval kStatus_PHY_SMIVisitTimeout  PHY SMI visit time out
+ * @retval kStatus_PHY_AutoNegotiateFail  PHY auto negotiate fail
+ */
+status_t PHY_Init(ENET_Type *base, uint32_t phyAddr, uint32_t srcClock_Hz);
+
+/*!
+ * @brief PHY Write function. This function write data over the SMI to
+ * the specified PHY register. This function is called by all PHY interfaces.
+ *
+ * @param base    ENET peripheral base address.
+ * @param phyAddr The PHY address.
+ * @param phyReg  The PHY register.
+ * @param data    The data written to the PHY register.
+ * @retval kStatus_Success     PHY write success
+ * @retval kStatus_PHY_SMIVisitTimeout  PHY SMI visit time out
+ */
+status_t PHY_Write(ENET_Type *base, uint32_t phyAddr, uint32_t phyReg, uint32_t data);
+
+/*!
+ * @brief PHY Read function. This interface read data over the SMI from the
+ * specified PHY register. This function is called by all PHY interfaces.
+ *
+ * @param base     ENET peripheral base address.
+ * @param phyAddr  The PHY address.
+ * @param phyReg   The PHY register.
+ * @param dataPtr  The address to store the data read from the PHY register.
+ * @retval kStatus_Success  PHY read success
+ * @retval kStatus_PHY_SMIVisitTimeout  PHY SMI visit time out
+ */
+status_t PHY_Read(ENET_Type *base, uint32_t phyAddr, uint32_t phyReg, uint32_t *dataPtr);
+
+/*!
+ * @brief Enables/disables PHY loopback.
+ *
+ * @param base     ENET peripheral base address.
+ * @param phyAddr  The PHY address.
+ * @param mode     The loopback mode to be enabled, please see "phy_loop_t".
+ * the two loopback mode should not be both set. when one loopback mode is set
+ * the other one should be disabled.
+ * @param enable   True to enable, false to disable.
+ * @retval kStatus_Success  PHY loopback success
+ * @retval kStatus_PHY_SMIVisitTimeout  PHY SMI visit time out
+ */
+status_t PHY_EnableLoopback(ENET_Type *base, uint32_t phyAddr, phy_loop_t mode, bool enable);
+
+/*!
+ * @brief Gets the PHY link status.
+ *
+ * @param base     ENET peripheral base address.
+ * @param phyAddr  The PHY address.
+ * @param status   The link up or down status of the PHY.
+ *         - true the link is up.
+ *         - false the link is down.
+ * @retval kStatus_Success   PHY get link status success
+ * @retval kStatus_PHY_SMIVisitTimeout  PHY SMI visit time out
+ */
+status_t PHY_GetLinkStatus(ENET_Type *base, uint32_t phyAddr, bool *status);
+
+/*!
+ * @brief Gets the PHY link speed and duplex.
+ *
+ * @param base     ENET peripheral base address.
+ * @param phyAddr  The PHY address.
+ * @param speed    The address of PHY link speed.
+ * @param duplex   The link duplex of PHY.
+ * @retval kStatus_Success   PHY get link speed and duplex success
+ * @retval kStatus_PHY_SMIVisitTimeout  PHY SMI visit time out
+ */
+status_t PHY_GetLinkSpeedDuplex(ENET_Type *base, uint32_t phyAddr, phy_speed_t *speed, phy_duplex_t *duplex);
+
+/* @} */
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*! @}*/
+
+#endif /* _FSL_PHY_H_ */

+ 6 - 4
bsp/frdm-k64f/rtconfig.h

@@ -100,7 +100,9 @@
 #define DFS_FD_MAX					4
 
 /* SECTION: lwip, a lighwight TCP/IP protocol stack */
-/* #define RT_USING_LWIP */
+#define RT_USING_LWIP
+/* Enable LwIP debug output */
+//#define RT_LWIP_DEBUG
 /* LwIP uses RT-Thread Memory Management */
 #define RT_LWIP_USING_RT_MEM
 /* Enable ICMP protocol*/
@@ -152,8 +154,8 @@
 #define CHECKSUM_CHECK_IP               0
 #define CHECKSUM_CHECK_UDP              0
 
-#define CHECKSUM_GEN_TCP                0
-#define CHECKSUM_GEN_IP                 0
-#define CHECKSUM_GEN_UDP                0
+#define CHECKSUM_GEN_TCP                1
+#define CHECKSUM_GEN_IP                 1
+#define CHECKSUM_GEN_UDP                1
 
 #endif