diff --git a/.github/workflows/cmake_arm.yml b/.github/workflows/cmake_arm.yml
index f97645ad1..80ab1ea71 100644
--- a/.github/workflows/cmake_arm.yml
+++ b/.github/workflows/cmake_arm.yml
@@ -38,7 +38,7 @@ jobs:
family:
# Alphabetical order
- 'imxrt'
- - 'kinetis_kl'
+ - 'kinetis_k kinetis_kl'
- 'lpc17 lpc18 lpc40 lpc43'
- 'lpc54 lpc55'
- 'mcx'
diff --git a/.idea/cmake.xml b/.idea/cmake.xml
index 3cb883e62..ebc6a0570 100644
--- a/.idea/cmake.xml
+++ b/.idea/cmake.xml
@@ -59,6 +59,7 @@
+
diff --git a/hw/bsp/board_mcu.h b/hw/bsp/board_mcu.h
index d40f33bbe..013eb1c83 100644
--- a/hw/bsp/board_mcu.h
+++ b/hw/bsp/board_mcu.h
@@ -47,7 +47,7 @@
#elif TU_CHECK_MCU(OPT_MCU_LPC51UXX, OPT_MCU_LPC54XXX, OPT_MCU_LPC55XX, OPT_MCU_MCXN9)
#include "fsl_device_registers.h"
-#elif TU_CHECK_MCU(OPT_MCU_KINETIS_KL, OPT_MCU_KINETIS_K32L)
+#elif TU_CHECK_MCU(OPT_MCU_KINETIS_KL, OPT_MCU_KINETIS_K32L, OPT_MCU_KINETIS_K)
#include "fsl_device_registers.h"
#elif CFG_TUSB_MCU == OPT_MCU_NRF5X
diff --git a/hw/bsp/family_support.cmake b/hw/bsp/family_support.cmake
index ff3393cfd..d84077ed8 100644
--- a/hw/bsp/family_support.cmake
+++ b/hw/bsp/family_support.cmake
@@ -429,6 +429,18 @@ function(family_flash_pyocd TARGET)
endfunction()
+# Add flash teensy_cli target
+function(family_flash_teensy TARGET)
+ if (NOT DEFINED TEENSY_CLI)
+ set(TEENSY_CLI teensy_loader_cli)
+ endif ()
+
+ add_custom_target(${TARGET}-teensy
+ DEPENDS ${TARGET}
+ COMMAND ${TEENSY_CLI} --mcu=${TEENSY_MCU} -w -s $/${TARGET}.hex
+ )
+endfunction()
+
# Add flash using NXP's LinkServer (redserver)
# https://www.nxp.com/design/software/development-software/mcuxpresso-software-and-tools-/linkserver-for-microcontrollers:LINKERSERVER
function(family_flash_nxplink TARGET)
diff --git a/hw/bsp/kinetis_k/FreeRTOSConfig/FreeRTOSConfig.h b/hw/bsp/kinetis_k/FreeRTOSConfig/FreeRTOSConfig.h
new file mode 100644
index 000000000..ed46508a4
--- /dev/null
+++ b/hw/bsp/kinetis_k/FreeRTOSConfig/FreeRTOSConfig.h
@@ -0,0 +1,165 @@
+/*
+ * FreeRTOS Kernel V10.0.0
+ * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy of
+ * this software and associated documentation files (the "Software"), to deal in
+ * the Software without restriction, including without limitation the rights to
+ * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
+ * the Software, and to permit persons to whom the Software is furnished to do so,
+ * subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all
+ * copies or substantial portions of the Software. If you wish to use our Amazon
+ * FreeRTOS name, please do so in a fair use way that does not cause confusion.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
+ * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
+ * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
+ * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+ *
+ * http://www.FreeRTOS.org
+ * http://aws.amazon.com/freertos
+ *
+ * 1 tab == 4 spaces!
+ */
+
+
+#ifndef FREERTOS_CONFIG_H
+#define FREERTOS_CONFIG_H
+
+/*-----------------------------------------------------------
+ * Application specific definitions.
+ *
+ * These definitions should be adjusted for your particular hardware and
+ * application requirements.
+ *
+ * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
+ * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
+ *
+ * See http://www.freertos.org/a00110.html.
+ *----------------------------------------------------------*/
+
+// skip if included from IAR assembler
+#ifndef __IASMARM__
+ #include "fsl_device_registers.h"
+#endif
+
+/* Cortex M23/M33 port configuration. */
+#define configENABLE_MPU 0
+#define configENABLE_FPU 1
+#define configENABLE_TRUSTZONE 0
+#define configMINIMAL_SECURE_STACK_SIZE (1024)
+
+#define configUSE_PREEMPTION 1
+#define configUSE_PORT_OPTIMISED_TASK_SELECTION 0
+#define configCPU_CLOCK_HZ SystemCoreClock
+#define configTICK_RATE_HZ ( 1000 )
+#define configMAX_PRIORITIES ( 5 )
+#define configMINIMAL_STACK_SIZE ( 128 )
+#define configTOTAL_HEAP_SIZE ( configSUPPORT_DYNAMIC_ALLOCATION*4*1024 )
+#define configMAX_TASK_NAME_LEN 16
+#define configUSE_16_BIT_TICKS 0
+#define configIDLE_SHOULD_YIELD 1
+#define configUSE_MUTEXES 1
+#define configUSE_RECURSIVE_MUTEXES 1
+#define configUSE_COUNTING_SEMAPHORES 1
+#define configQUEUE_REGISTRY_SIZE 2
+#define configUSE_QUEUE_SETS 0
+#define configUSE_TIME_SLICING 0
+#define configUSE_NEWLIB_REENTRANT 0
+#define configENABLE_BACKWARD_COMPATIBILITY 1
+#define configSTACK_ALLOCATION_FROM_SEPARATE_HEAP 0
+
+#define configSUPPORT_STATIC_ALLOCATION 1
+#define configSUPPORT_DYNAMIC_ALLOCATION 0
+
+/* Hook function related definitions. */
+#define configUSE_IDLE_HOOK 0
+#define configUSE_TICK_HOOK 0
+#define configUSE_MALLOC_FAILED_HOOK 0 // cause nested extern warning
+#define configCHECK_FOR_STACK_OVERFLOW 2
+
+/* Run time and task stats gathering related definitions. */
+#define configGENERATE_RUN_TIME_STATS 0
+#define configRECORD_STACK_HIGH_ADDRESS 1
+#define configUSE_TRACE_FACILITY 1 // legacy trace
+#define configUSE_STATS_FORMATTING_FUNCTIONS 0
+
+/* Co-routine definitions. */
+#define configUSE_CO_ROUTINES 0
+#define configMAX_CO_ROUTINE_PRIORITIES 2
+
+/* Software timer related definitions. */
+#define configUSE_TIMERS 1
+#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES-2)
+#define configTIMER_QUEUE_LENGTH 32
+#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE
+
+/* Optional functions - most linkers will remove unused functions anyway. */
+#define INCLUDE_vTaskPrioritySet 0
+#define INCLUDE_uxTaskPriorityGet 0
+#define INCLUDE_vTaskDelete 0
+#define INCLUDE_vTaskSuspend 1 // required for queue, semaphore, mutex to be blocked indefinitely with portMAX_DELAY
+#define INCLUDE_xResumeFromISR 0
+#define INCLUDE_vTaskDelayUntil 1
+#define INCLUDE_vTaskDelay 1
+#define INCLUDE_xTaskGetSchedulerState 0
+#define INCLUDE_xTaskGetCurrentTaskHandle 1
+#define INCLUDE_uxTaskGetStackHighWaterMark 0
+#define INCLUDE_xTaskGetIdleTaskHandle 0
+#define INCLUDE_xTimerGetTimerDaemonTaskHandle 0
+#define INCLUDE_pcTaskGetTaskName 0
+#define INCLUDE_eTaskGetState 0
+#define INCLUDE_xEventGroupSetBitFromISR 0
+#define INCLUDE_xTimerPendFunctionCall 0
+
+/* Define to trap errors during development. */
+// Halt CPU (breakpoint) when hitting error, only apply for Cortex M3, M4, M7
+#if defined(__ARM_ARCH_7M__) || defined (__ARM_ARCH_7EM__)
+ #define configASSERT(_exp) \
+ do {\
+ if ( !(_exp) ) { \
+ volatile uint32_t* ARM_CM_DHCSR = ((volatile uint32_t*) 0xE000EDF0UL); /* Cortex M CoreDebug->DHCSR */ \
+ if ( (*ARM_CM_DHCSR) & 1UL ) { /* Only halt mcu if debugger is attached */ \
+ taskDISABLE_INTERRUPTS(); \
+ __asm("BKPT #0\n"); \
+ }\
+ }\
+ } while(0)
+#else
+ #define configASSERT( x )
+#endif
+
+/* FreeRTOS hooks to NVIC vectors */
+#define xPortPendSVHandler PendSV_Handler
+#define xPortSysTickHandler SysTick_Handler
+#define vPortSVCHandler SVC_Handler
+
+//--------------------------------------------------------------------+
+// Interrupt nesting behavior configuration.
+//--------------------------------------------------------------------+
+
+// For Cortex-M specific: __NVIC_PRIO_BITS is defined in mcu header
+#define configPRIO_BITS 4
+
+/* The lowest interrupt priority that can be used in a call to a "set priority" function. */
+#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY ((1<C1 = ((MCG->C1 & ~MCG_C1_FRDIV_MASK) | MCG_C1_FRDIV(frdiv));
+}
+
+/*******************************************************************************
+ ************************ BOARD_InitBootClocks function ************************
+ ******************************************************************************/
+void BOARD_InitBootClocks(void)
+{
+}
+
+/*******************************************************************************
+ ********************** Configuration BOARD_BootClockRUN ***********************
+ ******************************************************************************/
+/* clang-format off */
+/* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+!!Configuration
+name: BOARD_BootClockRUN
+outputs:
+- {id: Bus_clock.outFreq, value: 60 MHz}
+- {id: CLKOUT.outFreq, value: 40 MHz}
+- {id: Core_clock.outFreq, value: 120 MHz, locked: true, accuracy: '0.001'}
+- {id: ENET1588TSCLK.outFreq, value: 50 MHz}
+- {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: 2 MHz}
+- {id: OSCERCLK.outFreq, value: 50 MHz}
+- {id: PLLFLLCLK.outFreq, value: 120 MHz}
+- {id: RMIICLK.outFreq, value: 50 MHz}
+- {id: SDHCCLK.outFreq, value: 50 MHz}
+- {id: System_clock.outFreq, value: 120 MHz}
+- {id: TRACECLKIN.outFreq, value: 120 MHz}
+- {id: USB48MCLK.outFreq, value: 48 MHz}
+settings:
+- {id: MCGMode, value: PEE}
+- {id: CLKOUTConfig, value: 'yes'}
+- {id: ENETTimeSrcConfig, value: 'yes'}
+- {id: MCG.FRDIV.scale, value: '32'}
+- {id: MCG.IRCS.sel, value: MCG.FCRDIV}
+- {id: MCG.IREFS.sel, value: MCG.FRDIV}
+- {id: MCG.PLLS.sel, value: MCG.PLL}
+- {id: MCG.PRDIV.scale, value: '15'}
+- {id: MCG.VDIV.scale, value: '36'}
+- {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: RMIISrcConfig, value: 'yes'}
+- {id: RTCCLKOUTConfig, value: 'yes'}
+- {id: RTC_CR_OSCE_CFG, value: Enabled}
+- {id: RTC_CR_OSC_CAP_LOAD_CFG, value: SC10PF}
+- {id: SDHCClkConfig, value: 'yes'}
+- {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}
+- {id: TraceClkConfig, value: 'yes'}
+- {id: USBClkConfig, value: 'yes'}
+sources:
+- {id: OSC.OSC.outFreq, value: 50 MHz, enabled: true}
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/
+/* clang-format on */
+
+/*******************************************************************************
+ * 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_IrcFast, /* Fast internal reference clock selected */
+ .fcrdiv = 0x1U, /* Fast IRC divider: divided by 2 */
+ .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 = 0xeU, /* PLL Reference divider: divided by 15 */
+ .vdiv = 0xcU, /* VCO divider: multiplied by 36 */
+ },
+ };
+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;
+ /* Enable USB FS clock. */
+ CLOCK_EnableUsbfs0Clock(kCLOCK_UsbSrcPll0, SIM_USB_CLK_120000000HZ);
+ /* Set enet timestamp clock source. */
+ CLOCK_SetEnetTime0Clock(SIM_ENET_1588T_CLK_SEL_OSCERCLK_CLK);
+ /* Set RMII clock source. */
+ CLOCK_SetRmii0Clock(SIM_ENET_RMII_CLK_SEL_EXTAL_CLK);
+ /* Set SDHC clock source. */
+ CLOCK_SetSdhc0Clock(SIM_SDHC_CLK_SEL_OSCERCLK_CLK);
+ /* Set CLKOUT source. */
+ CLOCK_SetClkOutClock(SIM_CLKOUT_SEL_FLEXBUS_CLK);
+ /* Set debug trace clock source. */
+ CLOCK_SetTraceClock(SIM_TRACE_CLK_SEL_CORE_SYSTEM_CLK);
+}
+
+/*******************************************************************************
+ ********************* Configuration BOARD_BootClockVLPR ***********************
+ ******************************************************************************/
+/* clang-format off */
+/* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+!!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: 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_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 TOOLS **********/
+/* clang-format on */
+
+/*******************************************************************************
+ * Variables for BOARD_BootClockVLPR configuration
+ ******************************************************************************/
+const mcg_config_t mcgConfig_BOARD_BootClockVLPR =
+ {
+ .mcgMode = kMCG_ModeBLPI, /* BLPI - Bypassed Low Power Internal */
+ .irclkEnableMode = MCG_IRCLK_DISABLE, /* MCGIRCLK disabled */
+ .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;
+}
diff --git a/hw/bsp/kinetis_k/boards/frdm_k64f/board/clock_config.h b/hw/bsp/kinetis_k/boards/frdm_k64f/board/clock_config.h
new file mode 100644
index 000000000..88b141834
--- /dev/null
+++ b/hw/bsp/kinetis_k/boards/frdm_k64f/board/clock_config.h
@@ -0,0 +1,104 @@
+/***********************************************************************************************************************
+ * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file
+ * will be overwritten if the respective MCUXpresso Config Tools is used to update this file.
+ **********************************************************************************************************************/
+
+#ifndef _CLOCK_CONFIG_H_
+#define _CLOCK_CONFIG_H_
+
+#include "fsl_common.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+#define BOARD_XTAL0_CLK_HZ 50000000U /*!< Board xtal0 frequency in Hz */
+
+/*******************************************************************************
+ ************************ BOARD_InitBootClocks function ************************
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus*/
+
+/*!
+ * @brief This function executes default configuration of clocks.
+ *
+ */
+void BOARD_InitBootClocks(void);
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus*/
+
+/*******************************************************************************
+ ********************** 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_ */
diff --git a/hw/bsp/kinetis_k/boards/frdm_k64f/board/pin_mux.c b/hw/bsp/kinetis_k/boards/frdm_k64f/board/pin_mux.c
new file mode 100644
index 000000000..f4c245eef
--- /dev/null
+++ b/hw/bsp/kinetis_k/boards/frdm_k64f/board/pin_mux.c
@@ -0,0 +1,852 @@
+/***********************************************************************************************************************
+ * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file
+ * will be overwritten if the respective MCUXpresso Config Tools is used to update this file.
+ **********************************************************************************************************************/
+
+/* clang-format off */
+/*
+ * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+!!GlobalInfo
+product: Pins v14.0
+processor: MK64FN1M0xxx12
+package_id: MK64FN1M0VLL12
+mcu_data: ksdk2_0
+processor_version: 14.0.0
+board: FRDM-K64F
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
+ */
+/* clang-format on */
+
+#include "fsl_common.h"
+#include "fsl_port.h"
+#include "fsl_gpio.h"
+#include "pin_mux.h"
+
+/* FUNCTION ************************************************************************************************************
+ *
+ * Function Name : BOARD_InitBootPins
+ * Description : Calls initialization functions.
+ *
+ * END ****************************************************************************************************************/
+void BOARD_InitBootPins(void)
+{
+ BOARD_InitButtons();
+ BOARD_InitLEDs();
+ BOARD_InitDEBUG_UART();
+}
+
+/* clang-format off */
+/*
+ * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+BOARD_InitPins:
+- options: {callFromInitBoot: 'false', prefix: BOARD_, coreID: core0, enableClock: 'true'}
+- pin_list: []
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
+ */
+/* clang-format on */
+
+/* FUNCTION ************************************************************************************************************
+ *
+ * Function Name : BOARD_InitPins
+ * Description : Configures pin routing and optionally pin electrical features.
+ *
+ * END ****************************************************************************************************************/
+void BOARD_InitPins(void)
+{
+}
+
+/* clang-format off */
+/*
+ * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+BOARD_InitButtons:
+- options: {callFromInitBoot: 'true', prefix: BOARD_, coreID: core0, enableClock: 'true'}
+- pin_list:
+ - {pin_num: '78', peripheral: GPIOC, signal: 'GPIO, 6', pin_signal: CMP0_IN0/PTC6/LLWU_P10/SPI0_SOUT/PDB0_EXTRG/I2S0_RX_BCLK/FB_AD9/I2S0_MCLK, identifier: SW2,
+ direction: INPUT, slew_rate: fast, open_drain: disable, drive_strength: low, pull_select: up, pull_enable: enable, passive_filter: disable}
+ - {pin_num: '38', peripheral: GPIOA, signal: 'GPIO, 4', pin_signal: PTA4/LLWU_P3/FTM0_CH1/NMI_b/EZP_CS_b, direction: INPUT, slew_rate: fast, open_drain: disable,
+ drive_strength: low, pull_select: down, pull_enable: disable, passive_filter: disable}
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
+ */
+/* clang-format on */
+
+/* FUNCTION ************************************************************************************************************
+ *
+ * Function Name : BOARD_InitButtons
+ * Description : Configures pin routing and optionally pin electrical features.
+ *
+ * END ****************************************************************************************************************/
+void BOARD_InitButtons(void)
+{
+ /* Port A Clock Gate Control: Clock enabled */
+ CLOCK_EnableClock(kCLOCK_PortA);
+ /* Port C Clock Gate Control: Clock enabled */
+ CLOCK_EnableClock(kCLOCK_PortC);
+
+ gpio_pin_config_t SW3_config = {
+ .pinDirection = kGPIO_DigitalInput,
+ .outputLogic = 0U
+ };
+ /* Initialize GPIO functionality on pin PTA4 (pin 38) */
+ GPIO_PinInit(BOARD_SW3_GPIO, BOARD_SW3_PIN, &SW3_config);
+
+ gpio_pin_config_t SW2_config = {
+ .pinDirection = kGPIO_DigitalInput,
+ .outputLogic = 0U
+ };
+ /* Initialize GPIO functionality on pin PTC6 (pin 78) */
+ GPIO_PinInit(BOARD_SW2_GPIO, BOARD_SW2_PIN, &SW2_config);
+
+ const port_pin_config_t SW3 = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as PTA4 */
+ kPORT_MuxAsGpio,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTA4 (pin 38) is configured as PTA4 */
+ PORT_SetPinConfig(BOARD_SW3_PORT, BOARD_SW3_PIN, &SW3);
+
+ const port_pin_config_t SW2 = {/* Internal pull-up resistor is enabled */
+ kPORT_PullUp,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as PTC6 */
+ kPORT_MuxAsGpio,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTC6 (pin 78) is configured as PTC6 */
+ PORT_SetPinConfig(BOARD_SW2_PORT, BOARD_SW2_PIN, &SW2);
+}
+
+/* clang-format off */
+/*
+ * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+BOARD_InitLEDs:
+- options: {callFromInitBoot: 'true', prefix: BOARD_, coreID: core0, enableClock: 'true'}
+- pin_list:
+ - {pin_num: '67', peripheral: GPIOB, signal: 'GPIO, 21', pin_signal: PTB21/SPI2_SCK/FB_AD30/CMP1_OUT, direction: OUTPUT, gpio_init_state: 'true', slew_rate: slow,
+ open_drain: disable, drive_strength: low, pull_select: down, pull_enable: disable, passive_filter: disable}
+ - {pin_num: '68', peripheral: GPIOB, signal: 'GPIO, 22', pin_signal: PTB22/SPI2_SOUT/FB_AD29/CMP2_OUT, direction: OUTPUT, gpio_init_state: 'true', slew_rate: slow,
+ open_drain: disable, drive_strength: low, pull_select: down, pull_enable: disable, passive_filter: disable}
+ - {pin_num: '33', peripheral: GPIOE, signal: 'GPIO, 26', pin_signal: PTE26/ENET_1588_CLKIN/UART4_CTS_b/RTC_CLKOUT/USB_CLKIN, direction: OUTPUT, gpio_init_state: 'true',
+ slew_rate: slow, open_drain: disable, drive_strength: low, pull_select: down, pull_enable: disable, passive_filter: disable}
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
+ */
+/* clang-format on */
+
+/* FUNCTION ************************************************************************************************************
+ *
+ * Function Name : BOARD_InitLEDs
+ * Description : Configures pin routing and optionally pin electrical features.
+ *
+ * END ****************************************************************************************************************/
+void BOARD_InitLEDs(void)
+{
+ /* Port B Clock Gate Control: Clock enabled */
+ CLOCK_EnableClock(kCLOCK_PortB);
+ /* Port E Clock Gate Control: Clock enabled */
+ CLOCK_EnableClock(kCLOCK_PortE);
+
+ gpio_pin_config_t LED_BLUE_config = {
+ .pinDirection = kGPIO_DigitalOutput,
+ .outputLogic = 1U
+ };
+ /* Initialize GPIO functionality on pin PTB21 (pin 67) */
+ GPIO_PinInit(BOARD_LED_BLUE_GPIO, BOARD_LED_BLUE_PIN, &LED_BLUE_config);
+
+ gpio_pin_config_t LED_RED_config = {
+ .pinDirection = kGPIO_DigitalOutput,
+ .outputLogic = 1U
+ };
+ /* Initialize GPIO functionality on pin PTB22 (pin 68) */
+ GPIO_PinInit(BOARD_LED_RED_GPIO, BOARD_LED_RED_PIN, &LED_RED_config);
+
+ gpio_pin_config_t LED_GREEN_config = {
+ .pinDirection = kGPIO_DigitalOutput,
+ .outputLogic = 1U
+ };
+ /* Initialize GPIO functionality on pin PTE26 (pin 33) */
+ GPIO_PinInit(BOARD_LED_GREEN_GPIO, BOARD_LED_GREEN_PIN, &LED_GREEN_config);
+
+ const port_pin_config_t LED_BLUE = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Slow slew rate is configured */
+ kPORT_SlowSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as PTB21 */
+ kPORT_MuxAsGpio,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTB21 (pin 67) is configured as PTB21 */
+ PORT_SetPinConfig(BOARD_LED_BLUE_PORT, BOARD_LED_BLUE_PIN, &LED_BLUE);
+
+ const port_pin_config_t LED_RED = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Slow slew rate is configured */
+ kPORT_SlowSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as PTB22 */
+ kPORT_MuxAsGpio,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTB22 (pin 68) is configured as PTB22 */
+ PORT_SetPinConfig(BOARD_LED_RED_PORT, BOARD_LED_RED_PIN, &LED_RED);
+
+ const port_pin_config_t LED_GREEN = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Slow slew rate is configured */
+ kPORT_SlowSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as PTE26 */
+ kPORT_MuxAsGpio,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTE26 (pin 33) is configured as PTE26 */
+ PORT_SetPinConfig(BOARD_LED_GREEN_PORT, BOARD_LED_GREEN_PIN, &LED_GREEN);
+}
+
+/* clang-format off */
+/*
+ * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+BOARD_InitDEBUG_UART:
+- options: {callFromInitBoot: 'true', prefix: BOARD_, coreID: core0, enableClock: 'true'}
+- pin_list:
+ - {pin_num: '63', peripheral: UART0, signal: TX, pin_signal: PTB17/SPI1_SIN/UART0_TX/FTM_CLKIN1/FB_AD16/EWM_OUT_b, direction: OUTPUT, slew_rate: fast, open_drain: disable,
+ drive_strength: low, pull_select: down, pull_enable: disable, passive_filter: disable}
+ - {pin_num: '62', peripheral: UART0, signal: RX, pin_signal: PTB16/SPI1_SOUT/UART0_RX/FTM_CLKIN0/FB_AD17/EWM_IN, slew_rate: fast, open_drain: disable, drive_strength: low,
+ pull_select: down, pull_enable: disable, passive_filter: disable}
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
+ */
+/* clang-format on */
+
+/* FUNCTION ************************************************************************************************************
+ *
+ * Function Name : BOARD_InitDEBUG_UART
+ * Description : Configures pin routing and optionally pin electrical features.
+ *
+ * END ****************************************************************************************************************/
+void BOARD_InitDEBUG_UART(void)
+{
+ /* Port B Clock Gate Control: Clock enabled */
+ CLOCK_EnableClock(kCLOCK_PortB);
+
+ const port_pin_config_t DEBUG_UART_RX = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as UART0_RX */
+ kPORT_MuxAlt3,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTB16 (pin 62) is configured as UART0_RX */
+ PORT_SetPinConfig(BOARD_DEBUG_UART_RX_PORT, BOARD_DEBUG_UART_RX_PIN, &DEBUG_UART_RX);
+
+ const port_pin_config_t DEBUG_UART_TX = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as UART0_TX */
+ kPORT_MuxAlt3,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTB17 (pin 63) is configured as UART0_TX */
+ PORT_SetPinConfig(BOARD_DEBUG_UART_TX_PORT, BOARD_DEBUG_UART_TX_PIN, &DEBUG_UART_TX);
+
+ SIM->SOPT5 = ((SIM->SOPT5 &
+ /* Mask bits to zero which are setting */
+ (~(SIM_SOPT5_UART0TXSRC_MASK)))
+
+ /* UART 0 transmit data source select: UART0_TX pin. */
+ | SIM_SOPT5_UART0TXSRC(SOPT5_UART0TXSRC_UART_TX));
+}
+
+/* clang-format off */
+/*
+ * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+BOARD_InitOSC:
+- options: {callFromInitBoot: 'false', prefix: BOARD_, coreID: core0, enableClock: 'true'}
+- pin_list:
+ - {pin_num: '50', peripheral: OSC, signal: EXTAL0, pin_signal: EXTAL0/PTA18/FTM0_FLT2/FTM_CLKIN0, identifier: EXTAL0, slew_rate: no_init, open_drain: no_init, drive_strength: no_init,
+ pull_select: no_init, pull_enable: no_init, passive_filter: no_init}
+ - {pin_num: '29', peripheral: RTC, signal: EXTAL32, pin_signal: EXTAL32}
+ - {pin_num: '28', peripheral: RTC, signal: XTAL32, pin_signal: XTAL32}
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
+ */
+/* clang-format on */
+
+/* FUNCTION ************************************************************************************************************
+ *
+ * Function Name : BOARD_InitOSC
+ * Description : Configures pin routing and optionally pin electrical features.
+ *
+ * END ****************************************************************************************************************/
+void BOARD_InitOSC(void)
+{
+ /* Port A Clock Gate Control: Clock enabled */
+ CLOCK_EnableClock(kCLOCK_PortA);
+
+ /* PORTA18 (pin 50) is configured as EXTAL0 */
+ PORT_SetPinMux(BOARD_EXTAL0_PORT, BOARD_EXTAL0_PIN, kPORT_PinDisabledOrAnalog);
+}
+
+/* clang-format off */
+/*
+ * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+BOARD_InitACCEL:
+- options: {callFromInitBoot: 'false', prefix: BOARD_, coreID: core0, enableClock: 'true'}
+- pin_list:
+ - {pin_num: '32', peripheral: I2C0, signal: SDA, pin_signal: ADC0_SE18/PTE25/UART4_RX/I2C0_SDA/EWM_IN, slew_rate: fast, open_drain: enable, drive_strength: low,
+ pull_select: up, pull_enable: enable, passive_filter: disable}
+ - {pin_num: '31', peripheral: I2C0, signal: SCL, pin_signal: ADC0_SE17/PTE24/UART4_TX/I2C0_SCL/EWM_OUT_b, slew_rate: fast, open_drain: enable, drive_strength: low,
+ pull_select: up, pull_enable: enable, passive_filter: disable}
+ - {pin_num: '78', peripheral: GPIOC, signal: 'GPIO, 6', pin_signal: CMP0_IN0/PTC6/LLWU_P10/SPI0_SOUT/PDB0_EXTRG/I2S0_RX_BCLK/FB_AD9/I2S0_MCLK, identifier: ACCEL_INT1,
+ direction: INPUT, slew_rate: fast, open_drain: enable, drive_strength: low, pull_select: up, pull_enable: enable, passive_filter: disable}
+ - {pin_num: '85', peripheral: GPIOC, signal: 'GPIO, 13', pin_signal: PTC13/UART4_CTS_b/FB_AD26, direction: INPUT, slew_rate: fast, open_drain: enable, drive_strength: low,
+ pull_select: up, pull_enable: enable, passive_filter: disable}
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
+ */
+/* clang-format on */
+
+/* FUNCTION ************************************************************************************************************
+ *
+ * Function Name : BOARD_InitACCEL
+ * Description : Configures pin routing and optionally pin electrical features.
+ *
+ * END ****************************************************************************************************************/
+void BOARD_InitACCEL(void)
+{
+ /* Port C Clock Gate Control: Clock enabled */
+ CLOCK_EnableClock(kCLOCK_PortC);
+ /* Port E Clock Gate Control: Clock enabled */
+ CLOCK_EnableClock(kCLOCK_PortE);
+
+ gpio_pin_config_t ACCEL_INT1_config = {
+ .pinDirection = kGPIO_DigitalInput,
+ .outputLogic = 0U
+ };
+ /* Initialize GPIO functionality on pin PTC6 (pin 78) */
+ GPIO_PinInit(BOARD_ACCEL_INT1_GPIO, BOARD_ACCEL_INT1_PIN, &ACCEL_INT1_config);
+
+ gpio_pin_config_t ACCEL_INT2_config = {
+ .pinDirection = kGPIO_DigitalInput,
+ .outputLogic = 0U
+ };
+ /* Initialize GPIO functionality on pin PTC13 (pin 85) */
+ GPIO_PinInit(BOARD_ACCEL_INT2_GPIO, BOARD_ACCEL_INT2_PIN, &ACCEL_INT2_config);
+
+ const port_pin_config_t ACCEL_INT2 = {/* Internal pull-up resistor is enabled */
+ kPORT_PullUp,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is enabled */
+ kPORT_OpenDrainEnable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as PTC13 */
+ kPORT_MuxAsGpio,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTC13 (pin 85) is configured as PTC13 */
+ PORT_SetPinConfig(BOARD_ACCEL_INT2_PORT, BOARD_ACCEL_INT2_PIN, &ACCEL_INT2);
+
+ const port_pin_config_t ACCEL_INT1 = {/* Internal pull-up resistor is enabled */
+ kPORT_PullUp,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is enabled */
+ kPORT_OpenDrainEnable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as PTC6 */
+ kPORT_MuxAsGpio,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTC6 (pin 78) is configured as PTC6 */
+ PORT_SetPinConfig(BOARD_ACCEL_INT1_PORT, BOARD_ACCEL_INT1_PIN, &ACCEL_INT1);
+
+ const port_pin_config_t ACCEL_SCL = {/* Internal pull-up resistor is enabled */
+ kPORT_PullUp,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is enabled */
+ kPORT_OpenDrainEnable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as I2C0_SCL */
+ kPORT_MuxAlt5,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTE24 (pin 31) is configured as I2C0_SCL */
+ PORT_SetPinConfig(BOARD_ACCEL_SCL_PORT, BOARD_ACCEL_SCL_PIN, &ACCEL_SCL);
+
+ const port_pin_config_t ACCEL_SDA = {/* Internal pull-up resistor is enabled */
+ kPORT_PullUp,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is enabled */
+ kPORT_OpenDrainEnable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as I2C0_SDA */
+ kPORT_MuxAlt5,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTE25 (pin 32) is configured as I2C0_SDA */
+ PORT_SetPinConfig(BOARD_ACCEL_SDA_PORT, BOARD_ACCEL_SDA_PIN, &ACCEL_SDA);
+}
+
+/* clang-format off */
+/*
+ * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+BOARD_InitENET:
+- options: {callFromInitBoot: 'false', prefix: BOARD_, coreID: core0, enableClock: 'true'}
+- pin_list:
+ - {pin_num: '54', peripheral: ENET, signal: RMII_MDC, pin_signal: ADC0_SE9/ADC1_SE9/PTB1/I2C0_SDA/FTM1_CH1/RMII0_MDC/MII0_MDC/FTM1_QD_PHB, slew_rate: fast, open_drain: disable,
+ drive_strength: low, pull_select: down, pull_enable: disable, passive_filter: disable}
+ - {pin_num: '53', peripheral: ENET, signal: RMII_MDIO, pin_signal: ADC0_SE8/ADC1_SE8/PTB0/LLWU_P5/I2C0_SCL/FTM1_CH0/RMII0_MDIO/MII0_MDIO/FTM1_QD_PHA, slew_rate: fast,
+ open_drain: enable, drive_strength: low, pull_select: up, pull_enable: enable, passive_filter: disable}
+ - {pin_num: '43', peripheral: ENET, signal: RMII_RXD0, pin_signal: CMP2_IN1/PTA13/LLWU_P4/CAN0_RX/FTM1_CH1/RMII0_RXD0/MII0_RXD0/I2C2_SDA/I2S0_TX_FS/FTM1_QD_PHB,
+ slew_rate: fast, open_drain: disable, drive_strength: low, pull_select: down, pull_enable: disable, passive_filter: disable}
+ - {pin_num: '42', peripheral: ENET, signal: RMII_RXD1, pin_signal: CMP2_IN0/PTA12/CAN0_TX/FTM1_CH0/RMII0_RXD1/MII0_RXD1/I2C2_SCL/I2S0_TXD0/FTM1_QD_PHA, slew_rate: fast,
+ open_drain: disable, drive_strength: low, pull_select: down, pull_enable: disable, passive_filter: disable}
+ - {pin_num: '39', peripheral: ENET, signal: RMII_RXER, pin_signal: PTA5/USB_CLKIN/FTM0_CH2/RMII0_RXER/MII0_RXER/CMP2_OUT/I2S0_TX_BCLK/JTAG_TRST_b, slew_rate: fast,
+ open_drain: disable, drive_strength: low, pull_select: down, pull_enable: disable, passive_filter: disable}
+ - {pin_num: '46', peripheral: ENET, signal: RMII_TXD0, pin_signal: PTA16/SPI0_SOUT/UART0_CTS_b/UART0_COL_b/RMII0_TXD0/MII0_TXD0/I2S0_RX_FS/I2S0_RXD1, slew_rate: fast,
+ open_drain: disable, drive_strength: low, pull_select: down, pull_enable: disable, passive_filter: disable}
+ - {pin_num: '47', peripheral: ENET, signal: RMII_TXD1, pin_signal: ADC1_SE17/PTA17/SPI0_SIN/UART0_RTS_b/RMII0_TXD1/MII0_TXD1/I2S0_MCLK, slew_rate: fast, open_drain: disable,
+ drive_strength: low, pull_select: down, pull_enable: disable, passive_filter: disable}
+ - {pin_num: '45', peripheral: ENET, signal: RMII_TXEN, pin_signal: PTA15/SPI0_SCK/UART0_RX/RMII0_TXEN/MII0_TXEN/I2S0_RXD0, slew_rate: fast, open_drain: disable,
+ drive_strength: low, pull_select: down, pull_enable: disable, passive_filter: disable}
+ - {pin_num: '44', peripheral: ENET, signal: RMII_CRS_DV, pin_signal: PTA14/SPI0_PCS0/UART0_TX/RMII0_CRS_DV/MII0_RXDV/I2C2_SCL/I2S0_RX_BCLK/I2S0_TXD1, slew_rate: fast,
+ open_drain: disable, drive_strength: low, pull_select: down, pull_enable: disable, passive_filter: disable}
+ - {pin_num: '50', peripheral: ENET, signal: RMII_CLKIN, pin_signal: EXTAL0/PTA18/FTM0_FLT2/FTM_CLKIN0, identifier: RMII_RXCLK, slew_rate: fast, open_drain: disable,
+ drive_strength: low, pull_select: down, pull_enable: disable, passive_filter: disable}
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
+ */
+/* clang-format on */
+
+/* FUNCTION ************************************************************************************************************
+ *
+ * Function Name : BOARD_InitENET
+ * Description : Configures pin routing and optionally pin electrical features.
+ *
+ * END ****************************************************************************************************************/
+void BOARD_InitENET(void)
+{
+ /* Port A Clock Gate Control: Clock enabled */
+ CLOCK_EnableClock(kCLOCK_PortA);
+ /* Port B Clock Gate Control: Clock enabled */
+ CLOCK_EnableClock(kCLOCK_PortB);
+
+ const port_pin_config_t RMII0_RXD1 = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as RMII0_RXD1 */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTA12 (pin 42) is configured as RMII0_RXD1 */
+ PORT_SetPinConfig(BOARD_RMII0_RXD1_PORT, BOARD_RMII0_RXD1_PIN, &RMII0_RXD1);
+
+ const port_pin_config_t RMII0_RXD0 = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as RMII0_RXD0 */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTA13 (pin 43) is configured as RMII0_RXD0 */
+ PORT_SetPinConfig(BOARD_RMII0_RXD0_PORT, BOARD_RMII0_RXD0_PIN, &RMII0_RXD0);
+
+ const port_pin_config_t RMII0_CRS_DV = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as RMII0_CRS_DV */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTA14 (pin 44) is configured as RMII0_CRS_DV */
+ PORT_SetPinConfig(BOARD_RMII0_CRS_DV_PORT, BOARD_RMII0_CRS_DV_PIN, &RMII0_CRS_DV);
+
+ const port_pin_config_t RMII0_TXEN = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as RMII0_TXEN */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTA15 (pin 45) is configured as RMII0_TXEN */
+ PORT_SetPinConfig(BOARD_RMII0_TXEN_PORT, BOARD_RMII0_TXEN_PIN, &RMII0_TXEN);
+
+ const port_pin_config_t RMII0_TXD0 = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as RMII0_TXD0 */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTA16 (pin 46) is configured as RMII0_TXD0 */
+ PORT_SetPinConfig(BOARD_RMII0_TXD0_PORT, BOARD_RMII0_TXD0_PIN, &RMII0_TXD0);
+
+ const port_pin_config_t RMII0_TXD1 = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as RMII0_TXD1 */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTA17 (pin 47) is configured as RMII0_TXD1 */
+ PORT_SetPinConfig(BOARD_RMII0_TXD1_PORT, BOARD_RMII0_TXD1_PIN, &RMII0_TXD1);
+
+ const port_pin_config_t RMII_RXCLK = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as EXTAL0 */
+ kPORT_PinDisabledOrAnalog,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTA18 (pin 50) is configured as EXTAL0 */
+ PORT_SetPinConfig(BOARD_RMII_RXCLK_PORT, BOARD_RMII_RXCLK_PIN, &RMII_RXCLK);
+
+ const port_pin_config_t RMII0_RXER = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as RMII0_RXER */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTA5 (pin 39) is configured as RMII0_RXER */
+ PORT_SetPinConfig(BOARD_RMII0_RXER_PORT, BOARD_RMII0_RXER_PIN, &RMII0_RXER);
+
+ const port_pin_config_t RMII0_MDIO = {/* Internal pull-up resistor is enabled */
+ kPORT_PullUp,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is enabled */
+ kPORT_OpenDrainEnable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as RMII0_MDIO */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTB0 (pin 53) is configured as RMII0_MDIO */
+ PORT_SetPinConfig(BOARD_RMII0_MDIO_PORT, BOARD_RMII0_MDIO_PIN, &RMII0_MDIO);
+
+ const port_pin_config_t RMII0_MDC = {/* Internal pull-up/down resistor is disabled */
+ kPORT_PullDisable,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as RMII0_MDC */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTB1 (pin 54) is configured as RMII0_MDC */
+ PORT_SetPinConfig(BOARD_RMII0_MDC_PORT, BOARD_RMII0_MDC_PIN, &RMII0_MDC);
+
+ SIM->SOPT2 = ((SIM->SOPT2 &
+ /* Mask bits to zero which are setting */
+ (~(SIM_SOPT2_RMIISRC_MASK)))
+
+ /* RMII clock source select: EXTAL clock. */
+ | SIM_SOPT2_RMIISRC(SOPT2_RMIISRC_EXTAL));
+}
+
+/* clang-format off */
+/*
+ * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+BOARD_InitSDHC:
+- options: {callFromInitBoot: 'false', prefix: BOARD_, coreID: core0, enableClock: 'true'}
+- pin_list:
+ - {pin_num: '1', peripheral: SDHC, signal: 'DATA, 1', pin_signal: ADC1_SE4a/PTE0/SPI1_PCS1/UART1_TX/SDHC0_D1/TRACE_CLKOUT/I2C1_SDA/RTC_CLKOUT, slew_rate: fast,
+ open_drain: disable, drive_strength: high, pull_select: up, pull_enable: enable, passive_filter: disable}
+ - {pin_num: '2', peripheral: SDHC, signal: 'DATA, 0', pin_signal: ADC1_SE5a/PTE1/LLWU_P0/SPI1_SOUT/UART1_RX/SDHC0_D0/TRACE_D3/I2C1_SCL/SPI1_SIN, slew_rate: fast,
+ open_drain: disable, drive_strength: high, pull_select: up, pull_enable: enable, passive_filter: disable}
+ - {pin_num: '3', peripheral: SDHC, signal: DCLK, pin_signal: ADC0_DP2/ADC1_SE6a/PTE2/LLWU_P1/SPI1_SCK/UART1_CTS_b/SDHC0_DCLK/TRACE_D2, slew_rate: fast, open_drain: disable,
+ drive_strength: high, pull_select: up, pull_enable: enable, passive_filter: disable}
+ - {pin_num: '4', peripheral: SDHC, signal: CMD, pin_signal: ADC0_DM2/ADC1_SE7a/PTE3/SPI1_SIN/UART1_RTS_b/SDHC0_CMD/TRACE_D1/SPI1_SOUT, slew_rate: fast, open_drain: disable,
+ drive_strength: high, pull_select: up, pull_enable: enable, passive_filter: disable}
+ - {pin_num: '5', peripheral: SDHC, signal: 'DATA, 3', pin_signal: PTE4/LLWU_P2/SPI1_PCS0/UART3_TX/SDHC0_D3/TRACE_D0, slew_rate: fast, open_drain: disable, drive_strength: high,
+ pull_select: up, pull_enable: enable, passive_filter: disable}
+ - {pin_num: '6', peripheral: SDHC, signal: 'DATA, 2', pin_signal: PTE5/SPI1_PCS2/UART3_RX/SDHC0_D2/FTM3_CH0, slew_rate: fast, open_drain: disable, drive_strength: high,
+ pull_select: up, pull_enable: enable, passive_filter: disable}
+ - {pin_num: '7', peripheral: GPIOE, signal: 'GPIO, 6', pin_signal: PTE6/SPI1_PCS3/UART3_CTS_b/I2S0_MCLK/FTM3_CH1/USB_SOF_OUT, direction: INPUT, slew_rate: slow,
+ open_drain: disable, drive_strength: low, pull_select: down, pull_enable: enable, passive_filter: disable}
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
+ */
+/* clang-format on */
+
+/* FUNCTION ************************************************************************************************************
+ *
+ * Function Name : BOARD_InitSDHC
+ * Description : Configures pin routing and optionally pin electrical features.
+ *
+ * END ****************************************************************************************************************/
+void BOARD_InitSDHC(void)
+{
+ /* Port E Clock Gate Control: Clock enabled */
+ CLOCK_EnableClock(kCLOCK_PortE);
+
+ gpio_pin_config_t SDHC_CD_config = {
+ .pinDirection = kGPIO_DigitalInput,
+ .outputLogic = 0U
+ };
+ /* Initialize GPIO functionality on pin PTE6 (pin 7) */
+ GPIO_PinInit(BOARD_SDHC_CD_GPIO, BOARD_SDHC_CD_PIN, &SDHC_CD_config);
+
+ const port_pin_config_t SDHC0_D1 = {/* Internal pull-up resistor is enabled */
+ kPORT_PullUp,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* High drive strength is configured */
+ kPORT_HighDriveStrength,
+ /* Pin is configured as SDHC0_D1 */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTE0 (pin 1) is configured as SDHC0_D1 */
+ PORT_SetPinConfig(BOARD_SDHC0_D1_PORT, BOARD_SDHC0_D1_PIN, &SDHC0_D1);
+
+ const port_pin_config_t SDHC0_D0 = {/* Internal pull-up resistor is enabled */
+ kPORT_PullUp,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* High drive strength is configured */
+ kPORT_HighDriveStrength,
+ /* Pin is configured as SDHC0_D0 */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTE1 (pin 2) is configured as SDHC0_D0 */
+ PORT_SetPinConfig(BOARD_SDHC0_D0_PORT, BOARD_SDHC0_D0_PIN, &SDHC0_D0);
+
+ const port_pin_config_t SDHC0_DCLK = {/* Internal pull-up resistor is enabled */
+ kPORT_PullUp,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* High drive strength is configured */
+ kPORT_HighDriveStrength,
+ /* Pin is configured as SDHC0_DCLK */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTE2 (pin 3) is configured as SDHC0_DCLK */
+ PORT_SetPinConfig(BOARD_SDHC0_DCLK_PORT, BOARD_SDHC0_DCLK_PIN, &SDHC0_DCLK);
+
+ const port_pin_config_t SDHC0_CMD = {/* Internal pull-up resistor is enabled */
+ kPORT_PullUp,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* High drive strength is configured */
+ kPORT_HighDriveStrength,
+ /* Pin is configured as SDHC0_CMD */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTE3 (pin 4) is configured as SDHC0_CMD */
+ PORT_SetPinConfig(BOARD_SDHC0_CMD_PORT, BOARD_SDHC0_CMD_PIN, &SDHC0_CMD);
+
+ const port_pin_config_t SDHC0_D3 = {/* Internal pull-up resistor is enabled */
+ kPORT_PullUp,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* High drive strength is configured */
+ kPORT_HighDriveStrength,
+ /* Pin is configured as SDHC0_D3 */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTE4 (pin 5) is configured as SDHC0_D3 */
+ PORT_SetPinConfig(BOARD_SDHC0_D3_PORT, BOARD_SDHC0_D3_PIN, &SDHC0_D3);
+
+ const port_pin_config_t SDHC0_D2 = {/* Internal pull-up resistor is enabled */
+ kPORT_PullUp,
+ /* Fast slew rate is configured */
+ kPORT_FastSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* High drive strength is configured */
+ kPORT_HighDriveStrength,
+ /* Pin is configured as SDHC0_D2 */
+ kPORT_MuxAlt4,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTE5 (pin 6) is configured as SDHC0_D2 */
+ PORT_SetPinConfig(BOARD_SDHC0_D2_PORT, BOARD_SDHC0_D2_PIN, &SDHC0_D2);
+
+ const port_pin_config_t SDHC_CD = {/* Internal pull-down resistor is enabled */
+ kPORT_PullDown,
+ /* Slow slew rate is configured */
+ kPORT_SlowSlewRate,
+ /* Passive filter is disabled */
+ kPORT_PassiveFilterDisable,
+ /* Open drain is disabled */
+ kPORT_OpenDrainDisable,
+ /* Low drive strength is configured */
+ kPORT_LowDriveStrength,
+ /* Pin is configured as PTE6 */
+ kPORT_MuxAsGpio,
+ /* Pin Control Register fields [15:0] are not locked */
+ kPORT_UnlockRegister};
+ /* PORTE6 (pin 7) is configured as PTE6 */
+ PORT_SetPinConfig(BOARD_SDHC_CD_PORT, BOARD_SDHC_CD_PIN, &SDHC_CD);
+}
+
+/* clang-format off */
+/*
+ * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+BOARD_InitUSB:
+- options: {callFromInitBoot: 'false', prefix: BOARD_, coreID: core0, enableClock: 'true'}
+- pin_list:
+ - {pin_num: '10', peripheral: USB0, signal: DP, pin_signal: USB0_DP}
+ - {pin_num: '11', peripheral: USB0, signal: DM, pin_signal: USB0_DM}
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
+ */
+/* clang-format on */
+
+/* FUNCTION ************************************************************************************************************
+ *
+ * Function Name : BOARD_InitUSB
+ * Description : Configures pin routing and optionally pin electrical features.
+ *
+ * END ****************************************************************************************************************/
+void BOARD_InitUSB(void)
+{
+}
+/***********************************************************************************************************************
+ * EOF
+ **********************************************************************************************************************/
diff --git a/hw/bsp/kinetis_k/boards/frdm_k64f/board/pin_mux.h b/hw/bsp/kinetis_k/boards/frdm_k64f/board/pin_mux.h
new file mode 100644
index 000000000..6d64832ba
--- /dev/null
+++ b/hw/bsp/kinetis_k/boards/frdm_k64f/board/pin_mux.h
@@ -0,0 +1,645 @@
+/***********************************************************************************************************************
+ * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file
+ * will be overwritten if the respective MCUXpresso Config Tools is used to update this file.
+ **********************************************************************************************************************/
+
+#ifndef _PIN_MUX_H_
+#define _PIN_MUX_H_
+
+/***********************************************************************************************************************
+ * Definitions
+ **********************************************************************************************************************/
+
+/*! @brief Direction type */
+typedef enum _pin_mux_direction
+{
+ kPIN_MUX_DirectionInput = 0U, /* Input direction */
+ kPIN_MUX_DirectionOutput = 1U, /* Output direction */
+ kPIN_MUX_DirectionInputOrOutput = 2U /* Input or output direction */
+} pin_mux_direction_t;
+
+/*!
+ * @addtogroup pin_mux
+ * @{
+ */
+
+/***********************************************************************************************************************
+ * API
+ **********************************************************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @brief Calls initialization functions.
+ *
+ */
+void BOARD_InitBootPins(void);
+
+/*!
+ * @brief Configures pin routing and optionally pin electrical features.
+ *
+ */
+void BOARD_InitPins(void);
+
+/*! @name PORTC6 (number 78), U8[11]/SW2
+ @{ */
+/* Routed pin properties */
+#define BOARD_SW2_PERIPHERAL GPIOC /*!<@brief Peripheral name */
+#define BOARD_SW2_SIGNAL GPIO /*!<@brief Signal name */
+#define BOARD_SW2_CHANNEL 6 /*!<@brief Signal channel */
+#define BOARD_SW2_PIN_NAME PTC6 /*!<@brief Routed pin name */
+#define BOARD_SW2_LABEL "U8[11]/SW2" /*!<@brief Label */
+#define BOARD_SW2_NAME "SW2" /*!<@brief Identifier */
+#define BOARD_SW2_DIRECTION kPIN_MUX_DirectionInput /*!<@brief Direction */
+
+/* Symbols to be used with GPIO driver */
+#define BOARD_SW2_GPIO GPIOC /*!<@brief GPIO peripheral base pointer */
+#define BOARD_SW2_GPIO_PIN 6U /*!<@brief GPIO pin number */
+#define BOARD_SW2_GPIO_PIN_MASK (1U << 6U) /*!<@brief GPIO pin mask */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_SW2_PORT PORTC /*!<@brief PORT peripheral base pointer */
+#define BOARD_SW2_PIN 6U /*!<@brief PORT pin number */
+#define BOARD_SW2_PIN_MASK (1U << 6U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTA4 (number 38), SW3
+ @{ */
+/* Routed pin properties */
+#define BOARD_SW3_PERIPHERAL GPIOA /*!<@brief Peripheral name */
+#define BOARD_SW3_SIGNAL GPIO /*!<@brief Signal name */
+#define BOARD_SW3_CHANNEL 4 /*!<@brief Signal channel */
+#define BOARD_SW3_PIN_NAME PTA4 /*!<@brief Routed pin name */
+#define BOARD_SW3_LABEL "SW3" /*!<@brief Label */
+#define BOARD_SW3_NAME "SW3" /*!<@brief Identifier */
+#define BOARD_SW3_DIRECTION kPIN_MUX_DirectionInput /*!<@brief Direction */
+
+/* Symbols to be used with GPIO driver */
+#define BOARD_SW3_GPIO GPIOA /*!<@brief GPIO peripheral base pointer */
+#define BOARD_SW3_GPIO_PIN 4U /*!<@brief GPIO pin number */
+#define BOARD_SW3_GPIO_PIN_MASK (1U << 4U) /*!<@brief GPIO pin mask */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_SW3_PORT PORTA /*!<@brief PORT peripheral base pointer */
+#define BOARD_SW3_PIN 4U /*!<@brief PORT pin number */
+#define BOARD_SW3_PIN_MASK (1U << 4U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*!
+ * @brief Configures pin routing and optionally pin electrical features.
+ *
+ */
+void BOARD_InitButtons(void);
+
+/*! @name PORTB21 (number 67), D12[3]/LEDRGB_BLUE
+ @{ */
+/* Routed pin properties */
+#define BOARD_LED_BLUE_PERIPHERAL GPIOB /*!<@brief Peripheral name */
+#define BOARD_LED_BLUE_SIGNAL GPIO /*!<@brief Signal name */
+#define BOARD_LED_BLUE_CHANNEL 21 /*!<@brief Signal channel */
+#define BOARD_LED_BLUE_PIN_NAME PTB21 /*!<@brief Routed pin name */
+#define BOARD_LED_BLUE_LABEL "D12[3]/LEDRGB_BLUE" /*!<@brief Label */
+#define BOARD_LED_BLUE_NAME "LED_BLUE" /*!<@brief Identifier */
+#define BOARD_LED_BLUE_DIRECTION kPIN_MUX_DirectionOutput /*!<@brief Direction */
+
+/* Symbols to be used with GPIO driver */
+#define BOARD_LED_BLUE_GPIO GPIOB /*!<@brief GPIO peripheral base pointer */
+#define BOARD_LED_BLUE_GPIO_PIN 21U /*!<@brief GPIO pin number */
+#define BOARD_LED_BLUE_GPIO_PIN_MASK (1U << 21U) /*!<@brief GPIO pin mask */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_LED_BLUE_PORT PORTB /*!<@brief PORT peripheral base pointer */
+#define BOARD_LED_BLUE_PIN 21U /*!<@brief PORT pin number */
+#define BOARD_LED_BLUE_PIN_MASK (1U << 21U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTB22 (number 68), D12[1]/LEDRGB_RED
+ @{ */
+/* Routed pin properties */
+#define BOARD_LED_RED_PERIPHERAL GPIOB /*!<@brief Peripheral name */
+#define BOARD_LED_RED_SIGNAL GPIO /*!<@brief Signal name */
+#define BOARD_LED_RED_CHANNEL 22 /*!<@brief Signal channel */
+#define BOARD_LED_RED_PIN_NAME PTB22 /*!<@brief Routed pin name */
+#define BOARD_LED_RED_LABEL "D12[1]/LEDRGB_RED" /*!<@brief Label */
+#define BOARD_LED_RED_NAME "LED_RED" /*!<@brief Identifier */
+#define BOARD_LED_RED_DIRECTION kPIN_MUX_DirectionOutput /*!<@brief Direction */
+
+/* Symbols to be used with GPIO driver */
+#define BOARD_LED_RED_GPIO GPIOB /*!<@brief GPIO peripheral base pointer */
+#define BOARD_LED_RED_GPIO_PIN 22U /*!<@brief GPIO pin number */
+#define BOARD_LED_RED_GPIO_PIN_MASK (1U << 22U) /*!<@brief GPIO pin mask */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_LED_RED_PORT PORTB /*!<@brief PORT peripheral base pointer */
+#define BOARD_LED_RED_PIN 22U /*!<@brief PORT pin number */
+#define BOARD_LED_RED_PIN_MASK (1U << 22U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTE26 (number 33), J2[1]/D12[4]/LEDRGB_GREEN
+ @{ */
+/* Routed pin properties */
+#define BOARD_LED_GREEN_PERIPHERAL GPIOE /*!<@brief Peripheral name */
+#define BOARD_LED_GREEN_SIGNAL GPIO /*!<@brief Signal name */
+#define BOARD_LED_GREEN_CHANNEL 26 /*!<@brief Signal channel */
+#define BOARD_LED_GREEN_PIN_NAME PTE26 /*!<@brief Routed pin name */
+#define BOARD_LED_GREEN_LABEL "J2[1]/D12[4]/LEDRGB_GREEN" /*!<@brief Label */
+#define BOARD_LED_GREEN_NAME "LED_GREEN" /*!<@brief Identifier */
+#define BOARD_LED_GREEN_DIRECTION kPIN_MUX_DirectionOutput /*!<@brief Direction */
+
+/* Symbols to be used with GPIO driver */
+#define BOARD_LED_GREEN_GPIO GPIOE /*!<@brief GPIO peripheral base pointer */
+#define BOARD_LED_GREEN_GPIO_PIN 26U /*!<@brief GPIO pin number */
+#define BOARD_LED_GREEN_GPIO_PIN_MASK (1U << 26U) /*!<@brief GPIO pin mask */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_LED_GREEN_PORT PORTE /*!<@brief PORT peripheral base pointer */
+#define BOARD_LED_GREEN_PIN 26U /*!<@brief PORT pin number */
+#define BOARD_LED_GREEN_PIN_MASK (1U << 26U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*!
+ * @brief Configures pin routing and optionally pin electrical features.
+ *
+ */
+void BOARD_InitLEDs(void);
+
+#define SOPT5_UART0TXSRC_UART_TX 0x00u /*!<@brief UART 0 transmit data source select: UART0_TX pin */
+
+/*! @name PORTB17 (number 63), U10[1]/UART0_TX
+ @{ */
+/* Routed pin properties */
+#define BOARD_DEBUG_UART_TX_PERIPHERAL UART0 /*!<@brief Peripheral name */
+#define BOARD_DEBUG_UART_TX_SIGNAL TX /*!<@brief Signal name */
+#define BOARD_DEBUG_UART_TX_PIN_NAME UART0_TX /*!<@brief Routed pin name */
+#define BOARD_DEBUG_UART_TX_LABEL "U10[1]/UART0_TX" /*!<@brief Label */
+#define BOARD_DEBUG_UART_TX_NAME "DEBUG_UART_TX" /*!<@brief Identifier */
+#define BOARD_DEBUG_UART_TX_DIRECTION kPIN_MUX_DirectionOutput /*!<@brief Direction */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_DEBUG_UART_TX_PORT PORTB /*!<@brief PORT peripheral base pointer */
+#define BOARD_DEBUG_UART_TX_PIN 17U /*!<@brief PORT pin number */
+#define BOARD_DEBUG_UART_TX_PIN_MASK (1U << 17U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTB16 (number 62), U7[4]/UART0_RX
+ @{ */
+/* Routed pin properties */
+#define BOARD_DEBUG_UART_RX_PERIPHERAL UART0 /*!<@brief Peripheral name */
+#define BOARD_DEBUG_UART_RX_SIGNAL RX /*!<@brief Signal name */
+#define BOARD_DEBUG_UART_RX_PIN_NAME UART0_RX /*!<@brief Routed pin name */
+#define BOARD_DEBUG_UART_RX_LABEL "U7[4]/UART0_RX" /*!<@brief Label */
+#define BOARD_DEBUG_UART_RX_NAME "DEBUG_UART_RX" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_DEBUG_UART_RX_PORT PORTB /*!<@brief PORT peripheral base pointer */
+#define BOARD_DEBUG_UART_RX_PIN 16U /*!<@brief PORT pin number */
+#define BOARD_DEBUG_UART_RX_PIN_MASK (1U << 16U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*!
+ * @brief Configures pin routing and optionally pin electrical features.
+ *
+ */
+void BOARD_InitDEBUG_UART(void);
+
+/*! @name PORTA18 (number 50), U13[16]/RMII_RXCLK
+ @{ */
+/* Routed pin properties */
+#define BOARD_EXTAL0_PERIPHERAL OSC /*!<@brief Peripheral name */
+#define BOARD_EXTAL0_SIGNAL EXTAL0 /*!<@brief Signal name */
+#define BOARD_EXTAL0_PIN_NAME EXTAL0 /*!<@brief Routed pin name */
+#define BOARD_EXTAL0_LABEL "U13[16]/RMII_RXCLK" /*!<@brief Label */
+#define BOARD_EXTAL0_NAME "EXTAL0" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_EXTAL0_PORT PORTA /*!<@brief PORT peripheral base pointer */
+#define BOARD_EXTAL0_PIN 18U /*!<@brief PORT pin number */
+#define BOARD_EXTAL0_PIN_MASK (1U << 18U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name EXTAL32 (number 29), Y3[2]/EXTAL32_RTC
+ @{ */
+/* Routed pin properties */
+#define BOARD_ETAL32K_PERIPHERAL RTC /*!<@brief Peripheral name */
+#define BOARD_ETAL32K_SIGNAL EXTAL32 /*!<@brief Signal name */
+#define BOARD_ETAL32K_PIN_NAME EXTAL32 /*!<@brief Routed pin name */
+#define BOARD_ETAL32K_LABEL "Y3[2]/EXTAL32_RTC" /*!<@brief Label */
+#define BOARD_ETAL32K_NAME "ETAL32K" /*!<@brief Identifier */
+ /* @} */
+
+/*! @name XTAL32 (number 28), Y3[1]/XTAL32_RTC
+ @{ */
+/* Routed pin properties */
+#define BOARD_XTAL32K_PERIPHERAL RTC /*!<@brief Peripheral name */
+#define BOARD_XTAL32K_SIGNAL XTAL32 /*!<@brief Signal name */
+#define BOARD_XTAL32K_PIN_NAME XTAL32 /*!<@brief Routed pin name */
+#define BOARD_XTAL32K_LABEL "Y3[1]/XTAL32_RTC" /*!<@brief Label */
+#define BOARD_XTAL32K_NAME "XTAL32K" /*!<@brief Identifier */
+ /* @} */
+
+/*!
+ * @brief Configures pin routing and optionally pin electrical features.
+ *
+ */
+void BOARD_InitOSC(void);
+
+/*! @name PORTE25 (number 32), J2[18]/U8[6]/I2C0_SDA
+ @{ */
+/* Routed pin properties */
+#define BOARD_ACCEL_SDA_PERIPHERAL I2C0 /*!<@brief Peripheral name */
+#define BOARD_ACCEL_SDA_SIGNAL SDA /*!<@brief Signal name */
+#define BOARD_ACCEL_SDA_PIN_NAME I2C0_SDA /*!<@brief Routed pin name */
+#define BOARD_ACCEL_SDA_LABEL "J2[18]/U8[6]/I2C0_SDA" /*!<@brief Label */
+#define BOARD_ACCEL_SDA_NAME "ACCEL_SDA" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_ACCEL_SDA_PORT PORTE /*!<@brief PORT peripheral base pointer */
+#define BOARD_ACCEL_SDA_PIN 25U /*!<@brief PORT pin number */
+#define BOARD_ACCEL_SDA_PIN_MASK (1U << 25U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTE24 (number 31), J2[20]/U8[4]/I2C0_SCL
+ @{ */
+/* Routed pin properties */
+#define BOARD_ACCEL_SCL_PERIPHERAL I2C0 /*!<@brief Peripheral name */
+#define BOARD_ACCEL_SCL_SIGNAL SCL /*!<@brief Signal name */
+#define BOARD_ACCEL_SCL_PIN_NAME I2C0_SCL /*!<@brief Routed pin name */
+#define BOARD_ACCEL_SCL_LABEL "J2[20]/U8[4]/I2C0_SCL" /*!<@brief Label */
+#define BOARD_ACCEL_SCL_NAME "ACCEL_SCL" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_ACCEL_SCL_PORT PORTE /*!<@brief PORT peripheral base pointer */
+#define BOARD_ACCEL_SCL_PIN 24U /*!<@brief PORT pin number */
+#define BOARD_ACCEL_SCL_PIN_MASK (1U << 24U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTC6 (number 78), U8[11]/SW2
+ @{ */
+/* Routed pin properties */
+#define BOARD_ACCEL_INT1_PERIPHERAL GPIOC /*!<@brief Peripheral name */
+#define BOARD_ACCEL_INT1_SIGNAL GPIO /*!<@brief Signal name */
+#define BOARD_ACCEL_INT1_CHANNEL 6 /*!<@brief Signal channel */
+#define BOARD_ACCEL_INT1_PIN_NAME PTC6 /*!<@brief Routed pin name */
+#define BOARD_ACCEL_INT1_LABEL "U8[11]/SW2" /*!<@brief Label */
+#define BOARD_ACCEL_INT1_NAME "ACCEL_INT1" /*!<@brief Identifier */
+#define BOARD_ACCEL_INT1_DIRECTION kPIN_MUX_DirectionInput /*!<@brief Direction */
+
+/* Symbols to be used with GPIO driver */
+#define BOARD_ACCEL_INT1_GPIO GPIOC /*!<@brief GPIO peripheral base pointer */
+#define BOARD_ACCEL_INT1_GPIO_PIN 6U /*!<@brief GPIO pin number */
+#define BOARD_ACCEL_INT1_GPIO_PIN_MASK (1U << 6U) /*!<@brief GPIO pin mask */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_ACCEL_INT1_PORT PORTC /*!<@brief PORT peripheral base pointer */
+#define BOARD_ACCEL_INT1_PIN 6U /*!<@brief PORT pin number */
+#define BOARD_ACCEL_INT1_PIN_MASK (1U << 6U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTC13 (number 85), U8[9]
+ @{ */
+/* Routed pin properties */
+#define BOARD_ACCEL_INT2_PERIPHERAL GPIOC /*!<@brief Peripheral name */
+#define BOARD_ACCEL_INT2_SIGNAL GPIO /*!<@brief Signal name */
+#define BOARD_ACCEL_INT2_CHANNEL 13 /*!<@brief Signal channel */
+#define BOARD_ACCEL_INT2_PIN_NAME PTC13 /*!<@brief Routed pin name */
+#define BOARD_ACCEL_INT2_LABEL "U8[9]" /*!<@brief Label */
+#define BOARD_ACCEL_INT2_NAME "ACCEL_INT2" /*!<@brief Identifier */
+#define BOARD_ACCEL_INT2_DIRECTION kPIN_MUX_DirectionInput /*!<@brief Direction */
+
+/* Symbols to be used with GPIO driver */
+#define BOARD_ACCEL_INT2_GPIO GPIOC /*!<@brief GPIO peripheral base pointer */
+#define BOARD_ACCEL_INT2_GPIO_PIN 13U /*!<@brief GPIO pin number */
+#define BOARD_ACCEL_INT2_GPIO_PIN_MASK (1U << 13U) /*!<@brief GPIO pin mask */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_ACCEL_INT2_PORT PORTC /*!<@brief PORT peripheral base pointer */
+#define BOARD_ACCEL_INT2_PIN 13U /*!<@brief PORT pin number */
+#define BOARD_ACCEL_INT2_PIN_MASK (1U << 13U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*!
+ * @brief Configures pin routing and optionally pin electrical features.
+ *
+ */
+void BOARD_InitACCEL(void);
+
+#define SOPT2_RMIISRC_EXTAL 0x00u /*!<@brief RMII clock source select: EXTAL clock */
+
+/*! @name PORTB1 (number 54), U13[11]/RMII0_MDC
+ @{ */
+/* Routed pin properties */
+#define BOARD_RMII0_MDC_PERIPHERAL ENET /*!<@brief Peripheral name */
+#define BOARD_RMII0_MDC_SIGNAL RMII_MDC /*!<@brief Signal name */
+#define BOARD_RMII0_MDC_PIN_NAME RMII0_MDC /*!<@brief Routed pin name */
+#define BOARD_RMII0_MDC_LABEL "U13[11]/RMII0_MDC" /*!<@brief Label */
+#define BOARD_RMII0_MDC_NAME "RMII0_MDC" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_RMII0_MDC_PORT PORTB /*!<@brief PORT peripheral base pointer */
+#define BOARD_RMII0_MDC_PIN 1U /*!<@brief PORT pin number */
+#define BOARD_RMII0_MDC_PIN_MASK (1U << 1U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTB0 (number 53), U13[10]/RMII0_MDIO
+ @{ */
+/* Routed pin properties */
+#define BOARD_RMII0_MDIO_PERIPHERAL ENET /*!<@brief Peripheral name */
+#define BOARD_RMII0_MDIO_SIGNAL RMII_MDIO /*!<@brief Signal name */
+#define BOARD_RMII0_MDIO_PIN_NAME RMII0_MDIO /*!<@brief Routed pin name */
+#define BOARD_RMII0_MDIO_LABEL "U13[10]/RMII0_MDIO" /*!<@brief Label */
+#define BOARD_RMII0_MDIO_NAME "RMII0_MDIO" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_RMII0_MDIO_PORT PORTB /*!<@brief PORT peripheral base pointer */
+#define BOARD_RMII0_MDIO_PIN 0U /*!<@brief PORT pin number */
+#define BOARD_RMII0_MDIO_PIN_MASK (1U << 0U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTA13 (number 43), U13[13]/RMII0_RXD_0
+ @{ */
+/* Routed pin properties */
+#define BOARD_RMII0_RXD0_PERIPHERAL ENET /*!<@brief Peripheral name */
+#define BOARD_RMII0_RXD0_SIGNAL RMII_RXD0 /*!<@brief Signal name */
+#define BOARD_RMII0_RXD0_PIN_NAME RMII0_RXD0 /*!<@brief Routed pin name */
+#define BOARD_RMII0_RXD0_LABEL "U13[13]/RMII0_RXD_0" /*!<@brief Label */
+#define BOARD_RMII0_RXD0_NAME "RMII0_RXD0" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_RMII0_RXD0_PORT PORTA /*!<@brief PORT peripheral base pointer */
+#define BOARD_RMII0_RXD0_PIN 13U /*!<@brief PORT pin number */
+#define BOARD_RMII0_RXD0_PIN_MASK (1U << 13U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTA12 (number 42), U13[12]/RMII0_RXD_1
+ @{ */
+/* Routed pin properties */
+#define BOARD_RMII0_RXD1_PERIPHERAL ENET /*!<@brief Peripheral name */
+#define BOARD_RMII0_RXD1_SIGNAL RMII_RXD1 /*!<@brief Signal name */
+#define BOARD_RMII0_RXD1_PIN_NAME RMII0_RXD1 /*!<@brief Routed pin name */
+#define BOARD_RMII0_RXD1_LABEL "U13[12]/RMII0_RXD_1" /*!<@brief Label */
+#define BOARD_RMII0_RXD1_NAME "RMII0_RXD1" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_RMII0_RXD1_PORT PORTA /*!<@brief PORT peripheral base pointer */
+#define BOARD_RMII0_RXD1_PIN 12U /*!<@brief PORT pin number */
+#define BOARD_RMII0_RXD1_PIN_MASK (1U << 12U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTA5 (number 39), U13[17]/RMII0_RXER
+ @{ */
+/* Routed pin properties */
+#define BOARD_RMII0_RXER_PERIPHERAL ENET /*!<@brief Peripheral name */
+#define BOARD_RMII0_RXER_SIGNAL RMII_RXER /*!<@brief Signal name */
+#define BOARD_RMII0_RXER_PIN_NAME RMII0_RXER /*!<@brief Routed pin name */
+#define BOARD_RMII0_RXER_LABEL "U13[17]/RMII0_RXER" /*!<@brief Label */
+#define BOARD_RMII0_RXER_NAME "RMII0_RXER" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_RMII0_RXER_PORT PORTA /*!<@brief PORT peripheral base pointer */
+#define BOARD_RMII0_RXER_PIN 5U /*!<@brief PORT pin number */
+#define BOARD_RMII0_RXER_PIN_MASK (1U << 5U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTA16 (number 46), U13[20]/RMII0_TXD0
+ @{ */
+/* Routed pin properties */
+#define BOARD_RMII0_TXD0_PERIPHERAL ENET /*!<@brief Peripheral name */
+#define BOARD_RMII0_TXD0_SIGNAL RMII_TXD0 /*!<@brief Signal name */
+#define BOARD_RMII0_TXD0_PIN_NAME RMII0_TXD0 /*!<@brief Routed pin name */
+#define BOARD_RMII0_TXD0_LABEL "U13[20]/RMII0_TXD0" /*!<@brief Label */
+#define BOARD_RMII0_TXD0_NAME "RMII0_TXD0" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_RMII0_TXD0_PORT PORTA /*!<@brief PORT peripheral base pointer */
+#define BOARD_RMII0_TXD0_PIN 16U /*!<@brief PORT pin number */
+#define BOARD_RMII0_TXD0_PIN_MASK (1U << 16U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTA17 (number 47), U13[21]/RMII0_TXD1
+ @{ */
+/* Routed pin properties */
+#define BOARD_RMII0_TXD1_PERIPHERAL ENET /*!<@brief Peripheral name */
+#define BOARD_RMII0_TXD1_SIGNAL RMII_TXD1 /*!<@brief Signal name */
+#define BOARD_RMII0_TXD1_PIN_NAME RMII0_TXD1 /*!<@brief Routed pin name */
+#define BOARD_RMII0_TXD1_LABEL "U13[21]/RMII0_TXD1" /*!<@brief Label */
+#define BOARD_RMII0_TXD1_NAME "RMII0_TXD1" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_RMII0_TXD1_PORT PORTA /*!<@brief PORT peripheral base pointer */
+#define BOARD_RMII0_TXD1_PIN 17U /*!<@brief PORT pin number */
+#define BOARD_RMII0_TXD1_PIN_MASK (1U << 17U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTA15 (number 45), U13[19]/RMII0_TXEN
+ @{ */
+/* Routed pin properties */
+#define BOARD_RMII0_TXEN_PERIPHERAL ENET /*!<@brief Peripheral name */
+#define BOARD_RMII0_TXEN_SIGNAL RMII_TXEN /*!<@brief Signal name */
+#define BOARD_RMII0_TXEN_PIN_NAME RMII0_TXEN /*!<@brief Routed pin name */
+#define BOARD_RMII0_TXEN_LABEL "U13[19]/RMII0_TXEN" /*!<@brief Label */
+#define BOARD_RMII0_TXEN_NAME "RMII0_TXEN" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_RMII0_TXEN_PORT PORTA /*!<@brief PORT peripheral base pointer */
+#define BOARD_RMII0_TXEN_PIN 15U /*!<@brief PORT pin number */
+#define BOARD_RMII0_TXEN_PIN_MASK (1U << 15U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTA14 (number 44), U13[15]/RMII0_CRS_DV
+ @{ */
+/* Routed pin properties */
+#define BOARD_RMII0_CRS_DV_PERIPHERAL ENET /*!<@brief Peripheral name */
+#define BOARD_RMII0_CRS_DV_SIGNAL RMII_CRS_DV /*!<@brief Signal name */
+#define BOARD_RMII0_CRS_DV_PIN_NAME RMII0_CRS_DV /*!<@brief Routed pin name */
+#define BOARD_RMII0_CRS_DV_LABEL "U13[15]/RMII0_CRS_DV" /*!<@brief Label */
+#define BOARD_RMII0_CRS_DV_NAME "RMII0_CRS_DV" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_RMII0_CRS_DV_PORT PORTA /*!<@brief PORT peripheral base pointer */
+#define BOARD_RMII0_CRS_DV_PIN 14U /*!<@brief PORT pin number */
+#define BOARD_RMII0_CRS_DV_PIN_MASK (1U << 14U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTA18 (number 50), U13[16]/RMII_RXCLK
+ @{ */
+/* Routed pin properties */
+#define BOARD_RMII_RXCLK_PERIPHERAL ENET /*!<@brief Peripheral name */
+#define BOARD_RMII_RXCLK_SIGNAL RMII_CLKIN /*!<@brief Signal name */
+#define BOARD_RMII_RXCLK_PIN_NAME EXTAL0 /*!<@brief Routed pin name */
+#define BOARD_RMII_RXCLK_LABEL "U13[16]/RMII_RXCLK" /*!<@brief Label */
+#define BOARD_RMII_RXCLK_NAME "RMII_RXCLK" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_RMII_RXCLK_PORT PORTA /*!<@brief PORT peripheral base pointer */
+#define BOARD_RMII_RXCLK_PIN 18U /*!<@brief PORT pin number */
+#define BOARD_RMII_RXCLK_PIN_MASK (1U << 18U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*!
+ * @brief Configures pin routing and optionally pin electrical features.
+ *
+ */
+void BOARD_InitENET(void);
+
+/*! @name PORTE0 (number 1), J15[P8]/SDHC0_D1
+ @{ */
+/* Routed pin properties */
+#define BOARD_SDHC0_D1_PERIPHERAL SDHC /*!<@brief Peripheral name */
+#define BOARD_SDHC0_D1_SIGNAL DATA /*!<@brief Signal name */
+#define BOARD_SDHC0_D1_CHANNEL 1 /*!<@brief Signal channel */
+#define BOARD_SDHC0_D1_PIN_NAME SDHC0_D1 /*!<@brief Routed pin name */
+#define BOARD_SDHC0_D1_LABEL "J15[P8]/SDHC0_D1" /*!<@brief Label */
+#define BOARD_SDHC0_D1_NAME "SDHC0_D1" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_SDHC0_D1_PORT PORTE /*!<@brief PORT peripheral base pointer */
+#define BOARD_SDHC0_D1_PIN 0U /*!<@brief PORT pin number */
+#define BOARD_SDHC0_D1_PIN_MASK (1U << 0U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTE1 (number 2), J15[P7]/SDHC0_D0
+ @{ */
+/* Routed pin properties */
+#define BOARD_SDHC0_D0_PERIPHERAL SDHC /*!<@brief Peripheral name */
+#define BOARD_SDHC0_D0_SIGNAL DATA /*!<@brief Signal name */
+#define BOARD_SDHC0_D0_CHANNEL 0 /*!<@brief Signal channel */
+#define BOARD_SDHC0_D0_PIN_NAME SDHC0_D0 /*!<@brief Routed pin name */
+#define BOARD_SDHC0_D0_LABEL "J15[P7]/SDHC0_D0" /*!<@brief Label */
+#define BOARD_SDHC0_D0_NAME "SDHC0_D0" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_SDHC0_D0_PORT PORTE /*!<@brief PORT peripheral base pointer */
+#define BOARD_SDHC0_D0_PIN 1U /*!<@brief PORT pin number */
+#define BOARD_SDHC0_D0_PIN_MASK (1U << 1U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTE2 (number 3), J15[P5]/SDHC0_DCLK
+ @{ */
+/* Routed pin properties */
+#define BOARD_SDHC0_DCLK_PERIPHERAL SDHC /*!<@brief Peripheral name */
+#define BOARD_SDHC0_DCLK_SIGNAL DCLK /*!<@brief Signal name */
+#define BOARD_SDHC0_DCLK_PIN_NAME SDHC0_DCLK /*!<@brief Routed pin name */
+#define BOARD_SDHC0_DCLK_LABEL "J15[P5]/SDHC0_DCLK" /*!<@brief Label */
+#define BOARD_SDHC0_DCLK_NAME "SDHC0_DCLK" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_SDHC0_DCLK_PORT PORTE /*!<@brief PORT peripheral base pointer */
+#define BOARD_SDHC0_DCLK_PIN 2U /*!<@brief PORT pin number */
+#define BOARD_SDHC0_DCLK_PIN_MASK (1U << 2U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTE3 (number 4), J15[P3]/SDHC0_CMD
+ @{ */
+/* Routed pin properties */
+#define BOARD_SDHC0_CMD_PERIPHERAL SDHC /*!<@brief Peripheral name */
+#define BOARD_SDHC0_CMD_SIGNAL CMD /*!<@brief Signal name */
+#define BOARD_SDHC0_CMD_PIN_NAME SDHC0_CMD /*!<@brief Routed pin name */
+#define BOARD_SDHC0_CMD_LABEL "J15[P3]/SDHC0_CMD" /*!<@brief Label */
+#define BOARD_SDHC0_CMD_NAME "SDHC0_CMD" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_SDHC0_CMD_PORT PORTE /*!<@brief PORT peripheral base pointer */
+#define BOARD_SDHC0_CMD_PIN 3U /*!<@brief PORT pin number */
+#define BOARD_SDHC0_CMD_PIN_MASK (1U << 3U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTE4 (number 5), J15[P2]/SDHC0_D3
+ @{ */
+/* Routed pin properties */
+#define BOARD_SDHC0_D3_PERIPHERAL SDHC /*!<@brief Peripheral name */
+#define BOARD_SDHC0_D3_SIGNAL DATA /*!<@brief Signal name */
+#define BOARD_SDHC0_D3_CHANNEL 3 /*!<@brief Signal channel */
+#define BOARD_SDHC0_D3_PIN_NAME SDHC0_D3 /*!<@brief Routed pin name */
+#define BOARD_SDHC0_D3_LABEL "J15[P2]/SDHC0_D3" /*!<@brief Label */
+#define BOARD_SDHC0_D3_NAME "SDHC0_D3" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_SDHC0_D3_PORT PORTE /*!<@brief PORT peripheral base pointer */
+#define BOARD_SDHC0_D3_PIN 4U /*!<@brief PORT pin number */
+#define BOARD_SDHC0_D3_PIN_MASK (1U << 4U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTE5 (number 6), J15[P1]/SDHC0_D2
+ @{ */
+/* Routed pin properties */
+#define BOARD_SDHC0_D2_PERIPHERAL SDHC /*!<@brief Peripheral name */
+#define BOARD_SDHC0_D2_SIGNAL DATA /*!<@brief Signal name */
+#define BOARD_SDHC0_D2_CHANNEL 2 /*!<@brief Signal channel */
+#define BOARD_SDHC0_D2_PIN_NAME SDHC0_D2 /*!<@brief Routed pin name */
+#define BOARD_SDHC0_D2_LABEL "J15[P1]/SDHC0_D2" /*!<@brief Label */
+#define BOARD_SDHC0_D2_NAME "SDHC0_D2" /*!<@brief Identifier */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_SDHC0_D2_PORT PORTE /*!<@brief PORT peripheral base pointer */
+#define BOARD_SDHC0_D2_PIN 5U /*!<@brief PORT pin number */
+#define BOARD_SDHC0_D2_PIN_MASK (1U << 5U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*! @name PORTE6 (number 7), J15[G1]/SD_CARD_DETECT
+ @{ */
+/* Routed pin properties */
+#define BOARD_SDHC_CD_PERIPHERAL GPIOE /*!<@brief Peripheral name */
+#define BOARD_SDHC_CD_SIGNAL GPIO /*!<@brief Signal name */
+#define BOARD_SDHC_CD_CHANNEL 6 /*!<@brief Signal channel */
+#define BOARD_SDHC_CD_PIN_NAME PTE6 /*!<@brief Routed pin name */
+#define BOARD_SDHC_CD_LABEL "J15[G1]/SD_CARD_DETECT" /*!<@brief Label */
+#define BOARD_SDHC_CD_NAME "SDHC_CD" /*!<@brief Identifier */
+#define BOARD_SDHC_CD_DIRECTION kPIN_MUX_DirectionInput /*!<@brief Direction */
+
+/* Symbols to be used with GPIO driver */
+#define BOARD_SDHC_CD_GPIO GPIOE /*!<@brief GPIO peripheral base pointer */
+#define BOARD_SDHC_CD_GPIO_PIN 6U /*!<@brief GPIO pin number */
+#define BOARD_SDHC_CD_GPIO_PIN_MASK (1U << 6U) /*!<@brief GPIO pin mask */
+
+/* Symbols to be used with PORT driver */
+#define BOARD_SDHC_CD_PORT PORTE /*!<@brief PORT peripheral base pointer */
+#define BOARD_SDHC_CD_PIN 6U /*!<@brief PORT pin number */
+#define BOARD_SDHC_CD_PIN_MASK (1U << 6U) /*!<@brief PORT pin mask */
+ /* @} */
+
+/*!
+ * @brief Configures pin routing and optionally pin electrical features.
+ *
+ */
+void BOARD_InitSDHC(void);
+
+/*! @name USB0_DP (number 10), J22[3]/K64_MICRO_USB_DP
+ @{ */
+/* Routed pin properties */
+#define BOARD_USB_DP_PERIPHERAL USB0 /*!<@brief Peripheral name */
+#define BOARD_USB_DP_SIGNAL DP /*!<@brief Signal name */
+#define BOARD_USB_DP_PIN_NAME USB0_DP /*!<@brief Routed pin name */
+#define BOARD_USB_DP_LABEL "J22[3]/K64_MICRO_USB_DP" /*!<@brief Label */
+#define BOARD_USB_DP_NAME "USB_DP" /*!<@brief Identifier */
+ /* @} */
+
+/*! @name USB0_DM (number 11), J22[2]/K64_MICRO_USB_DN
+ @{ */
+/* Routed pin properties */
+#define BOARD_USB_DM_PERIPHERAL USB0 /*!<@brief Peripheral name */
+#define BOARD_USB_DM_SIGNAL DM /*!<@brief Signal name */
+#define BOARD_USB_DM_PIN_NAME USB0_DM /*!<@brief Routed pin name */
+#define BOARD_USB_DM_LABEL "J22[2]/K64_MICRO_USB_DN" /*!<@brief Label */
+#define BOARD_USB_DM_NAME "USB_DM" /*!<@brief Identifier */
+ /* @} */
+
+/*!
+ * @brief Configures pin routing and optionally pin electrical features.
+ *
+ */
+void BOARD_InitUSB(void);
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*!
+ * @}
+ */
+#endif /* _PIN_MUX_H_ */
+
+/***********************************************************************************************************************
+ * EOF
+ **********************************************************************************************************************/
diff --git a/hw/bsp/kinetis_k/boards/frdm_k64f/frdm_k64f.mex b/hw/bsp/kinetis_k/boards/frdm_k64f/frdm_k64f.mex
new file mode 100644
index 000000000..4a8c77f95
--- /dev/null
+++ b/hw/bsp/kinetis_k/boards/frdm_k64f/frdm_k64f.mex
@@ -0,0 +1,950 @@
+
+
+
+ MK64FN1M0xxx12
+ MK64FN1M0VLL12
+ FRDM-K64F
+ E1
+ ksdk2_0
+
+
+
+
+
+
+ true
+ true
+ false
+ true
+ false
+
+
+
+
+
+
+
+
+ 14.0.0
+
+
+
+ Configures pin routing and optionally pin electrical features.
+
+ false
+ BOARD_
+ core0
+ true
+
+
+
+
+ true
+
+
+
+
+
+
+ Configures pin routing and optionally pin electrical features.
+
+ true
+ BOARD_
+ core0
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Configures pin routing and optionally pin electrical features.
+
+ true
+ BOARD_
+ core0
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Configures pin routing and optionally pin electrical features.
+
+ true
+ BOARD_
+ core0
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Configures pin routing and optionally pin electrical features.
+
+ false
+ BOARD_
+ core0
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Configures pin routing and optionally pin electrical features.
+
+ false
+ BOARD_
+ core0
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Configures pin routing and optionally pin electrical features.
+
+ false
+ BOARD_
+ core0
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Configures pin routing and optionally pin electrical features.
+
+ false
+ BOARD_
+ core0
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Configures pin routing and optionally pin electrical features.
+
+ false
+ BOARD_
+ core0
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 14.0.0
+
+
+
+
+
+
+
+
+ true
+
+
+
+
+ INPUT
+
+
+
+
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+ 0.0.0
+
+
+
+
+
+
+
+ true
+
+
+
+
+ 2.8.0
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 14.0.0
+
+
+
+
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+ 0
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 0.0.0
+
+
+
+
+
+
+
diff --git a/hw/bsp/kinetis_k/boards/teensy_35/board.cmake b/hw/bsp/kinetis_k/boards/teensy_35/board.cmake
new file mode 100644
index 000000000..bd253d996
--- /dev/null
+++ b/hw/bsp/kinetis_k/boards/teensy_35/board.cmake
@@ -0,0 +1,17 @@
+set(MCU_VARIANT MK64F12)
+
+set(JLINK_DEVICE MK64FX512xxx12)
+set(TEENSY_MCU TEENSY35)
+set(PYOCD_TARGET k64f)
+
+set(LD_FILE_GNU ${SDK_DIR}/devices/${MCU_VARIANT}/gcc/MK64FX512xxx12_flash.ld)
+
+function(update_board TARGET)
+ target_sources(${TARGET} PUBLIC
+ ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/board/pin_mux.c
+ ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/board/clock_config.c
+ )
+ target_compile_definitions(${TARGET} PUBLIC
+ CPU_MK64FX512VMD12
+ )
+endfunction()
diff --git a/hw/bsp/kinetis_k/boards/teensy_35/board.h b/hw/bsp/kinetis_k/boards/teensy_35/board.h
new file mode 100644
index 000000000..f8173447a
--- /dev/null
+++ b/hw/bsp/kinetis_k/boards/teensy_35/board.h
@@ -0,0 +1,48 @@
+/*
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2023 Ha Thach (tinyusb.org)
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#ifndef BOARD_H
+#define BOARD_H
+
+//--------------------------------------------------------------------+
+// MACRO TYPEDEF CONSTANT ENUM DECLARATION
+//--------------------------------------------------------------------+
+// LED
+#define LED_PORT GPIOC
+#define LED_PIN 5
+#define LED_STATE_ON 1
+
+// Button
+
+// UART
+//#define UART_PORT UART0
+//#define UART_PIN_CLOCK kCLOCK_PortA
+//#define UART_PIN_PORT PORTA
+//#define UART_PIN_RX 1u
+//#define UART_PIN_TX 2u
+//#define UART_PIN_FUNCTION kPORT_MuxAlt2
+//#define SOPT5_UART0RXSRC_UART_RX 0x00u /*!< UART0 receive data source select: UART0_RX pin */
+//#define SOPT5_UART0TXSRC_UART_TX 0x00u /*!< UART0 transmit data source select: UART0_TX pin */
+
+#endif
diff --git a/hw/bsp/kinetis_k/boards/teensy_35/board.mk b/hw/bsp/kinetis_k/boards/teensy_35/board.mk
new file mode 100644
index 000000000..2c4f87c25
--- /dev/null
+++ b/hw/bsp/kinetis_k/boards/teensy_35/board.mk
@@ -0,0 +1,23 @@
+MCU_VARIANT = MK64F12
+
+CFLAGS += \
+ -DCPU_MK64FX512VMD12 \
+
+# mcu driver cause following warnings
+CFLAGS += -Wno-error=unused-parameter -Wno-error=format -Wno-error=redundant-decls
+
+SRC_C += \
+ $(BOARD_PATH)/board/clock_config.c \
+ $(BOARD_PATH)/board/pin_mux.c \
+
+LD_FILE = ${SDK_DIR}/devices/${MCU_VARIANT}/gcc/MK64FX512xxx12_flash.ld
+
+# For flash-jlink target
+JLINK_DEVICE = MK64FX512xxx12
+
+# For flash-pyocd target
+PYOCD_TARGET = k64f
+
+# flash by using teensy_loader_cli https://github.com/PaulStoffregen/teensy_loader_cli
+flash: $(BUILD)/$(PROJECT).hex
+ teensy_loader_cli --mcu=TEENSY35 -v -w $<
diff --git a/hw/bsp/kinetis_k/boards/teensy_35/board/clock_config.c b/hw/bsp/kinetis_k/boards/teensy_35/board/clock_config.c
new file mode 100644
index 000000000..b69d10ccb
--- /dev/null
+++ b/hw/bsp/kinetis_k/boards/teensy_35/board/clock_config.c
@@ -0,0 +1,186 @@
+/***********************************************************************************************************************
+ * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file
+ * will be overwritten if the respective MCUXpresso Config Tools is used to update this file.
+ **********************************************************************************************************************/
+/*
+ * 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.
+ */
+
+/* clang-format off */
+/* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+!!GlobalInfo
+product: Clocks v11.0
+processor: MK64FX512xxx12
+package_id: MK64FX512VLQ12
+mcu_data: ksdk2_0
+processor_version: 13.0.1
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/
+/* clang-format on */
+
+#include "clock_config.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+#define MCG_IRCLK_DISABLE 0U /*!< MCGIRCLK disabled */
+#define OSC_CAP0P 0U /*!< Oscillator 0pF capacitor load */
+#define OSC_ER_CLK_DISABLE 0U /*!< Disable external reference clock */
+#define SIM_OSC32KSEL_OSC32KCLK_CLK 0U /*!< OSC32KSEL select: OSC32KCLK clock */
+#define SIM_PLLFLLSEL_MCGPLLCLK_CLK 1U /*!< PLLFLL select: MCGPLLCLK clock */
+#define SIM_USB_CLK_120000000HZ 120000000U /*!< Input SIM frequency for USB: 120000000Hz */
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+/*******************************************************************************
+ * 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));
+}
+
+/*******************************************************************************
+ ************************ BOARD_InitBootClocks function ************************
+ ******************************************************************************/
+void BOARD_InitBootClocks(void)
+{
+ BOARD_BootClockRUN();
+}
+
+/*******************************************************************************
+ ********************** Configuration BOARD_BootClockRUN ***********************
+ ******************************************************************************/
+/* clang-format off */
+/* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+!!Configuration
+name: BOARD_BootClockRUN
+called_from_default_init: true
+outputs:
+- {id: Bus_clock.outFreq, value: 60 MHz}
+- {id: Core_clock.outFreq, value: 120 MHz}
+- {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: 500 kHz}
+- {id: PLLFLLCLK.outFreq, value: 120 MHz}
+- {id: System_clock.outFreq, value: 120 MHz}
+- {id: USB48MCLK.outFreq, value: 48 MHz}
+settings:
+- {id: MCGMode, value: PEE}
+- {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: '4'}
+- {id: MCG.VDIV.scale, value: '30'}
+- {id: MCG_C2_RANGE0_CFG, value: Very_high}
+- {id: MCG_C2_RANGE0_FRDIV_CFG, value: Very_high}
+- {id: MCG_C5_PLLCLKEN0_CFG, value: Enabled}
+- {id: RTC_CR_CLKO_CFG, value: Disabled}
+- {id: RTC_CR_OSC_CAP_LOAD_CFG, value: SC10PF}
+- {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.USBDIV.scale, value: '5'}
+- {id: SIM.USBFRAC.scale, value: '2'}
+- {id: SIM.USBSRCSEL.sel, value: SIM.USBDIV}
+- {id: USBClkConfig, value: 'yes'}
+sources:
+- {id: OSC.OSC.outFreq, value: 16 MHz, enabled: true}
+- {id: RTC.RTC32kHz.outFreq, value: 32.768 kHz, enabled: true}
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/
+/* clang-format on */
+
+/*******************************************************************************
+ * Variables for BOARD_BootClockRUN configuration
+ ******************************************************************************/
+const mcg_config_t mcgConfig_BOARD_BootClockRUN =
+ {
+ .mcgMode = kMCG_ModePEE, /* PEE - PLL Engaged External */
+ .irclkEnableMode = MCG_IRCLK_DISABLE, /* MCGIRCLK disabled */
+ .ircs = kMCG_IrcSlow, /* Slow internal reference clock selected */
+ .fcrdiv = 0x1U, /* Fast IRC divider: divided by 2 */
+ .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 = kMCG_PllEnableIndependent,/* MCGPLLCLK enabled independent of MCG clock mode, MCGPLLCLK disabled in STOP mode */
+ .prdiv = 0x3U, /* PLL Reference divider: divided by 4 */
+ .vdiv = 0x6U, /* VCO divider: multiplied by 30 */
+ },
+ };
+const sim_clock_config_t simConfig_BOARD_BootClockRUN =
+ {
+ .pllFllSel = SIM_PLLFLLSEL_MCGPLLCLK_CLK, /* PLLFLL select: MCGPLLCLK clock */
+ .er32kSrc = SIM_OSC32KSEL_OSC32KCLK_CLK, /* OSC32KSEL select: OSC32KCLK clock */
+ .clkdiv1 = 0x1240000U, /* SIM_CLKDIV1 - OUTDIV1: /1, OUTDIV2: /2, OUTDIV3: /3, OUTDIV4: /5 */
+ };
+const osc_config_t oscConfig_BOARD_BootClockRUN =
+ {
+ .freq = 16000000U, /* Oscillator frequency: 16000000Hz */
+ .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_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 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;
+ /* Enable USB FS clock. */
+ CLOCK_EnableUsbfs0Clock(kCLOCK_UsbSrcPll0, SIM_USB_CLK_120000000HZ);
+}
diff --git a/hw/bsp/kinetis_k/boards/teensy_35/board/clock_config.h b/hw/bsp/kinetis_k/boards/teensy_35/board/clock_config.h
new file mode 100644
index 000000000..8601da9c2
--- /dev/null
+++ b/hw/bsp/kinetis_k/boards/teensy_35/board/clock_config.h
@@ -0,0 +1,69 @@
+/***********************************************************************************************************************
+ * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file
+ * will be overwritten if the respective MCUXpresso Config Tools is used to update this file.
+ **********************************************************************************************************************/
+
+#ifndef _CLOCK_CONFIG_H_
+#define _CLOCK_CONFIG_H_
+
+#include "fsl_common.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+#define BOARD_XTAL0_CLK_HZ 16000000U /*!< Board xtal0 frequency in Hz */
+
+/*******************************************************************************
+ ************************ BOARD_InitBootClocks function ************************
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus*/
+
+/*!
+ * @brief This function executes default configuration of clocks.
+ *
+ */
+void BOARD_InitBootClocks(void);
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus*/
+
+/*******************************************************************************
+ ********************** 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*/
+
+#endif /* _CLOCK_CONFIG_H_ */
diff --git a/hw/bsp/kinetis_k/boards/teensy_35/board/pin_mux.c b/hw/bsp/kinetis_k/boards/teensy_35/board/pin_mux.c
new file mode 100644
index 000000000..d2c51e5c6
--- /dev/null
+++ b/hw/bsp/kinetis_k/boards/teensy_35/board/pin_mux.c
@@ -0,0 +1,61 @@
+/***********************************************************************************************************************
+ * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file
+ * will be overwritten if the respective MCUXpresso Config Tools is used to update this file.
+ **********************************************************************************************************************/
+
+/* clang-format off */
+/*
+ * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+!!GlobalInfo
+product: Pins v13.1
+processor: MK64FX512xxx12
+package_id: MK64FX512VLQ12
+mcu_data: ksdk2_0
+processor_version: 13.0.1
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
+ */
+/* clang-format on */
+
+#include "fsl_common.h"
+#include "fsl_port.h"
+#include "pin_mux.h"
+
+/* FUNCTION ************************************************************************************************************
+ *
+ * Function Name : BOARD_InitBootPins
+ * Description : Calls initialization functions.
+ *
+ * END ****************************************************************************************************************/
+void BOARD_InitBootPins(void)
+{
+ BOARD_InitPins();
+}
+
+/* clang-format off */
+/*
+ * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+BOARD_InitPins:
+- options: {callFromInitBoot: 'true', coreID: core0, enableClock: 'true'}
+- pin_list:
+ - {pin_num: '110', peripheral: GPIOC, signal: 'GPIO, 5', pin_signal: PTC5/LLWU_P9/SPI0_SCK/LPTMR0_ALT2/I2S0_RXD0/FB_AD10/CMP0_OUT/FTM0_CH2}
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
+ */
+/* clang-format on */
+
+/* FUNCTION ************************************************************************************************************
+ *
+ * Function Name : BOARD_InitPins
+ * Description : Configures pin routing and optionally pin electrical features.
+ *
+ * END ****************************************************************************************************************/
+void BOARD_InitPins(void)
+{
+ /* Port C Clock Gate Control: Clock enabled */
+ CLOCK_EnableClock(kCLOCK_PortC);
+
+ /* PORTC5 (pin 110) is configured as PTC5 */
+ PORT_SetPinMux(PORTC, 5U, kPORT_MuxAsGpio);
+}
+/***********************************************************************************************************************
+ * EOF
+ **********************************************************************************************************************/
diff --git a/hw/bsp/kinetis_k/boards/teensy_35/board/pin_mux.h b/hw/bsp/kinetis_k/boards/teensy_35/board/pin_mux.h
new file mode 100644
index 000000000..598ae8e9f
--- /dev/null
+++ b/hw/bsp/kinetis_k/boards/teensy_35/board/pin_mux.h
@@ -0,0 +1,45 @@
+/***********************************************************************************************************************
+ * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file
+ * will be overwritten if the respective MCUXpresso Config Tools is used to update this file.
+ **********************************************************************************************************************/
+
+#ifndef _PIN_MUX_H_
+#define _PIN_MUX_H_
+
+/*!
+ * @addtogroup pin_mux
+ * @{
+ */
+
+/***********************************************************************************************************************
+ * API
+ **********************************************************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @brief Calls initialization functions.
+ *
+ */
+void BOARD_InitBootPins(void);
+
+/*!
+ * @brief Configures pin routing and optionally pin electrical features.
+ *
+ */
+void BOARD_InitPins(void);
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*!
+ * @}
+ */
+#endif /* _PIN_MUX_H_ */
+
+/***********************************************************************************************************************
+ * EOF
+ **********************************************************************************************************************/
diff --git a/hw/bsp/kinetis_k/boards/teensy_35/teensy_35.mex b/hw/bsp/kinetis_k/boards/teensy_35/teensy_35.mex
new file mode 100644
index 000000000..52a087026
--- /dev/null
+++ b/hw/bsp/kinetis_k/boards/teensy_35/teensy_35.mex
@@ -0,0 +1,184 @@
+
+
+
+ MK64FX512xxx12
+ MK64FX512VLQ12
+ ksdk2_0
+
+
+
+
+
+
+ true
+ false
+ false
+ true
+ false
+
+
+
+
+
+
+
+
+ 13.0.1
+
+
+
+ Configures pin routing and optionally pin electrical features.
+
+ true
+ core0
+ true
+
+
+
+
+ true
+
+
+
+
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 13.0.1
+
+
+
+
+
+
+
+
+ true
+
+
+
+
+ INPUT
+
+
+
+
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ true
+
+
+
+
+
+
+ N/A
+
+
+
+
+
+
+ 13.0.1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ N/A
+
+
+
+
diff --git a/hw/bsp/kinetis_k/family.c b/hw/bsp/kinetis_k/family.c
new file mode 100644
index 000000000..6df29c1fc
--- /dev/null
+++ b/hw/bsp/kinetis_k/family.c
@@ -0,0 +1,144 @@
+/*
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2018, hathach (tinyusb.org)
+ * Copyright (c) 2020, Koji Kitayama
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#include "bsp/board_api.h"
+#include "board.h"
+#include "fsl_device_registers.h"
+#include "fsl_gpio.h"
+#include "fsl_port.h"
+#include "fsl_clock.h"
+#include "fsl_uart.h"
+#include "fsl_sysmpu.h"
+
+#include "board/clock_config.h"
+#include "board/pin_mux.h"
+
+//--------------------------------------------------------------------+
+// Forward USB interrupt events to TinyUSB IRQ Handler
+//--------------------------------------------------------------------+
+void USB0_IRQHandler(void) {
+#if CFG_TUH_ENABLED
+ tuh_int_handler(0);
+#endif
+#if CFG_TUD_ENABLED
+ tud_int_handler(0);
+#endif
+}
+
+void board_init(void) {
+ BOARD_InitBootPins();
+ BOARD_BootClockRUN();
+ SystemCoreClockUpdate();
+ SYSMPU_Enable(SYSMPU, 0);
+
+#if CFG_TUSB_OS == OPT_OS_NONE
+ // 1ms tick timer
+ SysTick_Config(SystemCoreClock / 1000);
+#elif CFG_TUSB_OS == OPT_OS_FREERTOS
+ // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher )
+ NVIC_SetPriority(USB0_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY );
+#endif
+
+ // LED
+ gpio_pin_config_t led_config = { kGPIO_DigitalOutput, 0 };
+ GPIO_PinInit(LED_PORT, LED_PIN, &led_config);
+ board_led_write(false);
+
+#if defined(BUTTON_PORT) && defined(BUTTON_PIN)
+ gpio_pin_config_t button_config = { kGPIO_DigitalInput, 0 };
+ GPIO_PinInit(BUTTON_PORT, BUTTON_PIN, &button_config);
+#endif
+
+#ifdef UART_DEV
+ const uart_config_t uart_config = {
+ .baudRate_Bps = 115200UL,
+ .parityMode = kUART_ParityDisabled,
+ .stopBitCount = kUART_OneStopBit,
+ .txFifoWatermark = 0U,
+ .rxFifoWatermark = 1U,
+ .idleType = kUART_IdleTypeStartBit,
+ .enableTx = true,
+ .enableRx = true
+ };
+ UART_Init(UART_DEV, &uart_config, UART_CLOCK);
+#endif
+
+ // USB
+ // USB clock is configured in BOARD_BootClockRUN()
+}
+
+//--------------------------------------------------------------------+
+// Board porting API
+//--------------------------------------------------------------------+
+
+void board_led_write(bool state) {
+ GPIO_PinWrite(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1 - LED_STATE_ON));
+}
+
+uint32_t board_button_read(void) {
+#if defined(BUTTON_PORT) && defined(BUTTON_PIN)
+ return BUTTON_STATE_ACTIVE == GPIO_PinRead(BUTTON_PORT, BUTTON_PIN);
+#else
+ return 0;
+#endif
+}
+
+int board_uart_read(uint8_t *buf, int len) {
+ (void) buf;
+ (void) len;
+#ifdef UART_DEV
+ // Read blocking will block until there is data
+// UART_ReadBlocking(UART_DEV, buf, len);
+// return len;
+ return 0;
+#else
+ return 0;
+#endif
+}
+
+int board_uart_write(void const *buf, int len) {
+ (void) buf;
+ (void) len;
+
+#ifdef UART_DEV
+ UART_WriteBlocking(UART_DEV, (uint8_t const*) buf, len);
+ return len;
+#else
+ return 0;
+#endif
+}
+
+#if CFG_TUSB_OS == OPT_OS_NONE
+volatile uint32_t system_ticks = 0;
+
+void SysTick_Handler(void) {
+ system_ticks++;
+}
+
+uint32_t board_millis(void) {
+ return system_ticks;
+}
+
+#endif
diff --git a/hw/bsp/kinetis_k/family.cmake b/hw/bsp/kinetis_k/family.cmake
new file mode 100644
index 000000000..452ef4b26
--- /dev/null
+++ b/hw/bsp/kinetis_k/family.cmake
@@ -0,0 +1,112 @@
+include_guard()
+
+if (NOT BOARD)
+ message(FATAL_ERROR "BOARD not specified")
+endif ()
+
+set(SDK_DIR ${TOP}/hw/mcu/nxp/mcux-sdk)
+set(CMSIS_DIR ${TOP}/lib/CMSIS_5)
+
+# include board specific
+include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake)
+
+# toolchain set up
+set(CMAKE_SYSTEM_PROCESSOR cortex-m4 CACHE INTERNAL "System Processor")
+set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/arm_${TOOLCHAIN}.cmake)
+
+set(FAMILY_MCUS KINETIS_K CACHE INTERNAL "")
+
+
+#------------------------------------
+# BOARD_TARGET
+#------------------------------------
+# only need to be built ONCE for all examples
+function(add_board_target BOARD_TARGET)
+ if (NOT TARGET ${BOARD_TARGET})
+ add_library(${BOARD_TARGET} STATIC
+ # driver
+ ${SDK_DIR}/drivers/gpio/fsl_gpio.c
+ ${SDK_DIR}/drivers/uart/fsl_uart.c
+ ${SDK_DIR}/devices/${MCU_VARIANT}/drivers/fsl_clock.c
+ ${SDK_DIR}/devices/${MCU_VARIANT}/system_${MCU_VARIANT}.c
+ )
+ target_compile_definitions(${BOARD_TARGET} PUBLIC
+ )
+ target_include_directories(${BOARD_TARGET} PUBLIC
+ ${CMSIS_DIR}/CMSIS/Core/Include
+ ${SDK_DIR}/devices/${MCU_VARIANT}
+ ${SDK_DIR}/devices/${MCU_VARIANT}/drivers
+ ${SDK_DIR}/drivers/common
+ ${SDK_DIR}/drivers/gpio
+ ${SDK_DIR}/drivers/port
+ ${SDK_DIR}/drivers/smc
+ ${SDK_DIR}/drivers/sysmpu
+ ${SDK_DIR}/drivers/uart
+ )
+
+ update_board(${BOARD_TARGET})
+
+ # LD_FILE and STARTUP_FILE can be defined in board.cmake
+ set(STARTUP_FILE_GNU ${SDK_DIR}/devices/${MCU_VARIANT}/gcc/startup_${MCU_VARIANT}.S)
+
+ target_sources(${BOARD_TARGET} PUBLIC
+ ${STARTUP_FILE_${CMAKE_C_COMPILER_ID}}
+ )
+
+ if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
+ target_link_options(${BOARD_TARGET} PUBLIC
+ "LINKER:--script=${LD_FILE_GNU}"
+ # nanolib
+ --specs=nosys.specs --specs=nano.specs
+ )
+ elseif (CMAKE_C_COMPILER_ID STREQUAL "IAR")
+ target_link_options(${BOARD_TARGET} PUBLIC
+ "LINKER:--config=${LD_FILE_IAR}"
+ )
+ endif ()
+ endif ()
+endfunction()
+
+
+#------------------------------------
+# Functions
+#------------------------------------
+function(family_configure_example TARGET RTOS)
+ family_configure_common(${TARGET} ${RTOS})
+
+ # Board target
+ add_board_target(board_${BOARD})
+
+ #---------- Port Specific ----------
+ # These files are built for each example since it depends on example's tusb_config.h
+ target_sources(${TARGET} PUBLIC
+ # BSP
+ ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/family.c
+ ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../board.c
+ )
+ target_include_directories(${TARGET} PUBLIC
+ # family, hw, board
+ ${CMAKE_CURRENT_FUNCTION_LIST_DIR}
+ ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../../
+ ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD}
+ )
+
+ # Add TinyUSB target and port source
+ family_add_tinyusb(${TARGET} OPT_MCU_KINETIS_K ${RTOS})
+ target_sources(${TARGET}-tinyusb PUBLIC
+ ${TOP}/src/portable/chipidea/ci_fs/dcd_ci_fs.c
+ ${TOP}/src/portable/nxp/khci/hcd_khci.c
+ )
+ target_link_libraries(${TARGET}-tinyusb PUBLIC board_${BOARD})
+
+ # Link dependencies
+ target_link_libraries(${TARGET} PUBLIC board_${BOARD} ${TARGET}-tinyusb)
+
+ # Flashing
+ family_flash_jlink(${TARGET})
+
+ if (DEFINED TEENSY_MCU)
+ family_add_bin_hex(${TARGET})
+ family_flash_teensy(${TARGET})
+ endif ()
+endfunction()
diff --git a/hw/bsp/kinetis_k/family.mk b/hw/bsp/kinetis_k/family.mk
new file mode 100644
index 000000000..995873eec
--- /dev/null
+++ b/hw/bsp/kinetis_k/family.mk
@@ -0,0 +1,35 @@
+SDK_DIR = hw/mcu/nxp/mcux-sdk
+DEPS_SUBMODULES += $(SDK_DIR) lib/CMSIS_5
+
+MCU_DIR = $(SDK_DIR)/devices/${MCU_VARIANT}
+include $(TOP)/$(BOARD_PATH)/board.mk
+CPU_CORE ?= cortex-m4
+
+CFLAGS += \
+ -DCFG_TUSB_MCU=OPT_MCU_KINETIS_K \
+
+LDFLAGS += \
+ -Wl,--defsym,__stack_size__=0x400 \
+ -Wl,--defsym,__heap_size__=0
+
+SRC_C += \
+ src/portable/nxp/khci/dcd_khci.c \
+ src/portable/nxp/khci/hcd_khci.c \
+ $(MCU_DIR)/system_${MCU_VARIANT}.c \
+ $(MCU_DIR)/drivers/fsl_clock.c \
+ $(SDK_DIR)/drivers/gpio/fsl_gpio.c \
+ $(SDK_DIR)/drivers/uart/fsl_uart.c \
+
+INC += \
+ $(TOP)/$(BOARD_PATH) \
+ $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \
+ $(TOP)/$(MCU_DIR) \
+ $(TOP)/$(MCU_DIR)/drivers \
+ $(TOP)/$(SDK_DIR)/drivers/common \
+ $(TOP)/$(SDK_DIR)/drivers/gpio \
+ $(TOP)/$(SDK_DIR)/drivers/port \
+ $(TOP)/$(SDK_DIR)/drivers/smc \
+ $(TOP)/$(SDK_DIR)/drivers/sysmpu \
+ $(TOP)/$(SDK_DIR)/drivers/uart \
+
+SRC_S += ${SDK_DIR}/devices/${MCU_VARIANT}/gcc/startup_${MCU_VARIANT}.S
diff --git a/src/common/tusb_mcu.h b/src/common/tusb_mcu.h
index e589c4c86..308ee713c 100644
--- a/src/common/tusb_mcu.h
+++ b/src/common/tusb_mcu.h
@@ -107,7 +107,7 @@
#define TUP_DCD_ENDPOINT_MAX 8
#define TUP_RHPORT_HIGHSPEED 1
-#elif TU_CHECK_MCU(OPT_MCU_KINETIS_KL, OPT_MCU_KINETIS_K32L)
+#elif TU_CHECK_MCU(OPT_MCU_KINETIS_KL, OPT_MCU_KINETIS_K32L, OPT_MCU_KINETIS_K)
#define TUP_USBIP_CHIPIDEA_FS
#define TUP_USBIP_CHIPIDEA_FS_KINETIS
#define TUP_DCD_ENDPOINT_MAX 16
diff --git a/src/portable/chipidea/ci_fs/ci_fs_kinetis.h b/src/portable/chipidea/ci_fs/ci_fs_kinetis.h
index cd21af1c7..31e14a546 100644
--- a/src/portable/chipidea/ci_fs/ci_fs_kinetis.h
+++ b/src/portable/chipidea/ci_fs/ci_fs_kinetis.h
@@ -36,14 +36,12 @@
#define CI_FS_REG(_port) ((ci_fs_regs_t*) USB0_BASE)
#define CI_REG CI_FS_REG(0)
-void dcd_int_enable(uint8_t rhport)
-{
+void dcd_int_enable(uint8_t rhport) {
(void) rhport;
NVIC_EnableIRQ(USB0_IRQn);
}
-void dcd_int_disable(uint8_t rhport)
-{
+void dcd_int_disable(uint8_t rhport) {
(void) rhport;
NVIC_DisableIRQ(USB0_IRQn);
}
diff --git a/src/portable/chipidea/ci_fs/dcd_ci_fs.c b/src/portable/chipidea/ci_fs/dcd_ci_fs.c
index 9327e09d8..4b1d488b5 100644
--- a/src/portable/chipidea/ci_fs/dcd_ci_fs.c
+++ b/src/portable/chipidea/ci_fs/dcd_ci_fs.c
@@ -271,9 +271,17 @@ void dcd_init(uint8_t rhport)
{
(void) rhport;
+ // save crystal-less setting (recovery clock)
+ uint32_t clk_recover_irc_en = CI_REG->CLK_RECOVER_IRC_EN;
+ uint32_t clk_recover_ctrl = CI_REG->CLK_RECOVER_CTRL;;
+
CI_REG->USBTRC0 |= USB_USBTRC0_USBRESET_MASK;
while (CI_REG->USBTRC0 & USB_USBTRC0_USBRESET_MASK);
+ // restore crystal-less setting
+ CI_REG->CLK_RECOVER_IRC_EN = clk_recover_irc_en;
+ CI_REG->CLK_RECOVER_CTRL |= clk_recover_ctrl;
+
tu_memclr(&_dcd, sizeof(_dcd));
CI_REG->USBTRC0 |= TU_BIT(6); /* software must set this bit to 1 */
CI_REG->BDT_PAGE1 = (uint8_t)((uintptr_t)_dcd.bdt >> 8);
diff --git a/src/portable/nxp/khci/dcd_khci.c b/src/portable/nxp/khci/dcd_khci.c
index 5c65ea33d..3419c2565 100644
--- a/src/portable/nxp/khci/dcd_khci.c
+++ b/src/portable/nxp/khci/dcd_khci.c
@@ -269,9 +269,21 @@ void dcd_init(uint8_t rhport)
{
(void) rhport;
+ // save crystal-less setting (recovery clock)
+ #ifdef USB_CLK_RECOVER_IRC_EN_IRC_EN
+ uint32_t clk_recover_irc_en = KHCI->CLK_RECOVER_IRC_EN;
+ uint32_t clk_recover_ctrl = KHCI->CLK_RECOVER_CTRL;
+ #endif
+
KHCI->USBTRC0 |= USB_USBTRC0_USBRESET_MASK;
while (KHCI->USBTRC0 & USB_USBTRC0_USBRESET_MASK);
+ // restore crystal-less setting
+ #ifdef USB_CLK_RECOVER_IRC_EN_IRC_EN
+ KHCI->CLK_RECOVER_IRC_EN = clk_recover_irc_en;
+ KHCI->CLK_RECOVER_CTRL |= clk_recover_ctrl;
+ #endif
+
tu_memclr(&_dcd, sizeof(_dcd));
KHCI->USBTRC0 |= TU_BIT(6); /* software must set this bit to 1 */
KHCI->BDTPAGE1 = (uint8_t)((uintptr_t)_dcd.bdt >> 8);
diff --git a/src/tusb_option.h b/src/tusb_option.h
index 767323bdd..96378cb80 100644
--- a/src/tusb_option.h
+++ b/src/tusb_option.h
@@ -125,6 +125,7 @@
#define OPT_MCU_KINETIS_KL 1200 ///< NXP KL series
#define OPT_MCU_KINETIS_K32L 1201 ///< NXP K32L series
#define OPT_MCU_KINETIS_K32 1201 ///< Alias to K32L
+#define OPT_MCU_KINETIS_K 1202 ///< NXP K series
#define OPT_MCU_MKL25ZXX 1200 ///< Alias to KL (obsolete)
#define OPT_MCU_K32L2BXX 1201 ///< Alias to K32 (obsolete)
diff --git a/tools/get_deps.py b/tools/get_deps.py
index d561a1b36..67273ed2f 100644
--- a/tools/get_deps.py
+++ b/tools/get_deps.py
@@ -52,7 +52,7 @@ deps_optional = {
'lpc11 lpc13 lpc15 lpc17 lpc18 lpc40 lpc43'],
'hw/mcu/nxp/mcux-sdk': ['https://github.com/hathach/mcux-sdk.git',
'950819b7de9b32f92c3edf396bc5ffb8d66e7009',
- 'kinetis_k32l2 kinetis_kl lpc51 lpc54 lpc55 mcx imxrt'],
+ 'kinetis_k kinetis_k32l2 kinetis_kl lpc51 lpc54 lpc55 mcx imxrt'],
'hw/mcu/raspberry_pi/Pico-PIO-USB': ['https://github.com/sekigon-gonnoc/Pico-PIO-USB.git',
'0f747aaa0c16f750bdfa2ba37ec25d6c8e1bc117',
'rp2040'],