summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-04-16 08:48:42 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-04-16 08:48:42 -0600
commit96e074f55f96608dcddfa7b663010c660493b1a2 (patch)
treef86aed122b28db6e444058f9b120c6bfb6312657 /nuttx/arch
parent869392869bf4dec4a58549d50ace330163d7269a (diff)
downloadpx4-nuttx-96e074f55f96608dcddfa7b663010c660493b1a2.tar.gz
px4-nuttx-96e074f55f96608dcddfa7b663010c660493b1a2.tar.bz2
px4-nuttx-96e074f55f96608dcddfa7b663010c660493b1a2.zip
Initial support for the Kinetis L family and the Freedom KL25Z board from Alan Carvalho de Assis
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/Kconfig7
-rw-r--r--nuttx/arch/arm/include/kl/chip.h120
-rw-r--r--nuttx/arch/arm/include/kl/irq.h166
-rw-r--r--nuttx/arch/arm/src/kl/Kconfig432
-rw-r--r--nuttx/arch/arm/src/kl/Make.defs80
-rw-r--r--nuttx/arch/arm/src/kl/chip.h75
-rw-r--r--nuttx/arch/arm/src/kl/chip/k25z120_pinmux.h508
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_clk.h288
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_fmc.h389
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_gcr.h373
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_gpio.h556
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_internal.h841
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_llwu.h252
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_mcg.h186
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_memorymap.h196
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_osc.h84
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_pinmux.h69
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_port.h431
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_sim.h542
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_uart.h521
-rw-r--r--nuttx/arch/arm/src/kl/kl_cfmconfig.c42
-rw-r--r--nuttx/arch/arm/src/kl/kl_clockconfig.c275
-rw-r--r--nuttx/arch/arm/src/kl/kl_clockconfig.c_orig209
-rw-r--r--nuttx/arch/arm/src/kl/kl_config.h235
-rw-r--r--nuttx/arch/arm/src/kl/kl_dumpgpio.c143
-rw-r--r--nuttx/arch/arm/src/kl/kl_gpio.c309
-rw-r--r--nuttx/arch/arm/src/kl/kl_gpio.h259
-rw-r--r--nuttx/arch/arm/src/kl/kl_idle.c187
-rw-r--r--nuttx/arch/arm/src/kl/kl_irq.c435
-rw-r--r--nuttx/arch/arm/src/kl/kl_irq.h65
-rw-r--r--nuttx/arch/arm/src/kl/kl_led.c28
-rw-r--r--nuttx/arch/arm/src/kl/kl_lowputc.c403
-rw-r--r--nuttx/arch/arm/src/kl/kl_lowputc.h125
-rw-r--r--nuttx/arch/arm/src/kl/kl_serial.c1347
-rw-r--r--nuttx/arch/arm/src/kl/kl_start.c199
-rw-r--r--nuttx/arch/arm/src/kl/kl_timerisr.c249
-rw-r--r--nuttx/arch/arm/src/kl/kl_userspace.c114
-rw-r--r--nuttx/arch/arm/src/kl/kl_userspace.h76
38 files changed, 10816 insertions, 0 deletions
diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig
index 63151fdc7..8215bdc53 100644
--- a/nuttx/arch/arm/Kconfig
+++ b/nuttx/arch/arm/Kconfig
@@ -51,6 +51,13 @@ config ARCH_CHIP_KINETIS
---help---
Freescale Kinetis Architectures (ARM Cortex-M4)
+config ARCH_CHIP_KL
+ bool "Freescale Kinetis L"
+ select ARCH_CORTEXM0
+ select ARCH_HAVE_CMNVECTOR
+ ---help---
+ Freescale Kinetis L Architectures (ARM Cortex-M0+)
+
config ARCH_CHIP_LM
bool "TI Stellaris"
select ARCH_HAVE_MPU
diff --git a/nuttx/arch/arm/include/kl/chip.h b/nuttx/arch/arm/include/kl/chip.h
new file mode 100644
index 000000000..c1e84245d
--- /dev/null
+++ b/nuttx/arch/arm/include/kl/chip.h
@@ -0,0 +1,120 @@
+/************************************************************************************
+ * arch/arm/include/kinetis/chip.h
+ *
+ * Copyright (C) 2013, 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_INCLUDE_KL_CHIP_H
+#define __ARCH_ARM_INCLUDE_KL_CHIP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Get customizations for each supported chip */
+
+#if defined(CONFIG_ARCH_CHIP_MKL25Z128)
+
+# define KL_Z128 1 /* Kinetics KL25Z128 family */
+# define KL_FLASH_SIZE (128*1024) /* 64Kb */
+# define KL_SRAM_SIZE (16*1024) /* 16Kb */
+# undef KL_MPU /* No memory protection unit */
+# undef KL_EXTBUS /* No external bus interface */
+# define KL_NDMACH 4 /* Up to 4 DMA channels */
+# undef KL_NENET /* No Ethernet controller */
+# define KL_NUSBHOST 1 /* One USB host controller */
+# define KL_NUSBOTG 1 /* With USB OTG controller */
+# define KL_NUSBDEV 1 /* One USB device controller */
+# undef KL_NSDHC /* No SD host controller */
+# define KL_NTOUCHIF 1 /* Xtrinsic touch sensing interface */
+# define KL_NI2C 2 /* Two I2C modules */
+# undef KL_NISO7816 /* No UART with ISO-786 */
+# define KL_NUART 3 /* Three UARTs */
+# define KL_NSPI 2 /* Two SPI modules */
+# undef KL_NCAN /* No CAN in 64-pin chips */
+# define KL_NI2S 1 /* One I2S module */
+# undef KL_NSLCD /* One segment LCD interface (up to 25x8/29x4) */
+# define KL_NADC16 1 /* One 16-bit ADC */
+# undef KL_NADC12 /* No 12-channel ADC */
+# undef KL_NADC13 /* No 13-channel ADC */
+# undef KL_NADC15 /* No 15-channel ADC */
+# undef KL_NADC18 /* No 18-channel ADC */
+# undef KL_NPGA /* No Programmable Gain Amplifiers */
+# define KL_NCMP 1 /* One analog comparator */
+# define KL_NDAC6 1 /* Three 6-bit DAC */
+# define KL_NDAC12 1 /* Two 12-bit DAC */
+# define KL_NVREF 1 /* Voltage reference */
+# define KL_NTIMERS8 1 /* One 8 channel timers */
+# undef KL_NTIMERS12 /* No 12 channel timers */
+# undef KL_NTIMERS20 /* No 20 channel timers */
+# undef KL_NRNG /* No random number generator */
+# define KL_NRTC 1 /* Real time clock */
+# undef KL_NMMCAU /* No hardware encryption */
+# undef KL_NTAMPER /* No tamper detect */
+# undef KL_NCRC /* No CRC */
+
+#else
+# error "Unsupported Kinetis chip"
+#endif
+
+/* NVIC priority levels *************************************************************/
+/* Each priority field holds a priority value, 0-15. The lower the value, the greater
+ * the priority of the corresponding interrupt. The processor implements only
+ * bits[7:4] of each field, bits[3:0] read as zero and ignore writes.
+ */
+
+#define NVIC_SYSH_PRIORITY_MIN 0xc0 /* All bits[7:6] set is minimum priority */
+#define NVIC_SYSH_PRIORITY_DEFAULT 0x80 /* Midpoint is the default */
+#define NVIC_SYSH_PRIORITY_MAX 0x00 /* Zero is maximum priority */
+#define NVIC_SYSH_PRIORITY_STEP 0x40 /* Steps between supported priority values */
+
+#define NVIC_SYSH_DISABLE_PRIORITY (NVIC_SYSH_PRIORITY_MAX + NVIC_SYSH_PRIORITY_STEP)
+#define NVIC_SYSH_SVCALL_PRIORITY NVIC_SYSH_PRIORITY_MAX
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+#endif /* __ARCH_ARM_INCLUDE_KL_CHIP_H */
diff --git a/nuttx/arch/arm/include/kl/irq.h b/nuttx/arch/arm/include/kl/irq.h
new file mode 100644
index 000000000..0279ea372
--- /dev/null
+++ b/nuttx/arch/arm/include/kl/irq.h
@@ -0,0 +1,166 @@
+/************************************************************************************
+ * arch/arm/include/kinetis/irq.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly through
+ * nuttx/irq.h
+ */
+
+#ifndef __ARCH_ARM_INCLUDE_KL_IRQ_H
+#define __ARCH_ARM_INCLUDE_KL_IRQ_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/irq.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* IRQ numbers **********************************************************************/
+/* The IRQ numbers corresponds directly to vector numbers and hence map directly to
+ * bits in the NVIC. This does, however, waste several words of memory in the IRQ
+ * to handle mapping tables.
+ */
+
+/* Processor Exceptions (vectors 0-15) */
+
+#define KL_IRQ_RESERVED (0) /* Reserved vector (only used with CONFIG_DEBUG) */
+ /* Vector 0: Reset stack pointer value */
+ /* Vector 1: Reset (not handler as an IRQ) */
+#define KL_IRQ_NMI (2) /* Vector 2: Non-Maskable Interrupt (NMI) */
+#define KL_IRQ_HARDFAULT (3) /* Vector 3: Hard fault */
+ /* Vectors 4-10: Reserved */
+#define KL_IRQ_SVCALL (11) /* Vector 11: SVC call */
+ /* Vector 12-13: Reserved */
+#define KL_IRQ_PENDSV (14) /* Vector 14: Pendable system service request */
+#define KL_IRQ_SYSTICK (15) /* Vector 15: System tick */
+
+/* External interrupts (vectors >= 16) */
+
+#define KL_IRQ_EXTINT (16)
+
+/* K40 Family ***********************************************************************
+ *
+ * The interrupt vectors for the following parts is defined in Freescale document
+ * K40P144M100SF2RM
+ */
+
+#if defined(CONFIG_ARCH_CHIP_MKL25Z128)
+
+# define KL_IRQ_DMACH0 (16) /* Vector 16: DMA channel 0 transfer complete */
+# define KL_IRQ_DMACH1 (17) /* Vector 17: DMA channel 1 transfer complete */
+# define KL_IRQ_DMACH2 (18) /* Vector 18: DMA channel 2 transfer complete */
+# define KL_IRQ_DMACH3 (19) /* Vector 19: DMA channel 3 transfer complete */
+ /* Vector 20: Reserved */
+# define KL_IRQ_FTFA (21) /* Vector 21: FTFA */
+# define KL_IRQ_LVDLVW (22) /* Vector 22: LVD_LVW */
+# define KL_IRQ_LLW (23) /* Vector 23: LLW */
+# define KL_IRQ_I2C0 (24) /* Vector 24: I2C0 */
+# define KL_IRQ_I2C1 (25) /* Vector 25: I2C1 */
+# define KL_IRQ_SPI0 (26) /* Vector 26: SPI0 */
+# define KL_IRQ_SPI1 (27) /* Vector 27: SPI1 */
+# define KL_IRQ_UART0 (28) /* Vector 28: UART0 */
+# define KL_IRQ_UART1 (29) /* Vector 29: UART1 */
+# define KL_IRQ_UART2 (30) /* Vector 30: UART2 */
+# define KL_IRQ_ADC0 (31) /* Vector 31: Analog Device Converter 0 */
+# define KL_IRQ_CMP0 (32) /* Vector 32: Comparator 0 */
+# define KL_IRQ_TPM0 (33) /* Vector 33: Timer/PWM Module 0 */
+# define KL_IRQ_TPM1 (34) /* Vector 34: Timer/PWM Module 1 */
+# define KL_IRQ_TPM2 (35) /* Vector 35: Timer/PWM Module 2 */
+# define KL_IRQ_RTC (36) /* Vector 36: Realtime Clock */
+# define KL_IRQ_RTCSEC (37) /* Vector 37: Realtime Clock, seconds interrupt */
+# define KL_IRQ_PIT (38) /* Vector 38: Programmable Interrupt Timer */
+ /* Vector 39: Reserved */
+# define KL_IRQ_USB0 (40) /* Vector 40: USB0 */
+# define KL_IRQ_DAC0 (41) /* Vector 41: Digital Analog Converter 0 */
+# define KL_IRQ_TSI0 (42) /* Vector 42: TSI0 */
+# define KL_IRQ_MCG (43) /* Vector 43: MCG */
+# define KL_IRQ_LPTIMER (44) /* Vector 44: Low Power Timer */
+ /* Vector 45: Reserved */
+# define KL_IRQ_PORTA (46) /* Vector 46: GPIO Port A */
+# define KL_IRQ_PORTD (47) /* Vector 47: GPIO Port D */
+
+/* Note that the total number of IRQ numbers supported is equal to the number of
+ * valid interrupt vectors. This is wasteful in that certain tables are sized by
+ * this value. There are only 94 valid interrupts so, potentially the numver of
+ * IRQs to could be reduced to 94. However, equating IRQ numbers with vector numbers
+ * also simplifies operations on NVIC registers and (at least in my state of mind
+ * now) seems to justify the waste.
+ */
+
+# define NR_VECTORS (64) /* 64 vectors */
+# define NR_IRQS (64) /* 64 interrupts but 48 IRQ numbers */
+# define KL_IRQ_INTERRUPT (64)
+
+#else
+ /* The interrupt vectors for other parts are defined in other documents and may or
+ * may not be the same as above (the family members are all very similar) This
+ * error just means that you have to look at the document and determine for yourself
+ * if the memory map is the same.
+ */
+
+# error "No IRQ numbers for this Kinetis L part"
+#endif
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_ARM_INCLUDE_KL_IRQ_H */
+
diff --git a/nuttx/arch/arm/src/kl/Kconfig b/nuttx/arch/arm/src/kl/Kconfig
new file mode 100644
index 000000000..3d69482a1
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/Kconfig
@@ -0,0 +1,432 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+comment "Kinetis Configuration Options"
+
+choice
+ prompt "Kinetis Chip Selection"
+ default ARCH_CHIP_MKL25Z128
+ depends on ARCH_CHIP_KL
+
+config ARCH_CHIP_MKL25Z128
+ bool "MKL25Z128"
+ select ARCH_FAMILY_KL2X
+
+endchoice
+
+# Chip families
+
+config ARCH_FAMILY_KL2X
+ bool
+ default n
+
+menu "Kinetis Peripheral Support"
+
+config KL_TRACE
+ bool "Trace"
+ default n
+ ---help---
+ Enable trace clocking on power up.
+
+config KL_FLEXBUS
+ bool "FlexBus"
+ default n
+ ---help---
+ Enable flexbus clocking on power up.
+
+config KL_UART0
+ bool "UART0"
+ default n
+ select ARCH_HAVE_UART0
+ ---help---
+ Support UART0
+
+config KL_UART1
+ bool "UART1"
+ default n
+ select ARCH_HAVE_UART1
+ ---help---
+ Support UART1
+
+config KL_UART2
+ bool "UART2"
+ default n
+ select ARCH_HAVE_UART2
+ ---help---
+ Support UART2
+
+config KL_UART3
+ bool "UART3"
+ default n
+ select ARCH_HAVE_UART3
+ ---help---
+ Support UART3
+
+config KL_UART4
+ bool "UART4"
+ default n
+ select ARCH_HAVE_UART4
+ ---help---
+ Support UART4
+
+config KL_UART5
+ bool "UART5"
+ default n
+ select ARCH_HAVE_UART5
+ ---help---
+ Support UART5
+
+config KL_ENET
+ bool "Ethernet"
+ default n
+ depends on ARCH_FAMILY_K60
+ select NET
+ ---help---
+ Support Ethernet (K60 only)
+
+config KL_RNGB
+ bool "Random number generator"
+ default n
+ depends on ARCH_FAMILY_K60
+ ---help---
+ Support the random number generator(K60 only)
+
+config KL_FLEXCAN0
+ bool "FlexCAN0"
+ default n
+ ---help---
+ Support FlexCAN0
+
+config KL_FLEXCAN1
+ bool "FlexCAN1"
+ default n
+ ---help---
+ Support FlexCAN1
+
+config KL_SPI0
+ bool "SPI0"
+ default n
+ ---help---
+ Support SPI0
+
+config KL_SPI1
+ bool "SPI1"
+ default n
+ ---help---
+ Support SPI1
+
+config KL_SPI2
+ bool "SPI2"
+ default n
+ ---help---
+ Support SPI2
+
+config KL_I2C0
+ bool "I2C0"
+ default n
+ ---help---
+ Support I2C0
+
+config KL_I2C1
+ bool "I2C1"
+ default n
+ ---help---
+ Support I2C1
+
+config KL_I2S
+ bool "I2S"
+ default n
+ ---help---
+ Support I2S
+
+config KL_DAC0
+ bool "DAC0"
+ default n
+ ---help---
+ Support DAC0
+
+config KL_DAC1
+ bool "DAC1"
+ default n
+ ---help---
+ Support DAC1
+
+config KL_ADC0
+ bool "ADC0"
+ default n
+ ---help---
+ Support ADC0
+
+config KL_ADC1
+ bool "ADC1"
+ default n
+ ---help---
+ Support ADC1
+
+config KL_CMP
+ bool "CMP"
+ default n
+ ---help---
+ Support CMP
+
+config KL_VREF
+ bool "VREF"
+ default n
+ ---help---
+ Support VREF
+
+config KL_SDHC
+ bool "SDHC"
+ default n
+ select MMCSD_SDIO
+ ---help---
+ Support SD host controller
+
+config KL_FTM0
+ bool "FTM0"
+ default n
+ ---help---
+ Support FlexTimer 0
+
+config KL_FTM1
+ bool "FTM1"
+ default n
+ ---help---
+ Support FlexTimer 1
+
+config KL_FTM2
+ bool "FTM2"
+ default n
+ ---help---
+ Support FlexTimer 2
+
+config KL_LPTIMER
+ bool "Low power timer (LPTIMER)"
+ default n
+ ---help---
+ Support the low power timer
+
+config KL_RTC
+ bool "RTC"
+ default n
+ ---help---
+ Support RTC
+
+config KL_SLCD
+ bool "Segment LCD (SLCD)"
+ default n
+ depends on ARCH_FAMILY_K40
+ ---help---
+ Support the segment LCD (K40 only)
+
+config KL_EWM
+ bool "External watchdog (WVM)"
+ default n
+ ---help---
+ Support the external watchdog
+
+config KL_CMT
+ bool "Carrier modulator transmitter (CMT)"
+ default n
+ ---help---
+ Support Carrier Modulator Transmitter
+
+config KL_USBOTG
+ bool "USB OTG"
+ default n
+ ---help---
+ Support USB OTG (see also USBHOST and USBDEV)
+
+config KL_USBDCD
+ bool "USB device controller"
+ default n
+ ---help---
+ Support the USB Device Charger Detection module
+
+config KL_LLWU
+ bool "Low leakage wake-up unit (LLWU)"
+ default n
+ ---help---
+ Support the Low Leakage Wake-Up Unit
+
+config KL_TSI
+ bool "Touchscreen interface (TSI)"
+ default n
+ ---help---
+ Support the touch screeen interface
+
+config KL_FTFL
+ bool "FLASH (FTFL)"
+ default n
+ ---help---
+ Support FLASH
+
+config KL_DMA
+ bool "DMA"
+ default n
+ ---help---
+ Support DMA
+
+config KL_CRC
+ bool "CRC"
+ default n
+ ---help---
+ Support CRC
+
+config KL_PDB
+ bool "Programmable delay block (PDB)"
+ default n
+ ---help---
+ Support the Programmable Delay Block
+
+config KL_PIT
+ bool "Programmable interval timer (PIT)"
+ default n
+ ---help---
+ Support Programmable Interval Timers
+
+endmenu
+
+comment "Kinetis GPIO Interrupt Configuration"
+
+config GPIO_IRQ
+ bool "GPIO pin interrupts"
+ ---help---
+ Enable support for interrupting GPIO pins
+
+if GPIO_IRQ
+
+config KL_PORTAINTS
+ bool "GPIOA interrupts"
+ ---help---
+ Enable support for 32 interrupts from GPIO port A pins
+
+config KL_PORTBINTS
+ bool "GPIOB interrupts"
+ ---help---
+ Enable support for 32 interrupts from GPIO port B pins
+
+config KL_PORTCINTS
+ bool "GPIOC interrupts"
+ ---help---
+ Enable support for 32 interrupts from GPIO port C pins
+
+config KL_PORTDINTS
+ bool "GPIOD interrupts"
+ ---help---
+ Enable support for 32 interrupts from GPIO port D pins
+
+config KL_PORTEINTS
+ bool "GPIOE interrupts"
+ ---help---
+ Enable support for 32 interrupts from GPIO port E pins
+
+endif
+
+if KL_ENET
+
+comment "Kinetis Ethernet Configuration"
+
+config ENET_ENHANCEDBD
+ bool "Use enhanced buffer descriptors"
+ default n
+ ---help---
+ Use enhanced, 32-byte buffer descriptors
+
+config ENET_NETHIFS
+ int "Number of Ethernet interfaces"
+ default 1
+ ---help---
+ Number of Ethernet interfaces supported by the hardware. Must be
+ one for now.
+
+config ENET_NRXBUFFERS
+ int "Number of Ethernet Rx buffers"
+ default 6
+ ---help---
+ Number of Ethernet Rx buffers to use. The size of one buffer is
+ determined by CONFIG_NET_BUFSIZE
+
+config ENET_NTXBUFFERS
+ int "Number of Ethernet Tx buffers"
+ default 2
+ ---help---
+ Number of Ethernet Tx buffers to use. The size of one buffer is
+ determined by CONFIG_NET_BUFSIZE
+
+config ENET_PHYADDR
+ int "PHY address"
+ default 1
+ ---help---
+ MII/RMII address of the PHY
+
+config ENET_USEMII
+ bool "Use MII interface"
+ default n
+ ---help---
+ The the MII PHY interface. Default: Use RMII interface
+
+endif
+
+if KL_SDHC
+
+comment "Kinetis SDHC Configuration"
+
+config KL_SDHC_ABSFREQ
+ bool "Custom transfer frequencies"
+ default n
+ ---help---
+ Select SDCLK frequencies corresponding to various modes of operation.
+ These values may be provided in either the NuttX configuration file
+ or in the board.h file
+
+ NOTE: These settings are not currently used. Since there are only
+ four frequencies, it makes more sense to just "can" the fixed
+ frequency prescaler and divider values.
+
+if KL_SDHC_ABSFREQ
+
+config KL_IDMODE_FREQ
+ int "ID mode frequency"
+ default 400000
+ ---help---
+ Initial, ID mode SD frequency
+
+config KL_MMCXFR_FREQ
+ int "MMC transfer frequency"
+ default 20000000
+ ---help---
+ Frequency to use for transferring data to/from an MMC card
+
+config KL_SD1BIT_FREQ
+ int "SD 1-bit transfer frequency"
+ default 20000000
+ depends on CONFIG_SDIO_WIDTH_D1_ONLY
+ ---help---
+ Frequency to use for transferring data to/from an SD card using on a single data liune.
+
+config KL_SD4BIT_FREQ
+ int "SD 4-bit transfer frequency"
+ default 20000000
+ depends on !CONFIG_SDIO_WIDTH_D1_ONLY
+ ---help---
+ Frequency to use for transferring data to/from an SD card using all four data lines.
+
+endif
+
+config KL_SDHC_DMAPRIO
+ int "SDHC DMA priority"
+ depends on SDIO_DMA
+ ---help---
+ SDHC DMA priority
+
+endif
+
+comment "Kinetis UART Configuration"
+
+config KL_UARTFIFOS
+ bool "Enable UART0 FIFO"
+ default n
+ depends on KL_UART0
diff --git a/nuttx/arch/arm/src/kl/Make.defs b/nuttx/arch/arm/src/kl/Make.defs
new file mode 100644
index 000000000..a71160ed0
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/Make.defs
@@ -0,0 +1,80 @@
+############################################################################
+# arch/arm/src/kl/Make.defs
+#
+# Copyright (C) 2013 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+HEAD_ASRC =
+
+CMN_ASRCS = up_exception.S up_saveusercontext.S up_fullcontextrestore.S
+CMN_ASRCS += up_switchcontext.S vfork.S
+
+CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c
+CMN_CSRCS += up_createstack.c up_mdelay.c up_udelay.c up_exit.c
+CMN_CSRCS += up_initialize.c up_initialstate.c up_interruptcontext.c
+CMN_CSRCS += up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c
+CMN_CSRCS += up_releasepending.c up_releasestack.c up_reprioritizertr.c
+CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c up_systemreset.c
+CMN_CSRCS += up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c
+CMN_CSRCS += up_svcall.c up_vectors.c up_vfork.c
+
+ifeq ($(CONFIG_NUTTX_KERNEL),y)
+CMN_CSRCS += up_task_start.c up_pthread_start.c up_stackframe.c
+ifneq ($(CONFIG_DISABLE_SIGNALS),y)
+CMN_CSRCS += up_signal_dispatch.c
+CMN_UASRCS += up_signal_handler.S
+endif
+endif
+
+ifeq ($(CONFIG_DEBUG_STACK),y)
+CMN_CSRCS += up_checkstack.c
+endif
+
+ifeq ($(CONFIG_ELF),y)
+CMN_CSRCS += up_elf.c
+endif
+
+ifeq ($(CONFIG_DEBUG),y)
+CMN_CSRCS += up_dumpnvic.c
+endif
+
+CHIP_ASRCS =
+CHIP_CSRCS = kl_clockconfig.c kl_gpio.c kl_idle.c kl_irq.c kl_lowputc.c
+CHIP_CSRCS += kl_serial.c kl_start.c kl_timerisr.c kl_cfmconfig.c kl_led.c
+
+ifeq ($(CONFIG_NUTTX_KERNEL),y)
+CHIP_CSRCS += kl_userspace.c
+endif
+
+ifeq ($(CONFIG_DEBUG),y)
+CHIP_CSRCS += kl_dumpgpio.c
+endif
diff --git a/nuttx/arch/arm/src/kl/chip.h b/nuttx/arch/arm/src/kl/chip.h
new file mode 100644
index 000000000..2f24e1501
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip.h
@@ -0,0 +1,75 @@
+/************************************************************************************
+ * arch/arm/src/kl/chip.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_CHIP_H
+#define __ARCH_ARM_SRC_KL_CHIP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/* Include the chip capabilities file */
+
+#include <arch/kl/chip.h>
+
+/* Define the number of interrupt vectors that needed to be support for this chip */
+
+#define ARMV6M_PERIPHERAL_INTERRUPTS 32
+
+/* Include the memory map file. Other chip hardware files should then include
+ * this file for the proper setup.
+ */
+
+#include "chip/kl_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KL_CHIP_H */
diff --git a/nuttx/arch/arm/src/kl/chip/k25z120_pinmux.h b/nuttx/arch/arm/src/kl/chip/k25z120_pinmux.h
new file mode 100644
index 000000000..20bc4923b
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/k25z120_pinmux.h
@@ -0,0 +1,508 @@
+/********************************************************************************************
+ * arch/arm/src/kinetis/kinetis_k40pinmux.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ********************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KINETIS_KINETIS_K40PINMUX_H
+#define __ARCH_ARM_SRC_KINETIS_KINETIS_K40PINMUX_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Reference: Paragraph 10.3.1, p 227, of FreeScale document K40P144M100SF2RM
+ *
+ * In most cases, there are alternative configurations for various pins. Those alternative
+ * pins are labeled with a suffix like _1, _2, etc. in order to distinguish them. Logic in
+ * the board.h file must select the correct pin configuration for the board by defining a pin
+ * configuration (with no suffix) that maps to the correct alternative.
+ */
+
+#define PIN_TSI0_CH1 (PIN_ANALOG | PIN_PORTA | PIN0)
+#define PIN_UART0_CTS_1 (PIN_ALT2 | PIN_PORTA | PIN0)
+#define PIN_FTM0_CH5_1 (PIN_ALT3 | PIN_PORTA | PIN0)
+#define PIN_JTAG_TCLK (PIN_ALT7 | PIN_PORTA | PIN0)
+#define PIN_SWD_CLK (PIN_ALT7 | PIN_PORTA | PIN0)
+#define PIN_TSI0_CH2 (PIN_ANALOG | PIN_PORTA | PIN1)
+#define PIN_UART0_RX_1 (PIN_ALT2 | PIN_PORTA | PIN1)
+#define PIN_FTM0_CH6_1 (PIN_ALT3 | PIN_PORTA | PIN1)
+#define PIN_JTAG_TDI (PIN_ALT7 | PIN_PORTA | PIN1)
+#define PIN_TSI0_CH3 (PIN_ANALOG | PIN_PORTA | PIN2)
+#define PIN_UART0_TX_1 (PIN_ALT2 | PIN_PORTA | PIN2)
+#define PIN_FTM0_CH7_1 (PIN_ALT3 | PIN_PORTA | PIN2)
+#define PIN_JTAG_TDO (PIN_ALT7 | PIN_PORTA | PIN2)
+#define PIN_TRACE_SWO (PIN_ALT7 | PIN_PORTA | PIN2)
+#define PIN_TSI0_CH4 (PIN_ANALOG | PIN_PORTA | PIN3)
+#define PIN_UART0_RTS_1 (PIN_ALT2 | PIN_PORTA | PIN3)
+#define PIN_FTM0_CH0_1 (PIN_ALT3 | PIN_PORTA | PIN3)
+#define PIN_JTAG_TMS (PIN_ALT7 | PIN_PORTA | PIN3)
+#define PIN_SWD_DIO (PIN_ALT7 | PIN_PORTA | PIN3)
+#define PIN_TSI0_CH5 (PIN_ANALOG | PIN_PORTA | PIN4)
+#define PIN_FTM0_CH1_1 (PIN_ALT3 | PIN_PORTA | PIN4)
+#define PIN_NMI (PIN_ALT7 | PIN_PORTA | PIN4)
+#define PIN_FTM0_CH2_1 (PIN_ALT3 | PIN_PORTA | PIN5)
+#define PIN_CMP2_OUT_1 (PIN_ALT5 | PIN_PORTA | PIN5)
+#define PIN_I2S0_RX_BCLK_1 (PIN_ALT6 | PIN_PORTA | PIN5)
+#define PIN_JTAG_TRST (PIN_ALT7 | PIN_PORTA | PIN5)
+#define PIN_FTM0_CH3_1 (PIN_ALT3 | PIN_PORTA | PIN6)
+#define PIN_FB_CLKOUT (PIN_ALT5 | PIN_PORTA | PIN6)
+#define PIN_TRACE_CLKOUT (PIN_ALT7 | PIN_PORTA | PIN6)
+#define PIN_ADC0_SE10 (PIN_ANALOG | PIN_PORTA | PIN7)
+#define PIN_FTM0_CH4_1 (PIN_ALT3 | PIN_PORTA | PIN7)
+#define PIN_FB_AD18 (PIN_ALT5 | PIN_PORTA | PIN7)
+#define PIN_TRACE_D3 (PIN_ALT7 | PIN_PORTA | PIN7)
+#define PIN_ADC0_SE11 (PIN_ANALOG | PIN_PORTA | PIN8)
+#define PIN_FTM1_CH0_1 (PIN_ALT3 | PIN_PORTA | PIN8)
+#define PIN_FB_AD17 (PIN_ALT5 | PIN_PORTA | PIN8)
+#define PIN_FTM1_QD_PHA_1 (PIN_ALT6 | PIN_PORTA | PIN8)
+#define PIN_TRACE_D2 (PIN_ALT7 | PIN_PORTA | PIN8)
+#define PIN_FTM1_CH1_1 (PIN_ALT3 | PIN_PORTA | PIN9)
+#define PIN_FB_AD16 (PIN_ALT5 | PIN_PORTA | PIN9)
+#define PIN_FTM1_QD_PHB_1 (PIN_ALT6 | PIN_PORTA | PIN9)
+#define PIN_TRACE_D1 (PIN_ALT7 | PIN_PORTA | PIN9)
+#define PIN_FTM2_CH0_1 (PIN_ALT3 | PIN_PORTA | PIN10)
+#define PIN_FB_AD15 (PIN_ALT5 | PIN_PORTA | PIN10)
+#define PIN_FTM2_QD_PHA_1 (PIN_ALT6 | PIN_PORTA | PIN10)
+#define PIN_TRACE_D0 (PIN_ALT7 | PIN_PORTA | PIN10)
+#define PIN_FTM2_CH1_1 (PIN_ALT3 | PIN_PORTA | PIN11)
+#define PIN_FB_OE (PIN_ALT5 | PIN_PORTA | PIN11)
+#define PIN_FTM2_QD_PHB_1 (PIN_ALT6 | PIN_PORTA | PIN11)
+#define PIN_CMP2_IN0 (PIN_ANALOG | PIN_PORTA | PIN12)
+#define PIN_CAN0_TX_1 (PIN_ALT2 | PIN_PORTA | PIN12)
+#define PIN_FTM1_CH0_2 (PIN_ALT3 | PIN_PORTA | PIN12)
+#define PIN_FB_CS5 (PIN_ALT5 | PIN_PORTA | PIN12)
+#define PIN_FB_TSIZ1 (PIN_ALT5 | PIN_PORTA | PIN12)
+#define PIN_FB_BE23_16_BLS15_8 (PIN_ALT5 | PIN_PORTA | PIN12)
+#define PIN_I2S0_TXD_1 (PIN_ALT6 | PIN_PORTA | PIN12)
+#define PIN_FTM1_QD_PHA_2 (PIN_ALT7 | PIN_PORTA | PIN12)
+#define PIN_CMP2_IN1 (PIN_ANALOG | PIN_PORTA | PIN13)
+#define PIN_CAN0_RX_1 (PIN_ALT2 | PIN_PORTA | PIN13)
+#define PIN_FTM1_CH1_2 (PIN_ALT3 | PIN_PORTA | PIN13)
+#define PIN_FB_CS4 (PIN_ALT5 | PIN_PORTA | PIN13)
+#define PIN_FB_TSIZ0 (PIN_ALT5 | PIN_PORTA | PIN13)
+#define PIN_FB_BE31_24_BLS7_0 (PIN_ALT5 | PIN_PORTA | PIN13)
+#define PIN_I2S0_TX_FS_1 (PIN_ALT6 | PIN_PORTA | PIN13)
+#define PIN_FTM1_QD_PHB_2 (PIN_ALT7 | PIN_PORTA | PIN13)
+#define PIN_SPI0_PCS0_1 (PIN_ALT2 | PIN_PORTA | PIN14)
+#define PIN_UART0_TX_2 (PIN_ALT3 | PIN_PORTA | PIN14)
+#define PIN_FB_AD31 (PIN_ALT5 | PIN_PORTA | PIN14)
+#define PIN_I2S0_TX_BCLK_1 (PIN_ALT6 | PIN_PORTA | PIN14)
+#define PIN_SPI0_SCK_1 (PIN_ALT2 | PIN_PORTA | PIN15)
+#define PIN_UART0_RX_2 (PIN_ALT3 | PIN_PORTA | PIN15)
+#define PIN_FB_AD30 (PIN_ALT5 | PIN_PORTA | PIN15)
+#define PIN_I2S0_RXD_1 (PIN_ALT6 | PIN_PORTA | PIN15)
+#define PIN_SPI0_SOUT_1 (PIN_ALT2 | PIN_PORTA | PIN16)
+#define PIN_UART0_CTS_2 (PIN_ALT3 | PIN_PORTA | PIN16)
+#define PIN_FB_AD29 (PIN_ALT5 | PIN_PORTA | PIN16)
+#define PIN_I2S0_RX_FS_1 (PIN_ALT6 | PIN_PORTA | PIN16)
+#define PIN_ADC1_SE17 (PIN_ANALOG | PIN_PORTA | PIN17)
+#define PIN_SPI0_SIN_1 (PIN_ALT2 | PIN_PORTA | PIN17)
+#define PIN_UART0_RTS_2 (PIN_ALT3 | PIN_PORTA | PIN17)
+#define PIN_FB_AD28 (PIN_ALT5 | PIN_PORTA | PIN17)
+#define PIN_I2S0_MCLK_1 (PIN_ALT6 | PIN_PORTA | PIN17)
+#define PIN_I2S0_CLKIN_1 (PIN_ALT7 | PIN_PORTA | PIN17)
+#define PIN_EXTAL (PIN_ANALOG | PIN_PORTA | PIN18)
+#define PIN_FTM0_FLT2_1 (PIN_ALT3 | PIN_PORTA | PIN18)
+#define PIN_FTM_CLKIN0 (PIN_ALT4 | PIN_PORTA | PIN18)
+#define PIN_XTAL (PIN_ANALOG | PIN_PORTA | PIN19)
+#define PIN_FTM1_FLT0_1 (PIN_ALT3 | PIN_PORTA | PIN19)
+#define PIN_FTM_CLKIN1 (PIN_ALT4 | PIN_PORTA | PIN19)
+#define PIN_LPT0_ALT1 (PIN_ALT6 | PIN_PORTA | PIN19)
+#define PIN_FB_AD14 (PIN_ALT5 | PIN_PORTA | PIN24)
+#define PIN_FB_AD13 (PIN_ALT5 | PIN_PORTA | PIN25)
+#define PIN_FB_AD12 (PIN_ALT5 | PIN_PORTA | PIN26)
+#define PIN_FB_AD11 (PIN_ALT5 | PIN_PORTA | PIN27)
+#define PIN_FB_AD10 (PIN_ALT5 | PIN_PORTA | PIN28)
+#define PIN_FB_AD19 (PIN_ALT5 | PIN_PORTA | PIN29)
+
+#define PIN_LCD_P0 (PIN_ANALOG | PIN_PORTB | PIN0)
+#define PIN_ADC0_SE8 (PIN_ANALOG | PIN_PORTB | PIN0)
+#define PIN_ADC1_SE8 (PIN_ANALOG | PIN_PORTB | PIN0)
+#define PIN_TSI0_CH0 (PIN_ANALOG | PIN_PORTB | PIN0)
+#define PIN_I2C0_SCL_1 (PIN_ALT2 | PIN_PORTB | PIN0)
+#define PIN_FTM1_CH0_3 (PIN_ALT3 | PIN_PORTB | PIN0)
+#define PIN_FTM1_QD_PHA_3 (PIN_ALT6 | PIN_PORTB | PIN0)
+#define PIN_LCD_P0F (PIN_ALT7 | PIN_PORTB | PIN0)
+#define PIN_LCD_P1 (PIN_ANALOG | PIN_PORTB | PIN1)
+#define PIN_ADC0_SE9 (PIN_ANALOG | PIN_PORTB | PIN1)
+#define PIN_ADC1_SE9 (PIN_ANALOG | PIN_PORTB | PIN1)
+#define PIN_TSI0_CH6 (PIN_ANALOG | PIN_PORTB | PIN1)
+#define PIN_I2C0_SDA_1 (PIN_ALT2 | PIN_PORTB | PIN1)
+#define PIN_FTM1_CH1_3 (PIN_ALT3 | PIN_PORTB | PIN1)
+#define PIN_FTM1_QD_PHB (PIN_ALT6 | PIN_PORTB | PIN1)
+#define PIN_LCD_P1F (PIN_ALT7 | PIN_PORTB | PIN1)
+#define PIN_LCD_P2 (PIN_ANALOG | PIN_PORTB | PIN2)
+#define PIN_ADC0_SE12 (PIN_ANALOG | PIN_PORTB | PIN2)
+#define PIN_TSI0_CH7 (PIN_ANALOG | PIN_PORTB | PIN2)
+#define PIN_I2C0_SCL_2 (PIN_ALT2 | PIN_PORTB | PIN2)
+#define PIN_UART0_RTS_3 (PIN_ALT3 | PIN_PORTB | PIN2)
+#define PIN_FTM0_FLT3 (PIN_ALT6 | PIN_PORTB | PIN2)
+#define PIN_LCD_P2F (PIN_ALT7 | PIN_PORTB | PIN2)
+#define PIN_LCD_P3 (PIN_ANALOG | PIN_PORTB | PIN3)
+#define PIN_ADC0_SE13 (PIN_ANALOG | PIN_PORTB | PIN3)
+#define PIN_TSI0_CH8 (PIN_ANALOG | PIN_PORTB | PIN3)
+#define PIN_I2C0_SDA_2 (PIN_ALT2 | PIN_PORTB | PIN3)
+#define PIN_UART0_CTS_3 (PIN_ALT3 | PIN_PORTB | PIN3)
+#define PIN_FTM0_FLT0_1 (PIN_ALT6 | PIN_PORTB | PIN3)
+#define PIN_LCD_P3F (PIN_ALT7 | PIN_PORTB | PIN3)
+#define PIN_LCD_P4 (PIN_ANALOG | PIN_PORTB | PIN4)
+#define PIN_ADC1_SE10 (PIN_ANALOG | PIN_PORTB | PIN4)
+#define PIN_FTM1_FLT0_2 (PIN_ALT6 | PIN_PORTB | PIN4)
+#define PIN_LCD_P4F (PIN_ALT7 | PIN_PORTB | PIN4)
+#define PIN_LCD_P5 (PIN_ANALOG | PIN_PORTB | PIN5)
+#define PIN_ADC1_SE11 (PIN_ANALOG | PIN_PORTB | PIN5)
+#define PIN_FTM2_FLT0_1 (PIN_ALT6 | PIN_PORTB | PIN5)
+#define PIN_LCD_P5F (PIN_ALT7 | PIN_PORTB | PIN5)
+#define PIN_LCD_P6 (PIN_ANALOG | PIN_PORTB | PIN6)
+#define PIN_ADC1_SE12 (PIN_ANALOG | PIN_PORTB | PIN6)
+#define PIN_LCD_P6F (PIN_ALT7 | PIN_PORTB | PIN6)
+#define PIN_LCD_P7 (PIN_ANALOG | PIN_PORTB | PIN7)
+#define PIN_ADC1_SE13 (PIN_ANALOG | PIN_PORTB | PIN7)
+#define PIN_LCD_P7F (PIN_ALT7 | PIN_PORTB | PIN7)
+#define PIN_LCD_P8 (PIN_ANALOG | PIN_PORTB | PIN8)
+#define PIN_UART3_RTS_1 (PIN_ALT3 | PIN_PORTB | PIN8)
+#define PIN_LCD_P8F (PIN_ALT7 | PIN_PORTB | PIN8)
+#define PIN_LCD_P9 (PIN_ANALOG | PIN_PORTB | PIN9)
+#define PIN_SPI1_PCS1_1 (PIN_ALT2 | PIN_PORTB | PIN9)
+#define PIN_UART3_CTS_1 (PIN_ALT3 | PIN_PORTB | PIN9)
+#define PIN_LCD_P9F (PIN_ALT7 | PIN_PORTB | PIN9)
+#define PIN_LCD_P10 (PIN_ANALOG | PIN_PORTB | PIN10)
+#define PIN_ADC1_SE14 (PIN_ANALOG | PIN_PORTB | PIN10)
+#define PIN_SPI1_PCS0_1 (PIN_ALT2 | PIN_PORTB | PIN10)
+#define PIN_UART3_RX_1 (PIN_ALT3 | PIN_PORTB | PIN10)
+#define PIN_FTM0_FLT1_1 (PIN_ALT6 | PIN_PORTB | PIN10)
+#define PIN_LCD_P10F (PIN_ALT7 | PIN_PORTB | PIN10)
+#define PIN_LCD_P11 (PIN_ANALOG | PIN_PORTB | PIN11)
+#define PIN_ADC1_SE15 (PIN_ANALOG | PIN_PORTB | PIN11)
+#define PIN_SPI1_SCK_1 (PIN_ALT2 | PIN_PORTB | PIN11)
+#define PIN_UART3_TX_1 (PIN_ALT3 | PIN_PORTB | PIN11)
+#define PIN_FTM0_FLT2_2 (PIN_ALT6 | PIN_PORTB | PIN11)
+#define PIN_LCD_P11F (PIN_ALT7 | PIN_PORTB | PIN11)
+#define PIN_LCD_P12 (PIN_ANALOG | PIN_PORTB | PIN16)
+#define PIN_TSI0_CH9 (PIN_ANALOG | PIN_PORTB | PIN16)
+#define PIN_SPI1_SOUT_1 (PIN_ALT2 | PIN_PORTB | PIN16)
+#define PIN_UART0_RX_3 (PIN_ALT3 | PIN_PORTB | PIN16)
+#define PIN_EWM_IN_1 (PIN_ALT6 | PIN_PORTB | PIN16)
+#define PIN_LCD_P12F (PIN_ALT7 | PIN_PORTB | PIN16)
+#define PIN_LCD_P13 (PIN_ANALOG | PIN_PORTB | PIN17)
+#define PIN_TSI0_CH10 (PIN_ANALOG | PIN_PORTB | PIN17)
+#define PIN_SPI1_SIN_1 (PIN_ALT2 | PIN_PORTB | PIN17)
+#define PIN_UART0_TX_3 (PIN_ALT3 | PIN_PORTB | PIN17)
+#define PIN_EWM_OUT_1 (PIN_ALT6 | PIN_PORTB | PIN17)
+#define PIN_LCD_P13F (PIN_ALT7 | PIN_PORTB | PIN17)
+#define PIN_LCD_P14 (PIN_ANALOG | PIN_PORTB | PIN18)
+#define PIN_TSI0_CH11 (PIN_ANALOG | PIN_PORTB | PIN18)
+#define PIN_CAN0_TX_2 (PIN_ALT2 | PIN_PORTB | PIN18)
+#define PIN_FTM2_CH0_2 (PIN_ALT3 | PIN_PORTB | PIN18)
+#define PIN_I2S0_TX_BCLK_2 (PIN_ALT4 | PIN_PORTB | PIN18)
+#define PIN_FTM2_QD_PHA_2 (PIN_ALT6 | PIN_PORTB | PIN18)
+#define PIN_LCD_P14F (PIN_ALT7 | PIN_PORTB | PIN18)
+#define PIN_LCD_P15 (PIN_ANALOG | PIN_PORTB | PIN19)
+#define PIN_TSI0_CH12 (PIN_ANALOG | PIN_PORTB | PIN19)
+#define PIN_CAN0_RX_2 (PIN_ALT2 | PIN_PORTB | PIN19)
+#define PIN_FTM2_CH1_2 (PIN_ALT3 | PIN_PORTB | PIN19)
+#define PIN_I2S0_TX_FS_2 (PIN_ALT4 | PIN_PORTB | PIN19)
+#define PIN_FTM2_QD_PHB_2 (PIN_ALT6 | PIN_PORTB | PIN19)
+#define PIN_LCD_P15F (PIN_ALT7 | PIN_PORTB | PIN19)
+#define PIN_LCD_P16 (PIN_ANALOG | PIN_PORTB | PIN20)
+#define PIN_SPI2_PCS0_1 (PIN_ALT2 | PIN_PORTB | PIN20)
+#define PIN_CMP0_OUT_1 (PIN_ALT6 | PIN_PORTB | PIN20)
+#define PIN_LCD_P16F (PIN_ALT7 | PIN_PORTB | PIN20)
+#define PIN_LCD_P17 (PIN_ANALOG | PIN_PORTB | PIN21)
+#define PIN_SPI2_SCK_1 (PIN_ALT2 | PIN_PORTB | PIN21)
+#define PIN_CMP1_OUT_1 (PIN_ALT6 | PIN_PORTB | PIN21)
+#define PIN_LCD_P17F (PIN_ALT7 | PIN_PORTB | PIN21)
+#define PIN_LCD_P18 (PIN_ANALOG | PIN_PORTB | PIN22)
+#define PIN_SPI2_SOUT_1 (PIN_ALT2 | PIN_PORTB | PIN22)
+#define PIN_CMP2_OUT_2 (PIN_ALT6 | PIN_PORTB | PIN22)
+#define PIN_LCD_P18F (PIN_ALT7 | PIN_PORTB | PIN22)
+#define PIN_LCD_P19 (PIN_ANALOG | PIN_PORTB | PIN23)
+#define PIN_SPI2_SIN_1 (PIN_ALT2 | PIN_PORTB | PIN23)
+#define PIN_SPI0_PCS5 (PIN_ALT3 | PIN_PORTB | PIN23)
+#define PIN_LCD_P19F (PIN_ALT7 | PIN_PORTB | PIN23)
+
+#define PIN_LCD_P20 (PIN_ANALOG | PIN_PORTC | PIN0)
+#define PIN_ADC0_SE14 (PIN_ANALOG | PIN_PORTC | PIN0)
+#define PIN_TSI0_CH13 (PIN_ANALOG | PIN_PORTC | PIN0)
+#define PIN_SPI0_PCS4 (PIN_ALT2 | PIN_PORTC | PIN0)
+#define PIN_PDB0_EXTRG_1 (PIN_ALT3 | PIN_PORTC | PIN0)
+#define PIN_I2S0_TXD_2 (PIN_ALT4 | PIN_PORTC | PIN0)
+#define PIN_LCD_P20F (PIN_ALT7 | PIN_PORTC | PIN0)
+#define PIN_LCD_P21 (PIN_ANALOG | PIN_PORTC | PIN1)
+#define PIN_ADC0_SE15 (PIN_ANALOG | PIN_PORTC | PIN1)
+#define PIN_TSI0_CH14 (PIN_ANALOG | PIN_PORTC | PIN1)
+#define PIN_SPI0_PCS3_1 (PIN_ALT2 | PIN_PORTC | PIN1)
+#define PIN_UART1_RTS_1 (PIN_ALT3 | PIN_PORTC | PIN1)
+#define PIN_FTM0_CH0_2 (PIN_ALT4 | PIN_PORTC | PIN1)
+#define PIN_LCD_P21F (PIN_ALT7 | PIN_PORTC | PIN1)
+#define PIN_LCD_P22 (PIN_ANALOG | PIN_PORTC | PIN2)
+#define PIN_ADC0_SE4B (PIN_ANALOG | PIN_PORTC | PIN2)
+#define PIN_CMP1_IN0 (PIN_ANALOG | PIN_PORTC | PIN2)
+#define PIN_TSI0_CH15 (PIN_ANALOG | PIN_PORTC | PIN2)
+#define PIN_SPI0_PCS2_1 (PIN_ALT2 | PIN_PORTC | PIN2)
+#define PIN_UART1_CTS_1 (PIN_ALT3 | PIN_PORTC | PIN2)
+#define PIN_FTM0_CH1_2 (PIN_ALT4 | PIN_PORTC | PIN2)
+#define PIN_LCD_P22F (PIN_ALT7 | PIN_PORTC | PIN2)
+#define PIN_LCD_P23 (PIN_ANALOG | PIN_PORTC | PIN3)
+#define PIN_CMP1_IN1 (PIN_ANALOG | PIN_PORTC | PIN3)
+#define PIN_SPI0_PCS1_1 (PIN_ALT2 | PIN_PORTC | PIN3)
+#define PIN_UART1_RX_1 (PIN_ALT3 | PIN_PORTC | PIN3)
+#define PIN_FTM0_CH2_2 (PIN_ALT4 | PIN_PORTC | PIN3)
+#define PIN_LCD_P23F (PIN_ALT7 | PIN_PORTC | PIN3)
+#define PIN_LCD_P24 (PIN_ANALOG | PIN_PORTC | PIN4)
+#define PIN_SPI0_PCS0_2 (PIN_ALT2 | PIN_PORTC | PIN4)
+#define PIN_UART1_TX_1 (PIN_ALT3 | PIN_PORTC | PIN4)
+#define PIN_FTM0_CH3_2 (PIN_ALT4 | PIN_PORTC | PIN4)
+#define PIN_CMP1_OUT_2 (PIN_ALT6 | PIN_PORTC | PIN4)
+#define PIN_LCD_P24F (PIN_ALT7 | PIN_PORTC | PIN4)
+#define PIN_LCD_P25 (PIN_ANALOG | PIN_PORTC | PIN5)
+#define PIN_SPI0_SCK_2 (PIN_ALT2 | PIN_PORTC | PIN5)
+#define PIN_LPT0_ALT2 (PIN_ALT4 | PIN_PORTC | PIN5)
+#define PIN_CMP0_OUT_2 (PIN_ALT6 | PIN_PORTC | PIN5)
+#define PIN_LCD_P25F (PIN_ALT7 | PIN_PORTC | PIN5)
+#define PIN_LCD_P26 (PIN_ANALOG | PIN_PORTC | PIN6)
+#define PIN_CMP0_IN0 (PIN_ANALOG | PIN_PORTC | PIN6)
+#define PIN_SPI0_SOUT_2 (PIN_ALT2 | PIN_PORTC | PIN6)
+#define PIN_PDB0_EXTRG_2 (PIN_ALT3 | PIN_PORTC | PIN6)
+#define PIN_LCD_P26F (PIN_ALT7 | PIN_PORTC | PIN6)
+#define PIN_LCD_P27 (PIN_ANALOG | PIN_PORTC | PIN7)
+#define PIN_CMP0_IN1 (PIN_ANALOG | PIN_PORTC | PIN7)
+#define PIN_SPI0_SIN_2 (PIN_ALT2 | PIN_PORTC | PIN7)
+#define PIN_LCD_P27F (PIN_ALT7 | PIN_PORTC | PIN7)
+#define PIN_LCD_P28 (PIN_ANALOG | PIN_PORTC | PIN8)
+#define PIN_ADC1_SE4B (PIN_ANALOG | PIN_PORTC | PIN8)
+#define PIN_CMP0_IN2 (PIN_ANALOG | PIN_PORTC | PIN8)
+#define PIN_I2S0_MCLK_2 (PIN_ALT4 | PIN_PORTC | PIN8)
+#define PIN_I2S0_CLKIN_2 (PIN_ALT5 | PIN_PORTC | PIN8)
+#define PIN_LCD_P28F (PIN_ALT7 | PIN_PORTC | PIN8)
+#define PIN_LCD_P29 (PIN_ANALOG | PIN_PORTC | PIN9)
+#define PIN_ADC1_SE5B (PIN_ANALOG | PIN_PORTC | PIN9)
+#define PIN_CMP0_IN3 (PIN_ANALOG | PIN_PORTC | PIN9)
+#define PIN_I2S0_RX_BCLK_2 (PIN_ALT4 | PIN_PORTC | PIN9)
+#define PIN_FTM2_FLT0_2 (PIN_ALT6 | PIN_PORTC | PIN9)
+#define PIN_LCD_P29F (PIN_ALT7 | PIN_PORTC | PIN9)
+#define PIN_LCD_P30 (PIN_ANALOG | PIN_PORTC | PIN10)
+#define PIN_ADC1_SE6B (PIN_ANALOG | PIN_PORTC | PIN10)
+#define PIN_CMP0_IN4 (PIN_ANALOG | PIN_PORTC | PIN10)
+#define PIN_I2C1_SCL_1 (PIN_ALT2 | PIN_PORTC | PIN10)
+#define PIN_I2S0_RX_FS_2 (PIN_ALT4 | PIN_PORTC | PIN10)
+#define PIN_LCD_P30F (PIN_ALT7 | PIN_PORTC | PIN10)
+#define PIN_LCD_P31 (PIN_ANALOG | PIN_PORTC | PIN11)
+#define PIN_ADC1_SE7B (PIN_ANALOG | PIN_PORTC | PIN11)
+#define PIN_I2C1_SDA_1 (PIN_ALT2 | PIN_PORTC | PIN11)
+#define PIN_I2S0_RXD_2 (PIN_ALT4 | PIN_PORTC | PIN11)
+#define PIN_LCD_P31F (PIN_ALT7 | PIN_PORTC | PIN11)
+#define PIN_LCD_P32 (PIN_ANALOG | PIN_PORTC | PIN12)
+#define PIN_UART4_RTS_1 (PIN_ALT3 | PIN_PORTC | PIN12)
+#define PIN_LCD_P32F (PIN_ALT7 | PIN_PORTC | PIN12)
+#define PIN_LCD_P33 (PIN_ANALOG | PIN_PORTC | PIN13)
+#define PIN_UART4_CTS_1 (PIN_ALT3 | PIN_PORTC | PIN13)
+#define PIN_LCD_P33F (PIN_ALT7 | PIN_PORTC | PIN13)
+#define PIN_LCD_P34 (PIN_ANALOG | PIN_PORTC | PIN14)
+#define PIN_UART4_RX_1 (PIN_ALT3 | PIN_PORTC | PIN14)
+#define PIN_LCD_P34F (PIN_ALT7 | PIN_PORTC | PIN14)
+#define PIN_LCD_P35 (PIN_ANALOG | PIN_PORTC | PIN15)
+#define PIN_UART4_TX_1 (PIN_ALT3 | PIN_PORTC | PIN15)
+#define PIN_LCD_P35F (PIN_ALT7 | PIN_PORTC | PIN15)
+#define PIN_LCD_P36 (PIN_ANALOG | PIN_PORTC | PIN16)
+#define PIN_CAN1_RX_1 (PIN_ALT2 | PIN_PORTC | PIN16)
+#define PIN_UART3_RX_2 (PIN_ALT3 | PIN_PORTC | PIN16)
+#define PIN_LCD_P36F (PIN_ALT7 | PIN_PORTC | PIN16)
+#define PIN_LCD_P37 (PIN_ANALOG | PIN_PORTC | PIN17)
+#define PIN_CAN1_TX_1 (PIN_ALT2 | PIN_PORTC | PIN17)
+#define PIN_UART3_TX_2 (PIN_ALT3 | PIN_PORTC | PIN17)
+#define PIN_LCD_P37F (PIN_ALT7 | PIN_PORTC | PIN17)
+#define PIN_LCD_P38 (PIN_ANALOG | PIN_PORTC | PIN18)
+#define PIN_UART3_RTS_2 (PIN_ALT3 | PIN_PORTC | PIN18)
+#define PIN_LCD_P38F (PIN_ALT7 | PIN_PORTC | PIN18)
+#define PIN_LCD_P39 (PIN_ANALOG | PIN_PORTC | PIN19)
+#define PIN_UART3_CTS_2 (PIN_ALT3 | PIN_PORTC | PIN19)
+#define PIN_LCD_P39F (PIN_ALT7 | PIN_PORTC | PIN19)
+
+#define PIN_LCD_P40 (PIN_ANALOG | PIN_PORTD | PIN0)
+#define PIN_SPI0_PCS0_3 (PIN_ALT2 | PIN_PORTD | PIN0)
+#define PIN_UART2_RTS (PIN_ALT3 | PIN_PORTD | PIN0)
+#define PIN_LCD_P40F (PIN_ALT7 | PIN_PORTD | PIN0)
+#define PIN_LCD_P41 (PIN_ANALOG | PIN_PORTD | PIN1)
+#define PIN_ADC0_SE5B (PIN_ANALOG | PIN_PORTD | PIN1)
+#define PIN_SPI0_SCK_3 (PIN_ALT2 | PIN_PORTD | PIN1)
+#define PIN_UART2_CTS (PIN_ALT3 | PIN_PORTD | PIN1)
+#define PIN_LCD_P41F (PIN_ALT7 | PIN_PORTD | PIN1)
+#define PIN_LCD_P42 (PIN_ANALOG | PIN_PORTD | PIN2)
+#define PIN_SPI0_SOUT_3 (PIN_ALT2 | PIN_PORTD | PIN2)
+#define PIN_UART2_RX (PIN_ALT3 | PIN_PORTD | PIN2)
+#define PIN_LCD_P42F (PIN_ALT7 | PIN_PORTD | PIN2)
+#define PIN_LCD_P43 (PIN_ANALOG | PIN_PORTD | PIN3)
+#define PIN_SPI0_SIN_3 (PIN_ALT2 | PIN_PORTD | PIN3)
+#define PIN_UART2_TX (PIN_ALT3 | PIN_PORTD | PIN3)
+#define PIN_LCD_P43F (PIN_ALT7 | PIN_PORTD | PIN3)
+#define PIN_LCD_P44 (PIN_ANALOG | PIN_PORTD | PIN4)
+#define PIN_SPI0_PCS1_2 (PIN_ALT2 | PIN_PORTD | PIN4)
+#define PIN_UART0_RTS_4 (PIN_ALT3 | PIN_PORTD | PIN4)
+#define PIN_FTM0_CH4_2 (PIN_ALT4 | PIN_PORTD | PIN4)
+#define PIN_EWM_IN_2 (PIN_ALT6 | PIN_PORTD | PIN4)
+#define PIN_LCD_P44F (PIN_ALT7 | PIN_PORTD | PIN4)
+#define PIN_LCD_P45 (PIN_ANALOG | PIN_PORTD | PIN5)
+#define PIN_ADC0_SE6B (PIN_ANALOG | PIN_PORTD | PIN5)
+#define PIN_SPI0_PCS2_2 (PIN_ALT2 | PIN_PORTD | PIN5)
+#define PIN_UART0_CTS_4 (PIN_ALT3 | PIN_PORTD | PIN5)
+#define PIN_FTM0_CH5_2 (PIN_ALT4 | PIN_PORTD | PIN5)
+#define PIN_EWM_OUT_2 (PIN_ALT6 | PIN_PORTD | PIN5)
+#define PIN_LCD_P45F (PIN_ALT7 | PIN_PORTD | PIN5)
+#define PIN_LCD_P46 (PIN_ANALOG | PIN_PORTD | PIN6)
+#define PIN_ADC0_SE7B (PIN_ANALOG | PIN_PORTD | PIN6)
+#define PIN_SPI0_PCS3_2 (PIN_ALT2 | PIN_PORTD | PIN6)
+#define PIN_UART0_RX_4 (PIN_ALT3 | PIN_PORTD | PIN6)
+#define PIN_FTM0_CH6_2 (PIN_ALT4 | PIN_PORTD | PIN6)
+#define PIN_FTM0_FLT0_2 (PIN_ALT6 | PIN_PORTD | PIN6)
+#define PIN_LCD_P46F (PIN_ALT7 | PIN_PORTD | PIN6)
+#define PIN_LCD_P47 (PIN_ANALOG | PIN_PORTD | PIN7)
+#define PIN_CMT_IRO (PIN_ALT2 | PIN_PORTD | PIN7)
+#define PIN_UART0_TX_4 (PIN_ALT3 | PIN_PORTD | PIN7)
+#define PIN_FTM0_CH7_2 (PIN_ALT4 | PIN_PORTD | PIN7)
+#define PIN_FTM0_FLT1_2 (PIN_ALT6 | PIN_PORTD | PIN7)
+#define PIN_LCD_P47F (PIN_ALT7 | PIN_PORTD | PIN7)
+#define PIN_UART5_RTS_1 (PIN_ALT3 | PIN_PORTD | PIN10)
+#define PIN_FB_AD9 (PIN_ALT5 | PIN_PORTD | PIN10)
+#define PIN_SPI2_PCS0_2 (PIN_ALT2 | PIN_PORTD | PIN11)
+#define PIN_UART5_CTS_1 (PIN_ALT3 | PIN_PORTD | PIN11)
+#define PIN_SDHC0_CLKIN (PIN_ALT4 | PIN_PORTD | PIN11)
+#define PIN_FB_AD8 (PIN_ALT5 | PIN_PORTD | PIN11)
+#define PIN_SPI2_SCK_2 (PIN_ALT2 | PIN_PORTD | PIN12)
+#define PIN_SDHC0_D4 (PIN_ALT4 | PIN_PORTD | PIN12)
+#define PIN_FB_AD7 (PIN_ALT5 | PIN_PORTD | PIN12)
+#define PIN_SPI2_SOUT_2 (PIN_ALT2 | PIN_PORTD | PIN13)
+#define PIN_SDHC0_D5 (PIN_ALT4 | PIN_PORTD | PIN13)
+#define PIN_FB_AD6 (PIN_ALT5 | PIN_PORTD | PIN13)
+#define PIN_SPI2_SIN_2 (PIN_ALT2 | PIN_PORTD | PIN14)
+#define PIN_SDHC0_D6 (PIN_ALT4 | PIN_PORTD | PIN14)
+#define PIN_FB_AD5 (PIN_ALT5 | PIN_PORTD | PIN14)
+#define PIN_SPI2_PCS1 (PIN_ALT2 | PIN_PORTD | PIN15)
+#define PIN_SDHC0_D7 (PIN_ALT4 | PIN_PORTD | PIN15)
+#define PIN_FB_RW (PIN_ALT5 | PIN_PORTD | PIN15)
+
+#define PIN_ADC1_SE4A (PIN_ANALOG | PIN_PORTE | PIN0)
+#define PIN_SPI1_PCS1_2 (PIN_ALT2 | PIN_PORTE | PIN0)
+#define PIN_UART1_TX_2 (PIN_ALT3 | PIN_PORTE | PIN0)
+#define PIN_SDHC0_D1 (PIN_ALT4 | PIN_PORTE | PIN0)
+#define PIN_FB_AD27 (PIN_ALT5 | PIN_PORTE | PIN0)
+#define PIN_I2C1_SDA_2 (PIN_ALT6 | PIN_PORTE | PIN0)
+#define PIN_ADC1_SE5A (PIN_ANALOG | PIN_PORTE | PIN1)
+#define PIN_SPI1_SOUT_2 (PIN_ALT2 | PIN_PORTE | PIN1)
+#define PIN_UART1_RX_2 (PIN_ALT3 | PIN_PORTE | PIN1)
+#define PIN_SDHC0_D0 (PIN_ALT4 | PIN_PORTE | PIN1)
+#define PIN_FB_AD26 (PIN_ALT5 | PIN_PORTE | PIN1)
+#define PIN_I2C1_SCL_2 (PIN_ALT6 | PIN_PORTE | PIN1)
+#define PIN_ADC1_SE6A (PIN_ANALOG | PIN_PORTE | PIN2)
+#define PIN_SPI1_SCK_2 (PIN_ALT2 | PIN_PORTE | PIN2)
+#define PIN_UART1_CTS_2 (PIN_ALT3 | PIN_PORTE | PIN2)
+#define PIN_SDHC0_DCLK (PIN_ALT4 | PIN_PORTE | PIN2)
+#define PIN_FB_AD25 (PIN_ALT5 | PIN_PORTE | PIN2)
+#define PIN_ADC1_SE7A (PIN_ANALOG | PIN_PORTE | PIN3)
+#define PIN_SPI1_SIN_2 (PIN_ALT2 | PIN_PORTE | PIN3)
+#define PIN_UART1_RTS_2 (PIN_ALT3 | PIN_PORTE | PIN3)
+#define PIN_SDHC0_CMD (PIN_ALT4 | PIN_PORTE | PIN3)
+#define PIN_FB_AD24 (PIN_ALT5 | PIN_PORTE | PIN3)
+#define PIN_SPI1_PCS0_2 (PIN_ALT2 | PIN_PORTE | PIN4)
+#define PIN_UART3_TX_3 (PIN_ALT3 | PIN_PORTE | PIN4)
+#define PIN_SDHC0_D3 (PIN_ALT4 | PIN_PORTE | PIN4)
+#define PIN_FB_CS3 (PIN_ALT5 | PIN_PORTE | PIN4)
+#define PIN_FB_BE7_0_BLS31_24 (PIN_ALT5 | PIN_PORTE | PIN4)
+#define PIN_FB_TA (PIN_ALT6 | PIN_PORTE | PIN4)
+#define PIN_SPI1_PCS2 (PIN_ANALOG | PIN_PORTE | PIN5)
+#define PIN_UART3_RX_3 (PIN_ALT2 | PIN_PORTE | PIN5)
+#define PIN_SDHC0_D2 (PIN_ALT3 | PIN_PORTE | PIN5)
+#define PIN_FB_TBST (PIN_ALT4 | PIN_PORTE | PIN5)
+#define PIN_FB_CS2 (PIN_ALT5 | PIN_PORTE | PIN5)
+#define PIN_FB_BE15_8_BLS23_16 (PIN_ALT5 | PIN_PORTE | PIN5)
+#define PIN_SPI1_PCS3 (PIN_ALT2 | PIN_PORTE | PIN6)
+#define PIN_UART3_CTS_3 (PIN_ALT3 | PIN_PORTE | PIN6)
+#define PIN_I2S0_MCLK_3 (PIN_ALT4 | PIN_PORTE | PIN6)
+#define PIN_FB_ALE (PIN_ALT5 | PIN_PORTE | PIN6)
+#define PIN_FB_CS1 (PIN_ALT5 | PIN_PORTE | PIN6)
+#define PIN_FB_TS (PIN_ALT5 | PIN_PORTE | PIN6)
+#define PIN_I2S0_CLKIN_3 (PIN_ALT6 | PIN_PORTE | PIN6)
+#define PIN_UART3_RTS_3 (PIN_ALT3 | PIN_PORTE | PIN7)
+#define PIN_I2S0_RXD_3 (PIN_ALT4 | PIN_PORTE | PIN7)
+#define PIN_FB_CS0 (PIN_ALT5 | PIN_PORTE | PIN7)
+#define PIN_UART5_TX (PIN_ALT3 | PIN_PORTE | PIN8)
+#define PIN_I2S0_RX_FS_3 (PIN_ALT4 | PIN_PORTE | PIN8)
+#define PIN_FB_AD4 (PIN_ALT5 | PIN_PORTE | PIN8)
+#define PIN_UART5_RX (PIN_ALT3 | PIN_PORTE | PIN9)
+#define PIN_I2S0_RX_BCLK_3 (PIN_ALT4 | PIN_PORTE | PIN9)
+#define PIN_FB_AD3 (PIN_ALT5 | PIN_PORTE | PIN9)
+#define PIN_UART5_CTS_2 (PIN_ALT3 | PIN_PORTE | PIN10)
+#define PIN_I2S0_TXD_3 (PIN_ALT4 | PIN_PORTE | PIN10)
+#define PIN_FB_AD2 (PIN_ALT5 | PIN_PORTE | PIN10)
+#define PIN_UART5_RTS_2 (PIN_ALT3 | PIN_PORTE | PIN11)
+#define PIN_I2S0_TX_FS_3 (PIN_ALT4 | PIN_PORTE | PIN11)
+#define PIN_FB_AD1 (PIN_ALT5 | PIN_PORTE | PIN11)
+#define PIN_I2S0_TX_BCLK_3 (PIN_ALT4 | PIN_PORTE | PIN12)
+#define PIN_FB_AD0 (PIN_ALT5 | PIN_PORTE | PIN12)
+#define PIN_ADC0_SE17 (PIN_ANALOG | PIN_PORTE | PIN24)
+#define PIN_CAN1_TX_2 (PIN_ALT2 | PIN_PORTE | PIN24)
+#define PIN_UART4_TX_2 (PIN_ALT3 | PIN_PORTE | PIN24)
+#define PIN_EWM_OUT_3 (PIN_ALT6 | PIN_PORTE | PIN24)
+#define PIN_ADC0_SE18 (PIN_ANALOG | PIN_PORTE | PIN25)
+#define PIN_CAN1_RX_2 (PIN_ALT2 | PIN_PORTE | PIN25)
+#define PIN_UART4_RX_2 (PIN_ALT3 | PIN_PORTE | PIN25)
+#define PIN_FB_AD23 (PIN_ALT5 | PIN_PORTE | PIN25)
+#define PIN_EWM_IN_3 (PIN_ALT6 | PIN_PORTE | PIN25)
+#define PIN_UART4_CTS_2 (PIN_ALT3 | PIN_PORTE | PIN26)
+#define PIN_FB_AD22 (PIN_ALT5 | PIN_PORTE | PIN26)
+#define PIN_RTC_CLKOUT (PIN_ALT6 | PIN_PORTE | PIN26)
+#define PIN_USB_CLKIN (PIN_ALT7 | PIN_PORTE | PIN26)
+#define PIN_UART4_RTS_2 (PIN_ALT3 | PIN_PORTE | PIN27)
+#define PIN_FB_AD21 (PIN_ALT5 | PIN_PORTE | PIN27)
+#define PIN_FB_AD20 (PIN_ALT5 | PIN_PORTE | PIN28)
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KINETIS_KINETIS_K40PINMUX_H */
diff --git a/nuttx/arch/arm/src/kl/chip/kl_clk.h b/nuttx/arch/arm/src/kl/chip/kl_clk.h
new file mode 100644
index 000000000..2125d4dea
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/kl_clk.h
@@ -0,0 +1,288 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_clk.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ********************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_CHIP_KL_CLK_H
+#define __ARCH_ARM_SRC_KL_CHIP_KL_CLK_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Well-known clock frequencies *************************************************************/
+
+#define KL_INTHI_FREQUENCY 22118400
+#define KL_INTLO_FREQUENCY 10000
+
+/* Register offsets *************************************************************************/
+
+#define KL_CLK_PWRCON_OFFSET 0x0000 /* System power down control register */
+#define KL_CLK_AHBCLK_OFFSET 0x0004 /* AHB devices clock enable control register */
+#define KL_CLK_APBCLK_OFFSET 0x0008 /* APB devices clock enable control register */
+#define KL_CLK_CLKSTATUS_OFFSET 0x000c /* Clock status monitor register */
+#define KL_CLK_CLKSEL0_OFFSET 0x0010 /* Clock source select control register 0 */
+#define KL_CLK_CLKSEL1_OFFSET 0x0014 /* Clock source select control register 1 */
+#define KL_CLK_CLKSEL2_OFFSET 0x001c /* Clock source select control register 2 */
+#define KL_CLK_CLKDIV_OFFSET 0x0018 /* Clock divider number register */
+#define KL_CLK_PLLCON_OFFSET 0x0020 /* PLL control register */
+#define KL_CLK_FRQDIV_OFFSET 0x0024 /* Frequency divider control register */
+
+/* Register addresses ***********************************************************************/
+
+#define KL_CLK_PWRCON (KL_CLK_BASE+KL_CLK_PWRCON_OFFSET)
+#define KL_CLK_AHBCLK (KL_CLK_BASE+KL_CLK_AHBCLK_OFFSET)
+#define KL_CLK_APBCLK (KL_CLK_BASE+KL_CLK_APBCLK_OFFSET)
+#define KL_CLK_CLKSTATUS (KL_CLK_BASE+KL_CLK_CLKSTATUS_OFFSET)
+#define KL_CLK_CLKSEL0 (KL_CLK_BASE+KL_CLK_CLKSEL0_OFFSET)
+#define KL_CLK_CLKSEL1 (KL_CLK_BASE+KL_CLK_CLKSEL1_OFFSET)
+#define KL_CLK_CLKSEL2 (KL_CLK_BASE+KL_CLK_CLKSEL2_OFFSET)
+#define KL_CLK_CLKDIV (KL_CLK_BASE+KL_CLK_CLKDIV_OFFSET)
+#define KL_CLK_PLLCON (KL_CLK_BASE+KL_CLK_PLLCON_OFFSET)
+#define KL_CLK_FRQDIV (KL_CLK_BASE+KL_CLK_FRQDIV_OFFSET)
+
+/* Register bit-field definitions ***********************************************************/
+
+/* System power down control register */
+
+#define CLK_PWRCON_XTL12M_EN (1 << 0) /* Bit 0: External 4~24 mhz high speed crystal enable */
+#define CLK_PWRCON_XTL32K_EN (1 << 1) /* Bit 1: External 32.768 khz low speed crystal enable */
+#define CLK_PWRCON_OSC22M_EN (1 << 2) /* Bit 2: Internal 22.1184 MHz high speed oscillator enable */
+#define CLK_PWRCON_OSC10K_EN (1 << 3) /* Bit 3: Internal 10KHz low speed oscillator enable */
+#define CLK_PWRCON_PD_WU_DLY (1 << 4) /* Bit 4: Enable the wake-up delay counter */
+#define CLK_PWRCON_PD_WU_INT_EN (1 << 5) /* Bit 5: Power down mode wake-up interrupt status */
+#define CLK_PWRCON_PD_WU_STS (1 << 6) /* Bit 6: Power down mode wake-up interupt status */
+#define CLK_PWRCON_PWR_DOWN_EN (1 << 7) /* Bit 7: System power down enable bit */
+#define CLK_PWRCON_PD_WAIT_CPU (1 << 8) /* Bit 8: Power down entry condition */
+
+/* AHB devices clock enable control register */
+
+#define CLK_AHBCLK_PDMA_EN (1 << 1) /* Bit 1: PDMA acontroller clock enable control */
+#define CLK_AHBCLK_ISP_EN (1 << 2) /* Bit 2: FLASH ISPO controller clock enable control */
+#define CLK_AHBCLK_EBI_EN (1 << 3) /* Bit 3: EBI controller clock enable control */
+
+/* APB devices clock enable control register */
+
+#define CLK_APBCLK_WDT_EN (1 << 0) /* Bit 0: Watchdog time clock enable */
+#define CLK_APBCLK_RTC_EN (1 << 1) /* Bit 1: Real time clock clock enable */
+#define CLK_APBCLK_TMR0_EN (1 << 2) /* Bit 2: Timer0 clock enable */
+#define CLK_APBCLK_TMR1_EN (1 << 3) /* Bit 3: Timer1 clock enable */
+#define CLK_APBCLK_TMR2_EN (1 << 4) /* Bit 4: Timer2 clock enable */
+#define CLK_APBCLK_TMR3_EN (1 << 5) /* Bit 5: Timer3 clock enable */
+#define CLK_APBCLK_FDIV_EN (1 << 6) /* Bit 6: Frequency divider output clock enable */
+#define CLK_APBCLK_I2C0_EN (1 << 8) /* Bit 8: I2C0 clock enable */
+#define CLK_APBCLK_I2C1_EN (1 << 9) /* Bit 9: I2C1 clock enable */
+#define CLK_APBCLK_SPI0_EN (1 << 12) /* Bit 12: SPI0 clock enable */
+#define CLK_APBCLK_SPI1_EN (1 << 13) /* Bit 13: SPI1 clock enable */
+#define CLK_APBCLK_SPI2_EN (1 << 14) /* Bit 14: SPI2 clock enable */
+#define CLK_APBCLK_SPI3_EN (1 << 15) /* Bit 15: SPI3 clock enable */
+#define CLK_APBCLK_UART0_EN (1 << 16) /* Bit 16: UART0 clock enable */
+#define CLK_APBCLK_UART1_EN (1 << 17) /* Bit 17: UART1 clock enable */
+#define CLK_APBCLK_UART2_EN (1 << 18) /* Bit 18: UART2 clock enable */
+#define CLK_APBCLK_PWM01_EN (1 << 20) /* Bit 20: PWM_01 clock enable */
+#define CLK_APBCLK_PWM23_EN (1 << 21) /* Bit 21: PWM_23 clock enable */
+#define CLK_APBCLK_PWM45_EN (1 << 22) /* Bit 22: PWM_45 clock enable */
+#define CLK_APBCLK_PWM67_EN (1 << 23) /* Bit 23: PWM_67 clock enable */
+#define CLK_APBCLK_USBD_EN (1 << 27) /* Bit 27: USB 2.0 FS device controller clock enable */
+#define CLK_APBCLK_ADC_EN (1 << 28) /* Bit 28: Analog-digital-converter clock enable */
+#define CLK_APBCLK_I2S_EN (1 << 29) /* Bit 29: I2S clock enable */
+#define CLK_APBCLK_ACMP_EN (1 << 30) /* Bit 30: Analog comparator clock enable */
+#define CLK_APBCLK_PS2_EN (1 << 31) /* Bit 31: PS/2 clock enable */
+
+/* Clock status monitor register */
+
+#define CLK_CLKSTATUS_XTL12M_STB (1 << 0) /* Bit 0: External 4~24 mhz high speed crystal
+ * clock source stable flag */
+#define CLK_CLKSTATUS_STL32K_STB (1 << 1) /* Bit 1: External 32.768 kHz low speed crystal
+ * clock source stable flag */
+#define CLK_CLKSTATUS_PLL_STB (1 << 2) /* Bit 2: Internal PLL clock source stable flag */
+#define CLK_CLKSTATUS_OSC10K_STB (1 << 3) /* Bit 3: Internal 10kHz low speed clock source
+ * stable flag */
+#define CLK_CLKSTATUS_OSC22M_STB (1 << 4) /* Bit 4: Internal 22.1184MHz high speed
+ * osciallator clock source stable flag */
+#define CLK_CLKSTATUS_CLK_SW_FAIL (1 << 7) /* Bit 7: Clock switching fail flag */
+
+/* Clock source select control register 0 */
+
+#define CLK_CLKSEL0_HCLK_S_SHIFT (0) /* Bits 0-2: HCLK clock source select */
+#define CLK_CLKSEL0_HCLK_S_MASK (7 << CLK_CLKSEL0_HCLK_S_SHIFT)
+# define CLK_CLKSEL0_HCLK_S_XTALHI (0 << CLK_CLKSEL0_HCLK_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL0_HCLK_S_XTALLO (1 << CLK_CLKSEL0_HCLK_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL0_HCLK_S_PLL (2 << CLK_CLKSEL0_HCLK_S_SHIFT) /* PLL clock */
+# define CLK_CLKSEL0_HCLK_S_INTLO (3 << CLK_CLKSEL0_HCLK_S_SHIFT) /* Internal low speed clock */
+# define CLK_CLKSEL0_HCLK_S_INTHI (7 << CLK_CLKSEL0_HCLK_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL0_STCLK_S_SHIFT (3) /* Bits 3-5: Cortex M0 Systick clock source select */
+#define CLK_CLKSEL0_STCLK_S_MASK (7 << CLK_CLKSEL0_STCLK_S_SHIFT)
+# define CLK_CLKSEL0_STCLK_S_XTALHI (0 << CLK_CLKSEL0_STCLK_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL0_STCLK_S_XTALLO (1 << CLK_CLKSEL0_STCLK_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL0_STCLK_S_XTALDIV2 (2 << CLK_CLKSEL0_STCLK_S_SHIFT) /* High speed XTAL clock/2 */
+# define CLK_CLKSEL0_STCLK_S_HCLKDIV2 (3 << CLK_CLKSEL0_STCLK_S_SHIFT) /* HCLK/2 */
+# define CLK_CLKSEL0_STCLK_S_INTDIV2 (7 << CLK_CLKSEL0_STCLK_S_SHIFT) /* Internal high speed clock/2 */
+
+/* Clock source select control register 1 */
+
+#define CLK_CLKSEL1_WDT_S_SHIFT (0) /* Bits 0-1: Watchdog timer clock source select */
+#define CLK_CLKSEL1_WDT_S_MASK (3 << CLK_CLKSEL1_WDT_S_SHIFT)
+# define CLK_CLKSEL1_ADC_S_HCLKDIV (2 << CLK_CLKSEL1_WDT_S_SHIFT) /* HCLK / 2048 */
+# define CLK_CLKSEL1_ADC_S_INTLO (3 << CLK_CLKSEL1_WDT_S_SHIFT) /* Internal low speed clock */
+#define CLK_CLKSEL1_ADC_S_SHIFT (2) /* Bits 2-3: ADC clock source select */
+#define CLK_CLKSEL1_ADC_S_MASK (3 << CLK_CLKSEL1_ADC_S_SHIFT)
+# define CLK_CLKSEL1_ADC_S_XTALHI (0 << CLK_CLKSEL1_ADC_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_ADC_S_PLL (1 << CLK_CLKSEL1_ADC_S_SHIFT) /* PLL */
+# define CLK_CLKSEL1_ADC_S_INTHI (3 << CLK_CLKSEL1_ADC_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL1_TMR0_S_SHIFT (8) /* Bits 8-10: Timer0 clock source select */
+#define CLK_CLKSEL1_TMR0_S_MASK (7 << CLK_CLKSEL1_TMR0_S_SHIFT)
+# define CLK_CLKSEL1_TMR0_S_XTALHI (0 << CLK_CLKSEL1_TMR0_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_TMR0_S_XTALLO (1 << CLK_CLKSEL1_TMR0_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_TMR0_S_HCLK (2 << CLK_CLKSEL1_TMR0_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_TMR0_S_INTHI (7 << CLK_CLKSEL1_TMR0_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL1_TMR1_S_SHIFT (12) /* Bits 12-14: Timer1 clock source select */
+#define CLK_CLKSEL1_TMR1_S_MASK (7 << CLK_CLKSEL1_TMR1_S_SHIFT)
+# define CLK_CLKSEL1_TMR1_S_XTALHI (0 << CLK_CLKSEL1_TMR1_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_TMR1_S_XTALLO (1 << CLK_CLKSEL1_TMR1_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_TMR1_S_HCLK (2 << CLK_CLKSEL1_TMR1_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_TMR1_S_INTHI (7 << CLK_CLKSEL1_TMR1_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL1_TMR2_S_SHIFT (16) /* Bits 16-18: Timer2 clock source select */
+#define CLK_CLKSEL1_TMR2_S_MASK (7 << CLK_CLKSEL1_TMR2_S_SHIFT)
+# define CLK_CLKSEL1_TMR2_S_XTALHI (0 << CLK_CLKSEL1_TMR2_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_TMR2_S_XTALLO (1 << CLK_CLKSEL1_TMR2_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_TMR2_S_HCLK (2 << CLK_CLKSEL1_TMR2_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_TMR2_S_INTHI (7 << CLK_CLKSEL1_TMR2_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL1_TMR3_S_SHIFT (20) /* Bits 20-22: Timer3 clock source select */
+#define CLK_CLKSEL1_TMR3_S_MASK (7 << CLK_CLKSEL1_TMR3_S_SHIFT)
+# define CLK_CLKSEL1_TMR3_S_XTALHI (0 << CLK_CLKSEL1_TMR3_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_TMR3_S_XTALLO (1 << CLK_CLKSEL1_TMR3_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_TMR3_S_HCLK (2 << CLK_CLKSEL1_TMR3_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_TMR3_S_INTHI (7 << CLK_CLKSEL1_TMR3_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL1_UART_S_SHIFT (24) /* Bits 24-25: UART clock source select */
+#define CLK_CLKSEL1_UART_S_MASK (3 << CLK_CLKSEL1_UART_S_SHIFT)
+# define CLK_CLKSEL1_UART_S_XTALHI (0 << CLK_CLKSEL1_UART_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_UART_S_PLL (1 << CLK_CLKSEL1_UART_S_SHIFT) /* PLL */
+# define CLK_CLKSEL1_UART_S_INTHI (3 << CLK_CLKSEL1_UART_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL1_PWM01_S_SHIFT (28) /* Bits 28-29: PWM0 and PWM1 clock source select */
+#define CLK_CLKSEL1_PWM01_S_MASK (3 << CLK_CLKSEL1_PWM01_S_SHIFT)
+# define CLK_CLKSEL1_PWM01_S_XTALHI (0 << CLK_CLKSEL1_PWM01_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_PWM01_S_XTALLO (1 << CLK_CLKSEL1_PWM01_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_PWM01_S_HCLK (2 << CLK_CLKSEL1_PWM01_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_PWM01_S_INTHI (3 << CLK_CLKSEL1_PWM01_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL1_PWM23_S_SHIFT (30) /* Bits 30-31: PWM2 and PWM3 clock source select */
+#define CLK_CLKSEL1_PWM23_S_MASK (3 << CLK_CLKSEL1_PWM23_S_SHIFT)
+# define CLK_CLKSEL1_PWM23_S_XTALHI (0 << CLK_CLKSEL1_PWM23_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_PWM23_S_XTALLO (1 << CLK_CLKSEL1_PWM23_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_PWM23_S_HCLK (2 << CLK_CLKSEL1_PWM23_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_PWM23_S_INTHI (3 << CLK_CLKSEL1_PWM23_S_SHIFT) /* Internal high speed clock */
+
+/* Clock source select control register 2 */
+
+#define CLK_CLKSEL2_I2S_S_SHIFT (0) /* Bits 0-1: I2S clock source select */
+#define CLK_CLKSEL2_I2S_S_MASK (3 << CLK_CLKSEL2_I2S_S_SHIFT)
+# define CLK_CLKSEL1_I2S_S_XTALHI (0 << CLK_CLKSEL2_I2S_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_I2S_S_XTALLO (1 << CLK_CLKSEL2_I2S_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_I2S_S_HCLK (2 << CLK_CLKSEL2_I2S_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_I2S_S_INTHI (3 << CLK_CLKSEL2_I2S_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL2_FRQDIV_S_SHIFT (2) /* Bits 2-3: Frequency divider clock source select */
+#define CLK_CLKSEL2_FRQDIV_S_MASK (3 << CLK_CLKSEL2_FRQDIV_S_SHIFT)
+# define CLK_CLKSEL1_FRQDIV_S_XTALHI (0 << CLK_CLKSEL2_FRQDIV_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_FRQDIV_S_XTALLO (1 << CLK_CLKSEL2_FRQDIV_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_FRQDIV_S_HCLK (2 << CLK_CLKSEL2_FRQDIV_S_SHIFT) /* HCLK */
+#define CLK_CLKSEL2_PWM45_S_SHIFT (4) /* Bits 4-5: PWM4 and PWM5 clock source select */
+#define CLK_CLKSEL2_PWM45_S_MASK (3 << CLK_CLKSEL2_PWM45_S_SHIFT)
+# define CLK_CLKSEL1_PWM45_S_XTALHI (0 << CLK_CLKSEL2_PWM45_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_PWM45_S_XTALLO (1 << CLK_CLKSEL2_PWM45_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_PWM45_S_HCLK (2 << CLK_CLKSEL2_PWM45_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_PWM45_S_INTHI (3 << CLK_CLKSEL2_PWM45_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL2_PWM67_S_SHIFT (6) /* Bits 6-7: PWM6 and PWM7 clock source select */
+#define CLK_CLKSEL2_PWM67_S_MASK (3 << CLK_CLKSEL2_PWM67_S_SHIFT)
+# define CLK_CLKSEL1_PWM67_S_XTALHI (0 << CLK_CLKSEL2_PWM67_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_PWM67_S_XTALLO (1 << CLK_CLKSEL2_PWM67_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_PWM67_S_HCLK (2 << CLK_CLKSEL2_PWM67_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_PWM67_S_INTHI (3 << CLK_CLKSEL2_PWM67_S_SHIFT) /* Internal high speed clock */
+
+/* Clock divider number register */
+
+#define CLK_CLKDIV_HCLK_N_SHIFT (0) /* Bits 0-3: HCLCK divide from clock source */
+#define CLK_CLKDIV_HCLK_N_MASK (15 << CLK_CLKDIV_HCLK_N_SHIFT)
+# define CLK_CLKDIV_HCLK_N(n) (((n)-1) << CLK_CLKDIV_HCLK_N_SHIFT) /* n=1..16 */
+#define CLK_CLKDIV_USB_N_SHIFT (4) /* Bits 4-7: USBD divide from clock source */
+#define CLK_CLKDIV_USB_N_MASK (15 << CLK_CLKDIV_USB_N_SHIFT)
+# define CLK_CLKDIV_USB_N(n) (((n)-1) << CLK_CLKDIV_USB_N_SHIFT) /* n=1..16 */
+#define CLK_CLKDIV_UART_N_SHIFT (8) /* Bits 8-11 UART divide from clock source */
+#define CLK_CLKDIV_UART_N_MASK (15 << CLK_CLKDIV_UART_N_SHIFT)
+# define CLK_CLKDIV_UART_N(n) (((n)-1) << CLK_CLKDIV_UART_N_SHIFT) /* n=1..16 */
+#define CLK_CLKDIV_ADC_N_SHIFT (16) /* Bits 16-23: ADC divide from clock source */
+#define CLK_CLKDIV_ADC_N_MASK (255 << CLK_CLKDIV_ADC_N_SHIFT)
+# define CLK_CLKDIV_ADC_N(n) (((n)-1) << CLK_CLKDIV_UART_N_SHIFT) /* n=1..256 */
+
+/* PLL control register */
+
+#define CLK_PLLCON_FB_DV_SHIFT (0) /* Bits 0-8: PLL feedback divider control pins */
+#define CLK_PLLCON_FB_DV_MASK (0x1ff << CLK_PLLCON_FB_DV_SHIFT)
+# define CLK_PLLCON_FB_DV(n) ((n) << CLK_PLLCON_FB_DV_SHIFT)
+#define CLK_PLLCON_IN_DV_SHIFT (9) /* bits 9-13: PLL input divider control pins */
+#define CLK_PLLCON_IN_DV_MASK (0x1f << CLK_PLLCON_IN_DV_SHIFT)
+# define CLK_PLLCON_IN_DV(n) ((n) << CLK_PLLCON_IN_DV_SHIFT)
+#define CLK_PLLCON_OUT_DV_SHIFT (14) /* Bits 14-15: PLL output divider control pins */
+#define CLK_PLLCON_OUT_DV_MASK (3 << CLK_PLLCON_OUT_DV_SHIFT)
+# define CLK_PLLCON_OUT_DV(n) ((n) << CLK_PLLCON_OUT_DV_SHIFT)
+#define CLK_PLLCON_PD (1 << 16) /* Bit 16: Power down mode */
+#define CLK_PLLCON_BP (1 << 17) /* Bit 17: PLL bypass control */
+#define CLK_PLLCON_OE (1 << 18) /* Bit 18: PLL OE (FOUT enable) pin control */
+#define CLK_PLLCON_PLL_SRC (1 << 19) /* Bit 19: PLL source clock select */
+
+/* Frequency divider control register */
+
+#define CLK_FRQDIV_FSEL_SHIFT (0) /* Bits 0-3: Divider output frequency selection bits */
+#define CLK_FRQDIV_FSEL_MASK (15 << CLK_FRQDIV_FSEL_SHIFT)
+# define CLK_FRQDIV_FSEL(n) ((n) << CLK_FRQDIV_FSEL_SHIFT) /* fout = fin / (2^(n+1)) */
+#define CLK_FRQDIV_DIVIDER_EN (1 << 4) /* Bit 4: Frequency divider enable bit */
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KL_CHIP_KL_CLK_H */
diff --git a/nuttx/arch/arm/src/kl/chip/kl_fmc.h b/nuttx/arch/arm/src/kl/chip/kl_fmc.h
new file mode 100644
index 000000000..d11aedc6b
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/kl_fmc.h
@@ -0,0 +1,389 @@
+/************************************************************************************
+ * arch/arm/src/kl/kl_fmc.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_KL_FMC_H
+#define __ARCH_ARM_SRC_KL_KL_FMC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register Offsets *****************************************************************/
+
+#define KL_FMC_PFAPR_OFFSET 0x0000 /* Flash Access Protection Register */
+#define KL_FMC_PFB0CR_OFFSET 0x0004 /* Flash Bank 0 Control Register */
+#define KL_FMC_PFB1CR_OFFSET 0x0008 /* Flash Bank 1 Control Register */
+
+/* Cache Directory Storage for way=w and set=s, w=0..3, s=0..7 */
+
+#define KL_FMC_TAGVD_OFFSET(w,s) (0x100+((w)<<5)+((s)<<2))
+
+#define KL_FMC_TAGVDW0S0_OFFSET 0x0100 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW0S1_OFFSET 0x0104 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW0S2_OFFSET 0x0108 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW0S3_OFFSET 0x010c /* Cache Directory Storage */
+#define KL_FMC_TAGVDW0S4_OFFSET 0x0110 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW0S5_OFFSET 0x0114 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW0S6_OFFSET 0x0118 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW0S7_OFFSET 0x011c /* Cache Directory Storage */
+
+#define KL_FMC_TAGVDW1S0_OFFSET 0x0120 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW1S1_OFFSET 0x0124 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW1S2_OFFSET 0x0128 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW1S3_OFFSET 0x012c /* Cache Directory Storage */
+#define KL_FMC_TAGVDW1S4_OFFSET 0x0130 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW1S5_OFFSET 0x0134 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW1S6_OFFSET 0x0138 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW1S7_OFFSET 0x013c /* Cache Directory Storage */
+
+#define KL_FMC_TAGVDW2S0_OFFSET 0x0140 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW2S1_OFFSET 0x0144 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW2S2_OFFSET 0x0148 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW2S3_OFFSET 0x014c /* Cache Directory Storage */
+#define KL_FMC_TAGVDW2S4_OFFSET 0x0150 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW2S5_OFFSET 0x0154 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW2S6_OFFSET 0x0158 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW2S7_OFFSET 0x015c /* Cache Directory Storage */
+
+#define KL_FMC_TAGVDW3S0_OFFSET 0x0160 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW3S1_OFFSET 0x0164 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW3S2_OFFSET 0x0168 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW3S3_OFFSET 0x016c /* Cache Directory Storage */
+#define KL_FMC_TAGVDW3S4_OFFSET 0x0170 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW3S5_OFFSET 0x0174 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW3S6_OFFSET 0x0178 /* Cache Directory Storage */
+#define KL_FMC_TAGVDW3S7_OFFSET 0x017c /* Cache Directory Storage */
+
+/* Cache Data Storage (upper and lower) for way=w and set=s, w=0..3, s=0..7 */
+
+#define KL_FMC_DATAU_OFFSET(w,s) (0x200+((w)<<6)+((s)<<2))
+#define KL_FMC_DATAL_OFFSET(w,s) (0x204+((w)<<6)+((s)<<2))
+
+#define KL_FMC_DATAW0S0U_OFFSET 0x0200 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW0S0L_OFFSET 0x0204 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW0S1U_OFFSET 0x0208 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW0S1L_OFFSET 0x020c /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW0S2U_OFFSET 0x0210 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW0S2L_OFFSET 0x0214 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW0S3U_OFFSET 0x0218 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW0S3L_OFFSET 0x021c /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW0S4U_OFFSET 0x0220 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW0S4L_OFFSET 0x0224 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW0S5U_OFFSET 0x0228 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW0S5L_OFFSET 0x022c /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW0S6U_OFFSET 0x0230 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW0S6L_OFFSET 0x0234 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW0S7U_OFFSET 0x0238 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW0S7L_OFFSET 0x023c /* Cache Data Storage (lower word) */
+
+#define KL_FMC_DATAW1S0U_OFFSET 0x0240 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW1S0L_OFFSET 0x0244 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW1S1U_OFFSET 0x0248 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW1S1L_OFFSET 0x024c /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW1S2U_OFFSET 0x0250 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW1S2L_OFFSET 0x0254 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW1S3U_OFFSET 0x0258 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW1S3L_OFFSET 0x025c /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW1S4U_OFFSET 0x0260 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW1S4L_OFFSET 0x0264 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW1S5U_OFFSET 0x0268 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW1S5L_OFFSET 0x026c /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW1S6U_OFFSET 0x0270 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW1S6L_OFFSET 0x0274 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW1S7U_OFFSET 0x0278 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW1S7L_OFFSET 0x027c /* Cache Data Storage (lower word) */
+
+#define KL_FMC_DATAW2S0U_OFFSET 0x0280 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW2S0L_OFFSET 0x0284 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW2S1U_OFFSET 0x0288 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW2S1L_OFFSET 0x028c /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW2S2U_OFFSET 0x0290 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW2S2L_OFFSET 0x0294 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW2S3U_OFFSET 0x0298 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW2S3L_OFFSET 0x029c /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW2S4U_OFFSET 0x02a0 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW2S4L_OFFSET 0x02a4 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW2S5U_OFFSET 0x02a8 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW2S5L_OFFSET 0x02ac /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW2S6U_OFFSET 0x02b0 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW2S6L_OFFSET 0x02b4 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW2S7U_OFFSET 0x02b8 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW2S7L_OFFSET 0x02bc /* Cache Data Storage (lower word) */
+
+#define KL_FMC_DATAW3S0U_OFFSET 0x02c0 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW3S0L_OFFSET 0x02c4 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW3S1U_OFFSET 0x02c8 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW3S1L_OFFSET 0x02cc /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW3S2U_OFFSET 0x02d0 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW3S2L_OFFSET 0x02d4 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW3S3U_OFFSET 0x02d8 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW3S3L_OFFSET 0x02dc /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW3S4U_OFFSET 0x02e0 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW3S4L_OFFSET 0x02e4 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW3S5U_OFFSET 0x02e8 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW3S5L_OFFSET 0x02ec /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW3S6U_OFFSET 0x02f0 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW3S6L_OFFSET 0x02f4 /* Cache Data Storage (lower word) */
+#define KL_FMC_DATAW3S7U_OFFSET 0x02f8 /* Cache Data Storage (upper word) */
+#define KL_FMC_DATAW3S7L_OFFSET 0x02fc /* Cache Data Storage (lower word) */
+
+/* Register Addresses ***************************************************************/
+
+#define KL_FMC_PFAPR (KL_FMC_BASE+KL_FMC_PFAPR_OFFSET)
+#define KL_FMC_PFB0CR (KL_FMC_BASE+KL_FMC_PFB0CR_OFFSET)
+#define KL_FMC_PFB1CR (KL_FMC_BASE+KL_FMC_PFB1CR_OFFSET)
+
+/* Cache Directory Storage for way=w and set=s, w=0..3, s=0..7 */
+
+#define KL_FMC_TAGVD(w,s) (KL_FMC_BASE+KL_FMC_TAGVD_OFFSET(w,s))
+
+#define KL_FMC_TAGVDW0S0 (KL_FMC_BASE+KL_FMC_TAGVDW0S0_OFFSET)
+#define KL_FMC_TAGVDW0S1 (KL_FMC_BASE+KL_FMC_TAGVDW0S1_OFFSET)
+#define KL_FMC_TAGVDW0S2 (KL_FMC_BASE+KL_FMC_TAGVDW0S2_OFFSET)
+#define KL_FMC_TAGVDW0S3 (KL_FMC_BASE+KL_FMC_TAGVDW0S3_OFFSET)
+#define KL_FMC_TAGVDW0S4 (KL_FMC_BASE+KL_FMC_TAGVDW0S4_OFFSET)
+#define KL_FMC_TAGVDW0S5 (KL_FMC_BASE+KL_FMC_TAGVDW0S5_OFFSET)
+#define KL_FMC_TAGVDW0S6 (KL_FMC_BASE+KL_FMC_TAGVDW0S6_OFFSET)
+#define KL_FMC_TAGVDW0S7 (KL_FMC_BASE+KL_FMC_TAGVDW0S7_OFFSET)
+
+#define KL_FMC_TAGVDW1S0 (KL_FMC_BASE+KL_FMC_TAGVDW1S0_OFFSET)
+#define KL_FMC_TAGVDW1S1 (KL_FMC_BASE+KL_FMC_TAGVDW1S1_OFFSET)
+#define KL_FMC_TAGVDW1S2 (KL_FMC_BASE+KL_FMC_TAGVDW1S2_OFFSET)
+#define KL_FMC_TAGVDW1S3 (KL_FMC_BASE+KL_FMC_TAGVDW1S3_OFFSET)
+#define KL_FMC_TAGVDW1S4 (KL_FMC_BASE+KL_FMC_TAGVDW1S4_OFFSET)
+#define KL_FMC_TAGVDW1S5 (KL_FMC_BASE+KL_FMC_TAGVDW1S5_OFFSET)
+#define KL_FMC_TAGVDW1S6 (KL_FMC_BASE+KL_FMC_TAGVDW1S6_OFFSET)
+#define KL_FMC_TAGVDW1S7 (KL_FMC_BASE+KL_FMC_TAGVDW1S7_OFFSET)
+
+#define KL_FMC_TAGVDW2S0 (KL_FMC_BASE+KL_FMC_TAGVDW2S0_OFFSET)
+#define KL_FMC_TAGVDW2S1 (KL_FMC_BASE+KL_FMC_TAGVDW2S1_OFFSET)
+#define KL_FMC_TAGVDW2S2 (KL_FMC_BASE+KL_FMC_TAGVDW2S2_OFFSET)
+#define KL_FMC_TAGVDW2S3 (KL_FMC_BASE+KL_FMC_TAGVDW2S3_OFFSET)
+#define KL_FMC_TAGVDW2S4 (KL_FMC_BASE+KL_FMC_TAGVDW2S4_OFFSET)
+#define KL_FMC_TAGVDW2S5 (KL_FMC_BASE+KL_FMC_TAGVDW2S5_OFFSET)
+#define KL_FMC_TAGVDW2S6 (KL_FMC_BASE+KL_FMC_TAGVDW2S6_OFFSET)
+#define KL_FMC_TAGVDW2S7 (KL_FMC_BASE+KL_FMC_TAGVDW2S7_OFFSET)
+
+#define KL_FMC_TAGVDW3S0 (KL_FMC_BASE+KL_FMC_TAGVDW3S0_OFFSET)
+#define KL_FMC_TAGVDW3S1 (KL_FMC_BASE+KL_FMC_TAGVDW3S1_OFFSET)
+#define KL_FMC_TAGVDW3S2 (KL_FMC_BASE+KL_FMC_TAGVDW3S2_OFFSET)
+#define KL_FMC_TAGVDW3S3 (KL_FMC_BASE+KL_FMC_TAGVDW3S3_OFFSET)
+#define KL_FMC_TAGVDW3S4 (KL_FMC_BASE+KL_FMC_TAGVDW3S4_OFFSET)
+#define KL_FMC_TAGVDW3S5 (KL_FMC_BASE+KL_FMC_TAGVDW3S5_OFFSET)
+#define KL_FMC_TAGVDW3S6 (KL_FMC_BASE+KL_FMC_TAGVDW3S6_OFFSET)
+#define KL_FMC_TAGVDW3S7 (KL_FMC_BASE+KL_FMC_TAGVDW3S7_OFFSET)
+
+/* Cache Data Storage (upper and lower) for way=w and set=s, w=0..3, s=0..7 */
+
+#define KL_FMC_DATAU(w,s) (KL_FMC_BASE+KL_FMC_DATAU_OFFSET(w,s))
+#define KL_FMC_DATAL(w,s) (KL_FMC_BASE+KL_FMC_DATAL_OFFSET(w,s))
+
+#define KL_FMC_DATAW0S0U (KL_FMC_BASE+KL_FMC_DATAW0S0U_OFFSET)
+#define KL_FMC_DATAW0S0L (KL_FMC_BASE+KL_FMC_DATAW0S0L_OFFSET)
+#define KL_FMC_DATAW0S1U (KL_FMC_BASE+KL_FMC_DATAW0S1U_OFFSET)
+#define KL_FMC_DATAW0S1L (KL_FMC_BASE+KL_FMC_DATAW0S1L_OFFSET)
+#define KL_FMC_DATAW0S2U (KL_FMC_BASE+KL_FMC_DATAW0S2U_OFFSET)
+#define KL_FMC_DATAW0S2L (KL_FMC_BASE+KL_FMC_DATAW0S2L_OFFSET)
+#define KL_FMC_DATAW0S3U (KL_FMC_BASE+KL_FMC_DATAW0S3U_OFFSET)
+#define KL_FMC_DATAW0S3L (KL_FMC_BASE+KL_FMC_DATAW0S3L_OFFSET)
+#define KL_FMC_DATAW0S4U (KL_FMC_BASE+KL_FMC_DATAW0S4U_OFFSET)
+#define KL_FMC_DATAW0S4L (KL_FMC_BASE+KL_FMC_DATAW0S4L_OFFSET)
+#define KL_FMC_DATAW0S5U (KL_FMC_BASE+KL_FMC_DATAW0S5U_OFFSET)
+#define KL_FMC_DATAW0S5L (KL_FMC_BASE+KL_FMC_DATAW0S5L_OFFSET)
+#define KL_FMC_DATAW0S6U (KL_FMC_BASE+KL_FMC_DATAW0S6U_OFFSET)
+#define KL_FMC_DATAW0S6L (KL_FMC_BASE+KL_FMC_DATAW0S6L_OFFSET)
+#define KL_FMC_DATAW0S7U (KL_FMC_BASE+KL_FMC_DATAW0S7U_OFFSET)
+#define KL_FMC_DATAW0S7L (KL_FMC_BASE+KL_FMC_DATAW0S7L_OFFSET)
+
+#define KL_FMC_DATAW1S0U (KL_FMC_BASE+KL_FMC_DATAW1S0U_OFFSET)
+#define KL_FMC_DATAW1S0L (KL_FMC_BASE+KL_FMC_DATAW1S0L_OFFSET)
+#define KL_FMC_DATAW1S1U (KL_FMC_BASE+KL_FMC_DATAW1S1U_OFFSET)
+#define KL_FMC_DATAW1S1L (KL_FMC_BASE+KL_FMC_DATAW1S1L_OFFSET)
+#define KL_FMC_DATAW1S2U (KL_FMC_BASE+KL_FMC_DATAW1S2U_OFFSET)
+#define KL_FMC_DATAW1S2L (KL_FMC_BASE+KL_FMC_DATAW1S2L_OFFSET)
+#define KL_FMC_DATAW1S3U (KL_FMC_BASE+KL_FMC_DATAW1S3U_OFFSET)
+#define KL_FMC_DATAW1S3L (KL_FMC_BASE+KL_FMC_DATAW1S3L_OFFSET)
+#define KL_FMC_DATAW1S4U (KL_FMC_BASE+KL_FMC_DATAW1S4U_OFFSET)
+#define KL_FMC_DATAW1S4L (KL_FMC_BASE+KL_FMC_DATAW1S4L_OFFSET)
+#define KL_FMC_DATAW1S5U (KL_FMC_BASE+KL_FMC_DATAW1S5U_OFFSET)
+#define KL_FMC_DATAW1S5L (KL_FMC_BASE+KL_FMC_DATAW1S5L_OFFSET)
+#define KL_FMC_DATAW1S6U (KL_FMC_BASE+KL_FMC_DATAW1S6U_OFFSET)
+#define KL_FMC_DATAW1S6L (KL_FMC_BASE+KL_FMC_DATAW1S6L_OFFSET)
+#define KL_FMC_DATAW1S7U (KL_FMC_BASE+KL_FMC_DATAW1S7U_OFFSET)
+#define KL_FMC_DATAW1S7L (KL_FMC_BASE+KL_FMC_DATAW1S7L_OFFSET)
+
+#define KL_FMC_DATAW2S0U (KL_FMC_BASE+KL_FMC_DATAW2S0U_OFFSET)
+#define KL_FMC_DATAW2S0L (KL_FMC_BASE+KL_FMC_DATAW2S0L_OFFSET)
+#define KL_FMC_DATAW2S1U (KL_FMC_BASE+KL_FMC_DATAW2S1U_OFFSET)
+#define KL_FMC_DATAW2S1L (KL_FMC_BASE+KL_FMC_DATAW2S1L_OFFSET)
+#define KL_FMC_DATAW2S2U (KL_FMC_BASE+KL_FMC_DATAW2S2U_OFFSET)
+#define KL_FMC_DATAW2S2L (KL_FMC_BASE+KL_FMC_DATAW2S2L_OFFSET)
+#define KL_FMC_DATAW2S3U (KL_FMC_BASE+KL_FMC_DATAW2S3U_OFFSET)
+#define KL_FMC_DATAW2S3L (KL_FMC_BASE+KL_FMC_DATAW2S3L_OFFSET)
+#define KL_FMC_DATAW2S4U (KL_FMC_BASE+KL_FMC_DATAW2S4U_OFFSET)
+#define KL_FMC_DATAW2S4L (KL_FMC_BASE+KL_FMC_DATAW2S4L_OFFSET)
+#define KL_FMC_DATAW2S5U (KL_FMC_BASE+KL_FMC_DATAW2S5U_OFFSET)
+#define KL_FMC_DATAW2S5L (KL_FMC_BASE+KL_FMC_DATAW2S5L_OFFSET)
+#define KL_FMC_DATAW2S6U (KL_FMC_BASE+KL_FMC_DATAW2S6U_OFFSET)
+#define KL_FMC_DATAW2S6L (KL_FMC_BASE+KL_FMC_DATAW2S6L_OFFSET)
+#define KL_FMC_DATAW2S7U (KL_FMC_BASE+KL_FMC_DATAW2S7U_OFFSET)
+#define KL_FMC_DATAW2S7L (KL_FMC_BASE+KL_FMC_DATAW2S7L_OFFSET)
+
+#define KL_FMC_DATAW3S0U (KL_FMC_BASE+KL_FMC_DATAW3S0U_OFFSET)
+#define KL_FMC_DATAW3S0L (KL_FMC_BASE+KL_FMC_DATAW3S0L_OFFSET)
+#define KL_FMC_DATAW3S1U (KL_FMC_BASE+KL_FMC_DATAW3S1U_OFFSET)
+#define KL_FMC_DATAW3S1L (KL_FMC_BASE+KL_FMC_DATAW3S1L_OFFSET)
+#define KL_FMC_DATAW3S2U (KL_FMC_BASE+KL_FMC_DATAW3S2U_OFFSET)
+#define KL_FMC_DATAW3S2L (KL_FMC_BASE+KL_FMC_DATAW3S2L_OFFSET)
+#define KL_FMC_DATAW3S3U (KL_FMC_BASE+KL_FMC_DATAW3S3U_OFFSET)
+#define KL_FMC_DATAW3S3L (KL_FMC_BASE+KL_FMC_DATAW3S3L_OFFSET)
+#define KL_FMC_DATAW3S4U (KL_FMC_BASE+KL_FMC_DATAW3S4U_OFFSET)
+#define KL_FMC_DATAW3S4L (KL_FMC_BASE+KL_FMC_DATAW3S4L_OFFSET)
+#define KL_FMC_DATAW3S5U (KL_FMC_BASE+KL_FMC_DATAW3S5U_OFFSET)
+#define KL_FMC_DATAW3S5L (KL_FMC_BASE+KL_FMC_DATAW3S5L_OFFSET)
+#define KL_FMC_DATAW3S6U (KL_FMC_BASE+KL_FMC_DATAW3S6U_OFFSET)
+#define KL_FMC_DATAW3S6L (KL_FMC_BASE+KL_FMC_DATAW3S6L_OFFSET)
+#define KL_FMC_DATAW3S7U (KL_FMC_BASE+KL_FMC_DATAW3S7U_OFFSET)
+#define KL_FMC_DATAW3S7L (KL_FMC_BASE+KL_FMC_DATAW3S7L_OFFSET)
+
+/* Register Bit Definitions *********************************************************/
+
+/* Flash Access Protection Register */
+/* Access protection bits (all masters) */
+
+#define FMC_PFAPR_NONE 0 /* No access may be performed by this master */
+#define FMC_PFAPR_RDONLY 1 /* Only read accesses may be performed by this master */
+#define FMC_PFAPR_WRONLY 2 /* Only write accesses may be performed by this master */
+#define FMC_PFAPR_RDWR 3 /* Both read and write accesses may be performed by this master */
+
+#define FMC_PFAPR_M0AP_SHIFT (0) /* Bits 0-1: Master 0 Access Protection */
+#define FMC_PFAPR_M0AP_MASK (3 << FMC_PFAPR_M0AP_SHIFT)
+#define FMC_PFAPR_M1AP_SHIFT (2) /* Bits 2-3: Master 1 Access Protection */
+#define FMC_PFAPR_M1AP_MASK (3 << FMC_PFAPR_M1AP_SHIFT)
+#define FMC_PFAPR_M2AP_SHIFT (4) /* Bits 4-5: Master 2 Access Protection */
+#define FMC_PFAPR_M2AP_MASK (3 << FMC_PFAPR_M2AP_SHIFT)
+#define FMC_PFAPR_M3AP_SHIFT (6) /* Bits 6-7: Master 3 Access Protection */
+#define FMC_PFAPR_M3AP_MASK (3 << FMC_PFAPR_M3AP_SHIFT)
+#define FMC_PFAPR_M4AP_SHIFT (8) /* Bits 8-9: Master 4 Access Protection */
+#define FMC_PFAPR_M4AP_MASK (3 << FMC_PFAPR_M4AP_SHIFT)
+#define FMC_PFAPR_M5AP_SHIFT (10) /* Bits 10-11: Master 5 Access Protection */
+#define FMC_PFAPR_M5AP_MASK (3 << FMC_PFAPR_M5AP_SHIFT)
+#define FMC_PFAPR_M6AP_SHIFT (12) /* Bits 12-13: Master 6 Access Protection */
+#define FMC_PFAPR_M6AP_MASK (3 << FMC_PFAPR_M6AP_SHIFT)
+#define FMC_PFAPR_M7AP_SHIFT (14) /* Bits 14-15: Master 7 Access Protection */
+#define FMC_PFAPR_M7AP_MASK (3 << FMC_PFAPR_M7AP_SHIFT)
+#define FMC_PFAPR_M0PFD (1 << 16) /* Bit 16: Master 0 Prefetch Disable */
+#define FMC_PFAPR_M1PFD (1 << 17) /* Bit 17: Master 1 Prefetch Disable */
+#define FMC_PFAPR_M2PFD (1 << 18) /* Bit 18: Master 2 Prefetch Disable */
+#define FMC_PFAPR_M3PFD (1 << 19) /* Bit 19: Master 3 Prefetch Disable */
+#define FMC_PFAPR_M4PFD (1 << 20) /* Bit 20: Master 4 Prefetch Disable */
+#define FMC_PFAPR_M5PFD (1 << 21) /* Bit 21: Master 5 Prefetch Disable */
+#define FMC_PFAPR_M6PFD (1 << 22) /* Bit 22: Master 6 Prefetch Disable */
+#define FMC_PFAPR_M7PFD (1 << 23) /* Bit 23: Master 7 Prefetch Disable */
+ /* Bits 24-31: Reserved */
+/* Flash Bank 0 Control Register */
+
+#define FMC_PFB0CR_B0SEBE (1 << 0) /* Bit 0: Bank 0 Single Entry Buffer Enable */
+#define FMC_PFB0CR_B0IPE (1 << 1) /* Bit 1: Bank 0 Instruction Prefetch Enable */
+#define FMC_PFB0CR_B0DPE (1 << 2) /* Bit 2: Bank 0 Data Prefetch Enable */
+#define FMC_PFB0CR_B0ICE (1 << 3) /* Bit 3: Bank 0 Instruction Cache Enable */
+#define FMC_PFB0CR_B0DCE (1 << 4) /* Bit 4: Bank 0 Data Cache Enable */
+#define FMC_PFB0CR_CRC_SHIFT (5) /* Bits 5-7: Cache Replacement Control */
+#define FMC_PFB0CR_CRC_MASK (7 << FMC_PFB0CR_CRC_SHIFT)
+# define FMC_PFB0CR_CRC_ALL (0 << FMC_PFB0CR_CRC_SHIFT) /* LRU all four ways */
+# define FMC_PFB0CR_CRC_I01D23 (2 << FMC_PFB0CR_CRC_SHIFT) /* LRU ifetches 0-1 data 2-3 */
+# define FMC_PFB0CR_CRC_I012D3 (3 << FMC_PFB0CR_CRC_SHIFT) /* LRU ifetches 0-3 data 3 */
+ /* Bits 8-16: Reserved */
+#define FMC_PFB0CR_B0MW_SHIFT (17) /* Bits 17-18: Bank 0 Memory Width */
+#define FMC_PFB0CR_B0MW_MASK (3 << FMC_PFB0CR_B0MW_SHIFT)
+# define FMC_PFB0CR_B0MW_32BITS (0 << FMC_PFB0CR_B0MW_SHIFT) /* 32 bits */
+# define FMC_PFB0CR_B0MW_64BITS (1 << FMC_PFB0CR_B0MW_SHIFT) /* 64 bits */
+#define FMC_PFB0CR_S_B_INV (1 << 19) /* Bit 19: Invalidate Prefetch Speculation Buffer */
+#define FMC_PFB0CR_CINV_WAY_SHIFT (20) /* Bits 20-23: Cache Invalidate Way x */
+#define FMC_PFB0CR_CINV_WAY_MASK (15 << FMC_PFB0CR_CINV_WAY_SHIFT)
+#define FMC_PFB0CR_CLCK_WAY_SHIFT (24) /* Bits 24-27: Cache Lock Way x */
+#define FMC_PFB0CR_CLCK_WAY_MASK (15 << FMC_PFB0CR_CLCK_WAY_SHIFT)
+#define FMC_PFB0CR_B0RWSC_SHIFT (28) /* Bits 28-31: Bank 0 Read Wait State Control */
+#define FMC_PFB0CR_B0RWSC_MASK (15 << FMC_PFB0CR_B0RWSC_SHIFT)
+
+/* Flash Bank 1 Control Register */
+
+#define FMC_PFB1CR_B1SEBE (1 << 0) /* Bit 0: Bank 1 Single Entry Buffer Enable */
+#define FMC_PFB1CR_B1IPE (1 << 1) /* Bit 1: Bank 1 Instruction Prefetch Enable */
+#define FMC_PFB1CR_B1DPE (1 << 2) /* Bit 2: Bank 1 Data Prefetch Enable */
+#define FMC_PFB1CR_B1ICE (1 << 3) /* Bit 3: Bank 1 Instruction Cache Enable */
+#define FMC_PFB1CR_B1DCE (1 << 4) /* Bit 4: Bank 1 Data Cache Enable */
+ /* Bits 5-16: Reserved */
+#define FMC_PFB1CR_B1MW_SHIFT (17) /* Bits 17-18: Bank 1 Memory Width */
+#define FMC_PFB1CR_B1MW_MASK (3 << FMC_PFB1CR_B1MW_SHIFT)
+# define FMC_PFB1CR_B1MW_32BITS (0 << FMC_PFB1CR_B1MW_SHIFT) /* 32 bits */
+# define FMC_PFB1CR_B1MW_64BITS (1 << FMC_PFB1CR_B1MW_SHIFT) /* 64 bits */
+ /* Bits 19-27: Reserved */
+#define FMC_PFB1CR_B1RWSC_SHIFT (28) /* Bits 28-31: Bank 1 Read Wait State Control */
+#define FMC_PFB1CR_B1RWSC_MASK (15 << FMC_PFB1CR_B0RWSC_SHIFT)
+
+/* Cache Directory Storage for way=w and set=s, w=0..3, s=0..7 */
+
+#define FMC_TAGVD_VALID (1 << 0) /* Bit 0: 1-bit valid for cache entry */
+ /* Bits 1-5: Reserved */
+#define FMC_TAGVD_TAG_SHIFT (6) /* Bits 6-18: 13-bit tag for cache entry */
+#define FMC_TAGVD_TAG_MASK (0x1fff << FMC_TAGVD_TAG_SHIFT)
+ /* Bits 19-31: Reserved */
+
+/* Cache Data Storage (upper and lower) for way=w and set=s, w=0..3, s=0..7.
+ * 64-bit data in two 32-bit registers.
+ */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KL_KL_FMC_H */
diff --git a/nuttx/arch/arm/src/kl/chip/kl_gcr.h b/nuttx/arch/arm/src/kl/chip/kl_gcr.h
new file mode 100644
index 000000000..f03f9f096
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/kl_gcr.h
@@ -0,0 +1,373 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_gcr.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ********************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_CHIP_KL_GCR_H
+#define __ARCH_ARM_SRC_KL_CHIP_KL_GCR_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+#define KL_GCR_PDID_OFFSET 0x0000 /* Part didentification number register */
+#define KL_GCR_RSTSRC_OFFSET 0x0004 /* System reset source register */
+#define KL_GCR_IPRSTC1_OFFSET 0x0008 /* IP Reset control register 1 */
+#define KL_GCR_IPRSTC2_OFFSET 0x000c /* IP Reset control register 2 */
+#define KL_GCR_CPR_OFFSET 0x0010 /* Chip performance register */
+#define KL_GCR_BODCR_OFFSET 0x0018 /* Brown-out detector control register */
+#define KL_GCR_TEMPCR_OFFSET 0x001c /* Temperature sensor control register */
+#define KL_GCR_PORCR_OFFSET 0x0024 /* Power-on-reset control register */
+#define KL_GCR_GPA_MFP_OFFSET 0x0030 /* Multiple function pin GPIOA control register */
+#define KL_GCR_GPB_MFP_OFFSET 0x0034 /* Multiple function pin GPIOB control register */
+#define KL_GCR_GPC_MFP_OFFSET 0x0038 /* Multiple function pin GPIOC control register */
+#define KL_GCR_GPD_MFP_OFFSET 0x003C /* Multiple function pin GPIOD control register */
+#define KL_GCR_GPE_MFP_OFFSET 0x0040 /* Multiple function pin GPIOE control register */
+#define KL_GCR_ALT_MFP_OFFSET 0x0050 /* Alternative multiple function pin control register */
+#define KL_GCR_REGWRPROT_OFFSET 0x0100 /* Register write-protection control register */
+
+/* Register addresses ***********************************************************************/
+
+#define KL_GCR_PDID (KL_GCR_BASE+KL_GCR_PDID_OFFSET)
+#define KL_GCR_RSTSRC (KL_GCR_BASE+KL_GCR_RSTSRC_OFFSET)
+#define KL_GCR_IPRSTC1 (KL_GCR_BASE+KL_GCR_IPRSTC1_OFFSET)
+#define KL_GCR_IPRSTC2 (KL_GCR_BASE+KL_GCR_IPRSTC2_OFFSET)
+#define KL_GCR_CPR (KL_GCR_BASE+KL_GCR_CPR_OFFSET)
+#define KL_GCR_BODCR (KL_GCR_BASE+KL_GCR_BODCR_OFFSET)
+#define KL_GCR_TEMPCR (KL_GCR_BASE+KL_GCR_TEMPCR_OFFSET)
+#define KL_GCR_PORCR (KL_GCR_BASE+KL_GCR_PORCR_OFFSET)
+#define KL_GCR_GPA_MFP (KL_GCR_BASE+KL_GCR_GPA_MFP_OFFSET)
+#define KL_GCR_GPB_MFP (KL_GCR_BASE+KL_GCR_GPB_MFP_OFFSET)
+#define KL_GCR_GPC_MFP (KL_GCR_BASE+KL_GCR_GPC_MFP_OFFSET)
+#define KL_GCR_GPD_MFP (KL_GCR_BASE+KL_GCR_GPD_MFP_OFFSET)
+#define KL_GCR_GPE_MFP (KL_GCR_BASE+KL_GCR_GPE_MFP_OFFSET)
+#define KL_GCR_ALT_MFP (KL_GCR_BASE+KL_GCR_ALT_MFP_OFFSET)
+#define KL_GCR_REGWRPROT (KL_GCR_BASE+KL_GCR_REGWRPROT_OFFSET)
+
+/* Register bit-field definitions ***********************************************************/
+
+/* Part didentification number register (32-bit part ID number) */
+
+/* System reset source register */
+
+#define GCR_RSTSRC_POR (1 << 0) /* Bit 0: Power-on reset (POR) or chip reset (CHIP_RST) */
+#define GCR_RSTSRC_RESET (1 << 1) /* Bit 1: /RESET pin */
+#define GCR_RSTSRC_WDT (1 << 2) /* Bit 2: Watchdog timer */
+#define GCR_RSTSRC_LVR (1 << 3) /* Bit 3: Low voltage reset controller */
+#define GCR_RSTSRC_BOD (1 << 4) /* Bit 4: Brown-out detection */
+#define GCR_RSTSRC_SYS (1 << 5) /* Bit 5: Software set AIRCR:SYSRESETREQ */
+#define GCR_RSTSRC_CPU (1 << 7) /* Bit 7: Sofware set CPU_RST */
+
+/* IP Reset control register 1 */
+
+#define GCR_IPRSTC1_CHIP_RST (1 << 0) /* Bit 0: Chip one-shot reset */
+#define GCR_IPRSTC1_CPU_RST (1 << 1) /* Bit 1: CPU kernel one-shot reset */
+#define GCR_IPRSTC1_PDMA_RST (1 << 2) /* Bit 2: PDMA controller reset */
+#define GCR_IPRSTC1_EBI_RST (1 << 3) /* Bit 3: EBI controller reset */
+
+/* IP Reset control register 2 */
+
+#define GCR_IPRSTC2_GPIO_RST (1 << 1) /* Bit 1: GPIO controller reset */
+#define GCR_IPRSTC2_TMR0_RST (1 << 2) /* Bit 2: Timer0 controller reset */
+#define GCR_IPRSTC2_TMR1_RST (1 << 3) /* Bit 3: Timer1 controller reset */
+#define GCR_IPRSTC2_TMR2_RST (1 << 4) /* Bit 4: Timer2 controller reset */
+#define GCR_IPRSTC2_TMR3_RST (1 << 5) /* Bit 5: Timer3 controller reset */
+#define GCR_IPRSTC2_I2C0_RST (1 << 8) /* Bit 8: I2C0 controller reset */
+#define GCR_IPRSTC2_I2C1_RST (1 << 9) /* Bit 9: I2C1 controller reset */
+#define GCR_IPRSTC2_SPI0_RST (1 << 12) /* Bit 12: SPI0 controller reset */
+#define GCR_IPRSTC2_SPI1_RST (1 << 13) /* Bit 13: SPI1 controller reset */
+#define GCR_IPRSTC2_SPI2_RST (1 << 14) /* Bit 14: SPI2 controller reset */
+#define GCR_IPRSTC2_SPI3_RST (1 << 15) /* Bit 15: SPI3 controller reset */
+#define GCR_IPRSTC2_UART0_RST (1 << 16) /* Bit 16: UART0 controller reset */
+#define GCR_IPRSTC2_UART1_RST (1 << 17) /* Bit 17: UART1 controller reset */
+#define GCR_IPRSTC2_UART2_RST (1 << 18) /* Bit 18: UART2 controller reset */
+#define GCR_IPRSTC2_PWM03_RST (1 << 20) /* Bit 20: PWM0/1/2/3 controller reset */
+#define GCR_IPRSTC2_PWM47_RST (1 << 21) /* Bit 21: PWM4/5/6/7 controller reset */
+#define GCR_IPRSTC2_ACMP_RST (1 << 22) /* Bit 22: Analog comparator controller reset */
+#define GCR_IPRSTC2_PS2_RST (1 << 23) /* Bit 23: PS/2 controller reset */
+#define GCR_IPRSTC2_USBD_RST (1 << 27) /* Bit 27: USB device controller reset */
+#define GCR_IPRSTC2_ADC_RST (1 << 28) /* Bit 28: ADC controller reset */
+#define GCR_IPRSTC2_I2S_RST (1 << 29) /* Bit 29: I2S controller reset */
+
+/* Chip performance register */
+
+#define GCR_CPR_HPE (1 << 0) /* Bit 0: High performance enable */
+
+/* Brown-out detector control register */
+
+#define GCR_BODCR_BOD_EN (1 << 0) /* Bit 0: Brown-ut detector enable */
+#define GCR_BODCR_BOD_VL_SHIFT (1) /* Bits 1-2: Brown-out detector threshold voltage selection */
+#define GCR_BODCR_BOD_VL_MASK (3 << GCR_BODCR_BOD_VL_SHIFT)
+# define GCR_BODCR_BOD_VL_2p2V (0 << GCR_BODCR_BOD_VL_SHIFT) /* 2.2V */
+# define GCR_BODCR_BOD_VL_2p7V (1 << GCR_BODCR_BOD_VL_SHIFT) /* 2.7V */
+# define GCR_BODCR_BOD_VL_3p8V (2 << GCR_BODCR_BOD_VL_SHIFT) /* 3.8V */
+# define GCR_BODCR_BOD_VL_4p5V (3 << GCR_BODCR_BOD_VL_SHIFT) /* 4.5V */
+#define GCR_BODCR_BOD_RSTEN (1 << 3) /* Bit 3: Brown-out reset enable */
+#define GCR_BODCR_BOD_INTF (1 << 4) /* Bit 4: Brown-out deletector interrupt flag */
+#define GCR_BODCR_BOD_LPM (1 << 5) /* Bit 5: Brown-out detector low power mode */
+#define GCR_BODCR_BOD_OUT (1 << 6) /* Bit 6: Brown-out detector output status */
+#define GCR_BODCR_LVR_EN (1 << 7) /* Bit 7: Low voltaghe reset enable */
+
+/* Temperature sensor control register */
+
+#define GCR_TEMPCR_VTEMP_EN (1 << 0) /* Bit 0: Temperature sensor enable */
+
+/* Power-on-reset control register */
+
+#define GCR_PORCR_MASK (0xffff) /* Bits 9-15: POR disable code */
+
+/* Multiple function pin GPIOA control register */
+
+#define GCR_GPA_MFP(n) (1 << (n)) /* Bits 0-15: PAn pin function selection */
+# define GCR_GPA_MFP0 (1 << 0)
+# define GCR_GPA_MFP1 (1 << 1)
+# define GCR_GPA_MFP2 (1 << 2)
+# define GCR_GPA_MFP3 (1 << 3)
+# define GCR_GPA_MFP4 (1 << 4)
+# define GCR_GPA_MFP5 (1 << 5)
+# define GCR_GPA_MFP6 (1 << 6)
+# define GCR_GPA_MFP7 (1 << 7)
+# define GCR_GPA_MFP8 (1 << 8)
+# define GCR_GPA_MFP9 (1 << 9)
+# define GCR_GPA_MFP10 (1 << 10)
+# define GCR_GPA_MFP11 (1 << 11)
+# define GCR_GPA_MFP12 (1 << 12)
+# define GCR_GPA_MFP13 (1 << 13)
+# define GCR_GPA_MFP14 (1 << 14)
+# define GCR_GPA_MFP15 (1 << 15)
+#define GCR_GPA_TYPE(n) (1 << ((n)+16)) /* Bits 16-31: Enable Schmitt trigger function */
+# define GCR_GPA_TYPE0 (1 << 0)
+# define GCR_GPA_TYPE1 (1 << 1)
+# define GCR_GPA_TYPE2 (1 << 2)
+# define GCR_GPA_TYPE3 (1 << 3)
+# define GCR_GPA_TYPE4 (1 << 4)
+# define GCR_GPA_TYPE5 (1 << 5)
+# define GCR_GPA_TYPE6 (1 << 6)
+# define GCR_GPA_TYPE7 (1 << 7)
+# define GCR_GPA_TYPE8 (1 << 8)
+# define GCR_GPA_TYPE9 (1 << 9)
+# define GCR_GPA_TYPE10 (1 << 10)
+# define GCR_GPA_TYPE11 (1 << 11)
+# define GCR_GPA_TYPE12 (1 << 12)
+# define GCR_GPA_TYPE13 (1 << 13)
+# define GCR_GPA_TYPE14 (1 << 14)
+# define GCR_GPA_TYPE15 (1 << 15)
+
+/* Multiple function pin GPIOB control register */
+
+#define GCR_GPB_MFP(n) (1 << (n)) /* Bits 0-15: PBn pin function selection */
+# define GCR_GPB_MFP0 (1 << 0)
+# define GCR_GPB_MFP1 (1 << 1)
+# define GCR_GPB_MFP2 (1 << 2)
+# define GCR_GPB_MFP3 (1 << 3)
+# define GCR_GPB_MFP4 (1 << 4)
+# define GCR_GPB_MFP5 (1 << 5)
+# define GCR_GPB_MFP6 (1 << 6)
+# define GCR_GPB_MFP7 (1 << 7)
+# define GCR_GPB_MFP8 (1 << 8)
+# define GCR_GPB_MFP9 (1 << 9)
+# define GCR_GPB_MFP10 (1 << 10)
+# define GCR_GPB_MFP11 (1 << 11)
+# define GCR_GPB_MFP12 (1 << 12)
+# define GCR_GPB_MFP13 (1 << 13)
+# define GCR_GPB_MFP14 (1 << 14)
+# define GCR_GPB_MFP15 (1 << 15)
+#define GCR_GPB_TYPE(n) (1 << ((n)+16)) /* Bits 16-31: Enable Schmitt trigger function */
+# define GCR_GPB_TYPE0 (1 << 0)
+# define GCR_GPB_TYPE1 (1 << 1)
+# define GCR_GPB_TYPE2 (1 << 2)
+# define GCR_GPB_TYPE3 (1 << 3)
+# define GCR_GPB_TYPE4 (1 << 4)
+# define GCR_GPB_TYPE5 (1 << 5)
+# define GCR_GPB_TYPE6 (1 << 6)
+# define GCR_GPB_TYPE7 (1 << 7)
+# define GCR_GPB_TYPE8 (1 << 8)
+# define GCR_GPB_TYPE9 (1 << 9)
+# define GCR_GPB_TYPE10 (1 << 10)
+# define GCR_GPB_TYPE11 (1 << 11)
+# define GCR_GPB_TYPE12 (1 << 12)
+# define GCR_GPB_TYPE13 (1 << 13)
+# define GCR_GPB_TYPE14 (1 << 14)
+# define GCR_GPB_TYPE15 (1 << 15)
+
+/* Multiple function pin GPIOC control register */
+
+#define GCR_GPC_MFP(n) (1 << (n)) /* Bits 0-15: PCn pin function selection */
+# define GCR_GPC_MFP0 (1 << 0)
+# define GCR_GPC_MFP1 (1 << 1)
+# define GCR_GPC_MFP2 (1 << 2)
+# define GCR_GPC_MFP3 (1 << 3)
+# define GCR_GPC_MFP4 (1 << 4)
+# define GCR_GPC_MFP5 (1 << 5)
+# define GCR_GPC_MFP6 (1 << 6)
+# define GCR_GPC_MFP7 (1 << 7)
+# define GCR_GPC_MFP8 (1 << 8)
+# define GCR_GPC_MFP9 (1 << 9)
+# define GCR_GPC_MFP10 (1 << 10)
+# define GCR_GPC_MFP11 (1 << 11)
+# define GCR_GPC_MFP12 (1 << 12)
+# define GCR_GPC_MFP13 (1 << 13)
+# define GCR_GPC_MFP14 (1 << 14)
+# define GCR_GPC_MFP15 (1 << 15)
+#define GCR_GPC_TYPE(n) (1 << ((n)+16)) /* Bits 16-31: Enable Schmitt trigger function */
+# define GCR_GPC_TYPE0 (1 << 0)
+# define GCR_GPC_TYPE1 (1 << 1)
+# define GCR_GPC_TYPE2 (1 << 2)
+# define GCR_GPC_TYPE3 (1 << 3)
+# define GCR_GPC_TYPE4 (1 << 4)
+# define GCR_GPC_TYPE5 (1 << 5)
+# define GCR_GPC_TYPE6 (1 << 6)
+# define GCR_GPC_TYPE7 (1 << 7)
+# define GCR_GPC_TYPE8 (1 << 8)
+# define GCR_GPC_TYPE9 (1 << 9)
+# define GCR_GPC_TYPE10 (1 << 10)
+# define GCR_GPC_TYPE11 (1 << 11)
+# define GCR_GPC_TYPE12 (1 << 12)
+# define GCR_GPC_TYPE13 (1 << 13)
+# define GCR_GPC_TYPE14 (1 << 14)
+# define GCR_GPC_TYPE15 (1 << 15)
+
+/* Multiple function pin GPIOD control register */
+
+#define GCR_GPD_MFP(n) (1 << (n)) /* Bits 0-15: PDn pin function selection */
+# define GCR_GPD_MFP0 (1 << 0)
+# define GCR_GPD_MFP1 (1 << 1)
+# define GCR_GPD_MFP2 (1 << 2)
+# define GCR_GPD_MFP3 (1 << 3)
+# define GCR_GPD_MFP4 (1 << 4)
+# define GCR_GPD_MFP5 (1 << 5)
+# define GCR_GPD_MFP6 (1 << 6)
+# define GCR_GPD_MFP7 (1 << 7)
+# define GCR_GPD_MFP8 (1 << 8)
+# define GCR_GPD_MFP9 (1 << 9)
+# define GCR_GPD_MFP10 (1 << 10)
+# define GCR_GPD_MFP11 (1 << 11)
+# define GCR_GPD_MFP12 (1 << 12)
+# define GCR_GPD_MFP13 (1 << 13)
+# define GCR_GPD_MFP14 (1 << 14)
+# define GCR_GPD_MFP15 (1 << 15)
+#define GCR_GPD_TYPE(n) (1 << ((n)+16)) /* Bits 16-31: Enable Schmitt trigger function */
+# define GCR_GPD_TYPE0 (1 << 0)
+# define GCR_GPD_TYPE1 (1 << 1)
+# define GCR_GPD_TYPE2 (1 << 2)
+# define GCR_GPD_TYPE3 (1 << 3)
+# define GCR_GPD_TYPE4 (1 << 4)
+# define GCR_GPD_TYPE5 (1 << 5)
+# define GCR_GPD_TYPE6 (1 << 6)
+# define GCR_GPD_TYPE7 (1 << 7)
+# define GCR_GPD_TYPE8 (1 << 8)
+# define GCR_GPD_TYPE9 (1 << 9)
+# define GCR_GPD_TYPE10 (1 << 10)
+# define GCR_GPD_TYPE11 (1 << 11)
+# define GCR_GPD_TYPE12 (1 << 12)
+# define GCR_GPD_TYPE13 (1 << 13)
+# define GCR_GPD_TYPE14 (1 << 14)
+# define GCR_GPD_TYPE15 (1 << 15)
+
+/* Multiple function pin GPIOE control register */
+
+#define GCR_GPE_MFP(n) (1 << (n)) /* Bits 0-15: PDn pin function selection */
+# define GCR_GPE_MFP0 (1 << 0)
+# define GCR_GPE_MFP1 (1 << 1)
+# define GCR_GPE_MFP2 (1 << 2)
+# define GCR_GPE_MFP3 (1 << 3)
+# define GCR_GPE_MFP4 (1 << 4)
+# define GCR_GPE_MFP5 (1 << 5)
+#define GCR_GPE_TYPE(n) (1 << ((n)+16)) /* Bits 16-31: Enable Schmitt trigger function */
+# define GCR_GPE_TYPE0 (1 << 0)
+# define GCR_GPE_TYPE1 (1 << 1)
+# define GCR_GPE_TYPE2 (1 << 2)
+# define GCR_GPE_TYPE3 (1 << 3)
+# define GCR_GPE_TYPE4 (1 << 4)
+# define GCR_GPE_TYPE5 (1 << 5)
+
+/* Alternative multiple function pin control register */
+
+#define GCR_ALT_MFP_PB10_S01 (1 << 0) /* Bit 0: Determines PB.10 function */
+#define GCR_ALT_MFP_PB9_S11 (1 << 1) /* Bit 1: Determines PB.9 function */
+#define GCR_ALT_MFP_PA7_S21 (1 << 2) /* Bit 2: Determines PA.7 function */
+#define GCR_ALT_MFP_PB14_S31 (1 << 3) /* Bit 3: Determines PB.14 function */
+#define GCR_ALT_MFP_PB11_PWM4 (1 << 4) /* Bit 4: Determines PB.11 function */
+#define GCR_ALT_MFP_PC0_I2SRCLK (1 << 5) /* Bit 5: Determines PC.0 function */
+#define GCR_ALT_MFP_PC1_I2SBCLK (1 << 6) /* Bit 6: Determines PC.1 function */
+#define GCR_ALT_MFP_PC2_I2SD1 (1 << 7) /* Bit 7: Determines PC.2 function */
+#define GCR_ALT_MFP_PC3_I2SD0 (1 << 8) /* Bit 8: Determines PC.3 function */
+#define GCR_ALT_MFP_PA15_I2SMCLK (1 << 9) /* Bit 9: Determines PA.15 function */
+#define GCR_ALT_MFP_PB12_CLKO (1 << 10) /* Bit 10: Determines PB.12 function */
+#define GCR_ALT_MFP_EBI_EN (1 << 11) /* Bit 11: Determines PA.6, PA.7, PA.10, PA.11,
+ * PB.6, PB.7, PB.12, PB.13, PC.6, PC.7, PC.14,
+ * PC.15 function */
+#define GCR_ALT_MFP_EBI_MCLK_EN (1 << 12) /* Bit 12: Determines PC.8 function */
+#define GCR_ALT_MFP_EBI_NWRL_EN (1 << 13) /* Bit 13: Determines PB.2 function */
+#define GCR_ALT_MFP_EBI_NWRH_WN (1 << 14) /* Bit 14: Determines PB.3 function */
+#define GCR_ALT_MFP_EBI_HB_EN0 (1 << 16) /* Bit 16: Determines PA.5 function */
+#define GCR_ALT_MFP_EBI_HB_EN1 (1 << 17) /* Bit 17: Determines PA.4 function */
+#define GCR_ALT_MFP_EBI_HB_EN2 (1 << 18) /* Bit 18: Determines PA.3 function */
+#define GCR_ALT_MFP_EBI_HB_EN3 (1 << 19) /* Bit 19: Determines PA.2 function */
+#define GCR_ALT_MFP_EBI_HB_EN4 (1 << 20) /* Bit 20: Determines PA.1 function */
+#define GCR_ALT_MFP_EBI_HB_EN5 (1 << 21) /* Bit 21: Determines PA.12 function */
+#define GCR_ALT_MFP_EBI_HB_EN6 (1 << 22) /* Bit 22: Determines PA.13 function */
+#define GCR_ALT_MFP_EBI_HB_EN7 (1 << 23) /* Bit 23: Determines PA.14 function */
+
+/* Register write-protection control register */
+
+ /* Write: */
+#define GCR_REGWRPROT_MASK (0xff) /* Bits 0-7: Register write protection code */
+# define GCR_REGWRPROT_1 (0x59) /* Disable sequence */
+# define GCR_REGWRPROT_2 (0x16)
+# define GCR_REGWRPROT_3 (0x88)
+ /* Read: */
+#define GCR_REGWRPROT_DIS (1 << 0) /* Bit 0: Register write protectino disable index */
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KL_CHIP_KL_GCR_H */
diff --git a/nuttx/arch/arm/src/kl/chip/kl_gpio.h b/nuttx/arch/arm/src/kl/chip/kl_gpio.h
new file mode 100644
index 000000000..8b6da17b6
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/kl_gpio.h
@@ -0,0 +1,556 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_gpio.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ********************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_CHIP_KL_GPIO_H
+#define __ARCH_ARM_SRC_KL_CHIP_KL_GPIO_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+#define KL_GPIO_PORTA 0
+#define KL_GPIO_PORTB 1
+#define KL_GPIO_PORTC 2
+#define KL_GPIO_PORTD 3
+#define KL_GPIO_PORTE 4
+
+#define KL_GPIO_NPORTS 5
+
+/* GPIO control registers */
+
+#define KL_GPIO_CTRL_OFFSET(n) (0x0000 + ((n) << 6))
+#define KL_GPIOA_CTRL_OFFSET (0x0000 + ((KL_GPIO_PORTA) << 6))
+#define KL_GPIOB_CTRL_OFFSET (0x0000 + ((KL_GPIO_PORTB) << 6))
+#define KL_GPIOC_CTRL_OFFSET (0x0000 + ((KL_GPIO_PORTC) << 6))
+#define KL_GPIOD_CTRL_OFFSET (0x0000 + ((KL_GPIO_PORTD) << 6))
+#define KL_GPIOE_CTRL_OFFSET (0x0000 + ((KL_GPIO_PORTE) << 6))
+
+#define KL_GPIO_PMD_OFFSET 0x0000 /* GPIO port pin I/O mode control */
+#define KL_GPIO_OFFD_OFFSET 0x0004 /* GPIO port pin digital input path disable control */
+#define KL_GPIO_DOUT_OFFSET 0x0008 /* GPIO port data output value */
+#define KL_GPIO_DMASK_OFFSET 0x000c /* GPIO port data output write mask */
+#define KL_GPIO_PIN_OFFSET 0x0010 /* GPIO port pin value */
+#define KL_GPIO_DBEN_OFFSET 0x0014 /* GPIO port de-bounce enable */
+#define KL_GPIO_IMD_OFFSET 0x0018 /* GPIO port interrupt mode control */
+#define KL_GPIO_IEN_OFFSET 0x001c /* GPIO port interrupt enable */
+#define KL_GPIO_ISRC_OFFSET 0x0020 /* GPIO port interrupt source flag */
+
+/* GPIO port A control registers */
+
+#define KL_GPIOA_PMD_OFFSET (KL_GPIOA_CTRL_OFFSET+KL_GPIO_PMD_OFFSET)
+#define KL_GPIOA_OFFD_OFFSET (KL_GPIOA_CTRL_OFFSET+KL_GPIO_OFFD_OFFSET)
+#define KL_GPIOA_DOUT_OFFSET (KL_GPIOA_CTRL_OFFSET+KL_GPIO_DOUT_OFFSET)
+#define KL_GPIOA_DMASK_OFFSET (KL_GPIOA_CTRL_OFFSET+KL_GPIO_DMASK_OFFSET)
+#define KL_GPIOA_PIN_OFFSET (KL_GPIOA_CTRL_OFFSET+KL_GPIO_PIN_OFFSET)
+#define KL_GPIOA_DBEN_OFFSET (KL_GPIOA_CTRL_OFFSET+KL_GPIO_DBEN_OFFSET)
+#define KL_GPIOA_IMD_OFFSET (KL_GPIOA_CTRL_OFFSET+KL_GPIO_IMD_OFFSET)
+#define KL_GPIOA_IEN_OFFSET (KL_GPIOA_CTRL_OFFSET+KL_GPIO_IEN_OFFSET)
+#define KL_GPIOA_ISRC_OFFSET (KL_GPIOA_CTRL_OFFSET+KL_GPIO_ISRC_OFFSET)
+
+/* GPIO port B control registers */
+
+#define KL_GPIOB_PMD_OFFSET (KL_GPIOB_CTRL_OFFSET+KL_GPIO_PMD_OFFSET)
+#define KL_GPIOB_OFFD_OFFSET (KL_GPIOB_CTRL_OFFSET+KL_GPIO_OFFD_OFFSET)
+#define KL_GPIOB_DOUT_OFFSET (KL_GPIOB_CTRL_OFFSET+KL_GPIO_DOUT_OFFSET)
+#define KL_GPIOB_DMASK_OFFSET (KL_GPIOB_CTRL_OFFSET+KL_GPIO_DMASK_OFFSET)
+#define KL_GPIOB_PIN_OFFSET (KL_GPIOB_CTRL_OFFSET+KL_GPIO_PIN_OFFSET)
+#define KL_GPIOB_DBEN_OFFSET (KL_GPIOB_CTRL_OFFSET+KL_GPIO_DBEN_OFFSET)
+#define KL_GPIOB_IMD_OFFSET (KL_GPIOB_CTRL_OFFSET+KL_GPIO_IMD_OFFSET)
+#define KL_GPIOB_IEN_OFFSET (KL_GPIOB_CTRL_OFFSET+KL_GPIO_IEN_OFFSET)
+#define KL_GPIOB_ISRC_OFFSET (KL_GPIOB_CTRL_OFFSET+KL_GPIO_ISRC_OFFSET)
+
+/* GPIO port C control registers */
+
+#define KL_GPIOC_PMD_OFFSET (KL_GPIOC_CTRL_OFFSET+KL_GPIO_PMD_OFFSET)
+#define KL_GPIOC_OFFD_OFFSET (KL_GPIOC_CTRL_OFFSET+KL_GPIO_OFFD_OFFSET)
+#define KL_GPIOC_DOUT_OFFSET (KL_GPIOC_CTRL_OFFSET+KL_GPIO_DOUT_OFFSET)
+#define KL_GPIOC_DMASK_OFFSET (KL_GPIOC_CTRL_OFFSET+KL_GPIO_DMASK_OFFSET)
+#define KL_GPIOC_PIN_OFFSET (KL_GPIOC_CTRL_OFFSET+KL_GPIO_PIN_OFFSET)
+#define KL_GPIOC_DBEN_OFFSET (KL_GPIOC_CTRL_OFFSET+KL_GPIO_DBEN_OFFSET)
+#define KL_GPIOC_IMD_OFFSET (KL_GPIOC_CTRL_OFFSET+KL_GPIO_IMD_OFFSET)
+#define KL_GPIOC_IEN_OFFSET (KL_GPIOC_CTRL_OFFSET+KL_GPIO_IEN_OFFSET)
+#define KL_GPIOC_ISRC_OFFSET (KL_GPIOC_CTRL_OFFSET+KL_GPIO_ISRC_OFFSET)
+
+/* GPIO port D control registers */
+
+#define KL_GPIOD_PMD_OFFSET (KL_GPIOD_CTRL_OFFSET+KL_GPIO_PMD_OFFSET)
+#define KL_GPIOD_OFFD_OFFSET (KL_GPIOD_CTRL_OFFSET+KL_GPIO_OFFD_OFFSET)
+#define KL_GPIOD_DOUT_OFFSET (KL_GPIOD_CTRL_OFFSET+KL_GPIO_DOUT_OFFSET)
+#define KL_GPIOD_DMASK_OFFSET (KL_GPIOD_CTRL_OFFSET+KL_GPIO_DMASK_OFFSET)
+#define KL_GPIOD_PIN_OFFSET (KL_GPIOD_CTRL_OFFSET+KL_GPIO_PIN_OFFSET)
+#define KL_GPIOD_DBEN_OFFSET (KL_GPIOD_CTRL_OFFSET+KL_GPIO_DBEN_OFFSET)
+#define KL_GPIOD_IMD_OFFSET (KL_GPIOD_CTRL_OFFSET+KL_GPIO_IMD_OFFSET)
+#define KL_GPIOD_IEN_OFFSET (KL_GPIOD_CTRL_OFFSET+KL_GPIO_IEN_OFFSET)
+#define KL_GPIOD_ISRC_OFFSET (KL_GPIOD_CTRL_OFFSET+KL_GPIO_ISRC_OFFSET)
+
+/* GPIO port E control registers */
+
+#define KL_GPIOE_PMD_OFFSET (KL_GPIOE_CTRL_OFFSET+KL_GPIO_PMD_OFFSET)
+#define KL_GPIOE_OFFD_OFFSET (KL_GPIOE_CTRL_OFFSET+KL_GPIO_OFFD_OFFSET)
+#define KL_GPIOE_DOUT_OFFSET (KL_GPIOE_CTRL_OFFSET+KL_GPIO_DOUT_OFFSET)
+#define KL_GPIOE_DMASK_OFFSET (KL_GPIOE_CTRL_OFFSET+KL_GPIO_DMASK_OFFSET)
+#define KL_GPIOE_PIN_OFFSET (KL_GPIOE_CTRL_OFFSET+KL_GPIO_PIN_OFFSET)
+#define KL_GPIOE_DBEN_OFFSET (KL_GPIOE_CTRL_OFFSET+KL_GPIO_DBEN_OFFSET)
+#define KL_GPIOE_IMD_OFFSET (KL_GPIOE_CTRL_OFFSET+KL_GPIO_IMD_OFFSET)
+#define KL_GPIOE_IEN_OFFSET (KL_GPIOE_CTRL_OFFSET+KL_GPIO_IEN_OFFSET)
+#define KL_GPIOE_ISRC_OFFSET (KL_GPIOE_CTRL_OFFSET+KL_GPIO_ISRC_OFFSET)
+
+/* Debounce control registers */
+
+#define KL_GPIO_DBNCECON_OFFSEt 0x0180 /* De-bounce cycle control register */
+
+/* GPIO port data I/O register offsets */
+
+#define KL_PORT_DATAIO_OFFSET(p) (0x0200 + ((p)<< 6))
+# define KL_PORTA_DATAIO_OFFSET (0x0200 + ((KL_GPIO_PORTA) << 6))
+# define KL_PORTB_DATAIO_OFFSET (0x0200 + ((KL_GPIO_PORTB) << 6))
+# define KL_PORTC_DATAIO_OFFSET (0x0200 + ((KL_GPIO_PORTC) << 6))
+# define KL_PORTD_DATAIO_OFFSET (0x0200 + ((KL_GPIO_PORTD) << 6))
+# define KL_PORTE_DATAIO_OFFSET (0x0200 + ((KL_GPIO_PORTE) << 6))
+
+/* GPIO port pin data I/O register offsets */
+
+#define KL_PORT_PIN_OFFSET(n) ((n) << 2)
+# define KL_PORT_PIN0_OFFSET (0 << 2)
+# define KL_PORT_PIN1_OFFSET (1 << 2)
+# define KL_PORT_PIN2_OFFSET (2 << 2)
+# define KL_PORT_PIN3_OFFSET (3 << 2)
+# define KL_PORT_PIN4_OFFSET (4 << 2)
+# define KL_PORT_PIN5_OFFSET (5 << 2)
+# define KL_PORT_PIN6_OFFSET (16 << 2)
+# define KL_PORT_PIN7_OFFSET (17 << 2)
+# define KL_PORT_PIN8_OFFSET (18 << 2)
+# define KL_PORT_PIN9_OFFSET (19 << 2)
+# define KL_PORT_PIN10_OFFSET (10 << 2)
+# define KL_PORT_PIN11_OFFSET (11 << 2)
+# define KL_PORT_PIN12_OFFSET (12 << 2)
+# define KL_PORT_PIN13_OFFSET (13 << 2)
+# define KL_PORT_PIN14_OFFSET (14 << 2)
+# define KL_PORT_PIN15_OFFSET (15 << 2)
+
+#define KL_PORT_PDIO_OFFSET(p,n) (KL_PORT_DATAIO_OFFSET(p)+KL_PORT_PIN_OFFSET(n))
+
+/* GPIO PA Pin Data Input/Output */
+
+#define KL_PORTA_PDIO_OFFSET(n) (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN_OFFSET(n))
+# define KL_PA1_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PA2_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PA3_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PA4_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PA5_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PA6_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PA7_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PA8_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PA9_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PA10_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PA11_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PA12_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PA13_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PA14_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PA15_PDIO_OFFSET (KL_PORTA_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+
+/* GPIO PB Pin Data Input/Output */
+
+#define KL_PORTB_PDIO_OFFSET(n) (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN_OFFSET(n))
+# define KL_PB1_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PB2_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PB3_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PB4_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PB5_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PB6_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PB7_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PB8_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PB9_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PB10_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PB11_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PB12_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PB13_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PB14_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PB15_PDIO_OFFSET (KL_PORTB_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+
+/* GPIO PC Pin Data Input/Output */
+
+#define KL_PORTC_PDIO_OFFSET(n) (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN_OFFSET(n))
+# define KL_PC1_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PC2_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PC3_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PC4_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PC5_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PC6_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PC7_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PC8_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PC9_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PC10_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PC11_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PC12_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PC13_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PC14_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PC15_PDIO_OFFSET (KL_PORTC_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+
+/* GPIO PD Pin Data Input/Output */
+
+#define KL_PORTD_PDIO_OFFSET(n) (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN_OFFSET(n))
+# define KL_PD1_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PD2_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PD3_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PD4_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PD5_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PD6_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PD7_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PD8_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PD9_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PD10_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PD11_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PD12_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PD13_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PD14_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+# define KL_PD15_PDIO_OFFSET (KL_PORTD_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+
+/* GPIO PE Pin Data Input/Output */
+
+#define KL_PORTE_PDIO_OFFSET(n) (KL_PORTE_DATAIO_OFFSET+KL_PORT_PIN_OFFSET(n))
+# define KL_PE5_PDIO_OFFSET (KL_PORTE_DATAIO_OFFSET+KL_PORT_PIN0_OFFSET)
+
+/* Register addresses ***********************************************************************/
+
+/* GPIO control registers */
+
+#define KL_GPIO_CTRL_BASE(n) (KL_GPIO_BASEOLD+KL_GPIO_CTRL_OFFSET(n))
+#define KL_GPIOA_CTRL_BASE (KL_GPIO_BASEOLD+KL_GPIOA_CTRL_OFFSET)
+#define KL_GPIOB_CTRL_BASE (KL_GPIO_BASEOLD+KL_GPIOB_CTRL_OFFSET)
+#define KL_GPIOC_CTRL_BASE (KL_GPIO_BASEOLD+KL_GPIOC_CTRL_OFFSET)
+#define KL_GPIOD_CTRL_BASE (KL_GPIO_BASEOLD+KL_GPIOD_CTRL_OFFSET)
+#define KL_GPIOE_CTRL_BASE (KL_GPIO_BASEOLD+KL_GPIOE_CTRL_OFFSET)
+
+/* GPIO port A control registers */
+
+#define KL_GPIOA_PMD (KL_GPIO_BASEOLD+KL_GPIOA_PMD_OFFSET)
+#define KL_GPIOA_OFFD (KL_GPIO_BASEOLD+KL_GPIOA_OFFD_OFFSET)
+#define KL_GPIOA_DOUT (KL_GPIO_BASEOLD+KL_GPIOA_DOUT_OFFSET)
+#define KL_GPIOA_DMASK (KL_GPIO_BASEOLD+KL_GPIOA_DMASK_OFFSET)
+#define KL_GPIOA_PIN (KL_GPIO_BASEOLD+KL_GPIOA_PIN_OFFSET)
+#define KL_GPIOA_DBEN (KL_GPIO_BASEOLD+KL_GPIOA_DBEN_OFFSET)
+#define KL_GPIOA_IMD (KL_GPIO_BASEOLD+KL_GPIOA_IMD_OFFSET)
+#define KL_GPIOA_IEN (KL_GPIO_BASEOLD+KL_GPIOA_IEN_OFFSET)
+#define KL_GPIOA_ISRC (KL_GPIO_BASEOLD+KL_GPIOA_ISRC_OFFSET)
+
+/* GPIO port B control registers */
+
+#define KL_GPIOB_PMD (KL_GPIO_BASEOLD+KL_GPIOB_PMD_OFFSET)
+#define KL_GPIOB_OFFD (KL_GPIO_BASEOLD+KL_GPIOB_OFFD_OFFSET)
+#define KL_GPIOB_DOUT (KL_GPIO_BASEOLD+KL_GPIOB_DOUT_OFFSET)
+#define KL_GPIOB_DMASK (KL_GPIO_BASEOLD+KL_GPIOB_DMASK_OFFSET)
+#define KL_GPIOB_PIN (KL_GPIO_BASEOLD+KL_GPIOB_PIN_OFFSET)
+#define KL_GPIOB_DBEN (KL_GPIO_BASEOLD+KL_GPIOB_DBEN_OFFSET)
+#define KL_GPIOB_IMD (KL_GPIO_BASEOLD+KL_GPIOB_IMD_OFFSET)
+#define KL_GPIOB_IEN (KL_GPIO_BASEOLD+KL_GPIOB_IEN_OFFSET)
+#define KL_GPIOB_ISRC (KL_GPIO_BASEOLD+KL_GPIOB_ISRC_OFFSET)
+
+/* GPIO port C control registers */
+
+#define KL_GPIOC_PMD (KL_GPIO_BASEOLD+KL_GPIOC_PMD_OFFSET)
+#define KL_GPIOC_OFFD (KL_GPIO_BASEOLD+KL_GPIOC_OFFD_OFFSET)
+#define KL_GPIOC_DOUT (KL_GPIO_BASEOLD+KL_GPIOC_DOUT_OFFSET)
+#define KL_GPIOC_DMASK (KL_GPIO_BASEOLD+KL_GPIOC_DMASK_OFFSET)
+#define KL_GPIOC_PIN (KL_GPIO_BASEOLD+KL_GPIOC_PIN_OFFSET)
+#define KL_GPIOC_DBEN (KL_GPIO_BASEOLD+KL_GPIOC_DBEN_OFFSET)
+#define KL_GPIOC_IMD (KL_GPIO_BASEOLD+KL_GPIOC_IMD_OFFSET)
+#define KL_GPIOC_IEN (KL_GPIO_BASEOLD+KL_GPIOC_IEN_OFFSET)
+#define KL_GPIOC_ISRC (KL_GPIO_BASEOLD+KL_GPIOC_ISRC_OFFSET)
+
+/* GPIO port D control registers */
+
+#define KL_GPIOD_PMD (KL_GPIO_BASEOLD+KL_GPIOD_PMD_OFFSET)
+#define KL_GPIOD_OFFD (KL_GPIO_BASEOLD+KL_GPIOD_OFFD_OFFSET)
+#define KL_GPIOD_DOUT (KL_GPIO_BASEOLD+KL_GPIOD_DOUT_OFFSET)
+#define KL_GPIOD_DMASK (KL_GPIO_BASEOLD+KL_GPIOD_DMASK_OFFSET)
+#define KL_GPIOD_PIN (KL_GPIO_BASEOLD+KL_GPIOD_PIN_OFFSET)
+#define KL_GPIOD_DBEN (KL_GPIO_BASEOLD+KL_GPIOD_DBEN_OFFSET)
+#define KL_GPIOD_IMD (KL_GPIO_BASEOLD+KL_GPIOD_IMD_OFFSET)
+#define KL_GPIOD_IEN (KL_GPIO_BASEOLD+KL_GPIOD_IEN_OFFSET)
+#define KL_GPIOD_ISRC (KL_GPIO_BASEOLD+KL_GPIOD_ISRC_OFFSET)
+
+/* GPIO port E control registers */
+
+#define KL_GPIOE_PMD (KL_GPIO_BASEOLD+KL_GPIOE_PMD_OFFSET)
+#define KL_GPIOE_OFFD (KL_GPIO_BASEOLD+KL_GPIOE_OFFD_OFFSET)
+#define KL_GPIOE_DOUT (KL_GPIO_BASEOLD+KL_GPIOE_DOUT_OFFSET)
+#define KL_GPIOE_DMASK (KL_GPIO_BASEOLD+KL_GPIOE_DMASK_OFFSET)
+#define KL_GPIOE_PIN (KL_GPIO_BASEOLD+KL_GPIOE_PIN_OFFSET)
+#define KL_GPIOE_DBEN (KL_GPIO_BASEOLD+KL_GPIOE_DBEN_OFFSET)
+#define KL_GPIOE_IMD (KL_GPIO_BASEOLD+KL_GPIOE_IMD_OFFSET)
+#define KL_GPIOE_IEN (KL_GPIO_BASEOLD+KL_GPIOE_IEN_OFFSET)
+#define KL_GPIOE_ISRC (KL_GPIO_BASEOLD+KL_GPIOE_ISRC_OFFSET)
+
+/* Debounce control registers */
+
+#define KL_GPIO_DBNCECON (KL_GPIO_BASEOLD+KL_GPIO_DBNCECON_OFFSET)
+
+/* GPIO port data I/O register offsets */
+
+#define KL_PORT_DATAIO_BASE(p) (KL_GPIO_BASEOLD+KL_PORT_DATAIO_OFFSET(p))
+# define KL_PORTA_DATAIO_BASE (KL_GPIO_BASEOLD+KL_PORTA_DATAIO_OFFSET)
+# define KL_PORTB_DATAIO_BASE (KL_GPIO_BASEOLD+KL_PORTB_DATAIO_OFFSET)
+# define KL_PORTC_DATAIO_BASE (KL_GPIO_BASEOLD+KL_PORTC_DATAIO_OFFSET)
+# define KL_PORTD_DATAIO_BASE (KL_GPIO_BASEOLD+KL_PORTD_DATAIO_OFFSET)
+# define KL_PORTE_DATAIO_BASE (KL_GPIO_BASEOLD+KL_PORTE_DATAIO_OFFSET)
+
+#define KL_PORT_PDIO(p,n) (KL_GPIO_BASEOLD+KL_PORT_PDIO_OFFSET(p,n))
+
+/* GPIO PA Pin Data Input/Output */
+
+#define KL_PORTA_PDIO(n) (KL_GPIO_BASEOLD+KL_PORTA_PDIO_OFFSET(n))
+# define KL_PA1_PDIO (KL_GPIO_BASEOLD+KL_PA1_PDIO_OFFSET)
+# define KL_PA2_PDIO (KL_GPIO_BASEOLD+KL_PA2_PDIO_OFFSET)
+# define KL_PA3_PDIO (KL_GPIO_BASEOLD+KL_PA3_PDIO_OFFSET)
+# define KL_PA4_PDIO (KL_GPIO_BASEOLD+KL_PA4_PDIO_OFFSET)
+# define KL_PA5_PDIO (KL_GPIO_BASEOLD+KL_PA5_PDIO_OFFSET)
+# define KL_PA6_PDIO (KL_GPIO_BASEOLD+KL_PA6_PDIO_OFFSET)
+# define KL_PA7_PDIO (KL_GPIO_BASEOLD+KL_PA7_PDIO_OFFSET)
+# define KL_PA8_PDIO (KL_GPIO_BASEOLD+KL_PA8_PDIO_OFFSET)
+# define KL_PA9_PDIO (KL_GPIO_BASEOLD+KL_PA9_PDIO_OFFSET)
+# define KL_PA10_PDIO (KL_GPIO_BASEOLD+KL_PA10_PDIO_OFFSET)
+# define KL_PA11_PDIO (KL_GPIO_BASEOLD+KL_PA11_PDIO_OFFSET)
+# define KL_PA12_PDIO (KL_GPIO_BASEOLD+KL_PA12_PDIO_OFFSET)
+# define KL_PA13_PDIO (KL_GPIO_BASEOLD+KL_PA13_PDIO_OFFSET)
+# define KL_PA14_PDIO (KL_GPIO_BASEOLD+KL_PA14_PDIO_OFFSET)
+# define KL_PA15_PDIO (KL_GPIO_BASEOLD+KL_PA15_PDIO_OFFSET)
+
+/* GPIO PB Pin Data Input/Output */
+
+#define KL_PORTB_PDIO(n) (KL_GPIO_BASEOLD+KL_PORTB_PDIO_OFFSET(n))
+# define KL_PB1_PDIO (KL_GPIO_BASEOLD+KL_PB1_PDIO_OFFSET)
+# define KL_PB2_PDIO (KL_GPIO_BASEOLD+KL_PB2_PDIO_OFFSET)
+# define KL_PB3_PDIO (KL_GPIO_BASEOLD+KL_PB3_PDIO_OFFSET)
+# define KL_PB4_PDIO (KL_GPIO_BASEOLD+KL_PB4_PDIO_OFFSET)
+# define KL_PB5_PDIO (KL_GPIO_BASEOLD+KL_PB5_PDIO_OFFSET)
+# define KL_PB6_PDIO (KL_GPIO_BASEOLD+KL_PB6_PDIO_OFFSET)
+# define KL_PB7_PDIO (KL_GPIO_BASEOLD+KL_PB7_PDIO_OFFSET)
+# define KL_PB8_PDIO (KL_GPIO_BASEOLD+KL_PB8_PDIO_OFFSET)
+# define KL_PB9_PDIO (KL_GPIO_BASEOLD+KL_PB9_PDIO_OFFSET)
+# define KL_PB10_PDIO (KL_GPIO_BASEOLD+KL_PB10_PDIO_OFFSET)
+# define KL_PB11_PDIO (KL_GPIO_BASEOLD+KL_PB11_PDIO_OFFSET)
+# define KL_PB12_PDIO (KL_GPIO_BASEOLD+KL_PB12_PDIO_OFFSET)
+# define KL_PB13_PDIO (KL_GPIO_BASEOLD+KL_PB13_PDIO_OFFSET)
+# define KL_PB14_PDIO (KL_GPIO_BASEOLD+KL_PB14_PDIO_OFFSET)
+# define KL_PB15_PDIO (KL_GPIO_BASEOLD+KL_PB15_PDIO_OFFSET)
+
+/* GPIO PC Pin Data Input/Output */
+
+#define KL_PORTC_PDIO(n) (KL_GPIO_BASEOLD+KL_PORTC_PDIO_OFFSET(n))
+# define KL_PC1_PDIO (KL_GPIO_BASEOLD+KL_PC1_PDIO_OFFSET)
+# define KL_PC2_PDIO (KL_GPIO_BASEOLD+KL_PC2_PDIO_OFFSET)
+# define KL_PC3_PDIO (KL_GPIO_BASEOLD+KL_PC3_PDIO_OFFSET)
+# define KL_PC4_PDIO (KL_GPIO_BASEOLD+KL_PC4_PDIO_OFFSET)
+# define KL_PC5_PDIO (KL_GPIO_BASEOLD+KL_PC5_PDIO_OFFSET)
+# define KL_PC6_PDIO (KL_GPIO_BASEOLD+KL_PC6_PDIO_OFFSET)
+# define KL_PC7_PDIO (KL_GPIO_BASEOLD+KL_PC7_PDIO_OFFSET)
+# define KL_PC8_PDIO (KL_GPIO_BASEOLD+KL_PC8_PDIO_OFFSET)
+# define KL_PC9_PDIO (KL_GPIO_BASEOLD+KL_PC9_PDIO_OFFSET)
+# define KL_PC10_PDIO (KL_GPIO_BASEOLD+KL_PC10_PDIO_OFFSET)
+# define KL_PC11_PDIO (KL_GPIO_BASEOLD+KL_PC11_PDIO_OFFSET)
+# define KL_PC12_PDIO (KL_GPIO_BASEOLD+KL_PC12_PDIO_OFFSET)
+# define KL_PC13_PDIO (KL_GPIO_BASEOLD+KL_PC13_PDIO_OFFSET)
+# define KL_PC14_PDIO (KL_GPIO_BASEOLD+KL_PC14_PDIO_OFFSET)
+# define KL_PC15_PDIO (KL_GPIO_BASEOLD+KL_PC15_PDIO_OFFSET)
+
+/* GPIO PD Pin Data Input/Output */
+
+#define KL_PORTD_PDIO(n) (KL_GPIO_BASEOLD+KL_PORTD_PDIO_OFFSET(n))
+# define KL_PD1_PDIO (KL_GPIO_BASEOLD+KL_PD1_PDIO_OFFSET)
+# define KL_PD2_PDIO (KL_GPIO_BASEOLD+KL_PD2_PDIO_OFFSET)
+# define KL_PD3_PDIO (KL_GPIO_BASEOLD+KL_PD3_PDIO_OFFSET)
+# define KL_PD4_PDIO (KL_GPIO_BASEOLD+KL_PD4_PDIO_OFFSET)
+# define KL_PD5_PDIO (KL_GPIO_BASEOLD+KL_PD5_PDIO_OFFSET)
+# define KL_PD6_PDIO (KL_GPIO_BASEOLD+KL_PD6_PDIO_OFFSET)
+# define KL_PD7_PDIO (KL_GPIO_BASEOLD+KL_PD7_PDIO_OFFSET)
+# define KL_PD8_PDIO (KL_GPIO_BASEOLD+KL_PD8_PDIO_OFFSET)
+# define KL_PD9_PDIO (KL_GPIO_BASEOLD+KL_PD9_PDIO_OFFSET)
+# define KL_PD10_PDIO (KL_GPIO_BASEOLD+KL_PD10_PDIO_OFFSET)
+# define KL_PD11_PDIO (KL_GPIO_BASEOLD+KL_PD11_PDIO_OFFSET)
+# define KL_PD12_PDIO (KL_GPIO_BASEOLD+KL_PD12_PDIO_OFFSET)
+# define KL_PD13_PDIO (KL_GPIO_BASEOLD+KL_PD13_PDIO_OFFSET)
+# define KL_PD14_PDIO (KL_GPIO_BASEOLD+KL_PD14_PDIO_OFFSET)
+# define KL_PD15_PDIO (KL_GPIO_BASEOLD+KL_PD15_PDIO_OFFSET)
+
+/* GPIO PE Pin Data Input/Output */
+
+#define KL_PORTE_PDIO(n) (KL_GPIO_BASEOLD+KL_PORTE_PDIO_OFFSET(n))
+# define KL_PE5_PDIO (KL_GPIO_BASEOLD+KL_PE5_PDIO_OFFSET)
+
+/* Register bit-field definitions ***********************************************************/
+
+/* GPIO port pin I/O mode control */
+
+#define GPIO_PMD_INPUT 0 /* Input */
+#define GPIO_PMD_OUTPUT 1 /* Push-pull output */
+#define GPIO_PMD_OPENDRAIN 2 /* Open drain output */
+#define GPIO_PMD_BIDI 3 /* Quasi bi-directional */
+
+#define GPIO_PMD_SHIFT(n) ((n) << 1) /* Bits 2n-2n+1: GPIOx Pin[n] mode control */
+#define GPIO_PMD_MASK(n) (3 << GPIO_PMD_SHIFT(n))
+# define GPIO_PMD(n,v) ((v) << GPIO_PMD_SHIFT(n))
+
+#define GPIO_PMD0_SHIFT (0) /* Bits 0-1: GPIOx Pin0 mode control */
+#define GPIO_PMD0_MASK (3 << GPIO_PMD0_SHIFT)
+# define GPIO_PMD0(v) ((v) << GPIO_PMD0_SHIFT)
+#define GPIO_PMD1_SHIFT (2) /* Bits 2-3: GPIOx Pin1 mode control */
+#define GPIO_PMD1_MASK (3 << GPIO_PMD1_SHIFT)
+# define GPIO_PMD1(v) ((v) << GPIO_PMD1_SHIFT)
+#define GPIO_PMD2_SHIFT (4) /* Bits 4-5: GPIOx Pin2 mode control */
+#define GPIO_PMD2_MASK (3 << GPIO_PMD2_SHIFT)
+# define GPIO_PMD2(v) ((v) << GPIO_PMD2_SHIFT)
+#define GPIO_PMD3_SHIFT (6) /* Bits 6-7: GPIOx Pin3 mode control */
+#define GPIO_PMD3_MASK (3 << GPIO_PMD3_SHIFT)
+# define GPIO_PMD3(v) ((v) << GPIO_PMD3_SHIFT)
+#define GPIO_PMD4_SHIFT (8) /* Bits 8-9: GPIOx Pin4 mode control */
+#define GPIO_PMD4_MASK (3 << GPIO_PMD4_SHIFT)
+# define GPIO_PMD4(v) ((v) << GPIO_PMD4_SHIFT)
+#define GPIO_PMD5_SHIFT (10) /* Bits 10-11: GPIOx Pin5 mode control */
+#define GPIO_PMD5_MASK (3 << GPIO_PMD5_SHIFT)
+# define GPIO_PMD5(v) ((v) << GPIO_PMD5_SHIFT)
+#define GPIO_PMD6_SHIFT (12) /* Bits 12-13: GPIOx Pin6 mode control */
+#define GPIO_PMD6_MASK (3 << GPIO_PMD6_SHIFT)
+# define GPIO_PMD6(v) ((v) << GPIO_PMD6_SHIFT)
+#define GPIO_PMD7_SHIFT (14) /* Bits 14-15: GPIOx Pin7 mode control */
+#define GPIO_PMD7_MASK (3 << GPIO_PMD7_SHIFT)
+# define GPIO_PMD7(v) ((v) << GPIO_PMD7_SHIFT)
+#define GPIO_PMD8_SHIFT (16) /* Bits 16-17: GPIOx Pin8 mode control */
+#define GPIO_PMD8_MASK (3 << GPIO_PMD8_SHIFT)
+# define GPIO_PMD8(v) ((v) << GPIO_PMD8_SHIFT)
+#define GPIO_PMD9_SHIFT (18) /* Bits 18-19: GPIOx Pin9 mode control */
+#define GPIO_PMD9_MASK (3 << GPIO_PMD9_SHIFT)
+# define GPIO_PMD9(v) ((v) << GPIO_PMD9_SHIFT)
+#define GPIO_PMD10_SHIFT (20) /* Bits 20-21: GPIOx Pin0 mode control */
+#define GPIO_PMD10_MASK (3 << GPIO_PMD10_SHIFT)
+# define GPIO_PMD10(v) ((v) << GPIO_PMD10_SHIFT)
+#define GPIO_PMD11_SHIFT (22) /* Bits 22-23: GPIOx Pin1 mode control */
+#define GPIO_PMD11_MASK (3 << GPIO_PMD11_SHIFT)
+# define GPIO_PMD11(v) ((v) << GPIO_PMD11_SHIFT)
+#define GPIO_PMD12_SHIFT (24) /* Bits 24-25: GPIOx Pin2 mode control */
+#define GPIO_PMD12_MASK (3 << GPIO_PMD12_SHIFT)
+# define GPIO_PMD12(v) ((v) << GPIO_PMD12_SHIFT)
+#define GPIO_PMD13_SHIFT (26) /* Bits 26-27: GPIOx Pin3 mode control */
+#define GPIO_PMD13_MASK (3 << GPIO_PMD13_SHIFT)
+# define GPIO_PMD13(v) ((v) << GPIO_PMD13_SHIFT)
+#define GPIO_PMD14_SHIFT (28) /* Bits 28-29: GPIOx Pin4 mode control */
+#define GPIO_PMD14_MASK (3 << GPIO_PMD14_SHIFT)
+# define GPIO_PMD14(v) ((v) << GPIO_PMD14_SHIFT)
+#define GPIO_PMD15_SHIFT (30) /* Bits 30-31: GPIOx Pin5 mode control */
+#define GPIO_PMD15_MASK (3 << GPIO_PMD15_SHIFT)
+# define GPIO_PMD15(v) ((v) << GPIO_PMD15_SHIFT)
+
+/* GPIO port pin digital input path disable control */
+
+#define GPIO_OFFD(n) (1 << (n)) /* Bit n: GPIOx Pin[n] digital input path disable control */
+
+/* GPIO port data output value */
+
+#define GPIO_DOUT(n) (1 << (n)) /* Bit n: GPIOx Pin[n] output value */
+
+/* GPIO port data output write mask */
+
+#define GPIO_DMASK(n) (1 << (n)) /* Bit n: GPIOx Pin[n] data output write mask */
+
+/* GPIO port pin value */
+
+#define GPIO_PIN(n) (1 << (n)) /* Bit n: GPIOx Pin[n] pin value */
+
+/* GPIO port de-bounce enable */
+
+#define GPIO_DBEN(n) (1 << (n)) /* Bit n: GPIOx Pin[n] input signal de-bounce enable */
+
+/* GPIO port interrupt mode control */
+
+#define GPIO_IMD(n) (1 << (n)) /* Bit n: GPIOx Pin[n] edge/level detection interrupt control */
+
+/* GPIO port interrupt enable */
+
+#define GPIO_IF_EN(n) (1 << (n)) /* Bit n: GPIOx Pin[n] interrupt enable low/falling */
+#define GPIO_IR_EN(n) (1 << ((n)+16)) /* Bit n: GPIOx Pin[n] interrupt enable high/rising */
+
+/* GPIO port interrupt source flag */
+
+#define GPIO_ISRC(n) (1 << (n)) /* Bit n: GPIOx Pin[n] interrupt source flag */
+
+/* De-bounce cycle control register */
+
+#define GPIO_DBNCECON_DBCLKSEL_SHIFT (0) /* Bits 0-3: De-bounce cycling count selection */
+#define GPIO_DBNCECON_DBCLKSEL_MASK (15 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_1 (0 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_2 (1 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_4 (2 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_8 (3 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_16 (4 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_32 (5 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_64 (6 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_128 (7 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_256 (8 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_512 (9 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_1024 (10 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_2048 (11 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_4096 (12 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_8102 (13 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_16384 (14 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_32768 (15 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+#define GPIO_DBNCECON_DBCLKSRC (1 << 4) /* Bit 4: De-bounce counter clock source selection */
+#define GPIO_DBNCECON_ICLK_ON (1 << 5) /* Bit 5: Interrupt clock on mode */
+
+/* GPIO port data I/O registers */
+
+#define PORT_MASK (1) /* Bit 0: GPIOx Pin[n] data I/O */
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KL_CHIP_KL_GPIO_H */
diff --git a/nuttx/arch/arm/src/kl/chip/kl_internal.h b/nuttx/arch/arm/src/kl/chip/kl_internal.h
new file mode 100644
index 000000000..3fb16afc6
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/kl_internal.h
@@ -0,0 +1,841 @@
+/************************************************************************************
+ * arch/arm/src/kl/kl_internal.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_KL_INTERNAL_H
+#define __ARCH_ARM_SRC_KL_KL_INTERNAL_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+
+#include <nuttx/irq.h>
+
+#include "up_internal.h"
+#include "kl_config.h"
+#include "chip.h"
+#include "kl_port.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Configuration ********************************************************************/
+
+/* Bit-encoded input to kl_pinconfig() *****************************************/
+/* General form (32-bits, only 22 bits are unused in the encoding):
+ *
+ * oooo mmmv iiii ifd- ---- -ppp ---b bbbb
+ */
+
+/* Bits 25-31: 7 bits are used to encode the basic pin configuration:
+ *
+ * oooo mmm- ---- ---- ---- ---- ---- ----
+ * oooommm:
+ * | `--- mmm: mode
+ * `------- oooo: options (may be combined)
+ */
+
+#define _PIN_MODE_SHIFT (25) /* Bits 25-27: Pin mode */
+#define _PIN_MODE_MASK (7 << _PIN_MODE_SHIFT)
+#define _PIN_OPTIONS_SHIFT (28) /* Bits 28-31: Pin mode options */
+#define _PIN_OPTIONS_MASK (15 << _PIN_OPTIONS_SHIFT)
+
+/* Port Modes */
+
+#define _PIN_MODE_ANALOG (0 << _PIN_MODE_SHIFT) /* 000 Pin Disabled (Analog) */
+#define _PIN_MODE_GPIO (1 << _PIN_MODE_SHIFT) /* 001 Alternative 1 (GPIO) */
+#define _PIN_MODE_ALT2 (2 << _PIN_MODE_SHIFT) /* 010 Alternative 2 */
+#define _PIN_MODE_ALT3 (3 << _PIN_MODE_SHIFT) /* 011 Alternative 3 */
+#define _PIN_MODE_ALT4 (4 << _PIN_MODE_SHIFT) /* 100 Alternative 4 */
+#define _PIN_MODE_ALT5 (5 << _PIN_MODE_SHIFT) /* 101 Alternative 5 */
+#define _PIN_MODE_ALT6 (6 << _PIN_MODE_SHIFT) /* 110 Alternative 6 */
+#define _PIN_MODE_ALT7 (7 << _PIN_MODE_SHIFT) /* 111 Alternative 7 */
+
+/* Options for all digital modes (Alternatives 1-7). None of the digital
+ * options apply if the analog mode is selected.
+ */
+
+#define _PIN_IO_MASK (1 << _PIN_OPTIONS_SHIFT) /* xxx1 Digital input/output mask */
+#define _PIN_INPUT (0 << _PIN_OPTIONS_SHIFT) /* xxx0 Digital input */
+#define _PIN_OUTPUT (1 << _PIN_OPTIONS_SHIFT) /* xxx1 Digital output */
+
+#define _PIN_INPUT_PULLMASK (7 << _PIN_OPTIONS_SHIFT) /* x111 Mask for pull-up or -down bits */
+#define _PIN_INPUT_PULLDOWN (2 << _PIN_OPTIONS_SHIFT) /* x010 Input with internal pull-down resistor */
+#define _PIN_INPUT_PULLUP (6 << _PIN_OPTIONS_SHIFT) /* x110 Input with internal pull-up resistor */
+
+#define _PIN_OUTPUT_SLEW_MASK (3 << _PIN_OPTIONS_SHIFT) /* xx11 Mask to test for slow slew rate */
+#define _PIN_OUTPUT_FAST (1 << _PIN_OPTIONS_SHIFT) /* xx01 Output with fast slew rate */
+#define _PIN_OUTPUT_SLOW (3 << _PIN_OPTIONS_SHIFT) /* xx11 Output with slow slew rate */
+#define _PIN_OUTPUT_OD_MASK (5 << _PIN_OPTIONS_SHIFT) /* x1x1 Mask to test for open drain */
+#define _PIN_OUTPUT_OPENDRAIN (5 << _PIN_OPTIONS_SHIFT) /* x1x1 Output with open drain enabled */
+#define _PIN_OUTPUT_DRIVE_MASK (9 << _PIN_OPTIONS_SHIFT) /* 1xx1 Mask to test for high drive strengh */
+#define _PIN_OUTPUT_LOWDRIVE (1 << _PIN_OPTIONS_SHIFT) /* 0xx1 Output with low drive strength */
+#define _PIN_OUTPUT_HIGHDRIVE (9 << _PIN_OPTIONS_SHIFT) /* 1xx1 Output with high drive strength */
+
+/* End-user pin modes and configurations. Notes: (1) None of the digital options
+ * are available for the analog mode, (2) digital settings may be combined (OR'ed)
+ * provided that input-only and output-only options are not intermixed.
+ */
+
+#define PIN_ANALOG _PIN_MODE_ANALOG
+
+#define GPIO_INPUT (_PIN_MODE_GPIO | _PIN_INPUT)
+#define GPIO_PULLDOWN (_PIN_MODE_GPIO | _PIN_INPUT_PULLDOWN)
+#define GPIO_PULLUP (_PIN_MODE_GPIO | _PIN_INPUT_PULLUP)
+#define GPIO_OUTPUT (_PIN_MODE_GPIO | _PIN_OUTPUT)
+#define GPIO_FAST (_PIN_MODE_GPIO | _PIN_OUTPUT_FAST)
+#define GPIO_SLOW (_PIN_MODE_GPIO | _PIN_OUTPUT_SLOW)
+#define GPIO_OPENDRAIN (_PIN_MODE_GPIO | _PIN_OUTPUT_LOWDRIVE)
+#define GPIO_LOWDRIVE (_PIN_MODE_GPIO | _PIN_OUTPUT_OPENDRAIN)
+#define GPIO_HIGHDRIVE (_PIN_MODE_GPIO | _PIN_OUTPUT_HIGHDRIVE)
+
+#define PIN_ALT2 _PIN_MODE_ALT2
+#define PIN_ALT2_INPUT (_PIN_MODE_ALT2 | _PIN_INPUT)
+#define PIN_ALT2_PULLDOWN (_PIN_MODE_ALT2 | _PIN_INPUT_PULLDOWN)
+#define PIN_ALT2_PULLUP (_PIN_MODE_ALT2 | _PIN_INPUT_PULLUP)
+#define PIN_ALT2_OUTPUT (_PIN_MODE_ALT2 | _PIN_OUTPUT)
+#define PIN_ALT2_FAST (_PIN_MODE_ALT2 | _PIN_OUTPUT_FAST)
+#define PIN_ALT2_SLOW (_PIN_MODE_ALT2 | _PIN_OUTPUT_SLOW)
+#define PIN_ALT2_OPENDRAIN (_PIN_MODE_ALT2 | _PIN_OUTPUT_LOWDRIVE)
+#define PIN_ALT2_LOWDRIVE (_PIN_MODE_ALT2 | _PIN_OUTPUT_OPENDRAIN)
+#define PIN_ALT2_HIGHDRIVE (_PIN_MODE_ALT2 | _PIN_OUTPUT_HIGHDRIVE)
+
+#define PIN_ALT3 _PIN_MODE_ALT3
+#define PIN_ALT3_INPUT (_PIN_MODE_ALT3 | _PIN_INPUT)
+#define PIN_ALT3_PULLDOWN (_PIN_MODE_ALT3 | _PIN_INPUT_PULLDOWN)
+#define PIN_ALT3_PULLUP (_PIN_MODE_ALT3 | _PIN_INPUT_PULLUP)
+#define PIN_ALT3_OUTPUT (_PIN_MODE_ALT3 | _PIN_OUTPUT)
+#define PIN_ALT3_FAST (_PIN_MODE_ALT3 | _PIN_OUTPUT_FAST)
+#define PIN_ALT3_SLOW (_PIN_MODE_ALT3 | _PIN_OUTPUT_SLOW)
+#define PIN_ALT3_OPENDRAIN (_PIN_MODE_ALT3 | _PIN_OUTPUT_LOWDRIVE)
+#define PIN_ALT3_LOWDRIVE (_PIN_MODE_ALT3 | _PIN_OUTPUT_OPENDRAIN)
+#define PIN_ALT3_HIGHDRIVE (_PIN_MODE_ALT3 | _PIN_OUTPUT_HIGHDRIVE)
+
+#define PIN_ALT4 _PIN_MODE_ALT4
+#define PIN_ALT4_INPUT (_PIN_MODE_ALT4 | _PIN_INPUT)
+#define PIN_ALT4_PULLDOWN (_PIN_MODE_ALT4 | _PIN_INPUT_PULLDOWN)
+#define PIN_ALT4_PULLUP (_PIN_MODE_ALT4 | _PIN_INPUT_PULLUP)
+#define PIN_ALT4_OUTPUT (_PIN_MODE_ALT4 | _PIN_OUTPUT)
+#define PIN_ALT4_FAST (_PIN_MODE_ALT4 | _PIN_OUTPUT_FAST)
+#define PIN_ALT4_SLOW (_PIN_MODE_ALT4 | _PIN_OUTPUT_SLOW)
+#define PIN_ALT4_OPENDRAIN (_PIN_MODE_ALT4 | _PIN_OUTPUT_LOWDRIVE)
+#define PIN_ALT4_LOWDRIVE (_PIN_MODE_ALT4 | _PIN_OUTPUT_OPENDRAIN)
+#define PIN_ALT4_HIGHDRIVE (_PIN_MODE_ALT4 | _PIN_OUTPUT_HIGHDRIVE)
+
+#define PIN_ALT5 _PIN_MODE_ALT5
+#define PIN_ALT5_INPUT (_PIN_MODE_ALT5 | _PIN_INPUT)
+#define PIN_ALT5_PULLDOWN (_PIN_MODE_ALT5 | _PIN_INPUT_PULLDOWN)
+#define PIN_ALT5_PULLUP (_PIN_MODE_ALT5 | _PIN_INPUT_PULLUP)
+#define PIN_ALT5_OUTPUT (_PIN_MODE_ALT5 | _PIN_OUTPUT)
+#define PIN_ALT5_FAST (_PIN_MODE_ALT5 | _PIN_OUTPUT_FAST)
+#define PIN_ALT5_SLOW (_PIN_MODE_ALT5 | _PIN_OUTPUT_SLOW)
+#define PIN_ALT5_OPENDRAIN (_PIN_MODE_ALT5 | _PIN_OUTPUT_LOWDRIVE)
+#define PIN_ALT5_LOWDRIVE (_PIN_MODE_ALT5 | _PIN_OUTPUT_OPENDRAIN)
+#define PIN_ALT5_HIGHDRIVE (_PIN_MODE_ALT5 | _PIN_OUTPUT_HIGHDRIVE)
+
+#define PIN_ALT6 _PIN_MODE_ALT6
+#define PIN_ALT6_INPUT (_PIN_MODE_ALT6 | _PIN_INPUT)
+#define PIN_ALT6_PULLDOWN (_PIN_MODE_ALT6 | _PIN_INPUT_PULLDOWN)
+#define PIN_ALT6_PULLUP (_PIN_MODE_ALT6 | _PIN_INPUT_PULLUP)
+#define PIN_ALT6_OUTPUT (_PIN_MODE_ALT6 | _PIN_OUTPUT)
+#define PIN_ALT6_FAST (_PIN_MODE_ALT6 | _PIN_OUTPUT_FAST)
+#define PIN_ALT6_SLOW (_PIN_MODE_ALT6 | _PIN_OUTPUT_SLOW)
+#define PIN_ALT6_OPENDRAIN (_PIN_MODE_ALT6 | _PIN_OUTPUT_LOWDRIVE)
+#define PIN_ALT6_LOWDRIVE (_PIN_MODE_ALT6 | _PIN_OUTPUT_OPENDRAIN)
+#define PIN_ALT6_HIGHDRIVE (_PIN_MODE_ALT6 | _PIN_OUTPUT_HIGHDRIVE)
+
+#define PIN_ALT7 _PIN_MODE_ALT7
+#define PIN_ALT7_INPUT (_PIN_MODE_ALT7 | _PIN_INPUT)
+#define PIN_ALT7_PULLDOWN (_PIN_MODE_ALT7 | _PIN_INPUT_PULLDOWN)
+#define PIN_ALT7_PULLUP (_PIN_MODE_ALT7 | _PIN_INPUT_PULLUP)
+#define PIN_ALT7_OUTPUT (_PIN_MODE_ALT7 | _PIN_OUTPUT)
+#define PIN_ALT7_FAST (_PIN_MODE_ALT7 | _PIN_OUTPUT_FAST)
+#define PIN_ALT7_SLOW (_PIN_MODE_ALT7 | _PIN_OUTPUT_SLOW)
+#define PIN_ALT7_OPENDRAIN (_PIN_MODE_ALT7 | _PIN_OUTPUT_LOWDRIVE)
+#define PIN_ALT7_LOWDRIVE (_PIN_MODE_ALT7 | _PIN_OUTPUT_OPENDRAIN)
+#define PIN_ALT7_HIGHDRIVE (_PIN_MODE_ALT7 | _PIN_OUTPUT_HIGHDRIVE)
+
+/* The initial value for GPIO (Alternative 1 outputs):
+ *
+ * ---- ---v ---- ---- ---- ---- ---- ----
+ *
+ * Passive Filter and digital filter enable are valid in all digital pin
+ * muxing modes.
+ */
+
+#define GPIO_OUTPUT_ONE (1 << 24) /* Bit 24: 1:Initial output value=1 */
+#define GPIO_OUTPUT_ZER0 (0) /* Bit 24: 0:Initial output value=0 */
+
+/* Five bits are used to incode DMA/interrupt options:
+ *
+ * ---- ---- iiii i--- ---- ---- ---- ----
+ *
+ * The pin interrupt configuration is valid in all digital pin muxing modes
+ * (restricted to inputs).
+ */
+
+#define _PIN_INT_SHIFT (20)
+#define _PIN_INT_MASK (31 << _PIN_INT_SHIFT)
+
+#define _PIN_INTDMA_MASK (3 << _PIN_INT_SHIFT)
+#define _PIN_INTDMA_NONE (0 << _PIN_INT_SHIFT)
+#define _PIN_DMA (1 << _PIN_INT_SHIFT)
+#define _PIN_INTERRUPT (2 << _PIN_INT_SHIFT)
+
+#define PIN_DMA_RISING (5 << _PIN_INT_SHIFT) /* 00101 DMA Request on rising edge */
+#define PIN_DMA_FALLING (9 << _PIN_INT_SHIFT) /* 01001 DMA Request on falling edge */
+#define PIN_DMA_BOTH (13 << _PIN_INT_SHIFT) /* 01101 DMA Request on either edge */
+#define PIN_INT_ZERO (2 << _PIN_INT_SHIFT) /* 00010 Interrupt when logic zero */
+#define PIN_INT_RISING (6 << _PIN_INT_SHIFT) /* 00110 Interrupt on rising edge */
+#define PIN_INT_FALLING (10 << _PIN_INT_SHIFT) /* 01010 Interrupt on falling edge */
+#define PIN_INT_BOTH (14 << _PIN_INT_SHIFT) /* 01110 Interrupt on either edge */
+#define PIN_INT_ONE (18 << _PIN_INT_SHIFT) /* 10010 Interrupt when logic one */
+
+/* Two bits is used to enable the filter options:
+ *
+ * ---- ---- ---- -fd- ---- ---- ---- ----
+ *
+ * Passive Filter and digital filter enable are valid in all digital pin
+ * muxing modes.
+ */
+
+#define PIN_PASV_FILTER (1 << 18) /* Bit 18: Enable passive filter */
+#define PIN_DIG_FILTER (1 << 17) /* Bit 17: Enable digital filter */
+
+/* Three bits are used to define the port number:
+ *
+ * ---- ---- ---- ---- ---- -ppp ---- ----
+ */
+
+#define _PIN_PORT_SHIFT (8) /* Bits 8-10: port number */
+#define _PIN_PORT_MASK (7 << _PIN_PORT_SHIFT)
+
+#define PIN_PORTA (KL_PORTA << _PIN_PORT_SHIFT)
+#define PIN_PORTB (KL_PORTB << _PIN_PORT_SHIFT)
+#define PIN_PORTC (KL_PORTC << _PIN_PORT_SHIFT)
+#define PIN_PORTD (KL_PORTD << _PIN_PORT_SHIFT)
+#define PIN_PORTE (KL_PORTE << _PIN_PORT_SHIFT)
+
+/* Five bits are used to define the pin number:
+ *
+ * ---- ---- ---- ---- ---- ---- ---b bbbb
+ */
+
+#define _PIN_SHIFT (0) /* Bits 0-4: port number */
+#define _PIN_MASK (31 << _PIN_SHIFT)
+
+#define PIN(n) ((n) << _PIN_SHIFT)
+#define PIN0 (0 << _PIN_SHIFT)
+#define PIN1 (1 << _PIN_SHIFT)
+#define PIN2 (2 << _PIN_SHIFT)
+#define PIN3 (3 << _PIN_SHIFT)
+#define PIN4 (4 << _PIN_SHIFT)
+#define PIN5 (5 << _PIN_SHIFT)
+#define PIN6 (6 << _PIN_SHIFT)
+#define PIN7 (7 << _PIN_SHIFT)
+#define PIN8 (8 << _PIN_SHIFT)
+#define PIN9 (9 << _PIN_SHIFT)
+#define PIN10 (10 << _PIN_SHIFT)
+#define PIN11 (11 << _PIN_SHIFT)
+#define PIN12 (12 << _PIN_SHIFT)
+#define PIN13 (13 << _PIN_SHIFT)
+#define PIN14 (14 << _PIN_SHIFT)
+#define PIN15 (15 << _PIN_SHIFT)
+#define PIN16 (16 << _PIN_SHIFT)
+#define PIN17 (17 << _PIN_SHIFT)
+#define PIN18 (18 << _PIN_SHIFT)
+#define PIN19 (19 << _PIN_SHIFT)
+#define PIN20 (20 << _PIN_SHIFT)
+#define PIN21 (21 << _PIN_SHIFT)
+#define PIN22 (22 << _PIN_SHIFT)
+#define PIN23 (23 << _PIN_SHIFT)
+#define PIN24 (24 << _PIN_SHIFT)
+#define PIN25 (25 << _PIN_SHIFT)
+#define PIN26 (26 << _PIN_SHIFT)
+#define PIN27 (27 << _PIN_SHIFT)
+#define PIN28 (28 << _PIN_SHIFT)
+#define PIN29 (29 << _PIN_SHIFT)
+#define PIN30 (30 << _PIN_SHIFT)
+#define PIN31 (31 << _PIN_SHIFT)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+typedef FAR void *DMA_HANDLE;
+typedef void (*dma_callback_t)(DMA_HANDLE handle, void *arg, int result);
+
+/* The following is used for sampling DMA registers when CONFIG DEBUG_DMA is selected */
+
+#ifdef CONFIG_DEBUG_DMA
+struct kl_dmaglobalregs_s
+{
+#warning "Missing logic"
+ /* Global Registers */
+};
+
+struct kl_dmachanregs_s
+{
+#warning "Missing logic"
+ /* Channel Registers */
+};
+
+struct kl_dmaregs_s
+{
+ /* Global Registers */
+
+ struct kl_dmaglobalregs_s gbl;
+
+ /* Channel Registers */
+
+ struct kl_dmachanregs_s ch;
+};
+#endif
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: kl_clockconfig
+ *
+ * Description:
+ * Called to initialize the Kinetis chip. This does whatever setup is needed to
+ * put the MCU in a usable state. This includes the initialization of clocking
+ * using the settings in board.h.
+ *
+ ************************************************************************************/
+
+void kl_clockconfig(void);
+
+/************************************************************************************
+ * Name: kl_lowsetup
+ *
+ * Description:
+ * Called at the very beginning of _start. Performs low level initialization
+ * including setup of the console UART. This UART done early so that the serial
+ * console is available for debugging very early in the boot sequence.
+ *
+ ************************************************************************************/
+
+void kl_lowsetup(void);
+
+/******************************************************************************
+ * Name: kl_uartreset
+ *
+ * Description:
+ * Reset a UART.
+ *
+ ******************************************************************************/
+
+#ifdef HAVE_UART_DEVICE
+void kl_uartreset(uintptr_t uart_base);
+#endif
+
+/******************************************************************************
+ * Name: kl_uartconfigure
+ *
+ * Description:
+ * Configure a UART as a RS-232 UART.
+ *
+ ******************************************************************************/
+
+#ifdef HAVE_UART_DEVICE
+void kl_uartconfigure(uintptr_t uart_base, uint32_t baud, uint32_t clock,
+ unsigned int parity, unsigned int nbits);
+#endif
+
+/************************************************************************************
+ * Name: kl_wddisable
+ *
+ * Description:
+ * Disable the watchdog timer
+ *
+ ************************************************************************************/
+
+void kl_wddisable(void);
+
+/************************************************************************************
+ * Name: kl_pinconfig
+ *
+ * Description:
+ * Configure a pin based on bit-encoded description of the pin.
+ *
+ ************************************************************************************/
+
+int kl_pinconfig(uint32_t cfgset);
+
+/************************************************************************************
+ * Name: kl_pinfilter
+ *
+ * Description:
+ * Configure the digital filter associated with a port. The digital filter
+ * capabilities of the PORT module are available in all digital pin muxing modes.
+ *
+ * Input parmeters:
+ * port - See KL_PORTn definitions in kl_port.h
+ * lpo - true: Digital Filters are clocked by the bus clock
+ * false: Digital Filters are clocked by the 1 kHz LPO clock
+ * width - Filter Length
+ *
+ ************************************************************************************/
+
+int kl_pinfilter(unsigned int port, bool lpo, unsigned int width);
+
+/************************************************************************************
+ * Name: kl_gpiowrite
+ *
+ * Description:
+ * Write one or zero to the selected GPIO pin
+ *
+ ************************************************************************************/
+
+void kl_gpiowrite(uint32_t pinset, bool value);
+
+/************************************************************************************
+ * Name: kl_gpioread
+ *
+ * Description:
+ * Read one or zero from the selected GPIO pin
+ *
+ ************************************************************************************/
+
+bool kl_gpioread(uint32_t pinset);
+
+/************************************************************************************
+ * Name: kl_pinirqinitialize
+ *
+ * Description:
+ * Initialize logic to support a second level of interrupt decoding for GPIO pins.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_GPIO_IRQ
+void kl_pinirqinitialize(void);
+#else
+# define kl_pinirqinitialize()
+#endif
+
+/************************************************************************************
+ * Name: kl_pinirqattach
+ *
+ * Description:
+ * Attach a pin interrupt handler. The normal initalization sequence is:
+ *
+ * 1. Call kl_pinconfig() to configure the interrupting pin (pin interrupts
+ * will be disabled.
+ * 2. Call kl_pinirqattach() to attach the pin interrupt handling function.
+ * 3. Call kl_pinirqenable() to enable interrupts on the pin.
+ *
+ * Parameters:
+ * - pinset: Pin configuration
+ * - pinisr: Pin interrupt service routine
+ *
+ * Returns:
+ * The previous value of the interrupt handler function pointer. This value may,
+ * for example, be used to restore the previous handler when multiple handlers are
+ * used.
+ *
+ ************************************************************************************/
+
+xcpt_t kl_pinirqattach(uint32_t pinset, xcpt_t pinisr);
+
+/************************************************************************************
+ * Name: kl_pinirqenable
+ *
+ * Description:
+ * Enable the interrupt for specified pin IRQ
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_GPIO_IRQ
+void kl_pinirqenable(uint32_t pinset);
+#else
+# define kl_pinirqenable(pinset)
+#endif
+
+/************************************************************************************
+ * Name: kl_pinirqdisable
+ *
+ * Description:
+ * Disable the interrupt for specified pin
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_GPIO_IRQ
+void kl_pinirqdisable(uint32_t pinset);
+#else
+# define kl_pinirqdisable(pinset)
+#endif
+
+/************************************************************************************
+ * Name: kl_pindmaenable
+ *
+ * Description:
+ * Enable DMA for specified pin
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_KL_DMA
+void kl_pindmaenable(uint32_t pinset);
+#endif
+
+/************************************************************************************
+ * Name: kl_pindmadisable
+ *
+ * Description:
+ * Disable DMA for specified pin
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_KL_DMA
+void kl_pindmadisable(uint32_t pinset);
+#endif
+
+/************************************************************************************
+ * Function: kl_pindump
+ *
+ * Description:
+ * Dump all GPIO registers associated with the base address of the provided pinset.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_DEBUG_GPIO
+int kl_pindump(uint32_t pinset, const char *msg);
+#else
+# define kl_pindump(p,m)
+#endif
+
+/************************************************************************************
+ * Name: kl_clrpend
+ *
+ * Description:
+ * Clear a pending interrupt at the NVIC. This does not seem to be required
+ * for most interrupts.
+ *
+ ************************************************************************************/
+
+void kl_clrpend(int irq);
+
+/************************************************************************************
+ * Name: kl_spi[n]select, kl_spi[n]status, and kl_spi[n]cmddata
+ *
+ * Description:
+ * These external functions must be provided by board-specific logic. They are
+ * implementations of the select, status, and cmddata methods of the SPI interface
+ * defined by struct spi_ops_s (see include/nuttx/spi.h). All other methods
+ * including up_spiinitialize()) are provided by common Kinetis logic. To use
+ * this common SPI logic on your board:
+ *
+ * 1. Provide logic in kl_boardinitialize() to configure SPI chip select
+ * pins.
+ * 2. Provide kl_spi[n]select() and kl_spi[n]status() functions
+ * in your board-specific logic. These functions will perform chip selection
+ * and status operations using GPIOs in the way your board is configured.
+ * 2. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide
+ * kl_spi[n]cmddata() functions in your board-specific logic. These
+ * functions will perform cmd/data selection operations using GPIOs in the way
+ * your board is configured.
+ * 3. Add a call to up_spiinitialize() in your low level application
+ * initialization logic
+ * 4. The handle returned by up_spiinitialize() may then be used to bind the
+ * SPI driver to higher level logic (e.g., calling
+ * mmcsd_spislotinitialize(), for example, will bind the SPI driver to
+ * the SPI MMC/SD driver).
+ *
+ ************************************************************************************/
+
+struct spi_dev_s;
+enum spi_dev_e;
+
+#ifdef CONFIG_KL_SPI0
+void kl_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
+uint8_t kl_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
+#ifdef CONFIG_SPI_CMDDATA
+int kl_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
+#endif
+#endif
+#ifdef CONFIG_KL_SPI1
+void kl_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
+uint8_t kl_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
+#ifdef CONFIG_SPI_CMDDATA
+int kl_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
+#endif
+#endif
+#ifdef CONFIG_KL_SPI2
+void kl_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
+uint8_t kl_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
+#ifdef CONFIG_SPI_CMDDATA
+int kl_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
+#endif
+#endif
+
+/****************************************************************************
+ * Name: ssp_flush
+ *
+ * Description:
+ * Flush and discard any words left in the RX fifo. This can be called
+ * from spi[n]select after a device is deselected (if you worry about such
+ * things).
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_KL_SPI0) || defined(CONFIG_KL_SPI0) || defined(CONFIG_KL_SPI2)
+struct spi_dev_s;
+void spi_flush(FAR struct spi_dev_s *dev);
+#endif
+
+/****************************************************************************
+ * Name: kl_dmainitialize
+ *
+ * Description:
+ * Initialize the GPDMA subsystem.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KL_DMA
+void kl_dmainitilaize(void);
+#endif
+
+/****************************************************************************
+ * Name: kl_dmachannel
+ *
+ * Description:
+ * Allocate a DMA channel. This function sets aside a DMA channel and
+ * gives the caller exclusive access to the DMA channel.
+ *
+ * Returned Value:
+ * One success, this function returns a non-NULL, void* DMA channel
+ * handle. NULL is returned on any failure. This function can fail only
+ * if no DMA channel is available.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KL_DMA
+DMA_HANDLE kl_dmachannel(void);
+#endif
+
+/****************************************************************************
+ * Name: kl_dmafree
+ *
+ * Description:
+ * Release a DMA channel. NOTE: The 'handle' used in this argument must
+ * NEVER be used again until kl_dmachannel() is called again to re-gain
+ * a valid handle.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KL_DMA
+void kl_dmafree(DMA_HANDLE handle);
+#endif
+
+/****************************************************************************
+ * Name: kl_dmasetup
+ *
+ * Description:
+ * Configure DMA for one transfer.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KL_DMA
+int kl_dmarxsetup(DMA_HANDLE handle, uint32_t control, uint32_t config,
+ uint32_t srcaddr, uint32_t destaddr, size_t nbytes);
+#endif
+
+/****************************************************************************
+ * Name: kl_dmastart
+ *
+ * Description:
+ * Start the DMA transfer
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KL_DMA
+int kl_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg);
+#endif
+
+/****************************************************************************
+ * Name: kl_dmastop
+ *
+ * Description:
+ * Cancel the DMA. After kl_dmastop() is called, the DMA channel is
+ * reset and kl_dmasetup() must be called before kl_dmastart() can be
+ * called again
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KL_DMA
+void kl_dmastop(DMA_HANDLE handle);
+#endif
+
+/****************************************************************************
+ * Name: kl_dmasample
+ *
+ * Description:
+ * Sample DMA register contents
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KL_DMA
+#ifdef CONFIG_DEBUG_DMA
+void kl_dmasample(DMA_HANDLE handle, struct kl_dmaregs_s *regs);
+#else
+# define kl_dmasample(handle,regs)
+#endif
+#endif
+
+/****************************************************************************
+ * Name: kl_dmadump
+ *
+ * Description:
+ * Dump previously sampled DMA register contents
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KL_DMA
+#ifdef CONFIG_DEBUG_DMA
+void kl_dmadump(DMA_HANDLE handle, const struct kl_dmaregs_s *regs,
+ const char *msg);
+#else
+# define kl_dmadump(handle,regs,msg)
+#endif
+#endif
+
+/****************************************************************************
+ * Name: sdhc_initialize
+ *
+ * Description:
+ * Initialize SDIO for operation.
+ *
+ * Input Parameters:
+ * slotno - Not used.
+ *
+ * Returned Values:
+ * A reference to an SDIO interface structure. NULL is returned on failures.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KL_SDHC
+struct sdio_dev_s;
+FAR struct sdio_dev_s *sdhc_initialize(int slotno);
+#endif
+
+/****************************************************************************
+ * Name: sdhc_mediachange
+ *
+ * Description:
+ * Called by board-specific logic -- posssible from an interrupt handler --
+ * in order to signal to the driver that a card has been inserted or
+ * removed from the slot
+ *
+ * Input Parameters:
+ * dev - An instance of the SDIO driver device state structure.
+ * cardinslot - true is a card has been detected in the slot; false if a
+ * card has been removed from the slot. Only transitions
+ * (inserted->removed or removed->inserted should be reported)
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KL_SDHC
+void sdhc_mediachange(FAR struct sdio_dev_s *dev, bool cardinslot);
+#endif
+
+/****************************************************************************
+ * Name: sdio_wrprotect
+ *
+ * Description:
+ * Called by board-specific logic to report if the card in the slot is
+ * mechanically write protected.
+ *
+ * Input Parameters:
+ * dev - An instance of the SDIO driver device state structure.
+ * wrprotect - true is a card is writeprotected.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KL_SDHC
+void sdhc_wrprotect(FAR struct sdio_dev_s *dev, bool wrprotect);
+#endif
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_KL_KL_INTERNAL_H */
diff --git a/nuttx/arch/arm/src/kl/chip/kl_llwu.h b/nuttx/arch/arm/src/kl/chip/kl_llwu.h
new file mode 100644
index 000000000..d84368963
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/kl_llwu.h
@@ -0,0 +1,252 @@
+/************************************************************************************
+ * arch/arm/src/kl/kl_llwu.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_KL_LLWU_H
+#define __ARCH_ARM_SRC_KL_KL_LLWU_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register Offsets *****************************************************************/
+
+#define KL_LLWU_PE1_OFFSET 0x0000 /* LLWU Pin Enable 1 Register */
+#define KL_LLWU_PE2_OFFSET 0x0001 /* LLWU Pin Enable 2 Register */
+#define KL_LLWU_PE3_OFFSET 0x0002 /* LLWU Pin Enable 3 Register */
+#define KL_LLWU_PE4_OFFSET 0x0003 /* LLWU Pin Enable 4 Register */
+#define KL_LLWU_ME_OFFSET 0x0004 /* LLWU Module Enable Register */
+#define KL_LLWU_F1_OFFSET 0x0005 /* LLWU Flag 1 Register */
+#define KL_LLWU_F2_OFFSET 0x0006 /* LLWU Flag 2 Register */
+#define KL_LLWU_F3_OFFSET 0x0007 /* LLWU Flag 3 Register */
+#define KL_LLWU_CS_OFFSET 0x0008 /* LLWU Control and Status Register */
+
+/* Register Addresses ***************************************************************/
+
+#define KL_LLWU_PE1 (KL_LLWU_BASE+KL_LLWU_PE1_OFFSET)
+#define KL_LLWU_PE2 (KL_LLWU_BASE+KL_LLWU_PE2_OFFSET)
+#define KL_LLWU_PE3 (KL_LLWU_BASE+KL_LLWU_PE3_OFFSET)
+#define KL_LLWU_PE4 (KL_LLWU_BASE+KL_LLWU_PE4_OFFSET)
+#define KL_LLWU_ME (KL_LLWU_BASE+KL_LLWU_ME_OFFSET)
+#define KL_LLWU_F1 (KL_LLWU_BASE+KL_LLWU_F1_OFFSET)
+#define KL_LLWU_F2 (KL_LLWU_BASE+KL_LLWU_F2_OFFSET)
+#define KL_LLWU_F3 (KL_LLWU_BASE+KL_LLWU_F3_OFFSET)
+#define KL_LLWU_CS (KL_LLWU_BASE+KL_LLWU_CS_OFFSET)
+
+/* Register Bit Definitions *********************************************************/
+
+/* LLWU Pin Enable 1 Register */
+
+#define LLWU_PE1_WUPE0_SHIFT (0) /* Bits 0-1: Wakeup Pin Enable for LLWU_P0 */
+#define LLWU_PE1_WUPE0_MASK (3 << LLWU_PE1_WUPE0_SHIFT)
+# define LLWU_PE1_WUPE0_DISABLED (0 << LLWU_PE1_WUPE0_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE1_WUPE0_RISING (1 << LLWU_PE1_WUPE0_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE1_WUPE0_FALLING (2 << LLWU_PE1_WUPE0_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE1_WUPE0_BOTH (3 << LLWU_PE1_WUPE0_SHIFT) /* Ext input enabled for any change */
+#define LLWU_PE1_WUPE1_SHIFT (2) /* Bits 2-3: Wakeup Pin Enable for LLWU_P1 */
+#define LLWU_PE1_WUPE1_MASK (3 << LLWU_PE1_WUPE1_SHIFT)
+# define LLWU_PE1_WUPE1_DISABLED (0 << LLWU_PE1_WUPE1_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE1_WUPE1_RISING (1 << LLWU_PE1_WUPE1_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE1_WUPE1_FALLING (2 << LLWU_PE1_WUPE1_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE1_WUPE1_BOTH (3 << LLWU_PE1_WUPE1_SHIFT) /* Ext input enabled for any change */
+#define LLWU_PE1_WUPE2_SHIFT (4) /* Bits 4-5: Wakeup Pin Enable for LLWU_P2 */
+#define LLWU_PE1_WUPE2_MASK (3 << LLWU_PE1_WUPE2_SHIFT)
+# define LLWU_PE1_WUPE2_DISABLED (0 << LLWU_PE1_WUPE2_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE1_WUPE2_RISING (1 << LLWU_PE1_WUPE2_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE1_WUPE2_FALLING (2 << LLWU_PE1_WUPE2_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE1_WUPE2_BOTH (3 << LLWU_PE1_WUPE2_SHIFT) /* Ext input enabled for any change */
+#define LLWU_PE1_WUPE3_SHIFT (6) /* Bits 6-7: Wakeup Pin Enable for LLWU_P3 */
+#define LLWU_PE1_WUPE3_MASK (3 << LLWU_PE1_WUPE3_SHIFT)
+# define LLWU_PE1_WUPE3_DISABLED (0 << LLWU_PE1_WUPE3_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE1_WUPE3_RISING (1 << LLWU_PE1_WUPE3_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE1_WUPE3_FALLING (2 << LLWU_PE1_WUPE3_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE1_WUPE3_BOTH (3 << LLWU_PE1_WUPE3_SHIFT) /* Ext input enabled for any change */
+
+/* LLWU Pin Enable 2 Register */
+
+#define LLWU_PE2_WUPE4_SHIFT (0) /* Bits 0-1: Wakeup Pin Enable for LLWU_P4 */
+#define LLWU_PE2_WUPE4_MASK (3 << LLWU_PE2_WUPE4_SHIFT)
+# define LLWU_PE2_WUPE4_DISABLED (0 << LLWU_PE2_WUPE4_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE2_WUPE4_RISING (1 << LLWU_PE2_WUPE4_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE2_WUPE4_FALLING (2 << LLWU_PE2_WUPE4_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE2_WUPE4_BOTH (3 << LLWU_PE2_WUPE4_SHIFT) /* Ext input enabled for any change */
+#define LLWU_PE2_WUPE5_SHIFT (2) /* Bits 2-3: Wakeup Pin Enable for LLWU_P5 */
+#define LLWU_PE2_WUPE5_MASK (3 << LLWU_PE2_WUPE5_SHIFT)
+# define LLWU_PE2_WUPE5_DISABLED (0 << LLWU_PE2_WUPE5_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE2_WUPE5_RISING (1 << LLWU_PE2_WUPE5_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE2_WUPE5_FALLING (2 << LLWU_PE2_WUPE5_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE2_WUPE5_BOTH (3 << LLWU_PE2_WUPE5_SHIFT) /* Ext input enabled for any change */
+#define LLWU_PE2_WUPE6_SHIFT (4) /* Bits 4-5: Wakeup Pin Enable for LLWU_P6 */
+#define LLWU_PE2_WUPE6_MASK (3 << LLWU_PE2_WUPE6_SHIFT)
+# define LLWU_PE2_WUPE6_DISABLED (0 << LLWU_PE2_WUPE6_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE2_WUPE6_RISING (1 << LLWU_PE2_WUPE6_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE2_WUPE6_FALLING (2 << LLWU_PE2_WUPE6_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE2_WUPE6_BOTH (3 << LLWU_PE2_WUPE6_SHIFT) /* Ext input enabled for any change */
+#define LLWU_PE2_WUPE7_SHIFT (6) /* Bits 6-7: Wakeup Pin Enable for LLWU_P7 */
+#define LLWU_PE2_WUPE7_MASK (3 << LLWU_PE2_WUPE7_SHIFT)
+# define LLWU_PE2_WUPE7_DISABLED (0 << LLWU_PE2_WUPE7_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE2_WUPE7_RISING (1 << LLWU_PE2_WUPE7_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE2_WUPE7_FALLING (2 << LLWU_PE2_WUPE7_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE2_WUPE7_BOTH (3 << LLWU_PE2_WUPE7_SHIFT) /* Ext input enabled for any change */
+
+/* LLWU Pin Enable 3 Register */
+
+#define LLWU_PE3_WUPE8_SHIFT (0) /* Bits 0-1: Wakeup Pin Enable for LLWU_P8 */
+#define LLWU_PE3_WUPE8_MASK (3 << LLWU_PE3_WUPE8_SHIFT)
+# define LLWU_PE3_WUPE8_DISABLED (0 << LLWU_PE3_WUPE8_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE3_WUPE8_RISING (1 << LLWU_PE3_WUPE8_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE3_WUPE8_FALLING (2 << LLWU_PE3_WUPE8_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE3_WUPE8_BOTH (3 << LLWU_PE3_WUPE8_SHIFT) /* Ext input enabled for any change */
+#define LLWU_PE3_WUPE9_SHIFT (2) /* Bits 2-3: Wakeup Pin Enable for LLWU_P9 */
+#define LLWU_PE3_WUPE9_MASK (3 << LLWU_PE3_WUPE9_SHIFT)
+# define LLWU_PE3_WUPE9_DISABLED (0 << LLWU_PE3_WUPE9_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE3_WUPE9_RISING (1 << LLWU_PE3_WUPE9_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE3_WUPE9_FALLING (2 << LLWU_PE3_WUPE9_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE3_WUPE9_BOTH (3 << LLWU_PE3_WUPE9_SHIFT) /* Ext input enabled for any change */
+#define LLWU_PE3_WUPE10_SHIFT (4) /* Bits 4-5: Wakeup Pin Enable for LLWU_P10 */
+#define LLWU_PE3_WUPE10_MASK (3 << LLWU_PE3_WUPE10_SHIFT)
+# define LLWU_PE3_WUPE10_DISABLED (0 << LLWU_PE3_WUPE10_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE3_WUPE10_RISING (1 << LLWU_PE3_WUPE10_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE3_WUPE10_FALLING (2 << LLWU_PE3_WUPE10_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE3_WUPE10_BOTH (3 << LLWU_PE3_WUPE10_SHIFT) /* Ext input enabled for any change */
+#define LLWU_PE3_WUPE11_SHIFT (6) /* Bits 6-7: Wakeup Pin Enable for LLWU_P11 */
+#define LLWU_PE3_WUPE11_MASK (3 << LLWU_PE3_WUPE11_SHIFT)
+# define LLWU_PE3_WUPE11_DISABLED (0 << LLWU_PE3_WUPE11_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE3_WUPE11_RISING (1 << LLWU_PE3_WUPE11_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE3_WUPE11_FALLING (2 << LLWU_PE3_WUPE11_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE3_WUPE11_BOTH (3 << LLWU_PE3_WUPE11_SHIFT) /* Ext input enabled for any change */
+
+/* LLWU Pin Enable 4 Register */
+
+#define LLWU_PE4_WUPE12_SHIFT (0) /* Bits 0-1: Wakeup Pin Enable for LLWU_P12 */
+#define LLWU_PE4_WUPE12_MASK (3 << LLWU_PE4_WUPE12_SHIFT)
+# define LLWU_PE4_WUPE12_DISABLED (0 << LLWU_PE4_WUPE12_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE4_WUPE12_RISING (1 << LLWU_PE4_WUPE12_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE4_WUPE12_FALLING (2 << LLWU_PE4_WUPE12_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE4_WUPE12_BOTH (3 << LLWU_PE4_WUPE12_SHIFT) /* Ext input enabled for any change */
+#define LLWU_PE4_WUPE13_SHIFT (2) /* Bits 2-3: Wakeup Pin Enable for LLWU_P13 */
+#define LLWU_PE4_WUPE13_MASK (3 << LLWU_PE4_WUPE13_SHIFT)
+# define LLWU_PE4_WUPE13_DISABLED (0 << LLWU_PE4_WUPE13_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE4_WUPE13_RISING (1 << LLWU_PE4_WUPE13_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE4_WUPE13_FALLING (2 << LLWU_PE4_WUPE13_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE4_WUPE13_BOTH (3 << LLWU_PE4_WUPE13_SHIFT) /* Ext input enabled for any change */
+#define LLWU_PE4_WUPE14_SHIFT (4) /* Bits 4-5: Wakeup Pin Enable for LLWU_P14 */
+#define LLWU_PE4_WUPE14_MASK (3 << LLWU_PE4_WUPE14_SHIFT)
+# define LLWU_PE4_WUPE14_DISABLED (0 << LLWU_PE4_WUPE14_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE4_WUPE14_RISING (1 << LLWU_PE4_WUPE14_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE4_WUPE14_FALLING (2 << LLWU_PE4_WUPE14_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE4_WUPE14_BOTH (3 << LLWU_PE4_WUPE14_SHIFT) /* Ext input enabled for any change */
+#define LLWU_PE4_WUPE15_SHIFT (6) /* Bits 6-7: Wakeup Pin Enable for LLWU_P15 */
+#define LLWU_PE4_WUPE15_MASK (3 << LLWU_PE4_WUPE15_SHIFT)
+# define LLWU_PE4_WUPE15_DISABLED (0 << LLWU_PE4_WUPE15_SHIFT) /* Ext input disabled as wakeup input */
+# define LLWU_PE4_WUPE15_RISING (1 << LLWU_PE4_WUPE15_SHIFT) /* Ext input enabled for rising edge */
+# define LLWU_PE4_WUPE15_FALLING (2 << LLWU_PE4_WUPE15_SHIFT) /* Ext input enabled for falling edge */
+# define LLWU_PE4_WUPE15_BOTH (3 << LLWU_PE4_WUPE15_SHIFT) /* Ext input enabled for any change */
+
+/* LLWU Module Enable Register */
+
+#define LLWU_ME_WUME(n) (1 << (n))
+#define LLWU_ME_WUME0 (1 << 0) /* Bit 0: Wakeup Module Enable for Module 0 */
+#define LLWU_ME_WUME1 (1 << 1) /* Bit 1: Wakeup Module Enable for Module 1 */
+#define LLWU_ME_WUME2 (1 << 2) /* Bit 2: Wakeup Module Enable for Module 2 */
+#define LLWU_ME_WUME3 (1 << 3) /* Bit 3: Wakeup Module Enable for Module 3 */
+#define LLWU_ME_WUME4 (1 << 4) /* Bit 4: Wakeup Module Enable for Module 4 */
+#define LLWU_ME_WUME5 (1 << 5) /* Bit 5: Wakeup Module Enable for Module 5 */
+#define LLWU_ME_WUME6 (1 << 6) /* Bit 6: Wakeup Module Enable for Module 6 */
+#define LLWU_ME_WUME7 (1 << 7) /* Bit 7: Wakeup Module Enable for Module 7 */
+
+/* LLWU Flag 1 Register */
+
+#define LLWU_F1_WUF(n) (1 << (n))
+#define LLWU_F1_WUF0 (1 << 0) /* Bit 0: Wakeup Flag for LLWU_P0 */
+#define LLWU_F1_WUF1 (1 << 1) /* Bit 1: Wakeup Flag for LLWU_P1 */
+#define LLWU_F1_WUF2 (1 << 2) /* Bit 2: Wakeup Flag for LLWU_P2 */
+#define LLWU_F1_WUF3 (1 << 3) /* Bit 3: Wakeup Flag for LLWU_P3 */
+#define LLWU_F1_WUF4 (1 << 4) /* Bit 4: Wakeup Flag for LLWU_P4 */
+#define LLWU_F1_WUF5 (1 << 5) /* Bit 5: Wakeup Flag for LLWU_P5 */
+#define LLWU_F1_WUF6 (1 << 6) /* Bit 6: Wakeup Flag for LLWU_P6 */
+#define LLWU_F1_WUF7 (1 << 7) /* Bit 7: Wakeup Flag for LLWU_P7 */
+
+/* LLWU Flag 2 Register */
+
+#define LLWU_F2_WUF(n) (1 << ((n)-8))
+#define LLWU_F2_WUF8 (1 << 8) /* Bit 0: Wakeup Flag for LLWU_P8 */
+#define LLWU_F2_WUF9 (1 << 9) /* Bit 1: Wakeup Flag for LLWU_P9 */
+#define LLWU_F2_WUF10 (1 << 10) /* Bit 2: Wakeup Flag for LLWU_P10 */
+#define LLWU_F2_WUF11 (1 << 11) /* Bit 3: Wakeup Flag for LLWU_P11 */
+#define LLWU_F2_WUF12 (1 << 12) /* Bit 4: Wakeup Flag for LLWU_P12 */
+#define LLWU_F2_WUF13 (1 << 13) /* Bit 5: Wakeup Flag for LLWU_P13 */
+#define LLWU_F2_WUF14 (1 << 14) /* Bit 6: Wakeup Flag for LLWU_P14 */
+#define LLWU_F2_WUF15 (1 << 15) /* Bit 7: Wakeup Flag for LLWU_P15 */
+
+/* LLWU Flag 3 Register */
+
+#define LLWU_F3_MWUF(n) (1 << (n))
+#define LLWU_F3_MWUF0 (1 << 0) /* Bit 0: Wakeup flag for module 0 */
+#define LLWU_F3_MWUF1 (1 << 1) /* Bit 1: Wakeup flag for module 1 */
+#define LLWU_F3_MWUF2 (1 << 2) /* Bit 2: Wakeup flag for module 2 */
+#define LLWU_F3_MWUF3 (1 << 3) /* Bit 3: Wakeup flag for module 3 */
+#define LLWU_F3_MWUF4 (1 << 4) /* Bit 4: Wakeup flag for module 4 */
+#define LLWU_F3_MWUF5 (1 << 5) /* Bit 5: Wakeup flag for module 5 */
+#define LLWU_F3_MWUF6 (1 << 6) /* Bit 6: Wakeup flag for module 6 */
+#define LLWU_F3_MWUF7 (1 << 7) /* Bit 7: Wakeup flag for module 7 */
+
+/* LLWU Control and Status Register */
+
+#define LLWU_CS_ACKISO (1 << 7) /* Bit 7: Acknowledge Isolation */
+ /* Bits 2-6: Reserved */
+#define LLWU_CS_FLTEP (1 << 1) /* Bit 1: Digital Filter on External Pin */
+#define LLWU_CS_FLTR (1 << 0) /* Bit 0: Digital Filter on RESET Pin */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KL_KL_LLWU_H */
diff --git a/nuttx/arch/arm/src/kl/chip/kl_mcg.h b/nuttx/arch/arm/src/kl/chip/kl_mcg.h
new file mode 100644
index 000000000..6b1d2e91d
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/kl_mcg.h
@@ -0,0 +1,186 @@
+/************************************************************************************
+ * arch/arm/src/kl/kl_mcg.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_KL_MCG_H
+#define __ARCH_ARM_SRC_KL_KL_MCG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register Offsets *****************************************************************/
+
+#define KL_MCG_C1_OFFSET 0x0000 /* MCG Control 1 Register */
+#define KL_MCG_C2_OFFSET 0x0001 /* MCG Control 2 Register */
+#define KL_MCG_C3_OFFSET 0x0002 /* MCG Control 3 Register */
+#define KL_MCG_C4_OFFSET 0x0003 /* MCG Control 4 Register */
+#define KL_MCG_C5_OFFSET 0x0004 /* MCG Control 5 Register */
+#define KL_MCG_C6_OFFSET 0x0005 /* MCG Control 6 Register */
+#define KL_MCG_S_OFFSET 0x0006 /* MCG Status Register */
+#define KL_MCG_ATC_OFFSET 0x0008 /* MCG Auto Trim Control Register */
+#define KL_MCG_ATCVH_OFFSET 0x000a /* MCG Auto Trim Compare Value High Register */
+#define KL_MCG_ATCVL_OFFSET 0x000b /* MCG Auto Trim Compare Value Low Register */
+
+/* Register Addresses ***************************************************************/
+
+#define KL_MCG_C1 (KL_MCG_BASE+KL_MCG_C1_OFFSET)
+#define KL_MCG_C2 (KL_MCG_BASE+KL_MCG_C2_OFFSET)
+#define KL_MCG_C3 (KL_MCG_BASE+KL_MCG_C3_OFFSET)
+#define KL_MCG_C4 (KL_MCG_BASE+KL_MCG_C4_OFFSET)
+#define KL_MCG_C5 (KL_MCG_BASE+KL_MCG_C5_OFFSET)
+#define KL_MCG_C6 (KL_MCG_BASE+KL_MCG_C6_OFFSET)
+#define KL_MCG_S (KL_MCG_BASE+KL_MCG_S_OFFSET)
+#define KL_MCG_ATC (KL_MCG_BASE+KL_MCG_ATC_OFFSET)
+#define KL_MCG_ATCVH (KL_MCG_BASE+KL_MCG_ATCVH_OFFSET)
+#define KL_MCG_ATCVL (KL_MCG_BASE+KL_MCG_ATCVL_OFFSET)
+
+/* Register Bit Definitions *********************************************************/
+
+/* MCG Control 1 Register (8-bit) */
+
+#define MCG_C1_IREFSTEN (1 << 0) /* Bit 0: Internal Reference Stop Enable */
+#define MCG_C1_IRCLKEN (1 << 1) /* Bit 1: Internal Reference Clock Enable */
+#define MCG_C1_IREFS (1 << 2) /* Bit 2: Internal Reference Select */
+#define MCG_C1_FRDIV_SHIFT (3) /* Bits 3-5: FLL External Reference Divider */
+#define MCG_C1_FRDIV_MASK (7 << MCG_C1_FRDIV_SHIFT)
+# define MCG_C1_FRDIV_R0DIV1 (0 << MCG_C1_FRDIV_SHIFT) /* RANGE==0 divider=1 */
+# define MCG_C1_FRDIV_R0DIV2 (1 << MCG_C1_FRDIV_SHIFT) /* RANGE==0 divider=2 */
+# define MCG_C1_FRDIV_R0DIV4 (2 << MCG_C1_FRDIV_SHIFT) /* RANGE==0 divider=4 */
+# define MCG_C1_FRDIV_R0DIV8 (3 << MCG_C1_FRDIV_SHIFT) /* RANGE==0 divider=8 */
+# define MCG_C1_FRDIV_R0DIV16 (4 << MCG_C1_FRDIV_SHIFT) /* RANGE==0 divider=16 */
+# define MCG_C1_FRDIV_R0DIV32 (5 << MCG_C1_FRDIV_SHIFT) /* RANGE==0 divider=32 */
+# define MCG_C1_FRDIV_R0DIV64 (6 << MCG_C1_FRDIV_SHIFT) /* RANGE==0 divider=64 */
+# define MCG_C1_FRDIV_R0DIV128 (7 << MCG_C1_FRDIV_SHIFT) /* RANGE==0 divider=128 */
+# define MCG_C1_FRDIV_DIV32 (0 << MCG_C1_FRDIV_SHIFT) /* RANGE!=0 divider=32 */
+# define MCG_C1_FRDIV_DIV64 (1 << MCG_C1_FRDIV_SHIFT) /* RANGE!=0 divider=64 */
+# define MCG_C1_FRDIV_DIV128 (2 << MCG_C1_FRDIV_SHIFT) /* RANGE!=0 divider=128 */
+# define MCG_C1_FRDIV_DIV256 (3 << MCG_C1_FRDIV_SHIFT) /* RANGE!=0 divider=256 */
+# define MCG_C1_FRDIV_DIV512 (4 << MCG_C1_FRDIV_SHIFT) /* RANGE!=0 divider=512 */
+# define MCG_C1_FRDIV_DIV1024 (5 << MCG_C1_FRDIV_SHIFT) /* RANGE!=0 divider=1024 */
+#define MCG_C1_CLKS_SHIFT (6) /* Bits 6-7: Clock Source Select */
+#define MCG_C1_CLKS_MASK (3 << MCG_C1_CLKS_SHIFT)
+# define MCG_C1_CLKS_PLL (0 << MCG_C1_CLKS_SHIFT) /* FLL or PLL output */
+# define MCG_C1_CLKS_INTREF (1 << MCG_C1_CLKS_SHIFT) /* Internal reference clock */
+# define MCG_C1_CLKS_EXTREF (2 << MCG_C1_CLKS_SHIFT) /* External reference clock */
+
+/* MCG Control 2 Register */
+
+#define MCG_C2_IRCS (1 << 0) /* Bit 0: Internal Reference Clock Select */
+#define MCG_C2_LP (1 << 1) /* Bit 1: Low Power Select */
+#define MCG_C2_EREFS (1 << 2) /* Bit 2: External Reference Select */
+#define MCG_C2_HGO (1 << 3) /* Bit 3: High Gain Oscillator Select */
+#define MCG_C2_RANGE_SHIFT (4) /* Bits 4-5: Frequency Range Select */
+#define MCG_C2_RANGE_MASK (3 << MCG_C2_RANGE_SHIFT)
+# define MCG_C2_RANGE_LOW (0 << MCG_C2_RANGE_SHIFT) /* Oscillator of 32 kHz to 40 kHz */
+# define MCG_C2_RANGE_HIGH (1 << MCG_C2_RANGE_SHIFT) /* Oscillator of 1 MHz to 8 MHz */
+# define MCG_C2_RANGE_VHIGH (2 << MCG_C2_RANGE_SHIFT) /* Oscillator of 8 MHz to 32 MHz */
+ /* Bits 6-7: Reserved */
+/* MCG Control 3 Register (8-bit Slow Internal Reference Clock Trim Setting) */
+
+/* MCG Control 4 Register (8-bit) */
+
+#define MCG_C4_SCFTRIM (1 << 0) /* Bit 0: Slow Internal Reference Clock Fine Trim */
+#define MCG_C4_FCTRIM_SHIFT (1) /* Bits 1-4: Fast Internal Reference Clock Trim Setting */
+#define MCG_C4_FCTRIM_MASK (15 << MCG_C4_FCTRIM_SHIFT)
+#define MCG_C4_DRST_DRS_SHIFT (5) /* Bits 5-6: DCO Range Select */
+#define MCG_C4_DRST_DRS_MASK (3 << MCG_C4_DRST_DRS_SHIFT)
+# define MCG_C4_DRST_DRS_LOW (0 << MCG_C4_DRST_DRS_SHIFT)
+# define MCG_C4_DRST_DRS_MID (1 << MCG_C4_DRST_DRS_SHIFT)
+# define MCG_C4_DRST_DRS_MIDHIGH (2 << MCG_C4_DRST_DRS_SHIFT)
+# define MCG_C4_DRST_DRS_HIGH (3 << MCG_C4_DRST_DRS_SHIFT)
+#define MCG_C4_DMX32 (1 << 7) /* Bit 7: DCO Maximum Frequency with 32.768 kHz Reference */
+
+/* MCG Control 5 Register */
+
+#define MCG_C5_PRDIV_SHIFT (0) /* Bits 0-4: PLL External Reference Divider */
+#define MCG_C5_PRDIV_MASK (31 << MCG_C5_PRDIV_SHIFT)
+# define MCG_C5_PRDIV(n) (n << MCG_C5_PRDIV_SHIFT) /* Divide factor n=1..25 */
+#define MCG_C5_PLLSTEN (1 << 5) /* Bit 5: PLL Stop Enable */
+#define MCG_C5_PLLCLKEN (1 << 6) /* Bit 6: PLL Clock Enable */
+ /* Bit 7: Reserved */
+
+/* MCG Control 6 Register */
+
+#define MCG_C6_VDIV_SHIFT (0) /* Bits 0-4: VCO Divider */
+#define MCG_C6_VDIV_MASK (31 << MCG_C6_VDIV_SHIFT)
+# define MCG_C6_VDIV(n) (((n)-24) << MCG_C6_VDIV_SHIFT) /* Divide factor n=24..55 */
+#define MCG_C6_CME (1 << 5) /* Bit 5: Clock Monitor Enable */
+#define MCG_C6_PLLS (1 << 6) /* Bit 6: PLL Select */
+#define MCG_C6_LOLIE (1 << 7) /* Bit 7: Loss of Lock Interrrupt Enable */
+
+/* MCG Status Register */
+
+#define MCG_S_IRCST (1 << 0) /* Bit 0: Internal Reference Clock Status */
+#define MCG_S_OSCINIT (1 << 1) /* Bit 1: OSC Initialization */
+#define MCG_S_CLKST_SHIFT (2) /* Bits 2-3: Clock Mode Status */
+#define MCG_S_CLKST_MASK (3 << MCG_S_CLKST_SHIFT)
+# define MCG_S_CLKST_FLL (0 << MCG_S_CLKST_SHIFT) /* Output of the FLL */
+# define MCG_S_CLKST_INTREF (1 << MCG_S_CLKST_SHIFT) /* Internal reference clock */
+# define MCG_S_CLKST_EXTREF (2 << MCG_S_CLKST_SHIFT) /* External reference clock */
+# define MCG_S_CLKST_PLL (3 << MCG_S_CLKST_SHIFT) /* Output of the PLL */
+#define MCG_S_IREFST (1 << 4) /* Bit 4: Internal Reference Status */
+#define MCG_S_PLLST (1 << 5) /* Bit 5: PLL Select Status */
+#define MCG_S_LOCK (1 << 6) /* Bit 6: Lock Status */
+#define MCG_S_LOLS (1 << 7) /* Bit 7: Loss of Lock Status */
+
+/* MCG Auto Trim Control Register */
+ /* Bits 0-4: Reserved */
+#define MCG_ATC_ATMF (1 << 5) /* Bit 5: Automatic Trim machine Fail Flag */
+#define MCG_ATC_ATMS (1 << 6) /* Bit 6: Automatic Trim Machine Select */
+#define MCG_ATC_ATME (1 << 7) /* Bit 7: Automatic Trim Machine Enable */
+
+/* MCG Auto Trim Compare Value High/Low Registers (8-bit compare value) */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KL_KL_MCG_H */
diff --git a/nuttx/arch/arm/src/kl/chip/kl_memorymap.h b/nuttx/arch/arm/src/kl/chip/kl_memorymap.h
new file mode 100644
index 000000000..86529d85d
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/kl_memorymap.h
@@ -0,0 +1,196 @@
+/************************************************************************************
+ * arch/arm/src/kl/kl_memorymap.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_KL_MEMORYMAP_H
+#define __ARCH_ARM_SRC_KL_KL_MEMORYMAP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* from NUC memmap */
+#define KL_GPIO_BASEOLD 0x50004000 /* -0x50007fff: GPIO control registers */
+#define KL_GCR_BASE 0x50000000 /* -0x500001ff: System global control registers */
+
+/* Memory Map ***********************************************************************/
+/* K40 Family
+ *
+ * The memory map for the following parts is defined in Freescale document
+ * K40P144M100SF2RM
+ */
+
+# define KL_FLASH_BASE 0x00000000 /* –0x0fffffff Program flash and read-
+ * only data (Includes exception
+ * vectors in first 1024 bytes) */
+# define KL_SRAML_BASE 0x18000000 /* –0x1fffffff SRAM_L: Lower SRAM
+ * (ICODE/DCODE) */
+# define KL_SRAMU_BASE 0x20000000 /* –0x200fffff SRAM_U: Upper SRAM bitband
+ * region */
+ /* 0x20100000 * –0x21ffffff Reserved */
+# define KL_SALIAS_BASE 0x22000000 /* –0x23ffffff Aliased to SRAM_U bitband */
+ /* 0x24000000 * –0x3fffffff Reserved */
+# define KL_BRIDGE0_BASE 0x40000000 /* –0x4007ffff Bitband region for peripheral
+ * bridge 0 (AIPS-Lite0) */
+# define KL_BRIDGE1_BASE 0x40080000 /* –0x400fffff Bitband region for peripheral
+ * bridge 1 (AIPS-Lite1) */
+# define KL_GPIOBB_BASE 0x400ff000 /* –0x400fffff Bitband region for general
+ * purpose input/output (GPIO) */
+ /* 0x40100000 * –0x41ffffff Reserved */
+# define KL_PALIAS_BASE 0x42000000 /* –0x43ffffff Aliased to peripheral bridge
+ * (AIPS-Lite) and general purpose
+ * input/output (GPIO) bitband */
+ /* 0x44000000 * –0x5fffffff Reserved */
+# define KL_FLEXBUS_WBBASE 0x60000000 /* –0x7fffffff FlexBus (External Memory -
+ * Write-back) */
+# define KL_FLEXBUS_WTBASE 0x80000000 /* –0x9fffffff FlexBus (External Memory -
+ * Write-through) */
+# define KL_FLEXBUS_NXBASE 0xa0000000 /* –0xdfffffff FlexBus (External Memory -
+ * Non-executable) */
+# define KL_PERIPH_BASE 0xe0000000 /* –0xe00fffff Private peripherals */
+ /* 0xe0100000 * –0xffffffff Reserved */
+
+/* Peripheral Bridge 0 Memory Map ***************************************************/
+
+# define KL_AIPS0_BASE 0x40000000 /* Peripheral bridge 0 (AIPS-Lite 0) */
+# define KL_XBAR_BASE 0x40004000 /* Crossbar switch */
+# define KL_DMAC_BASE 0x40008000 /* DMA controller */
+# define KL_DMADESC_BASE 0x40009000 /* DMA controller transfer control descriptors */
+# define KL_FLEXBUSC_BASE 0x4000c000 /* FlexBus controller */
+# define KL_MPU_BASE 0x4000d000 /* MPU */
+# define KL_FMC_BASE 0x4001f000 /* Flash memory controller */
+# define KL_FTFL_BASE 0x40020000 /* Flash memory */
+# define KL_DMAMUX0_BASE 0x40021000 /* DMA channel mutiplexer 0 */
+# define KL_CAN0_BASE 0x40024000 /* FlexCAN 0 */
+# define KL_SPI0_BASE 0x4002c000 /* SPI 0 */
+# define KL_SPI1_BASE 0x4002d000 /* SPI 1 */
+# define KL_I2S0_BASE 0x4002f000 /* I2S 0 */
+# define KL_CRC_BASE 0x40032000 /* CRC */
+# define KL_USBDCD_BASE 0x40035000 /* USB DCD */
+# define KL_PDB0_BASE 0x40036000 /* Programmable delay block */
+# define KL_PIT_BASE 0x40037000 /* Periodic interrupt timers (PIT) */
+# define KL_FTM0_BASE 0x40038000 /* FlexTimer 0 */
+# define KL_FTM1_BASE 0x40039000 /* FlexTimer 1 */
+# define KL_ADC0_BASE 0x4003b000 /* Analog-to-digital converter (ADC) 0 */
+# define KL_RTC_BASE 0x4003d000 /* Real time clock */
+# define KL_VBATR_BASE 0x4003e000 /* VBAT register file */
+# define KL_LPTMR_BASE 0x40040000 /* Low power timer */
+# define KL_SYSR_BASE 0x40041000 /* System register file */
+# define KL_DRYICE_BASE 0x40042000 /* DryIce */
+# define KL_DRYICESS_BASE 0x40043000 /* DryIce secure storage */
+# define KL_TSI0_BASE 0x40045000 /* Touch sense interface */
+# define KL_SIMLP_BASE 0x40047000 /* SIM low-power logic */
+# define KL_SIM_BASE 0x40048000 /* System integration module (SIM) */
+# define KL_PORT_BASE(n) (0x40049000 + ((n) << 12))
+# define KL_PORTA_BASE 0x40049000 /* Port A multiplexing control */
+# define KL_PORTB_BASE 0x4004a000 /* Port B multiplexing control */
+# define KL_PORTC_BASE 0x4004b000 /* Port C multiplexing control */
+# define KL_PORTD_BASE 0x4004c000 /* Port D multiplexing control */
+# define KL_PORTE_BASE 0x4004d000 /* Port E multiplexing control */
+# define KL_WDOG_BASE 0x40052000 /* Software watchdog */
+# define KL_EWM_BASE 0x40061000 /* External watchdog */
+# define KL_CMT_BASE 0x40062000 /* Carrier modulator timer (CMT) */
+# define KL_MCG_BASE 0x40064000 /* Multi-purpose Clock Generator (MCG) */
+# define KL_OSC_BASE 0x40065000 /* System oscillator (OSC) */
+# define KL_I2C0_BASE 0x40066000 /* I2C 0 */
+# define KL_I2C1_BASE 0x40067000 /* I2C 1 */
+# define KL_UART0_BASE 0x4006a000 /* UART0 */
+# define KL_UART1_BASE 0x4006b000 /* UART1 */
+# define KL_UART2_BASE 0x4006c000 /* UART2 */
+# define KL_UART3_BASE 0x4006d000 /* UART3 */
+# define KL_USB0_BASE 0x40072000 /* USB OTG FS/LS */
+# define KL_CMP_BASE 0x40073000 /* Analog comparator (CMP) / 6-bit digital-to-analog converter (DAC) */
+# define KL_VREF_BASE 0x40074000 /* Voltage reference (VREF) */
+# define KL_LLWU_BASE 0x4007c000 /* Low-leakage wakeup unit (LLWU) */
+# define KL_PMC_BASE 0x4007d000 /* Power management controller (PMC) */
+# define KL_SMC_BASE 0x4007e000 /* System Mode controller (SMC) */
+
+/* Peripheral Bridge 1 Memory Map ***************************************************/
+
+# define KL_AIPS1_BASE 0x40080000 /* Peripheral bridge 1 (AIPS-Lite 1) */
+# define KL_CAN1_BASE 0x400a4000 /* FlexCAN 1 */
+# define KL_SPI2_BASE 0x400ac000 /* SPI 2 */
+# define KL_SDHC_BASE 0x400b1000 /* SDHC */
+# define KL_FTM2_BASE 0x400b8000 /* FlexTimer 2 */
+# define KL_ADC1_BASE 0x400bb000 /* Analog-to-digital converter (ADC) 1 */
+# define KL_SLCD_BASE 0x400be000 /* Segment LCD */
+# define KL_DAC0_BASE 0x400cc000 /* 12-bit digital-to-analog converter (DAC) 0 */
+# define KL_DAC1_BASE 0x400cd000 /* 12-bit digital-to-analog converter (DAC) 1 */
+# define KL_UART4_BASE 0x400ea000 /* UART4 */
+# define KL_UART5_BASE 0x400eb000 /* UART5 */
+# define KL_XBARSS_BASE 0x400ff000 /* Not an AIPS-Lite slot. The 32-bit general
+ * purpose input/output module that shares the
+ * crossbar switch slave port with the AIPS-Lite
+ * is accessed at this address. */
+# define KL_GPIO_BASE(n) (0x400ff000 + ((n) << 6))
+# define KL_GPIOA_BASE 0x400ff000 /* GPIO PORTA registers */
+# define KL_GPIOB_BASE 0x400ff040 /* GPIO PORTB registers */
+# define KL_GPIOC_BASE 0x400ff080 /* GPIO PORTC registers */
+# define KL_GPIOD_BASE 0x400ff0c0 /* GPIO PORTD registers */
+# define KL_GPIOE_BASE 0x400ff100 /* GPIO PORTE registers */
+
+/* Private Peripheral Bus (PPB) Memory Map ******************************************/
+
+# define KL_ITM_BASE 0xe0000000 /* Instrumentation Trace Macrocell (ITM) */
+# define KL_DWT_BASE 0xe0001000 /* Data Watchpoint and Trace (DWT) */
+# define KL_FPB_BASE 0xe0002000 /* Flash Patch and Breakpoint (FPB) */
+# define KL_SCS_BASE 0xe000e000 /* System Control Space (SCS) (for NVIC) */
+# define KL_TPIU_BASE 0xe0040000 /* Trace Port Interface Unit (TPIU) */
+# define KL_ETM_BASE 0xe0041000 /* Embedded Trace Macrocell (ETM) */
+# define KL_ETB_BASE 0xe0042000 /* Embedded Trace Buffer (ETB) */
+# define KL_TFUN_BASE 0xe0043000 /* Embedded Trace Funnel */
+# define KL_MCM_BASE 0xe0080000 /* Miscellaneous Control Module (including ETB Almost Full) */
+# define KL_ROMTAB_BASE 0xe00ff000 /* ROM Table - allows auto-detection of debug components */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KL_KL_MEMORYMAP_H */
diff --git a/nuttx/arch/arm/src/kl/chip/kl_osc.h b/nuttx/arch/arm/src/kl/chip/kl_osc.h
new file mode 100644
index 000000000..8edef1e3c
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/kl_osc.h
@@ -0,0 +1,84 @@
+/********************************************************************************************
+ * arch/arm/src/kl/kl_osc.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ********************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_KL_OSC_H
+#define __ARCH_ARM_SRC_KL_KL_OSC_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+
+/* Register Offsets *************************************************************************/
+
+#define KL_OSC_CR_OFFSET 0x0000 /* OSC Control Register */
+
+/* Register Addresses ***********************************************************************/
+
+#define KL_OSC_CR (KL_OSC_BASE+KL_OSC_CR_OFFSET)
+
+/* Register Bit Definitions *****************************************************************/
+
+/* OSC Control Register (8-bit) */
+
+#define OSC_CR_ERCLKEN (1 << 7) /* Bit 7: External Reference Enable */
+ /* Bit 6: Reserved */
+#define OSC_CR_EREFSTEN (1 << 5) /* Bit 5: External Reference Stop Enable */
+ /* Bit 4: Reserved */
+#define OSC_CR_SC2P (1 << 3) /* Bit 3: Oscillator 2 pF Capacitor Load Configure */
+#define OSC_CR_SC4P (1 << 2) /* Bit 2: Oscillator 4 pF Capacitor Load Configure */
+#define OSC_CR_SC8P (1 << 1) /* Bit 1: Oscillator 8 pF Capacitor Load Configure */
+#define OSC_CR_SC16P (1 << 0) /* Bit 0: Oscillator 16 pF Capacitor Load Configure */
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KL_KL_OSC_H */
diff --git a/nuttx/arch/arm/src/kl/chip/kl_pinmux.h b/nuttx/arch/arm/src/kl/chip/kl_pinmux.h
new file mode 100644
index 000000000..dea0ebbe3
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/kl_pinmux.h
@@ -0,0 +1,69 @@
+/********************************************************************************************
+ * arch/arm/src/kl/kl_pinmux.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ********************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_KL_PINMUX_H
+#define __ARCH_ARM_SRC_KL_KL_PINMUX_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/* This file is just a wrapper around pin muxing header files for the Kinetis family selected
+ * by the logic in chip.h.
+ */
+
+#include "k25z120_pinmux.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KL_KL_PINMUX_H */
diff --git a/nuttx/arch/arm/src/kl/chip/kl_port.h b/nuttx/arch/arm/src/kl/chip/kl_port.h
new file mode 100644
index 000000000..3311cd4e2
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/kl_port.h
@@ -0,0 +1,431 @@
+/************************************************************************************
+ * arch/arm/src/kl/kl_port.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_KL_PORT_H
+#define __ARCH_ARM_SRC_KL_KL_PORT_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* General Definitions **************************************************************/
+
+#define KL_PORTA (0)
+#define KL_PORTB (1)
+#define KL_PORTC (2)
+#define KL_PORTD (3)
+#define KL_PORTE (4)
+#define KL_NPORTS (5)
+
+/* Register Offsets *****************************************************************/
+
+#define KL_PORT_PCR_OFFSET(n) ((n) << 2) /* Pin Control Register n, n=0..31 */
+#define KL_PORT_PCR0_OFFSET 0x0000 /* Pin Control Register 0 */
+#define KL_PORT_PCR1_OFFSET 0x0004 /* Pin Control Register 1 */
+#define KL_PORT_PCR2_OFFSET 0x0008 /* Pin Control Register 2 */
+#define KL_PORT_PCR3_OFFSET 0x000C /* Pin Control Register 3 */
+#define KL_PORT_PCR4_OFFSET 0x0010 /* Pin Control Register 4 */
+#define KL_PORT_PCR5_OFFSET 0x0014 /* Pin Control Register 5 */
+#define KL_PORT_PCR6_OFFSET 0x0018 /* Pin Control Register 6 */
+#define KL_PORT_PCR7_OFFSET 0x001c /* Pin Control Register 7 */
+#define KL_PORT_PCR8_OFFSET 0x0020 /* Pin Control Register 8 */
+#define KL_PORT_PCR9_OFFSET 0x0024 /* Pin Control Register 9 */
+#define KL_PORT_PCR10_OFFSET 0x0028 /* Pin Control Register 10 */
+#define KL_PORT_PCR11_OFFSET 0x002c /* Pin Control Register 11 */
+#define KL_PORT_PCR12_OFFSET 0x0030 /* Pin Control Register 12 */
+#define KL_PORT_PCR13_OFFSET 0x0034 /* Pin Control Register 13 */
+#define KL_PORT_PCR14_OFFSET 0x0038 /* Pin Control Register 14 */
+#define KL_PORT_PCR15_OFFSET 0x003c /* Pin Control Register 15 */
+#define KL_PORT_PCR16_OFFSET 0x0040 /* Pin Control Register 16 */
+#define KL_PORT_PCR17_OFFSET 0x0044 /* Pin Control Register 17 */
+#define KL_PORT_PCR18_OFFSET 0x0048 /* Pin Control Register 18 */
+#define KL_PORT_PCR19_OFFSET 0x004c /* Pin Control Register 19 */
+#define KL_PORT_PCR20_OFFSET 0x0050 /* Pin Control Register 20 */
+#define KL_PORT_PCR21_OFFSET 0x0054 /* Pin Control Register 21 */
+#define KL_PORT_PCR22_OFFSET 0x0058 /* Pin Control Register 22 */
+#define KL_PORT_PCR23_OFFSET 0x005c /* Pin Control Register 23 */
+#define KL_PORT_PCR24_OFFSET 0x0060 /* Pin Control Register 24 */
+#define KL_PORT_PCR25_OFFSET 0x0064 /* Pin Control Register 25 */
+#define KL_PORT_PCR26_OFFSET 0x0068 /* Pin Control Register 26 */
+#define KL_PORT_PCR27_OFFSET 0x006c /* Pin Control Register 27 */
+#define KL_PORT_PCR28_OFFSET 0x0070 /* Pin Control Register 28 */
+#define KL_PORT_PCR29_OFFSET 0x0074 /* Pin Control Register 29 */
+#define KL_PORT_PCR30_OFFSET 0x0078 /* Pin Control Register 30 */
+#define KL_PORT_PCR31_OFFSET 0x007c /* Pin Control Register 31 */
+#define KL_PORT_GPCLR_OFFSET 0x0080 /* Global Pin Control Low Register */
+#define KL_PORT_GPCHR_OFFSET 0x0084 /* Global Pin Control High Register */
+#define KL_PORT_ISFR_OFFSET 0x00a0 /* Interrupt Status Flag Register */
+#define KL_PORT_DFER_OFFSET 0x00c0 /* Digital Filter Enable Register */
+#define KL_PORT_DFCR_OFFSET 0x00c4 /* Digital Filter Clock Register */
+#define KL_PORT_DFWR_OFFSET 0x00c8 /* Digital Filter Width Register */
+
+/* Register Addresses ***************************************************************/
+
+#define KL_PORT_PCR(p,n) (KL_PORT_BASE(p)+KL_PORT_PCR_OFFSET(n)
+#define KL_PORT_PCR0(p) (KL_PORT_BASE(p)+KL_PORT_PCR0_OFFSET)
+#define KL_PORT_PCR1(p) (KL_PORT_BASE(p)+KL_PORT_PCR1_OFFSET)
+#define KL_PORT_PCR2(p) (KL_PORT_BASE(p)+KL_PORT_PCR2_OFFSET)
+#define KL_PORT_PCR3(p) (KL_PORT_BASE(p)+KL_PORT_PCR3_OFFSET)
+#define KL_PORT_PCR4(p) (KL_PORT_BASE(p)+KL_PORT_PCR4_OFFSET)
+#define KL_PORT_PCR5(p) (KL_PORT_BASE(p)+KL_PORT_PCR5_OFFSET)
+#define KL_PORT_PCR6(p) (KL_PORT_BASE(p)+KL_PORT_PCR6_OFFSET)
+#define KL_PORT_PCR7(p) (KL_PORT_BASE(p)+KL_PORT_PCR7_OFFSET)
+#define KL_PORT_PCR8(p) (KL_PORT_BASE(p)+KL_PORT_PCR8_OFFSET)
+#define KL_PORT_PCR9(p) (KL_PORT_BASE(p)+KL_PORT_PCR9_OFFSET)
+#define KL_PORT_PCR10(p) (KL_PORT_BASE(p)+KL_PORT_PCR10_OFFSET)
+#define KL_PORT_PCR11(p) (KL_PORT_BASE(p)+KL_PORT_PCR11_OFFSET)
+#define KL_PORT_PCR12(p) (KL_PORT_BASE(p)+KL_PORT_PCR12_OFFSET)
+#define KL_PORT_PCR13(p) (KL_PORT_BASE(p)+KL_PORT_PCR13_OFFSET)
+#define KL_PORT_PCR14(p) (KL_PORT_BASE(p)+KL_PORT_PCR14_OFFSET)
+#define KL_PORT_PCR15(p) (KL_PORT_BASE(p)+KL_PORT_PCR15_OFFSET)
+#define KL_PORT_PCR16(p) (KL_PORT_BASE(p)+KL_PORT_PCR16_OFFSET)
+#define KL_PORT_PCR17(p) (KL_PORT_BASE(p)+KL_PORT_PCR17_OFFSET)
+#define KL_PORT_PCR18(p) (KL_PORT_BASE(p)+KL_PORT_PCR18_OFFSET)
+#define KL_PORT_PCR19(p) (KL_PORT_BASE(p)+KL_PORT_PCR19_OFFSET)
+#define KL_PORT_PCR20(p) (KL_PORT_BASE(p)+KL_PORT_PCR20_OFFSET)
+#define KL_PORT_PCR21(p) (KL_PORT_BASE(p)+KL_PORT_PCR21_OFFSET)
+#define KL_PORT_PCR22(p) (KL_PORT_BASE(p)+KL_PORT_PCR22_OFFSET)
+#define KL_PORT_PCR23(p) (KL_PORT_BASE(p)+KL_PORT_PCR23_OFFSET)
+#define KL_PORT_PCR24(p) (KL_PORT_BASE(p)+KL_PORT_PCR24_OFFSET)
+#define KL_PORT_PCR25(p) (KL_PORT_BASE(p)+KL_PORT_PCR25_OFFSET)
+#define KL_PORT_PCR26(p) (KL_PORT_BASE(p)+KL_PORT_PCR26_OFFSET)
+#define KL_PORT_PCR27(p) (KL_PORT_BASE(p)+KL_PORT_PCR27_OFFSET)
+#define KL_PORT_PCR28(p) (KL_PORT_BASE(p)+KL_PORT_PCR28_OFFSET)
+#define KL_PORT_PCR29(p) (KL_PORT_BASE(p)+KL_PORT_PCR29_OFFSET)
+#define KL_PORT_PCR30(p) (KL_PORT_BASE(p)+KL_PORT_PCR30_OFFSET)
+#define KL_PORT_PCR31(p) (KL_PORT_BASE(p)+KL_PORT_PCR31_OFFSET)
+#define KL_PORT_GPCLR(p) (KL_PORT_BASE(p)+KL_PORT_GPCLR_OFFSET)
+#define KL_PORT_GPCHR(p) (KL_PORT_BASE(p)+KL_PORT_GPCHR_OFFSET)
+#define KL_PORT_ISFR(p) (KL_PORT_BASE(p)+KL_PORT_ISFR_OFFSET)
+#define KL_PORT_DFER(p) (KL_PORT_BASE(p)+KL_PORT_DFER_OFFSET)
+#define KL_PORT_DFCR(p) (KL_PORT_BASE(p)+KL_PORT_DFCR_OFFSET)
+#define KL_PORT_DFWR(p) (KL_PORT_BASE(p)+KL_PORT_DFWR_OFFSET)
+
+#define KL_PORTA_PCR(n) (KL_PORTA_BASE+KL_PORT_PCR_OFFSET(n)
+#define KL_PORTA_PCR0 (KL_PORTA_BASE+KL_PORT_PCR0_OFFSET)
+#define KL_PORTA_PCR1 (KL_PORTA_BASE+KL_PORT_PCR1_OFFSET)
+#define KL_PORTA_PCR2 (KL_PORTA_BASE+KL_PORT_PCR2_OFFSET)
+#define KL_PORTA_PCR3 (KL_PORTA_BASE+KL_PORT_PCR3_OFFSET)
+#define KL_PORTA_PCR4 (KL_PORTA_BASE+KL_PORT_PCR4_OFFSET)
+#define KL_PORTA_PCR5 (KL_PORTA_BASE+KL_PORT_PCR5_OFFSET)
+#define KL_PORTA_PCR6 (KL_PORTA_BASE+KL_PORT_PCR6_OFFSET)
+#define KL_PORTA_PCR7 (KL_PORTA_BASE+KL_PORT_PCR7_OFFSET)
+#define KL_PORTA_PCR8 (KL_PORTA_BASE+KL_PORT_PCR8_OFFSET)
+#define KL_PORTA_PCR9 (KL_PORTA_BASE+KL_PORT_PCR9_OFFSET)
+#define KL_PORTA_PCR10 (KL_PORTA_BASE+KL_PORT_PCR10_OFFSET)
+#define KL_PORTA_PCR11 (KL_PORTA_BASE+KL_PORT_PCR11_OFFSET)
+#define KL_PORTA_PCR12 (KL_PORTA_BASE+KL_PORT_PCR12_OFFSET)
+#define KL_PORTA_PCR13 (KL_PORTA_BASE+KL_PORT_PCR13_OFFSET)
+#define KL_PORTA_PCR14 (KL_PORTA_BASE+KL_PORT_PCR14_OFFSET)
+#define KL_PORTA_PCR15 (KL_PORTA_BASE+KL_PORT_PCR15_OFFSET)
+#define KL_PORTA_PCR16 (KL_PORTA_BASE+KL_PORT_PCR16_OFFSET)
+#define KL_PORTA_PCR17 (KL_PORTA_BASE+KL_PORT_PCR17_OFFSET)
+#define KL_PORTA_PCR18 (KL_PORTA_BASE+KL_PORT_PCR18_OFFSET)
+#define KL_PORTA_PCR19 (KL_PORTA_BASE+KL_PORT_PCR19_OFFSET)
+#define KL_PORTA_PCR20 (KL_PORTA_BASE+KL_PORT_PCR20_OFFSET)
+#define KL_PORTA_PCR21 (KL_PORTA_BASE+KL_PORT_PCR21_OFFSET)
+#define KL_PORTA_PCR22 (KL_PORTA_BASE+KL_PORT_PCR22_OFFSET)
+#define KL_PORTA_PCR23 (KL_PORTA_BASE+KL_PORT_PCR23_OFFSET)
+#define KL_PORTA_PCR24 (KL_PORTA_BASE+KL_PORT_PCR24_OFFSET)
+#define KL_PORTA_PCR25 (KL_PORTA_BASE+KL_PORT_PCR25_OFFSET)
+#define KL_PORTA_PCR26 (KL_PORTA_BASE+KL_PORT_PCR26_OFFSET)
+#define KL_PORTA_PCR27 (KL_PORTA_BASE+KL_PORT_PCR27_OFFSET)
+#define KL_PORTA_PCR28 (KL_PORTA_BASE+KL_PORT_PCR28_OFFSET)
+#define KL_PORTA_PCR29 (KL_PORTA_BASE+KL_PORT_PCR29_OFFSET)
+#define KL_PORTA_PCR30 (KL_PORTA_BASE+KL_PORT_PCR30_OFFSET)
+#define KL_PORTA_PCR31 (KL_PORTA_BASE+KL_PORT_PCR31_OFFSET)
+#define KL_PORTA_GPCLR (KL_PORTA_BASE+KL_PORT_GPCLR_OFFSET)
+#define KL_PORTA_GPCHR (KL_PORTA_BASE+KL_PORT_GPCHR_OFFSET)
+#define KL_PORTA_ISFR (KL_PORTA_BASE+KL_PORT_ISFR_OFFSET)
+#define KL_PORTA_DFER (KL_PORTA_BASE+KL_PORT_DFER_OFFSET)
+#define KL_PORTA_DFCR (KL_PORTA_BASE+KL_PORT_DFCR_OFFSET)
+#define KL_PORTA_DFWR (KL_PORTA_BASE+KL_PORT_DFWR_OFFSET)
+
+#define KL_PORTB_PCR(n) (KL_PORTB_BASE+KL_PORT_PCR_OFFSET(n)
+#define KL_PORTB_PCR0 (KL_PORTB_BASE+KL_PORT_PCR0_OFFSET)
+#define KL_PORTB_PCR1 (KL_PORTB_BASE+KL_PORT_PCR1_OFFSET)
+#define KL_PORTB_PCR2 (KL_PORTB_BASE+KL_PORT_PCR2_OFFSET)
+#define KL_PORTB_PCR3 (KL_PORTB_BASE+KL_PORT_PCR3_OFFSET)
+#define KL_PORTB_PCR4 (KL_PORTB_BASE+KL_PORT_PCR4_OFFSET)
+#define KL_PORTB_PCR5 (KL_PORTB_BASE+KL_PORT_PCR5_OFFSET)
+#define KL_PORTB_PCR6 (KL_PORTB_BASE+KL_PORT_PCR6_OFFSET)
+#define KL_PORTB_PCR7 (KL_PORTB_BASE+KL_PORT_PCR7_OFFSET)
+#define KL_PORTB_PCR8 (KL_PORTB_BASE+KL_PORT_PCR8_OFFSET)
+#define KL_PORTB_PCR9 (KL_PORTB_BASE+KL_PORT_PCR9_OFFSET)
+#define KL_PORTB_PCR10 (KL_PORTB_BASE+KL_PORT_PCR10_OFFSET)
+#define KL_PORTB_PCR11 (KL_PORTB_BASE+KL_PORT_PCR11_OFFSET)
+#define KL_PORTB_PCR12 (KL_PORTB_BASE+KL_PORT_PCR12_OFFSET)
+#define KL_PORTB_PCR13 (KL_PORTB_BASE+KL_PORT_PCR13_OFFSET)
+#define KL_PORTB_PCR14 (KL_PORTB_BASE+KL_PORT_PCR14_OFFSET)
+#define KL_PORTB_PCR15 (KL_PORTB_BASE+KL_PORT_PCR15_OFFSET)
+#define KL_PORTB_PCR16 (KL_PORTB_BASE+KL_PORT_PCR16_OFFSET)
+#define KL_PORTB_PCR17 (KL_PORTB_BASE+KL_PORT_PCR17_OFFSET)
+#define KL_PORTB_PCR18 (KL_PORTB_BASE+KL_PORT_PCR18_OFFSET)
+#define KL_PORTB_PCR19 (KL_PORTB_BASE+KL_PORT_PCR19_OFFSET)
+#define KL_PORTB_PCR20 (KL_PORTB_BASE+KL_PORT_PCR20_OFFSET)
+#define KL_PORTB_PCR21 (KL_PORTB_BASE+KL_PORT_PCR21_OFFSET)
+#define KL_PORTB_PCR22 (KL_PORTB_BASE+KL_PORT_PCR22_OFFSET)
+#define KL_PORTB_PCR23 (KL_PORTB_BASE+KL_PORT_PCR23_OFFSET)
+#define KL_PORTB_PCR24 (KL_PORTB_BASE+KL_PORT_PCR24_OFFSET)
+#define KL_PORTB_PCR25 (KL_PORTB_BASE+KL_PORT_PCR25_OFFSET)
+#define KL_PORTB_PCR26 (KL_PORTB_BASE+KL_PORT_PCR26_OFFSET)
+#define KL_PORTB_PCR27 (KL_PORTB_BASE+KL_PORT_PCR27_OFFSET)
+#define KL_PORTB_PCR28 (KL_PORTB_BASE+KL_PORT_PCR28_OFFSET)
+#define KL_PORTB_PCR29 (KL_PORTB_BASE+KL_PORT_PCR29_OFFSET)
+#define KL_PORTB_PCR30 (KL_PORTB_BASE+KL_PORT_PCR30_OFFSET)
+#define KL_PORTB_PCR31 (KL_PORTB_BASE+KL_PORT_PCR31_OFFSET)
+#define KL_PORTB_GPCLR (KL_PORTB_BASE+KL_PORT_GPCLR_OFFSET)
+#define KL_PORTB_GPCHR (KL_PORTB_BASE+KL_PORT_GPCHR_OFFSET)
+#define KL_PORTB_ISFR (KL_PORTB_BASE+KL_PORT_ISFR_OFFSET)
+#define KL_PORTB_DFER (KL_PORTB_BASE+KL_PORT_DFER_OFFSET)
+#define KL_PORTB_DFCR (KL_PORTB_BASE+KL_PORT_DFCR_OFFSET)
+#define KL_PORTB_DFWR (KL_PORTB_BASE+KL_PORT_DFWR_OFFSET)
+
+#define KL_PORTC_PCR(n) (KL_PORTC_BASE+KL_PORT_PCR_OFFSET(n)
+#define KL_PORTC_PCR0 (KL_PORTC_BASE+KL_PORT_PCR0_OFFSET)
+#define KL_PORTC_PCR1 (KL_PORTC_BASE+KL_PORT_PCR1_OFFSET)
+#define KL_PORTC_PCR2 (KL_PORTC_BASE+KL_PORT_PCR2_OFFSET)
+#define KL_PORTC_PCR3 (KL_PORTC_BASE+KL_PORT_PCR3_OFFSET)
+#define KL_PORTC_PCR4 (KL_PORTC_BASE+KL_PORT_PCR4_OFFSET)
+#define KL_PORTC_PCR5 (KL_PORTC_BASE+KL_PORT_PCR5_OFFSET)
+#define KL_PORTC_PCR6 (KL_PORTC_BASE+KL_PORT_PCR6_OFFSET)
+#define KL_PORTC_PCR7 (KL_PORTC_BASE+KL_PORT_PCR7_OFFSET)
+#define KL_PORTC_PCR8 (KL_PORTC_BASE+KL_PORT_PCR8_OFFSET)
+#define KL_PORTC_PCR9 (KL_PORTC_BASE+KL_PORT_PCR9_OFFSET)
+#define KL_PORTC_PCR10 (KL_PORTC_BASE+KL_PORT_PCR10_OFFSET)
+#define KL_PORTC_PCR11 (KL_PORTC_BASE+KL_PORT_PCR11_OFFSET)
+#define KL_PORTC_PCR12 (KL_PORTC_BASE+KL_PORT_PCR12_OFFSET)
+#define KL_PORTC_PCR13 (KL_PORTC_BASE+KL_PORT_PCR13_OFFSET)
+#define KL_PORTC_PCR14 (KL_PORTC_BASE+KL_PORT_PCR14_OFFSET)
+#define KL_PORTC_PCR15 (KL_PORTC_BASE+KL_PORT_PCR15_OFFSET)
+#define KL_PORTC_PCR16 (KL_PORTC_BASE+KL_PORT_PCR16_OFFSET)
+#define KL_PORTC_PCR17 (KL_PORTC_BASE+KL_PORT_PCR17_OFFSET)
+#define KL_PORTC_PCR18 (KL_PORTC_BASE+KL_PORT_PCR18_OFFSET)
+#define KL_PORTC_PCR19 (KL_PORTC_BASE+KL_PORT_PCR19_OFFSET)
+#define KL_PORTC_PCR20 (KL_PORTC_BASE+KL_PORT_PCR20_OFFSET)
+#define KL_PORTC_PCR21 (KL_PORTC_BASE+KL_PORT_PCR21_OFFSET)
+#define KL_PORTC_PCR22 (KL_PORTC_BASE+KL_PORT_PCR22_OFFSET)
+#define KL_PORTC_PCR23 (KL_PORTC_BASE+KL_PORT_PCR23_OFFSET)
+#define KL_PORTC_PCR24 (KL_PORTC_BASE+KL_PORT_PCR24_OFFSET)
+#define KL_PORTC_PCR25 (KL_PORTC_BASE+KL_PORT_PCR25_OFFSET)
+#define KL_PORTC_PCR26 (KL_PORTC_BASE+KL_PORT_PCR26_OFFSET)
+#define KL_PORTC_PCR27 (KL_PORTC_BASE+KL_PORT_PCR27_OFFSET)
+#define KL_PORTC_PCR28 (KL_PORTC_BASE+KL_PORT_PCR28_OFFSET)
+#define KL_PORTC_PCR29 (KL_PORTC_BASE+KL_PORT_PCR29_OFFSET)
+#define KL_PORTC_PCR30 (KL_PORTC_BASE+KL_PORT_PCR30_OFFSET)
+#define KL_PORTC_PCR31 (KL_PORTC_BASE+KL_PORT_PCR31_OFFSET)
+#define KL_PORTC_GPCLR (KL_PORTC_BASE+KL_PORT_GPCLR_OFFSET)
+#define KL_PORTC_GPCHR (KL_PORTC_BASE+KL_PORT_GPCHR_OFFSET)
+#define KL_PORTC_ISFR (KL_PORTC_BASE+KL_PORT_ISFR_OFFSET)
+#define KL_PORTC_DFER (KL_PORTC_BASE+KL_PORT_DFER_OFFSET)
+#define KL_PORTC_DFCR (KL_PORTC_BASE+KL_PORT_DFCR_OFFSET)
+#define KL_PORTC_DFWR (KL_PORTC_BASE+KL_PORT_DFWR_OFFSET)
+
+#define KL_PORTD_PCR(n) (KL_PORTD_BASE+KL_PORT_PCR_OFFSET(n)
+#define KL_PORTD_PCR0 (KL_PORTD_BASE+KL_PORT_PCR0_OFFSET)
+#define KL_PORTD_PCR1 (KL_PORTD_BASE+KL_PORT_PCR1_OFFSET)
+#define KL_PORTD_PCR2 (KL_PORTD_BASE+KL_PORT_PCR2_OFFSET)
+#define KL_PORTD_PCR3 (KL_PORTD_BASE+KL_PORT_PCR3_OFFSET)
+#define KL_PORTD_PCR4 (KL_PORTD_BASE+KL_PORT_PCR4_OFFSET)
+#define KL_PORTD_PCR5 (KL_PORTD_BASE+KL_PORT_PCR5_OFFSET)
+#define KL_PORTD_PCR6 (KL_PORTD_BASE+KL_PORT_PCR6_OFFSET)
+#define KL_PORTD_PCR7 (KL_PORTD_BASE+KL_PORT_PCR7_OFFSET)
+#define KL_PORTD_PCR8 (KL_PORTD_BASE+KL_PORT_PCR8_OFFSET)
+#define KL_PORTD_PCR9 (KL_PORTD_BASE+KL_PORT_PCR9_OFFSET)
+#define KL_PORTD_PCR10 (KL_PORTD_BASE+KL_PORT_PCR10_OFFSET)
+#define KL_PORTD_PCR11 (KL_PORTD_BASE+KL_PORT_PCR11_OFFSET)
+#define KL_PORTD_PCR12 (KL_PORTD_BASE+KL_PORT_PCR12_OFFSET)
+#define KL_PORTD_PCR13 (KL_PORTD_BASE+KL_PORT_PCR13_OFFSET)
+#define KL_PORTD_PCR14 (KL_PORTD_BASE+KL_PORT_PCR14_OFFSET)
+#define KL_PORTD_PCR15 (KL_PORTD_BASE+KL_PORT_PCR15_OFFSET)
+#define KL_PORTD_PCR16 (KL_PORTD_BASE+KL_PORT_PCR16_OFFSET)
+#define KL_PORTD_PCR17 (KL_PORTD_BASE+KL_PORT_PCR17_OFFSET)
+#define KL_PORTD_PCR18 (KL_PORTD_BASE+KL_PORT_PCR18_OFFSET)
+#define KL_PORTD_PCR19 (KL_PORTD_BASE+KL_PORT_PCR19_OFFSET)
+#define KL_PORTD_PCR20 (KL_PORTD_BASE+KL_PORT_PCR20_OFFSET)
+#define KL_PORTD_PCR21 (KL_PORTD_BASE+KL_PORT_PCR21_OFFSET)
+#define KL_PORTD_PCR22 (KL_PORTD_BASE+KL_PORT_PCR22_OFFSET)
+#define KL_PORTD_PCR23 (KL_PORTD_BASE+KL_PORT_PCR23_OFFSET)
+#define KL_PORTD_PCR24 (KL_PORTD_BASE+KL_PORT_PCR24_OFFSET)
+#define KL_PORTD_PCR25 (KL_PORTD_BASE+KL_PORT_PCR25_OFFSET)
+#define KL_PORTD_PCR26 (KL_PORTD_BASE+KL_PORT_PCR26_OFFSET)
+#define KL_PORTD_PCR27 (KL_PORTD_BASE+KL_PORT_PCR27_OFFSET)
+#define KL_PORTD_PCR28 (KL_PORTD_BASE+KL_PORT_PCR28_OFFSET)
+#define KL_PORTD_PCR29 (KL_PORTD_BASE+KL_PORT_PCR29_OFFSET)
+#define KL_PORTD_PCR30 (KL_PORTD_BASE+KL_PORT_PCR30_OFFSET)
+#define KL_PORTD_PCR31 (KL_PORTD_BASE+KL_PORT_PCR31_OFFSET)
+#define KL_PORTD_GPCLR (KL_PORTD_BASE+KL_PORT_GPCLR_OFFSET)
+#define KL_PORTD_GPCHR (KL_PORTD_BASE+KL_PORT_GPCHR_OFFSET)
+#define KL_PORTD_ISFR (KL_PORTD_BASE+KL_PORT_ISFR_OFFSET)
+#define KL_PORTD_DFER (KL_PORTD_BASE+KL_PORT_DFER_OFFSET)
+#define KL_PORTD_DFCR (KL_PORTD_BASE+KL_PORT_DFCR_OFFSET)
+#define KL_PORTD_DFWR (KL_PORTD_BASE+KL_PORT_DFWR_OFFSET)
+
+#define KL_PORTE_PCR(n) (KL_PORTE_BASE+KL_PORT_PCR_OFFSET(n)
+#define KL_PORTE_PCR0 (KL_PORTE_BASE+KL_PORT_PCR0_OFFSET)
+#define KL_PORTE_PCR1 (KL_PORTE_BASE+KL_PORT_PCR1_OFFSET)
+#define KL_PORTE_PCR2 (KL_PORTE_BASE+KL_PORT_PCR2_OFFSET)
+#define KL_PORTE_PCR3 (KL_PORTE_BASE+KL_PORT_PCR3_OFFSET)
+#define KL_PORTE_PCR4 (KL_PORTE_BASE+KL_PORT_PCR4_OFFSET)
+#define KL_PORTE_PCR5 (KL_PORTE_BASE+KL_PORT_PCR5_OFFSET)
+#define KL_PORTE_PCR6 (KL_PORTE_BASE+KL_PORT_PCR6_OFFSET)
+#define KL_PORTE_PCR7 (KL_PORTE_BASE+KL_PORT_PCR7_OFFSET)
+#define KL_PORTE_PCR8 (KL_PORTE_BASE+KL_PORT_PCR8_OFFSET)
+#define KL_PORTE_PCR9 (KL_PORTE_BASE+KL_PORT_PCR9_OFFSET)
+#define KL_PORTE_PCR10 (KL_PORTE_BASE+KL_PORT_PCR10_OFFSET)
+#define KL_PORTE_PCR11 (KL_PORTE_BASE+KL_PORT_PCR11_OFFSET)
+#define KL_PORTE_PCR12 (KL_PORTE_BASE+KL_PORT_PCR12_OFFSET)
+#define KL_PORTE_PCR13 (KL_PORTE_BASE+KL_PORT_PCR13_OFFSET)
+#define KL_PORTE_PCR14 (KL_PORTE_BASE+KL_PORT_PCR14_OFFSET)
+#define KL_PORTE_PCR15 (KL_PORTE_BASE+KL_PORT_PCR15_OFFSET)
+#define KL_PORTE_PCR16 (KL_PORTE_BASE+KL_PORT_PCR16_OFFSET)
+#define KL_PORTE_PCR17 (KL_PORTE_BASE+KL_PORT_PCR17_OFFSET)
+#define KL_PORTE_PCR18 (KL_PORTE_BASE+KL_PORT_PCR18_OFFSET)
+#define KL_PORTE_PCR19 (KL_PORTE_BASE+KL_PORT_PCR19_OFFSET)
+#define KL_PORTE_PCR20 (KL_PORTE_BASE+KL_PORT_PCR20_OFFSET)
+#define KL_PORTE_PCR21 (KL_PORTE_BASE+KL_PORT_PCR21_OFFSET)
+#define KL_PORTE_PCR22 (KL_PORTE_BASE+KL_PORT_PCR22_OFFSET)
+#define KL_PORTE_PCR23 (KL_PORTE_BASE+KL_PORT_PCR23_OFFSET)
+#define KL_PORTE_PCR24 (KL_PORTE_BASE+KL_PORT_PCR24_OFFSET)
+#define KL_PORTE_PCR25 (KL_PORTE_BASE+KL_PORT_PCR25_OFFSET)
+#define KL_PORTE_PCR26 (KL_PORTE_BASE+KL_PORT_PCR26_OFFSET)
+#define KL_PORTE_PCR27 (KL_PORTE_BASE+KL_PORT_PCR27_OFFSET)
+#define KL_PORTE_PCR28 (KL_PORTE_BASE+KL_PORT_PCR28_OFFSET)
+#define KL_PORTE_PCR29 (KL_PORTE_BASE+KL_PORT_PCR29_OFFSET)
+#define KL_PORTE_PCR30 (KL_PORTE_BASE+KL_PORT_PCR30_OFFSET)
+#define KL_PORTE_PCR31 (KL_PORTE_BASE+KL_PORT_PCR31_OFFSET)
+#define KL_PORTE_GPCLR (KL_PORTE_BASE+KL_PORT_GPCLR_OFFSET)
+#define KL_PORTE_GPCHR (KL_PORTE_BASE+KL_PORT_GPCHR_OFFSET)
+#define KL_PORTE_ISFR (KL_PORTE_BASE+KL_PORT_ISFR_OFFSET)
+#define KL_PORTE_DFER (KL_PORTE_BASE+KL_PORT_DFER_OFFSET)
+#define KL_PORTE_DFCR (KL_PORTE_BASE+KL_PORT_DFCR_OFFSET)
+#define KL_PORTE_DFWR (KL_PORTE_BASE+KL_PORT_DFWR_OFFSET)
+
+/* Register Bit Definitions *********************************************************/
+/* Pin Control Register n, n=0..31 */
+
+#define PORT_PCR_PS (1 << 0) /* Bit 0: Pull Select */
+#define PORT_PCR_PE (1 << 1) /* Bit 1: Pull Enable */
+#define PORT_PCR_SRE (1 << 2) /* Bit 2: Slew Rate Enable */
+ /* Bit 3: Reserved */
+#define PORT_PCR_PFE (1 << 4) /* Bit 4: Passive Filter Enable */
+#define PORT_PCR_ODE (1 << 5) /* Bit 5: Open Drain Enable */
+#define PORT_PCR_DSE (1 << 6) /* Bit 6: Drive Strength Enable */
+ /* Bit 7: Reserved */
+#define PORT_PCR_MUX_SHIFT (8) /* Bits 8-10: Pin Mux Control */
+#define PORT_PCR_MUX_MASK (7 << PORT_PCR_MUX_SHIFT)
+# define PORT_PCR_MUX_ANALOG (0 << PORT_PCR_MUX_SHIFT) /* Pin Disabled (Analog) */
+# define PORT_PCR_MUX_GPIO (1 << PORT_PCR_MUX_SHIFT) /* Alternative 1 (GPIO) */
+# define PORT_PCR_MUX_ALT1 (1 << PORT_PCR_MUX_SHIFT) /* Alternative 1 (GPIO) */
+# define PORT_PCR_MUX_ALT2 (2 << PORT_PCR_MUX_SHIFT) /* Alternative 2 (chip specific) */
+# define PORT_PCR_MUX_ALT3 (3 << PORT_PCR_MUX_SHIFT) /* Alternative 3 (chip specific) */
+# define PORT_PCR_MUX_ALT4 (4 << PORT_PCR_MUX_SHIFT) /* Alternative 4 (chip specific) */
+# define PORT_PCR_MUX_ALT5 (5 << PORT_PCR_MUX_SHIFT) /* Alternative 5 (chip specific) */
+# define PORT_PCR_MUX_ALT6 (6 << PORT_PCR_MUX_SHIFT) /* Alternative 6 (chip specific) */
+# define PORT_PCR_MUX_ALT7 (7 << PORT_PCR_MUX_SHIFT) /* Alternative 7 (chip specific / JTAG / NMI) */
+ /* Bits 11-14: Reserved */
+#define PORT_PCR_LK (1 << 15) /* Bit 15: Lock Register */
+#define PORT_PCR_IRQC_SHIFT (16) /* Bits 16-19: Interrupt Configuration */
+#define PORT_PCR_IRQC_MASK (15 << PORT_PCR_IRQC_SHIFT)
+# define PORT_PCR_IRQC_DISABLED (0 << PORT_PCR_IRQC_SHIFT) /* Interrupt/DMA Request disabled */
+# define PORT_PCR_IRQC_DMARISING (1 << PORT_PCR_IRQC_SHIFT) /* DMA Request on rising edge */
+# define PORT_PCR_IRQC_DMAFALLING (2 << PORT_PCR_IRQC_SHIFT) /* DMA Request on falling edge */
+# define PORT_PCR_IRQC_DMABOTH (3 << PORT_PCR_IRQC_SHIFT) /* DMA Request on either edge */
+# define PORT_PCR_IRQC_ZERO (8 << PORT_PCR_IRQC_SHIFT) /* Interrupt when logic zero */
+# define PORT_PCR_IRQC_RISING (9 << PORT_PCR_IRQC_SHIFT) /* Interrupt on rising edge */
+# define PORT_PCR_IRQC_FALLING (10 << PORT_PCR_IRQC_SHIFT) /* Interrupt on falling edge */
+# define PORT_PCR_IRQC_BOTH (11 << PORT_PCR_IRQC_SHIFT) /* Interrupt on either edge */
+# define PORT_PCR_IRQC_ONE (12 << PORT_PCR_IRQC_SHIFT) /* Interrupt when logic one */
+ /* Bits 20-23: Reserved */
+#define PORT_PCR_ISF (1 << 24) /* Bit 24: Interrupt Status Flag */
+ /* Bits 25-31: Reserved */
+
+/* Global Pin Control Low Register */
+
+#define PORT_GPCLR_GPWD_SHIFT (0) /* Bits 0-15: Global Pin Write Data */
+#define PORT_GPCLR_GPWD_MASK (0xffff << PORT_GPCLR_GPWD_SHIFT)
+# define PORT_GPCLR_GPWD(n) ((1 << (n)) << PORT_GPCLR_GPWD_SHIFT)
+#define PORT_GPCLR_GPWE_SHIFT (16) /* Bits 16-31: Global Pin Write Enable */
+#define PORT_GPCLR_GPWE_MASK (0xffff << PORT_GPCLR_GPWE_SHIFT)
+# define PORT_GPCLR_GPWE(n) ((1 << (n)) << PORT_GPCLR_GPWE_SHIFT)
+
+/* Global Pin Control High Register */
+
+#define PORT_GPCHR_
+
+#define PORT_GPCHR_GPWD_SHIFT (0) /* Bits 0-15: Global Pin Write Data */
+#define PORT_GPCHR_GPWD_MASK (0xffff << PORT_GPCHR_GPWD_SHIFT)
+# define PORT_GPCHR_GPWD(n) ((1 << (n)) << PORT_GPCHR_GPWD_SHIFT)
+#define PORT_GPCHR_GPWE_SHIFT (16) /* Bits 16-31: Global Pin Write Enable */
+#define PORT_GPCHR_GPWE_MASK (0xffff << PORT_GPCHR_GPWE_SHIFT)
+# define PORT_GPCHR_GPWE(n) ((1 << (n)) << PORT_GPCHR_GPWE_SHIFT)
+
+/* Interrupt Status Flag Register */
+
+#define PORT_ISFR(n) (1 << (n))
+
+/* Digital Filter Enable Register */
+
+#define PORT_DFER(n) (1 << (n))
+
+/* Digital Filter Clock Register */
+
+#define PORT_DFCR_CS (1 << 0) /* Bit 0: Clock Source */
+
+/* Digital Filter Width Register */
+
+#define PORT_DFWR_FILT_SHIFT (0) /* Bits 0-4: Filter Length */
+#define PORT_DFWR_FILT_MASK (31 << PORT_DFWR_FILT_SHIFT)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KL_KL_PORT_H */
diff --git a/nuttx/arch/arm/src/kl/chip/kl_sim.h b/nuttx/arch/arm/src/kl/chip/kl_sim.h
new file mode 100644
index 000000000..65f1428f9
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/kl_sim.h
@@ -0,0 +1,542 @@
+/************************************************************************************
+ * arch/arm/src/kl/kl_sim.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_KL_SIM_H
+#define __ARCH_ARM_SRC_KL_KL_SIM_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register Offsets *****************************************************************/
+
+#define KL_SIM_SOPT1_OFFSET 0x0000 /* System Options Register 1 */
+#define KL_SIM_SOPT2_OFFSET 0x0004 /* System Options Register 2 */
+#define KL_SIM_SOPT4_OFFSET 0x000c /* System Options Register 4 */
+#define KL_SIM_SOPT5_OFFSET 0x0010 /* System Options Register 5 */
+#define KL_SIM_SOPT6_OFFSET 0x0014 /* System Options Register 6 */
+#define KL_SIM_SOPT7_OFFSET 0x0018 /* System Options Register 7 */
+#define KL_SIM_SDID_OFFSET 0x0024 /* System Device Identification Register */
+#define KL_SIM_SCGC1_OFFSET 0x0028 /* System Clock Gating Control Register 1 */
+#define KL_SIM_SCGC2_OFFSET 0x002c /* System Clock Gating Control Register 2 */
+#define KL_SIM_SCGC3_OFFSET 0x0030 /* System Clock Gating Control Register 3 */
+#define KL_SIM_SCGC4_OFFSET 0x0034 /* System Clock Gating Control Register 4 */
+#define KL_SIM_SCGC5_OFFSET 0x0038 /* System Clock Gating Control Register 5 */
+#define KL_SIM_SCGC6_OFFSET 0x003c /* System Clock Gating Control Register 6 */
+#define KL_SIM_SCGC7_OFFSET 0x0040 /* System Clock Gating Control Register 7 */
+#define KL_SIM_CLKDIV1_OFFSET 0x0044 /* System Clock Divider Register 1 */
+#define KL_SIM_CLKDIV2_OFFSET 0x0048 /* System Clock Divider Register 2 */
+#define KL_SIM_FCFG1_OFFSET 0x004c /* Flash Configuration Register 1 */
+#define KL_SIM_FCFG2_OFFSET 0x0050 /* Flash Configuration Register 2 */
+#define KL_SIM_UIDH_OFFSET 0x0054 /* Unique Identification Register High */
+#define KL_SIM_UIDMH_OFFSET 0x0058 /* Unique Identification Register Mid-High */
+#define KL_SIM_UIDML_OFFSET 0x005c /* Unique Identification Register Mid Low */
+#define KL_SIM_UIDL_OFFSET 0x0060 /* Unique Identification Register Low */
+
+/* Register Addresses ***************************************************************/
+/* NOTE: The SIM_SOPT1 register is located at a different base address than the
+ * other SIM registers.
+ */
+
+#define KL_SIM_SOPT1 (KL_SIMLP_BASE+KL_SIM_SOPT1_OFFSET)
+#define KL_SIM_SOPT2 (KL_SIM_BASE+KL_SIM_SOPT2_OFFSET)
+#define KL_SIM_SOPT4 (KL_SIM_BASE+KL_SIM_SOPT4_OFFSET)
+#define KL_SIM_SOPT5 (KL_SIM_BASE+KL_SIM_SOPT5_OFFSET)
+#define KL_SIM_SOPT6 (KL_SIM_BASE+KL_SIM_SOPT6_OFFSET)
+#define KL_SIM_SOPT7 (KL_SIM_BASE+KL_SIM_SOPT7_OFFSET)
+#define KL_SIM_SDID (KL_SIM_BASE+KL_SIM_SDID_OFFSET)
+#define KL_SIM_SCGC1 (KL_SIM_BASE+KL_SIM_SCGC1_OFFSET)
+#define KL_SIM_SCGC2 (KL_SIM_BASE+KL_SIM_SCGC2_OFFSET)
+#define KL_SIM_SCGC3 (KL_SIM_BASE+KL_SIM_SCGC3_OFFSET)
+#define KL_SIM_SCGC4 (KL_SIM_BASE+KL_SIM_SCGC4_OFFSET)
+#define KL_SIM_SCGC5 (KL_SIM_BASE+KL_SIM_SCGC5_OFFSET)
+#define KL_SIM_SCGC6 (KL_SIM_BASE+KL_SIM_SCGC6_OFFSET)
+#define KL_SIM_SCGC7 (KL_SIM_BASE+KL_SIM_SCGC7_OFFSET)
+#define KL_SIM_CLKDIV1 (KL_SIM_BASE+KL_SIM_CLKDIV1_OFFSET)
+#define KL_SIM_CLKDIV2 (KL_SIM_BASE+KL_SIM_CLKDIV2_OFFSET)
+#define KL_SIM_FCFG1 (KL_SIM_BASE+KL_SIM_FCFG1_OFFSET)
+#define KL_SIM_FCFG2 (KL_SIM_BASE+KL_SIM_FCFG2_OFFSET)
+#define KL_SIM_UIDH (KL_SIM_BASE+KL_SIM_UIDH_OFFSET)
+#define KL_SIM_UIDMH (KL_SIM_BASE+KL_SIM_UIDMH_OFFSET)
+#define KL_SIM_UIDML (KL_SIM_BASE+KL_SIM_UIDML_OFFSET)
+#define KL_SIM_UIDL (KL_SIM_BASE+KL_SIM_UIDL_OFFSET)
+
+/* Register Bit Definitions *********************************************************/
+
+/* System Options Register 1 */
+ /* Bits 0-17: Reserved */
+#define SIM_SOPT1_OSC32KSEL (3 << 18) /* Bit 18-19: 32K oscillator clock select */
+ /* Bits 20-22: Reserved */
+#define SIM_SOPT1_MS (1 << 23) /* Bit 23: EzPort chip select pin state */
+ /* Bits 24-29: Reserved */
+#define SIM_SOPT1_USBSTBY (1 << 30) /* Bit 30: USB voltage regulator in standby mode */
+#define SIM_SOPT1_USBREGEN (1 << 31) /* Bit 31: USB voltage regulator enable */
+
+/* System Options Register 2 */
+
+#define SIM_SOPT2_MCGCLKSEL (1 << 0) /* Bit 0: MCG clock select */
+ /* Bits 1-7: Reserved */
+#define SIM_SOPT2_FBSL_SHIFT (8) /* Bits 8-9: FlexBus security level */
+#define SIM_SOPT2_FBSL_MASK (3 << SIM_SOPT2_FBSL_SHIFT)
+# define SIM_SOPT2_FBSL_NONE (0 << SIM_SOPT2_FBSL_SHIFT) /* All off-chip accesses disallowed */
+# define SIM_SOPT2_FBSL_DATA (2 << SIM_SOPT2_FBSL_SHIFT) /* Off-chip data accesses are allowed */
+# define SIM_SOPT2_FBSL_ALL (3 << SIM_SOPT2_FBSL_SHIFT) /* All Off-chip accesses allowed */
+ /* Bit 10: Reserved */
+#define SIM_SOPT2_CMTUARTPAD (1 << 11) /* Bit 11: CMT/UART pad drive strength */
+#define SIM_SOPT2_TRACECLKSEL (1 << 12) /* Bit 12: Debug trace clock select */
+ /* Bits 13-15: Reserved */
+#define SIM_SOPT2_PLLFLLSEL (1 << 16) /* Bit 16: PLL/FLL clock select */
+ /* Bit 17: Reserved */
+#define SIM_SOPT2_USBSRC (1 << 18) /* Bit 18: USB clock source select */
+ /* Bit 19: Reserved */
+#ifdef KL_K60
+# define SIM_SOPT2_TIMESRC (1 << 20) /* Bit 20: IEEE 1588 timestamp clock source select (K60) */
+#endif
+ /* Bits 12-23: Reserved */
+#define SIM_SOPT2_TPMSRC_SHIFT (24) /* Bits 24-25: I2S master clock source select */
+#define SIM_SOPT2_TPMSRC_MASK (3 << SIM_SOPT2_TPMSRC_SHIFT)
+# define SIM_SOPT2_TPMSRC_CLKDIS (0 << SIM_SOPT2_TPMSRC_SHIFT) /* Core/system clock / I2S fractional divider*/
+# define SIM_SOPT2_TPMSRC_MCGCLK (1 << SIM_SOPT2_TPMSRC_SHIFT) /* MCGPLLCLK/MCGFLLCLK clock/ I2S fractional divider */
+# define SIM_SOPT2_TPMSRC_OCSERCLK (2 << SIM_SOPT2_TPMSRC_SHIFT) /* OSCERCLK clock */
+# define SIM_SOPT2_TPMSRC_MCGIRCLK (3 << SIM_SOPT2_TPMSRC_SHIFT) /* External bypass clock (I2S0_CLKIN) */
+#define SIM_SOPT2_UART0SRC_SHIFT (26) /* Bits 26-27: UART0 clock source select */
+#define SIM_SOPT2_UART0SRC_MASK (3 << SIM_SOPT2_UART0SRC_SHIFT)
+#define SIM_SOPT2_UART0SRC_DIS (0 << SIM_SOPT2_UART0SRC_SHIFT)
+#define SIM_SOPT2_UART0SRC_MCGCLK (1 << SIM_SOPT2_UART0SRC_SHIFT)
+#define SIM_SOPT2_UART0SRC_OSCERCLK (2 << SIM_SOPT2_UART0SRC_SHIFT)
+#define SIM_SOPT2_UART0SRC_MCGIRCLK (3 << SIM_SOPT2_UART0SRC_SHIFT)
+#define SIM_SOPT2_SDHCSRC_SHIFT (28) /* Bits 28-29: SDHC clock source select*/
+#define SIM_SOPT2_SDHCSRC_MASK (3 << SIM_SOPT2_SDHCSRC_SHIFT)
+# define SIM_SOPT2_SDHCSRC_CORE (0 << SIM_SOPT2_SDHCSRC_SHIFT) /* Core/system clock */
+# define SIM_SOPT2_SDHCSRC_MCGCLK (1 << SIM_SOPT2_SDHCSRC_SHIFT) /* MCGPLLCLK/MCGFLLCLK clock */
+# define SIM_SOPT2_SDHCSRC_OCSERCLK (2 << SIM_SOPT2_SDHCSRC_SHIFT) /* OSCERCLK clock */
+# define SIM_SOPT2_SDHCSRC_EXTBYP (3 << SIM_SOPT2_SDHCSRC_SHIFT) /* External bypass clock (SDHC0_CLKIN) */ /* Bits 30-31: Reserved */
+
+/* System Options Register 4 */
+
+#define SIM_SOPT4_FTM0FLT0 (1 << 0) /* Bit 0: FTM0 Fault 0 Select */
+#define SIM_SOPT4_FTM0FLT1 (1 << 1) /* Bit 1: FTM0 Fault 1 Select */
+#define SIM_SOPT4_FTM0FLT2 (1 << 2) /* Bit 2: FTM0 Fault 2 Select */
+ /* Bit 3: Reserved */
+#define SIM_SOPT4_FTM1FLT0 (1 << 4) /* Bit 4: FTM1 Fault 0 Select */
+ /* Bits 5-7: Reserved */
+#define SIM_SOPT4_FTM2FLT0 (1 << 8) /* Bit 8: FTM2 Fault 0 Select */
+ /* Bits 9-17: Reserved */
+#define SIM_SOPT4_FTM1CH0SRC_SHIFT (18) /* Bits 18-19: FTM1 channel 0 input capture source select */
+#define SIM_SOPT4_FTM1CH0SRC_MASK (3 << SIM_SOPT4_FTM1CH0SRC_SHIFT)
+# define SIM_SOPT4_FTM1CH0SRC_CH0 (0 << SIM_SOPT4_FTM1CH0SRC_SHIFT) /* FTM1_CH0 signal */
+# define SIM_SOPT4_FTM1CH0SRC_CMP0 (1 << SIM_SOPT4_FTM1CH0SRC_SHIFT) /* CMP0 output */
+# define SIM_SOPT4_FTM1CH0SRC_CMP1 (2 << SIM_SOPT4_FTM1CH0SRC_SHIFT) /* CMP1 output */
+#define SIM_SOPT4_FTM2CH0SRC_SHIFT (20) /* Bits 20-21: FTM2 channel 0 input capture source select */
+#define SIM_SOPT4_FTM2CH0SRC_MASK (3 << SIM_SOPT4_FTM2CH0SRC_SHIFT)
+# define SIM_SOPT4_FTM2CH0SRC_CH0 (0 << SIM_SOPT4_FTM2CH0SRC_SHIFT) /* FTM2_CH0 signal */
+# define SIM_SOPT4_FTM2CH0SRC_CMP0 (1 << SIM_SOPT4_FTM2CH0SRC_SHIFT) /* CMP0 output */
+# define SIM_SOPT4_FTM2CH0SRC_CMP1 (2 << SIM_SOPT4_FTM2CH0SRC_SHIFT) /* CMP1 output */
+ /* Bits 22-23: Reserved */
+#define SIM_SOPT4_FTM0CLKSEL (1 << 24) /* Bit 24: FlexTimer 0 External Clock Pin Select */
+#define SIM_SOPT4_FTM1CLKSEL (1 << 25) /* Bit 25: FTM1 External Clock Pin Select */
+#define SIM_SOPT4_FTM2CLKSEL (1 << 26) /* Bit 26: FlexTimer 2 External Clock Pin Select */
+ /* Bits 27-31: Reserved */
+
+/* System Options Register 5 */
+
+#define SIM_SOPT5_UART0TXSRC_SHIFT (0) /* Bits 0-1: UART 0 transmit data source select */
+#define SIM_SOPT5_UART0TXSRC_MASK (3 << SIM_SOPT5_UART0TXSRC_SHIFT)
+# define SIM_SOPT5_UART0TXSRC_TX (0 << SIM_SOPT5_UART0TXSRC_SHIFT) /* UART0_TX pin */
+# define SIM_SOPT5_UART0TXSRC_FTM1 (1 << SIM_SOPT5_UART0TXSRC_SHIFT) /* UART0_TX modulated with FTM1 ch0 output */
+# define SIM_SOPT5_UART0TXSRC_FTM2 (2 << SIM_SOPT5_UART0TXSRC_SHIFT) /* UART0_TX modulated with FTM2 ch0 output */
+#define SIM_SOPT5_UART0RXSRC_SHIFT (2) /* Bits 2-3: UART 0 receive data source select */
+#define SIM_SOPT5_UART0RXSRC_MASK (3 << SIM_SOPT5_UART0RXSRC_SHIFT)
+# define SIM_SOPT5_UART0RXSRC_RX (0 << SIM_SOPT5_UART0RXSRC_SHIFT) /* UART0_RX pin */
+# define SIM_SOPT5_UART0RXSRC_CMP0 (1 << SIM_SOPT5_UART0RXSRC_SHIFT) /* CMP0 */
+# define SIM_SOPT5_UART0RXSRC_CMP1 (2 << SIM_SOPT5_UART0RXSRC_SHIFT) /* CMP1 */
+#define SIM_SOPT5_UART1TXSRC_SHIFT (4) /* Bits 4-5: UART 1 transmit data source select */
+#define SIM_SOPT5_UART1TXSRC_MASK (3 << SIM_SOPT5_UART1TXSRC_SHIFT)
+# define SIM_SOPT5_UART1TXSRC_TX (0 << SIM_SOPT5_UART1TXSRC_SHIFT) /* UART1_TX pin */
+# define SIM_SOPT5_UART1TXSRC_FTM1 (1 << SIM_SOPT5_UART1TXSRC_SHIFT) /* UART1_TX modulated with FTM1 ch0 output */
+# define SIM_SOPT5_UART1TXSRC_FTM2 (2 << SIM_SOPT5_UART1TXSRC_SHIFT) /* UART1_TX modulated with FTM2 ch0 output */
+#define SIM_SOPT5_UART1RXSRC_SHIFT (6) /* Bits 6-7: UART 1 receive data source select */
+#define SIM_SOPT5_UART1RXSRC_MASK (3 << SIM_SOPT5_UART1RXSRC_SHIFT)
+# define SIM_SOPT5_UART1RXSRC_RX (0 << SIM_SOPT5_UART1RXSRC_SHIFT) /* UART1_RX pin */
+# define SIM_SOPT5_UART1RXSRC_CMP0 (1 << SIM_SOPT5_UART1RXSRC_SHIFT) /* CMP0 */
+# define SIM_SOPT5_UART1RXSRC_CMP1 (2 << SIM_SOPT5_UART1RXSRC_SHIFT) /* CMP1 */
+ /* Bits 8-31: Reserved */
+/* System Options Register 6 */
+ /* Bits 0-23: Reserved */
+#define SIM_SOPT6_RSTFLTSEL_SHIFT (24) /* Bits 24-28: Reset pin filter select */
+#define SIM_SOPT6_RSTFLTSEL_MASK (31 << SIM_SOPT6_RSTFLTSEL_SHIFT)
+# define SIM_SOPT6_RSTFLTSEL(n) (((n)-1) << SIM_SOPT6_RSTFLTSEL_SHIFT) /* Bux clock filter count n, n=1..32 */
+#define SIM_SOPT6_RSTFLTEN_SHIFT (29) /* Bits 29-31: Reset pin filter enable */
+#define SIM_SOPT6_RSTFLTEN_MASK (7 << SIM_SOPT6_RSTFLTEN_SHIFT)
+#define SIM_SOPT6_RSTFLTEN_DISABLED (0 << SIM_SOPT6_RSTFLTEN_SHIFT) /* All filtering disabled */
+# define SIM_SOPT6_RSTFLTEN_BUSCLK1 (1 << SIM_SOPT6_RSTFLTEN_SHIFT) /* Bus clock filter enabled (normal); LPO clock filter enabled (stop) */
+# define SIM_SOPT6_RSTFLTEN_LPO1 (2 << SIM_SOPT6_RSTFLTEN_SHIFT) /* LPO clock filter enabled */
+# define SIM_SOPT6_RSTFLTEN_BUSCLK2 (3 << SIM_SOPT6_RSTFLTEN_SHIFT) /* Bus clock filter enabled (normal); All filtering disabled (stop) */
+# define SIM_SOPT6_RSTFLTEN_LPO2 (4 << SIM_SOPT6_RSTFLTEN_SHIFT) /* PO clock filter enabled (normal); All filtering disabled (stop) */
+
+/* System Options Register 7 */
+
+#define SIM_SOPT7_ADC0TRGSEL_SHIFT (0) /* Bits 0-3: ADC0 trigger select */
+#define SIM_SOPT7_ADC0TRGSEL_MASK (15 << SIM_SOPT7_ADC0TRGSEL_SHIFT)
+# define SIM_SOPT7_ADC0TRGSEL_PDB (0 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* PDB external trigger (PDB0_EXTRG) */
+# define SIM_SOPT7_ADC0TRGSEL_CMP0 (1 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* High speed comparator 0 output */
+# define SIM_SOPT7_ADC0TRGSEL_CMP1 (2 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* High speed comparator 1 output */
+# define SIM_SOPT7_ADC0TRGSEL_CMP2 (3 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* High speed comparator 2 output */
+# define SIM_SOPT7_ADC0TRGSEL_PIT0 (4 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* PIT trigger 0 */
+# define SIM_SOPT7_ADC0TRGSEL_PIT1 (5 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* PIT trigger 1 */
+# define SIM_SOPT7_ADC0TRGSEL_PIT2 (6 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* PIT trigger 2 */
+# define SIM_SOPT7_ADC0TRGSEL_PIT3 (7 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* PIT trigger 3 */
+# define SIM_SOPT7_ADC0TRGSEL_FTM0 (8 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* FTM0 trigger */
+# define SIM_SOPT7_ADC0TRGSEL_FTM1 (9 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* FTM1 trigger */
+# define SIM_SOPT7_ADC0TRGSEL_FTM2 (10 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* FTM2 trigger */
+# define SIM_SOPT7_ADC0TRGSEL_ALARM (12 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* RTC alarm */
+# define SIM_SOPT7_ADC0TRGSEL_SECS (13 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* RTC seconds */
+# define SIM_SOPT7_ADC0TRGSEL_LPTMR (14 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* Low-power timer trigger */
+#define SIM_SOPT7_ADC0PRETRGSEL (1 << 4) /* Bit 4: ADC0 pretrigger select */
+ /* Bits 5-6: Reserved */
+#define SIM_SOPT7_ADC0ALTTRGEN (1 << 7) /* Bit 7: ADC0 alternate trigger enable */
+#define SIM_SOPT7_ADC1TRGSEL_SHIFT (8) /* Bits 8-11: ADC1 trigger select */
+#define SIM_SOPT7_ADC1TRGSEL_MASK (15 << SIM_SOPT7_ADC1TRGSEL_SHIFT)
+# define SIM_SOPT7_ADC1TRGSEL_PDB (0 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* PDB external trigger (PDB0_EXTRG) */
+# define SIM_SOPT7_ADC1TRGSEL_CMP0 (1 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* High speed comparator 0 output */
+# define SIM_SOPT7_ADC1TRGSEL_CMP1 (2 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* High speed comparator 1 output */
+# define SIM_SOPT7_ADC1TRGSEL_CMP2 (3 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* High speed comparator 2 output */
+# define SIM_SOPT7_ADC1TRGSEL_PIT0 (4 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* PIT trigger 0 */
+# define SIM_SOPT7_ADC1TRGSEL_PIT1 (5 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* PIT trigger 1 */
+# define SIM_SOPT7_ADC1TRGSEL_PIT2 (6 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* PIT trigger 2 */
+# define SIM_SOPT7_ADC1TRGSEL_PIT3 (7 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* PIT trigger 3 */
+# define SIM_SOPT7_ADC1TRGSEL_FTM0 (8 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* FTM0 trigger */
+# define SIM_SOPT7_ADC1TRGSEL_FTM1 (9 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* FTM1 trigger */
+# define SIM_SOPT7_ADC1TRGSEL_FTM2 (10 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* FTM2 trigger */
+# define SIM_SOPT7_ADC1TRGSEL_ALARM (12 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* RTC alarm */
+# define SIM_SOPT7_ADC1TRGSEL_SECS (13 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* RTC seconds */
+# define SIM_SOPT7_ADC1TRGSEL_LPTMR (14 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* Low-power timer trigger */
+#define SIM_SOPT7_ADC1PRETRGSEL (1 << 12) /* Bit 12: ADC1 pre-trigger select */
+ /* Bits 13-14: Reserved */
+#define SIM_SOPT7_ADC1ALTTRGEN (1 << 15) /* Bit 15: ADC1 alternate trigger enable */
+ /* Bits 16-31: Reserved */
+/* System Device Identification Register */
+
+#define SIM_SDID_PINID_SHIFT (0) /* Bits 0-3: Pincount identification */
+#define SIM_SDID_PINID_MASK (15 << SIM_SDID_PINID_SHIFT)
+# define SIM_SDID_PINID_32PIN (2 << SIM_SDID_PINID_SHIFT) /* 32-pin */
+# define SIM_SDID_PINID_48PIN (4 << SIM_SDID_PINID_SHIFT) /* 48-pin */
+# define SIM_SDID_PINID_64PIN (5 << SIM_SDID_PINID_SHIFT) /* 64-pin */
+# define SIM_SDID_PINID_80PIN (6 << SIM_SDID_PINID_SHIFT) /* 80-pin */
+# define SIM_SDID_PINID_81PIN (7 << SIM_SDID_PINID_SHIFT) /* 81-pin */
+# define SIM_SDID_PINID_100PIN (8 << SIM_SDID_PINID_SHIFT) /* 100-pin */
+# define SIM_SDID_PINID_121PIN (9 << SIM_SDID_PINID_SHIFT) /* 121-pin */
+# define SIM_SDID_PINID_144PIN (10 << SIM_SDID_PINID_SHIFT) /* 144-pin */
+# define SIM_SDID_PINID_196PIN (12 << SIM_SDID_PINID_SHIFT) /* 196-pin */
+# define SIM_SDID_PINID_256PIN (14 << SIM_SDID_PINID_SHIFT) /* 256-pin */
+#define SIM_SDID_FAMID_SHIFT (4) /* Bits 4-6: Kinetis family identification */
+#define SIM_SDID_FAMID_MASK (7 << SIM_SDID_FAMID_SHIFT)
+# define SIM_SDID_FAMID_K10 (0 << SIM_SDID_FAMID_SHIFT) /* K10 */
+# define SIM_SDID_FAMID_K20 (1 << SIM_SDID_FAMID_SHIFT)) /* K20 */
+# define SIM_SDID_FAMID_K30 (2 << SIM_SDID_FAMID_SHIFT)) /* K30 */
+# define SIM_SDID_FAMID_K40 (3 << SIM_SDID_FAMID_SHIFT)) /* K40 */
+# define SIM_SDID_FAMID_K60 (4 << SIM_SDID_FAMID_SHIFT)) /* K60 */
+# define SIM_SDID_FAMID_K70 (5 << SIM_SDID_FAMID_SHIFT)) /* K70 */
+# define SIM_SDID_FAMID_K50 (6 << SIM_SDID_FAMID_SHIFT)) /* K50 and K52 */
+# define SIM_SDID_FAMID_K51 (7 << SIM_SDID_FAMID_SHIFT)) /* K51 and K53 */
+ /* Bits 7-11: Reserved */
+#define SIM_SDID_REVID_SHIFT (12) /* Bits 12-15: Device revision number */
+#define SIM_SDID_REVID_MASK (15 << SIM_SDID_REVID_SHIFT)
+ /* Bits 16-31: Reserved */
+/* System Clock Gating Control Register 1 */
+ /* Bits 0-9: Reserved */
+#define SIM_SCGC1_UART4 (1 << 10) /* Bit 10: UART4 Clock Gate Control */
+#define SIM_SCGC1_UART5 (1 << 11) /* Bit 11: UART5 Clock Gate Control */
+ /* Bits 12-31: Reserved */
+/* System Clock Gating Control Register 2 */
+
+#if defined(KL_NENET) && KL_NENET > 0
+# define SIM_SCGC2_ENET (1 << 0) /* Bit 0: ENET Clock Gate Control (K60) */
+#endif
+ /* Bits 1-11: Reserved */
+#define SIM_SCGC2_DAC0 (1 << 12) /* Bit 12: DAC0 Clock Gate Control */
+#define SIM_SCGC2_DAC1 (1 << 13) /* Bit 13: DAC1 Clock Gate Control */
+ /* Bits 14-31: Reserved */
+/* System Clock Gating Control Register 3 */
+
+#if defined(KL_NRNG) && KL_NRNG > 0
+# define SIM_SCGC3_RNGB (1 << 0) /* Bit 0: RNGB Clock Gate Control (K60) */
+#endif
+ /* Bits 1-3: Reserved */
+#define SIM_SCGC3_FLEXCAN1 (1 << 4) /* Bit 4: FlexCAN1 Clock Gate Control */
+ /* Bits 5-11: Reserved */
+#define SIM_SCGC3_SPI2 (1 << 12) /* Bit 12: SPI2 Clock Gate Control */
+ /* Bits 13-16: Reserved */
+#define SIM_SCGC3_SDHC (1 << 17) /* Bit 17: SDHC Clock Gate Control */
+ /* Bits 18-23: Reserved */
+#define SIM_SCGC3_FTM2 (1 << 24) /* Bit 24: FTM2 Clock Gate Control */
+ /* Bits 25-26: Reserved */
+#define SIM_SCGC3_ADC1 (1 << 27) /* Bit 27: ADC1 Clock Gate Control */
+ /* Bits 28-29: Reserved */
+#if defined(KL_NSLCD) && KL_NSLCD > 0
+# define SIM_SCGC3_SLCD (1 << 30) /* Bit 30: Segment LCD Clock Gate Control (K40) */
+#endif
+ /* Bit 31: Reserved */
+/* System Clock Gating Control Register 4 */
+ /* Bit 0: Reserved */
+#define SIM_SCGC4_EWM (1 << 1) /* Bit 1: EWM Clock Gate Control */
+#define SIM_SCGC4_CMT (1 << 2) /* Bit 2: CMT Clock Gate Control */
+ /* Bits 3-5: Reserved */
+#define SIM_SCGC4_I2C0 (1 << 6) /* Bit 6: I2C0 Clock Gate Control */
+#define SIM_SCGC4_I2C1 (1 << 7) /* Bit 7: I2C1 Clock Gate Control */
+
+#define SIM_SCGC4_UART0 (1 << 10) /* Bit 10: UART0 Clock Gate Control */
+#define SIM_SCGC4_UART1 (1 << 11) /* Bit 11: UART1 Clock Gate Control */
+#define SIM_SCGC4_UART2 (1 << 12) /* Bit 12: UART2 Clock Gate Control */
+#define SIM_SCGC4_UART3 (1 << 13) /* Bit 13: UART3 Clock Gate Control */
+ /* Bits 14-17: Reserved */
+#define SIM_SCGC4_USBOTG (1 << 18) /* Bit 18: USB Clock Gate Control */
+#define SIM_SCGC4_CMP (1 << 19) /* Bit 19: Comparator Clock Gate Control */
+#define SIM_SCGC4_VREF (1 << 20) /* Bit 20: VREF Clock Gate Control */
+ /* Bits 21-17: Reserved */
+#define SIM_SCGC4_LLWU (1 << 28) /* Bit 28: LLWU Clock Gate Control */
+ /* Bits 29-31: Reserved */
+/* System Clock Gating Control Register 5 */
+
+#define SIM_SCGC5_LPTIMER (1 << 0) /* Bit 0: Low Power Timer Clock Gate Control */
+#define SIM_SCGC5_REGFILE (1 << 1) /* Bit 1: Register File Clock Gate Control */
+ /* Bits 2-4: Reserved */
+#define SIM_SCGC5_TSI (1 << 5) /* Bit 5: TSI Clock Gate Control */
+ /* Bits 6-8: Reserved */
+#define SIM_SCGC5_PORTA (1 << 9) /* Bit 9: Port A Clock Gate Control */
+#define SIM_SCGC5_PORTB (1 << 10) /* Bit 10: Port B Clock Gate Control */
+#define SIM_SCGC5_PORTC (1 << 11) /* Bit 11: Port C Clock Gate Control */
+#define SIM_SCGC5_PORTD (1 << 12) /* Bit 12: Port D Clock Gate Control */
+#define SIM_SCGC5_PORTE (1 << 13) /* Bit 13: Port E Clock Gate Control */
+ /* Bits 14-31: Reserved */
+/* System Clock Gating Control Register 6 */
+
+#define SIM_SCGC6_FTFL (1 << 0) /* Bit 0: Flash Memory Clock Gate Control */
+#define SIM_SCGC6_DMAMUX (1 << 1) /* Bit 1: DMA Mux Clock Gate Control */
+ /* Bits 2-3: Reserved */
+#define SIM_SCGC6_FLEXCAN0 (1 << 4) /* Bit 4: FlexCAN0 Clock Gate Control */
+ /* Bits 5-11: Reserved */
+#define SIM_SCGC6_SPI0 (1 << 12) /* Bit 12: SPI0 Clock Gate Control */
+#define SIM_SCGC6_SPI1 (1 << 13) /* Bit 13: SPI1 Clock Gate Control */
+ /* Bit 14: Reserved */
+#define SIM_SCGC6_I2S (1 << 15) /* Bit 15: I2S Clock Gate Control */
+ /* Bits 16-17: Reserved */
+#define SIM_SCGC6_CRC (1 << 18) /* Bit 18: CRC Clock Gate Control */
+ /* Bits 19-20: Reserved */
+#define SIM_SCGC6_USBDCD (1 << 21) /* Bit 21: USB DCD Clock Gate Control */
+#define SIM_SCGC6_PDB (1 << 22) /* Bit 22: PDB Clock Gate Control */
+#define SIM_SCGC6_PIT (1 << 23) /* Bit 23: PIT Clock Gate Control */
+#define SIM_SCGC6_FTM0 (1 << 24) /* Bit 24: FTM0 Clock Gate Control */
+#define SIM_SCGC6_FTM1 (1 << 25) /* Bit 25: FTM1 Clock Gate Control */
+ /* Bit 26: Reserved */
+#define SIM_SCGC6_ADC0 (1 << 27) /* Bit 27: ADC0 Clock Gate Control */
+ /* Bit 28: Reserved */
+#define SIM_SCGC6_RTC (1 << 29) /* Bit 29: RTC Clock Gate Control */
+ /* Bits 30-31: Reserved */
+/* System Clock Gating Control Register 7 */
+
+#define SIM_SCGC7_FLEXBUS (1 << 0) /* Bit 0: FlexBus Clock Gate Control */
+#define SIM_SCGC7_DMA (1 << 1) /* Bit 1: DMA Clock Gate Control */
+#define SIM_SCGC7_MPU (1 << 2) /* Bit 2: MPU Clock Gate Control */
+ /* Bits 3-31: Reserved */
+/* System Clock Divider Register 1 */
+ /* Bits 0-15: Reserved */
+#define SIM_CLKDIV1_OUTDIV4_SHIFT (16) /* Bits 16-19: Clock 4 output divider value */
+#define SIM_CLKDIV1_OUTDIV4_MASK (15 << SIM_CLKDIV1_OUTDIV4_SHIFT)
+# define SIM_CLKDIV1_OUTDIV4(n) ((n) << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by n, n=1..16 */
+# define SIM_CLKDIV1_OUTDIV4_1 (0 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 1 */
+# define SIM_CLKDIV1_OUTDIV4_2 (1 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 2 */
+# define SIM_CLKDIV1_OUTDIV4_3 (2 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 3 */
+# define SIM_CLKDIV1_OUTDIV4_4 (3 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 4 */
+# define SIM_CLKDIV1_OUTDIV4_5 (4 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 5 */
+# define SIM_CLKDIV1_OUTDIV4_6 (5 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 6 */
+# define SIM_CLKDIV1_OUTDIV4_7 (6 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 7 */
+# define SIM_CLKDIV1_OUTDIV4_8 (7 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 8 */
+# define SIM_CLKDIV1_OUTDIV4_9 (8 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 9 */
+# define SIM_CLKDIV1_OUTDIV4_10 (9 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 10 */
+# define SIM_CLKDIV1_OUTDIV4_11 (10 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 11 */
+# define SIM_CLKDIV1_OUTDIV4_12 (11 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 12 */
+# define SIM_CLKDIV1_OUTDIV4_13 (12 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 13 */
+# define SIM_CLKDIV1_OUTDIV4_14 (13 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 14 */
+# define SIM_CLKDIV1_OUTDIV4_15 (14 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 15 */
+# define SIM_CLKDIV1_OUTDIV4_16 (15 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 16 */
+#define SIM_CLKDIV1_OUTDIV3_SHIFT (20) /* Bits 20-23: Clock 3 output divider value */
+#define SIM_CLKDIV1_OUTDIV3_MASK (15 << SIM_CLKDIV1_OUTDIV3_SHIFT)
+# define SIM_CLKDIV1_OUTDIV3(n) (((n)-1) << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by n, n=1..16 */
+# define SIM_CLKDIV1_OUTDIV3_1 (0 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 1 */
+# define SIM_CLKDIV1_OUTDIV3_2 (1 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 2 */
+# define SIM_CLKDIV1_OUTDIV3_3 (2 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 3 */
+# define SIM_CLKDIV1_OUTDIV3_4 (3 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 4 */
+# define SIM_CLKDIV1_OUTDIV3_5 (4 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 5 */
+# define SIM_CLKDIV1_OUTDIV3_6 (5 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 6 */
+# define SIM_CLKDIV1_OUTDIV3_7 (6 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 7 */
+# define SIM_CLKDIV1_OUTDIV3_8 (7 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 8 */
+# define SIM_CLKDIV1_OUTDIV3_9 (8 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 9 */
+# define SIM_CLKDIV1_OUTDIV3_10 (9 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 10 */
+# define SIM_CLKDIV1_OUTDIV3_11 (10 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 11 */
+# define SIM_CLKDIV1_OUTDIV3_12 (11 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 12 */
+# define SIM_CLKDIV1_OUTDIV3_13 (12 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 13 */
+# define SIM_CLKDIV1_OUTDIV3_14 (13 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 14 */
+# define SIM_CLKDIV1_OUTDIV3_15 (14 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 15 */
+# define SIM_CLKDIV1_OUTDIV3_16 (15 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 16 */
+#define SIM_CLKDIV1_OUTDIV2_SHIFT (24) /* Bits 24-27: Clock 2 output divider value */
+#define SIM_CLKDIV1_OUTDIV2_MASK (15 << SIM_CLKDIV1_OUTDIV2_SHIFT)
+# define SIM_CLKDIV1_OUTDIV2(n) (((n)-1) << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by n, n=1..16 */
+# define SIM_CLKDIV1_OUTDIV2_1 (0 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 1 */
+# define SIM_CLKDIV1_OUTDIV2_2 (1 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 2 */
+# define SIM_CLKDIV1_OUTDIV2_3 (2 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 3 */
+# define SIM_CLKDIV1_OUTDIV2_4 (3 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 4 */
+# define SIM_CLKDIV1_OUTDIV2_5 (4 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 5 */
+# define SIM_CLKDIV1_OUTDIV2_6 (5 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 6 */
+# define SIM_CLKDIV1_OUTDIV2_7 (6 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 7 */
+# define SIM_CLKDIV1_OUTDIV2_8 (7 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 8 */
+# define SIM_CLKDIV1_OUTDIV2_9 (8 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 9 */
+# define SIM_CLKDIV1_OUTDIV2_10 (9 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 10 */
+# define SIM_CLKDIV1_OUTDIV2_11 (10 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 11 */
+# define SIM_CLKDIV1_OUTDIV2_12 (11 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 12 */
+# define SIM_CLKDIV1_OUTDIV2_13 (12 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 13 */
+# define SIM_CLKDIV1_OUTDIV2_14 (13 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 14 */
+# define SIM_CLKDIV1_OUTDIV2_15 (14 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 15 */
+# define SIM_CLKDIV1_OUTDIV2_16 (15 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 16 */
+#define SIM_CLKDIV1_OUTDIV1_SHIFT (28) /* Bits 28-31: Clock 1 output divider value */
+#define SIM_CLKDIV1_OUTDIV1_MASK (15 << SIM_CLKDIV1_OUTDIV1_SHIFT)
+# define SIM_CLKDIV1_OUTDIV1(n) ((n) << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by n, n=1..16 */
+# define SIM_CLKDIV1_OUTDIV1_1 (0 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 1 */
+# define SIM_CLKDIV1_OUTDIV1_2 (1 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 2 */
+# define SIM_CLKDIV1_OUTDIV1_3 (2 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 3 */
+# define SIM_CLKDIV1_OUTDIV1_4 (3 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 4 */
+# define SIM_CLKDIV1_OUTDIV1_5 (4 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 5 */
+# define SIM_CLKDIV1_OUTDIV1_6 (5 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 6 */
+# define SIM_CLKDIV1_OUTDIV1_7 (6 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 7 */
+# define SIM_CLKDIV1_OUTDIV1_8 (7 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 8 */
+# define SIM_CLKDIV1_OUTDIV1_9 (8 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 9 */
+# define SIM_CLKDIV1_OUTDIV1_10 (9 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 10 */
+# define SIM_CLKDIV1_OUTDIV1_11 (10 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 11 */
+# define SIM_CLKDIV1_OUTDIV1_12 (11 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 12 */
+# define SIM_CLKDIV1_OUTDIV1_13 (12 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 13 */
+# define SIM_CLKDIV1_OUTDIV1_14 (13 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 14 */
+# define SIM_CLKDIV1_OUTDIV1_15 (14 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 15 */
+# define SIM_CLKDIV1_OUTDIV1_16 (15 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 16 */
+
+/* System Clock Divider Register 2 */
+
+#define SIM_CLKDIV2_USBFRAC (1 << 0) /* Bit 0: USB clock divider fraction */
+#define SIM_CLKDIV2_USBDIV_SHIFT (1) /* Bits 1-3: USB clock divider divisor */
+#define SIM_CLKDIV2_USBDIV_MASK (7 << SIM_CLKDIV2_USBDIV_SHIFT)
+ /* Bits 4-7: Reserved */
+#define SIM_CLKDIV2_I2SFRAC_SHIFT (8) /* Bits 8-15: I2S clock divider fraction */
+#define SIM_CLKDIV2_I2SFRAC_MASK (0xff << SIM_CLKDIV2_I2SFRAC_SHIFT)
+ /* Bits 16-19: Reserved */
+#define SIM_CLKDIV2_I2SDIV_SHIFT (20) /* Bits 20-31: I2S clock divider value */
+#define SIM_CLKDIV2_I2SDIV_MASK (0xfff << SIM_CLKDIV2_I2SDIV_SHIFT)
+
+/* Flash Configuration Register 1 */
+ /* Bits 0-7: Reserved */
+#define SIM_FCFG1_DEPART_SHIFT (8) /* Bits 8-11: FlexNVM partition */
+#define SIM_FCFG1_DEPART_MASK (15 << SIM_FCFG1_DEPART_SHIFT)
+ /* Bits 12-15: Reserved */
+#define SIM_FCFG1_EESIZE_SHIFT (16) /* Bits 16-19: EEPROM size*/
+#define SIM_FCFG1_EESIZE_MASK (15 << SIM_FCFG1_EESIZE_SHIFT)
+# define SIM_FCFG1_EESIZE_4KB (2 << SIM_FCFG1_EESIZE_SHIFT) /* 4 KB */
+# define SIM_FCFG1_EESIZE_2KB (3 << SIM_FCFG1_EESIZE_SHIFT) /* 2 KB */
+# define SIM_FCFG1_EESIZE_1KB (4 << SIM_FCFG1_EESIZE_SHIFT) /* 1 KB */
+# define SIM_FCFG1_EESIZE_512B (5 << SIM_FCFG1_EESIZE_SHIFT) /* 512 Bytes */
+# define SIM_FCFG1_EESIZE_256B (6 << SIM_FCFG1_EESIZE_SHIFT) /* 256 Bytes */
+# define SIM_FCFG1_EESIZE_128B (7 << SIM_FCFG1_EESIZE_SHIFT) /* 128 Bytes */
+# define SIM_FCFG1_EESIZE_64B (8 << SIM_FCFG1_EESIZE_SHIFT) /* 64 Bytes */
+# define SIM_FCFG1_EESIZE_32B (9 << SIM_FCFG1_EESIZE_SHIFT) /* 32 Bytes */
+# define SIM_FCFG1_EESIZE_NONE (15 << SIM_FCFG1_EESIZE_SHIFT) /* 0 Bytes */
+ /* Bits 20-23: Reserved */
+#ifdef KL_K40
+#define SIM_FCFG1_PFSIZE_SHIFT (24) /* Bits 24-27: Program flash size (K40) */
+#define SIM_FCFG1_PFSIZE_MASK (15 << SIM_FCFG1_PFSIZE_SHIFT)
+# define SIM_FCFG1_PFSIZE_128KB (7 << SIM_FCFG1_PFSIZE_SHIFT) /* 128KB program flash, 4KB protection region */
+# define SIM_FCFG1_PFSIZE_256KB (9 << SIM_FCFG1_PFSIZE_SHIFT) /* 256KB program flash, 8KB protection region */
+# define SIM_FCFG1_PFSIZE_512KB (11 << SIM_FCFG1_PFSIZE_SHIFT) /* 512KB program flash, 16KB protection region */
+# define SIM_FCFG1_PFSIZE_512KB2 (15 << SIM_FCFG1_PFSIZE_SHIFT) /* 512KB program flash, 16KB protection region */
+#define SIM_FCFG1_NVMSIZE_SHIFT (28) /* Bits 28-31: FlexNVM size (K40)*/
+#define SIM_FCFG1_NVMSIZE_MASK (15 << SIM_FCFG1_NVMSIZE_SHIFT)
+# define SIM_FCFG1_NVMSIZE_NONE (0 << SIM_FCFG1_NVMSIZE_SHIFT) /* 0KB FlexNVM */
+# define SIM_FCFG1_NVMSIZE_128KB (7 << SIM_FCFG1_NVMSIZE_SHIFT) /* 128KB FlexNVM, 16KB protection region */
+# define SIM_FCFG1_NVMSIZE_256KB (9 << SIM_FCFG1_NVMSIZE_SHIFT) /* 256KB FlexNVM, 32KB protection region */
+# define SIM_FCFG1_NVMSIZE_256KB2 (15 << SIM_FCFG1_NVMSIZE_SHIFT) /* 256KB FlexNVM, 32KB protection region */
+#endif
+
+#ifdef KL_K60
+#define SIM_FCFG1_FSIZE_SHIFT (24) /* Bits 24-31: Flash size (K60)*/
+#define SIM_FCFG1_FSIZE_MASK (0xff << SIM_FCFG1_FSIZE_SHIFT)
+# define SIM_FCFG1_FSIZE_32KB (2 << SIM_FCFG1_FSIZE_SHIFT) /* 32KB program flash, 1KB protection region */
+# define SIM_FCFG1_FSIZE_64KB (4 << SIM_FCFG1_FSIZE_SHIFT) /* 64KB program flash, 2KB protection region */
+# define SIM_FCFG1_FSIZE_128KB (6 << SIM_FCFG1_FSIZE_SHIFT) /* 128KB program flash, 4KB protection region */
+# define SIM_FCFG1_FSIZE_256KB (8 << SIM_FCFG1_FSIZE_SHIFT) /* 256KB program flash, 8KB protection region */
+# define SIM_FCFG1_FSIZE_512KB (12 << SIM_FCFG1_FSIZE_SHIFT) /* 512KB program flash, 16KB protection region */
+#endif
+
+/* Flash Configuration Register 2 */
+ /* Bits 0-15: Reserved */
+#define SIM_FCFG2_MAXADDR1_SHIFT (16) /* Bits 16-21: Max address block 1 */
+#define SIM_FCFG2_MAXADDR1_MASK (nn << SIM_FCFG2_MAXADDR1_SHIFT)
+ /* Bit 22: Reserved */
+#define SIM_FCFG2_PFLSH (1 << 23) /* Bit 23: Program flash */
+#define SIM_FCFG2_MAXADDR0_SHIFT (24) /* Bits 24-29: Max address block 0 */
+#define SIM_FCFG2_MAXADDR0_MASK (nn << SIM_FCFG2_MAXADDR0_SHIFT)
+ /* Bit 30: Reserved */
+#define SIM_FCFG2_SWAPPFLSH (1 << 31) /* Bit 31: Swap program flash */
+
+/* Unique Identification Register High. 32-bit Unique Identification. */
+/* Unique Identification Register Mid-High. 32-bit Unique Identification. */
+/* Unique Identification Register Mid Low. 32-bit Unique Identification. */
+/* Unique Identification Register Low. 32-bit Unique Identification. */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+#endif /* __ARCH_ARM_SRC_KL_KL_SIM_H */
diff --git a/nuttx/arch/arm/src/kl/chip/kl_uart.h b/nuttx/arch/arm/src/kl/chip/kl_uart.h
new file mode 100644
index 000000000..e04e9fd99
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/kl_uart.h
@@ -0,0 +1,521 @@
+/************************************************************************************
+ * arch/arm/src/kl/kl_uart.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_KL_UART_H
+#define __ARCH_ARM_SRC_KL_KL_UART_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "kl_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register Offsets *****************************************************************/
+
+#define KL_UART_BDH_OFFSET 0x0000 /* UART Baud Rate Register High */
+#define KL_UART_BDL_OFFSET 0x0001 /* UART Baud Rate Register Low */
+#define KL_UART_C1_OFFSET 0x0002 /* UART Control Register 1 */
+#define KL_UART_C2_OFFSET 0x0003 /* UART Control Register 2 */
+#define KL_UART_S1_OFFSET 0x0004 /* UART Status Register 1 */
+#define KL_UART_S2_OFFSET 0x0005 /* UART Status Register 2 */
+#define KL_UART_C3_OFFSET 0x0006 /* UART Control Register 3 */
+#define KL_UART_D_OFFSET 0x0007 /* UART Data Register */
+#define KL_UART_MA1_OFFSET 0x0008 /* UART Match Address Registers 1 */
+#define KL_UART_MA2_OFFSET 0x0009 /* UART Match Address Registers 2 */
+#define KL_UART_C4_OFFSET 0x000a /* UART Control Register 4 */
+#define KL_UART_C5_OFFSET 0x000b /* UART Control Register 5 */
+#define KL_UART_ED_OFFSET 0x000c /* UART Extended Data Register */
+#define KL_UART_MODEM_OFFSET 0x000d /* UART Modem Register */
+#define KL_UART_IR_OFFSET 0x000e /* UART Infrared Register */
+#define KL_UART_PFIFO_OFFSET 0x0010 /* UART FIFO Parameters */
+#define KL_UART_CFIFO_OFFSET 0x0011 /* UART FIFO Control Register */
+#define KL_UART_SFIFO_OFFSET 0x0012 /* UART FIFO Status Register */
+#define KL_UART_TWFIFO_OFFSET 0x0013 /* UART FIFO Transmit Watermark */
+#define KL_UART_TCFIFO_OFFSET 0x0014 /* UART FIFO Transmit Count */
+#define KL_UART_RWFIFO_OFFSET 0x0015 /* UART FIFO Receive Watermark */
+#define KL_UART_RCFIFO_OFFSET 0x0016 /* UART FIFO Receive Count */
+#define KL_UART_C7816_OFFSET 0x0017 /* UART 7816 Control Register */
+#define KL_UART_IE7816_OFFSET 0x0018 /* UART 7816 Interrupt Enable Register */
+#define KL_UART_IS7816_OFFSET 0x0019 /* UART 7816 Interrupt Status Register */
+#define KL_UART_WP7816T0_OFFSET 0x001a /* UART 7816 Wait Parameter Register */
+#define KL_UART_WP7816T1_OFFSET 0x001b /* UART 7816 Wait Parameter Register */
+#define KL_UART_WN7816_OFFSET 0x001c /* UART 7816 Wait N Register */
+#define KL_UART_WF7816_OFFSET 0x001d /* UART 7816 Wait FD Register */
+#define KL_UART_ET7816_OFFSET 0x001e /* UART 7816 Error Threshold Register */
+#define KL_UART_TL7816_OFFSET 0x001f /* UART 7816 Transmit Length Register */
+
+/* Register Addresses ***************************************************************/
+
+#if (KL_NISO7816+KL_NUART) > 0
+# define KL_UART0_BDH (KL_UART0_BASE+KL_UART_BDH_OFFSET)
+# define KL_UART0_BDL (KL_UART0_BASE+KL_UART_BDL_OFFSET)
+# define KL_UART0_C1 (KL_UART0_BASE+KL_UART_C1_OFFSET)
+# define KL_UART0_C2 (KL_UART0_BASE+KL_UART_C2_OFFSET)
+# define KL_UART0_S1 (KL_UART0_BASE+KL_UART_S1_OFFSET)
+# define KL_UART0_S2 (KL_UART0_BASE+KL_UART_S2_OFFSET)
+# define KL_UART0_C3 (KL_UART0_BASE+KL_UART_C3_OFFSET)
+# define KL_UART0_D (KL_UART0_BASE+KL_UART_D_OFFSET)
+# define KL_UART0_MA1 (KL_UART0_BASE+KL_UART_MA1_OFFSET)
+# define KL_UART0_MA2 (KL_UART0_BASE+KL_UART_MA2_OFFSET)
+# define KL_UART0_C4 (KL_UART0_BASE+KL_UART_C4_OFFSET)
+# define KL_UART0_C5 (KL_UART0_BASE+KL_UART_C5_OFFSET)
+# define KL_UART0_ED (KL_UART0_BASE+KL_UART_ED_OFFSET)
+# define KL_UART0_MODEM (KL_UART0_BASE+KL_UART_MODEM_OFFSET)
+# define KL_UART0_IR (KL_UART0_BASE+KL_UART_IR_OFFSET)
+# define KL_UART0_PFIFO (KL_UART0_BASE+KL_UART_PFIFO_OFFSET)
+# define KL_UART0_CFIFO (KL_UART0_BASE+KL_UART_CFIFO_OFFSET)
+# define KL_UART0_SFIFO (KL_UART0_BASE+KL_UART_SFIFO_OFFSET)
+# define KL_UART0_TWFIFO (KL_UART0_BASE+KL_UART_TWFIFO_OFFSET)
+# define KL_UART0_TCFIFO (KL_UART0_BASE+KL_UART_TCFIFO_OFFSET)
+# define KL_UART0_RWFIFO (KL_UART0_BASE+KL_UART_RWFIFO_OFFSET)
+# define KL_UART0_RCFIFO (KL_UART0_BASE+KL_UART_RCFIFO_OFFSET)
+# define KL_UART0_C7816 (KL_UART0_BASE+KL_UART_C7816_OFFSET)
+# define KL_UART0_IE7816 (KL_UART0_BASE+KL_UART_IE7816_OFFSET)
+# define KL_UART0_IS7816 (KL_UART0_BASE+KL_UART_IS7816_OFFSET)
+# define KL_UART0_WP7816T0 (KL_UART0_BASE+KL_UART_WP7816T0_OFFSET)
+# define KL_UART0_WP7816T1 (KL_UART0_BASE+KL_UART_WP7816T1_OFFSET)
+# define KL_UART0_WN7816 (KL_UART0_BASE+KL_UART_WN7816_OFFSET)
+# define KL_UART0_WF7816 (KL_UART0_BASE+KL_UART_WF7816_OFFSET)
+# define KL_UART0_ET7816 (KL_UART0_BASE+KL_UART_ET7816_OFFSET)
+# define KL_UART0_TL7816 (KL_UART0_BASE+KL_UART_TL7816_OFFSET)
+#endif
+
+#if (KL_NISO7816+KL_NUART) > 1
+# define KL_UART1_BDH (KL_UART1_BASE+KL_UART_BDH_OFFSET)
+# define KL_UART1_BDL (KL_UART1_BASE+KL_UART_BDL_OFFSET)
+# define KL_UART1_C1 (KL_UART1_BASE+KL_UART_C1_OFFSET)
+# define KL_UART1_C2 (KL_UART1_BASE+KL_UART_C2_OFFSET)
+# define KL_UART1_S1 (KL_UART1_BASE+KL_UART_S1_OFFSET)
+# define KL_UART1_S2 (KL_UART1_BASE+KL_UART_S2_OFFSET)
+# define KL_UART1_C3 (KL_UART1_BASE+KL_UART_C3_OFFSET)
+# define KL_UART1_D (KL_UART1_BASE+KL_UART_D_OFFSET)
+# define KL_UART1_MA1 (KL_UART1_BASE+KL_UART_MA1_OFFSET)
+# define KL_UART1_MA2 (KL_UART1_BASE+KL_UART_MA2_OFFSET)
+# define KL_UART1_C4 (KL_UART1_BASE+KL_UART_C4_OFFSET)
+# define KL_UART1_C5 (KL_UART1_BASE+KL_UART_C5_OFFSET)
+# define KL_UART1_ED (KL_UART1_BASE+KL_UART_ED_OFFSET)
+# define KL_UART1_MODEM (KL_UART1_BASE+KL_UART_MODEM_OFFSET)
+# define KL_UART1_IR (KL_UART1_BASE+KL_UART_IR_OFFSET)
+# define KL_UART1_PFIFO (KL_UART1_BASE+KL_UART_PFIFO_OFFSET)
+# define KL_UART1_CFIFO (KL_UART1_BASE+KL_UART_CFIFO_OFFSET)
+# define KL_UART1_SFIFO (KL_UART1_BASE+KL_UART_SFIFO_OFFSET)
+# define KL_UART1_TWFIFO (KL_UART1_BASE+KL_UART_TWFIFO_OFFSET)
+# define KL_UART1_TCFIFO (KL_UART1_BASE+KL_UART_TCFIFO_OFFSET)
+# define KL_UART1_RWFIFO (KL_UART1_BASE+KL_UART_RWFIFO_OFFSET)
+# define KL_UART1_RCFIFO (KL_UART1_BASE+KL_UART_RCFIFO_OFFSET)
+# define KL_UART1_C7816 (KL_UART1_BASE+KL_UART_C7816_OFFSET)
+# define KL_UART1_IE7816 (KL_UART1_BASE+KL_UART_IE7816_OFFSET)
+# define KL_UART1_IS7816 (KL_UART1_BASE+KL_UART_IS7816_OFFSET)
+# define KL_UART1_WP7816T0 (KL_UART1_BASE+KL_UART_WP7816T0_OFFSET)
+# define KL_UART1_WP7816T1 (KL_UART1_BASE+KL_UART_WP7816T1_OFFSET)
+# define KL_UART1_WN7816 (KL_UART1_BASE+KL_UART_WN7816_OFFSET)
+# define KL_UART1_WF7816 (KL_UART1_BASE+KL_UART_WF7816_OFFSET)
+# define KL_UART1_ET7816 (KL_UART1_BASE+KL_UART_ET7816_OFFSET)
+# define KL_UART1_TL7816 (KL_UART1_BASE+KL_UART_TL7816_OFFSET)
+#endif
+
+#if (KL_NISO7816+KL_NUART) > 2
+# define KL_UART2_BDH (KL_UART2_BASE+KL_UART_BDH_OFFSET)
+# define KL_UART2_BDL (KL_UART2_BASE+KL_UART_BDL_OFFSET)
+# define KL_UART2_C1 (KL_UART2_BASE+KL_UART_C1_OFFSET)
+# define KL_UART2_C2 (KL_UART2_BASE+KL_UART_C2_OFFSET)
+# define KL_UART2_S1 (KL_UART2_BASE+KL_UART_S1_OFFSET)
+# define KL_UART2_S2 (KL_UART2_BASE+KL_UART_S2_OFFSET)
+# define KL_UART2_C3 (KL_UART2_BASE+KL_UART_C3_OFFSET)
+# define KL_UART2_D (KL_UART2_BASE+KL_UART_D_OFFSET)
+# define KL_UART2_MA1 (KL_UART2_BASE+KL_UART_MA1_OFFSET)
+# define KL_UART2_MA2 (KL_UART2_BASE+KL_UART_MA2_OFFSET)
+# define KL_UART2_C4 (KL_UART2_BASE+KL_UART_C4_OFFSET)
+# define KL_UART2_C5 (KL_UART2_BASE+KL_UART_C5_OFFSET)
+# define KL_UART2_ED (KL_UART2_BASE+KL_UART_ED_OFFSET)
+# define KL_UART2_MODEM (KL_UART2_BASE+KL_UART_MODEM_OFFSET)
+# define KL_UART2_IR (KL_UART2_BASE+KL_UART_IR_OFFSET)
+# define KL_UART2_PFIFO (KL_UART2_BASE+KL_UART_PFIFO_OFFSET)
+# define KL_UART2_CFIFO (KL_UART2_BASE+KL_UART_CFIFO_OFFSET)
+# define KL_UART2_SFIFO (KL_UART2_BASE+KL_UART_SFIFO_OFFSET)
+# define KL_UART2_TWFIFO (KL_UART2_BASE+KL_UART_TWFIFO_OFFSET)
+# define KL_UART2_TCFIFO (KL_UART2_BASE+KL_UART_TCFIFO_OFFSET)
+# define KL_UART2_RWFIFO (KL_UART2_BASE+KL_UART_RWFIFO_OFFSET)
+# define KL_UART2_RCFIFO (KL_UART2_BASE+KL_UART_RCFIFO_OFFSET)
+# define KL_UART2_C7816 (KL_UART2_BASE+KL_UART_C7816_OFFSET)
+# define KL_UART2_IE7816 (KL_UART2_BASE+KL_UART_IE7816_OFFSET)
+# define KL_UART2_IS7816 (KL_UART2_BASE+KL_UART_IS7816_OFFSET)
+# define KL_UART2_WP7816T0 (KL_UART2_BASE+KL_UART_WP7816T0_OFFSET)
+# define KL_UART2_WP7816T1 (KL_UART2_BASE+KL_UART_WP7816T1_OFFSET)
+# define KL_UART2_WN7816 (KL_UART2_BASE+KL_UART_WN7816_OFFSET)
+# define KL_UART2_WF7816 (KL_UART2_BASE+KL_UART_WF7816_OFFSET)
+# define KL_UART2_ET7816 (KL_UART2_BASE+KL_UART_ET7816_OFFSET)
+# define KL_UART2_TL7816 (KL_UART2_BASE+KL_UART_TL7816_OFFSET)
+#endif
+
+#if (KL_NISO7816+KL_NUART) > 3
+# define KL_UART3_BDH (KL_UART3_BASE+KL_UART_BDH_OFFSET)
+# define KL_UART3_BDL (KL_UART3_BASE+KL_UART_BDL_OFFSET)
+# define KL_UART3_C1 (KL_UART3_BASE+KL_UART_C1_OFFSET)
+# define KL_UART3_C2 (KL_UART3_BASE+KL_UART_C2_OFFSET)
+# define KL_UART3_S1 (KL_UART3_BASE+KL_UART_S1_OFFSET)
+# define KL_UART3_S2 (KL_UART3_BASE+KL_UART_S2_OFFSET)
+# define KL_UART3_C3 (KL_UART3_BASE+KL_UART_C3_OFFSET)
+# define KL_UART3_D (KL_UART3_BASE+KL_UART_D_OFFSET)
+# define KL_UART3_MA1 (KL_UART3_BASE+KL_UART_MA1_OFFSET)
+# define KL_UART3_MA2 (KL_UART3_BASE+KL_UART_MA2_OFFSET)
+# define KL_UART3_C4 (KL_UART3_BASE+KL_UART_C4_OFFSET)
+# define KL_UART3_C5 (KL_UART3_BASE+KL_UART_C5_OFFSET)
+# define KL_UART3_ED (KL_UART3_BASE+KL_UART_ED_OFFSET)
+# define KL_UART3_MODEM (KL_UART3_BASE+KL_UART_MODEM_OFFSET)
+# define KL_UART3_IR (KL_UART3_BASE+KL_UART_IR_OFFSET)
+# define KL_UART3_PFIFO (KL_UART3_BASE+KL_UART_PFIFO_OFFSET)
+# define KL_UART3_CFIFO (KL_UART3_BASE+KL_UART_CFIFO_OFFSET)
+# define KL_UART3_SFIFO (KL_UART3_BASE+KL_UART_SFIFO_OFFSET)
+# define KL_UART3_TWFIFO (KL_UART3_BASE+KL_UART_TWFIFO_OFFSET)
+# define KL_UART3_TCFIFO (KL_UART3_BASE+KL_UART_TCFIFO_OFFSET)
+# define KL_UART3_RWFIFO (KL_UART3_BASE+KL_UART_RWFIFO_OFFSET)
+# define KL_UART3_RCFIFO (KL_UART3_BASE+KL_UART_RCFIFO_OFFSET)
+# define KL_UART3_C7816 (KL_UART3_BASE+KL_UART_C7816_OFFSET)
+# define KL_UART3_IE7816 (KL_UART3_BASE+KL_UART_IE7816_OFFSET)
+# define KL_UART3_IS7816 (KL_UART3_BASE+KL_UART_IS7816_OFFSET)
+# define KL_UART3_WP7816T0 (KL_UART3_BASE+KL_UART_WP7816T0_OFFSET)
+# define KL_UART3_WP7816T1 (KL_UART3_BASE+KL_UART_WP7816T1_OFFSET)
+# define KL_UART3_WN7816 (KL_UART3_BASE+KL_UART_WN7816_OFFSET)
+# define KL_UART3_WF7816 (KL_UART3_BASE+KL_UART_WF7816_OFFSET)
+# define KL_UART3_ET7816 (KL_UART3_BASE+KL_UART_ET7816_OFFSET)
+# define KL_UART3_TL7816 (KL_UART3_BASE+KL_UART_TL7816_OFFSET)
+#endif
+
+#if (KL_NISO7816+KL_NUART) > 4
+# define KL_UART4_BDH (KL_UART4_BASE+KL_UART_BDH_OFFSET)
+# define KL_UART4_BDL (KL_UART4_BASE+KL_UART_BDL_OFFSET)
+# define KL_UART4_C1 (KL_UART4_BASE+KL_UART_C1_OFFSET)
+# define KL_UART4_C2 (KL_UART4_BASE+KL_UART_C2_OFFSET)
+# define KL_UART4_S1 (KL_UART4_BASE+KL_UART_S1_OFFSET)
+# define KL_UART4_S2 (KL_UART4_BASE+KL_UART_S2_OFFSET)
+# define KL_UART4_C3 (KL_UART4_BASE+KL_UART_C3_OFFSET)
+# define KL_UART4_D (KL_UART4_BASE+KL_UART_D_OFFSET)
+# define KL_UART4_MA1 (KL_UART4_BASE+KL_UART_MA1_OFFSET)
+# define KL_UART4_MA2 (KL_UART4_BASE+KL_UART_MA2_OFFSET)
+# define KL_UART4_C4 (KL_UART4_BASE+KL_UART_C4_OFFSET)
+# define KL_UART4_C5 (KL_UART4_BASE+KL_UART_C5_OFFSET)
+# define KL_UART4_ED (KL_UART4_BASE+KL_UART_ED_OFFSET)
+# define KL_UART4_MODEM (KL_UART4_BASE+KL_UART_MODEM_OFFSET)
+# define KL_UART4_IR (KL_UART4_BASE+KL_UART_IR_OFFSET)
+# define KL_UART4_PFIFO (KL_UART4_BASE+KL_UART_PFIFO_OFFSET)
+# define KL_UART4_CFIFO (KL_UART4_BASE+KL_UART_CFIFO_OFFSET)
+# define KL_UART4_SFIFO (KL_UART4_BASE+KL_UART_SFIFO_OFFSET)
+# define KL_UART4_TWFIFO (KL_UART4_BASE+KL_UART_TWFIFO_OFFSET)
+# define KL_UART4_TCFIFO (KL_UART4_BASE+KL_UART_TCFIFO_OFFSET)
+# define KL_UART4_RWFIFO (KL_UART4_BASE+KL_UART_RWFIFO_OFFSET)
+# define KL_UART4_RCFIFO (KL_UART4_BASE+KL_UART_RCFIFO_OFFSET)
+# define KL_UART4_C7816 (KL_UART4_BASE+KL_UART_C7816_OFFSET)
+# define KL_UART4_IE7816 (KL_UART4_BASE+KL_UART_IE7816_OFFSET)
+# define KL_UART4_IS7816 (KL_UART4_BASE+KL_UART_IS7816_OFFSET)
+# define KL_UART4_WP7816T0 (KL_UART4_BASE+KL_UART_WP7816T0_OFFSET)
+# define KL_UART4_WP7816T1 (KL_UART4_BASE+KL_UART_WP7816T1_OFFSET)
+# define KL_UART4_WN7816 (KL_UART4_BASE+KL_UART_WN7816_OFFSET)
+# define KL_UART4_WF7816 (KL_UART4_BASE+KL_UART_WF7816_OFFSET)
+# define KL_UART4_ET7816 (KL_UART4_BASE+KL_UART_ET7816_OFFSET)
+# define KL_UART4_TL7816 (KL_UART4_BASE+KL_UART_TL7816_OFFSET)
+#endif
+
+#if (KL_NISO7816+KL_NUART) > 5
+# define KL_UART5_BDH (KL_UART5_BASE+KL_UART_BDH_OFFSET)
+# define KL_UART5_BDL (KL_UART5_BASE+KL_UART_BDL_OFFSET)
+# define KL_UART5_C1 (KL_UART5_BASE+KL_UART_C1_OFFSET)
+# define KL_UART5_C2 (KL_UART5_BASE+KL_UART_C2_OFFSET)
+# define KL_UART5_S1 (KL_UART5_BASE+KL_UART_S1_OFFSET)
+# define KL_UART5_S2 (KL_UART5_BASE+KL_UART_S2_OFFSET)
+# define KL_UART5_C3 (KL_UART5_BASE+KL_UART_C3_OFFSET)
+# define KL_UART5_D (KL_UART5_BASE+KL_UART_D_OFFSET)
+# define KL_UART5_MA1 (KL_UART5_BASE+KL_UART_MA1_OFFSET)
+# define KL_UART5_MA2 (KL_UART5_BASE+KL_UART_MA2_OFFSET)
+# define KL_UART5_C4 (KL_UART5_BASE+KL_UART_C4_OFFSET)
+# define KL_UART5_C5 (KL_UART5_BASE+KL_UART_C5_OFFSET)
+# define KL_UART5_ED (KL_UART5_BASE+KL_UART_ED_OFFSET)
+# define KL_UART5_MODEM (KL_UART5_BASE+KL_UART_MODEM_OFFSET)
+# define KL_UART5_IR (KL_UART5_BASE+KL_UART_IR_OFFSET)
+# define KL_UART5_PFIFO (KL_UART5_BASE+KL_UART_PFIFO_OFFSET)
+# define KL_UART5_CFIFO (KL_UART5_BASE+KL_UART_CFIFO_OFFSET)
+# define KL_UART5_SFIFO (KL_UART5_BASE+KL_UART_SFIFO_OFFSET)
+# define KL_UART5_TWFIFO (KL_UART5_BASE+KL_UART_TWFIFO_OFFSET)
+# define KL_UART5_TCFIFO (KL_UART5_BASE+KL_UART_TCFIFO_OFFSET)
+# define KL_UART5_RWFIFO (KL_UART5_BASE+KL_UART_RWFIFO_OFFSET)
+# define KL_UART5_RCFIFO (KL_UART5_BASE+KL_UART_RCFIFO_OFFSET)
+# define KL_UART5_C7816 (KL_UART5_BASE+KL_UART_C7816_OFFSET)
+# define KL_UART5_IE7816 (KL_UART5_BASE+KL_UART_IE7816_OFFSET)
+# define KL_UART5_IS7816 (KL_UART5_BASE+KL_UART_IS7816_OFFSET)
+# define KL_UART5_WP7816T0 (KL_UART5_BASE+KL_UART_WP7816T0_OFFSET)
+# define KL_UART5_WP7816T1 (KL_UART5_BASE+KL_UART_WP7816T1_OFFSET)
+# define KL_UART5_WN7816 (KL_UART5_BASE+KL_UART_WN7816_OFFSET)
+# define KL_UART5_WF7816 (KL_UART5_BASE+KL_UART_WF7816_OFFSET)
+# define KL_UART5_ET7816 (KL_UART5_BASE+KL_UART_ET7816_OFFSET)
+# define KL_UART5_TL7816 (KL_UART5_BASE+KL_UART_TL7816_OFFSET)
+#endif
+
+/* Register Bit Definitions *********************************************************/
+/* UART Baud Rate Register High */
+
+#define UART_BDH_SBR_SHIFT (0) /* Bits 0-4: MS Bits 8-13 of the UART Baud Rate Bits */
+#define UART_BDH_SBR_MASK (31 << UART_BDH_SBR_SHIFT)
+ /* Bit 5: Reserved */
+#define UART_BDH_RXEDGIE (1 << 6) /* Bit 6: RxD Input Active Edge Interrupt Enable */
+#define UART_BDH_LBKDIE (1 << 7) /* Bit 7: LIN Break Detect Interrupt Enable */
+
+/* BDH Bit Fields */
+#define UARTLP_BDH_SBR_MASK 0x1Fu
+#define UARTLP_BDH_SBR_SHIFT 0
+#define UARTLP_BDH_SBR(x) (((uint8_t)(((uint8_t)(x))<<UARTLP_BDH_SBR_SHIFT))&UARTLP_BDH_SBR_MASK)
+
+/* BDL Bit Fields */
+#define UARTLP_BDL_SBR_MASK 0xFFu
+#define UARTLP_BDL_SBR_SHIFT 0
+#define UARTLP_BDL_SBR(x) (((uint8_t)(((uint8_t)(x))<<UARTLP_BDL_SBR_SHIFT))&UARTLP_BDL_SBR_MASK)
+
+/* UART Baud Rate Register Low. Bits 0-7 of the UART baud rate bits. */
+
+/* UART Control Register 1 */
+
+#define UART_C1_PT (1 << 0) /* Bit 0: Parity Type */
+#define UART_C1_PE (1 << 1) /* Bit 1: Parity Enable */
+#define UART_C1_ILT (1 << 2) /* Bit 2: Idle Line Type Select */
+#define UART_C1_WAKE (1 << 3) /* Bit 3: Receiver Wakeup Method Select */
+#define UART_C1_M (1 << 4) /* Bit 4: 9-bit or 8-bit Mode Select */
+#define UART_C1_RSRC (1 << 5) /* Bit 5: Receiver Source Select */
+#define UART_C1_UARTSWAI (1 << 6) /* Bit 6: UART Stops in Wait Mode */
+#define UART_C1_LOOPS (1 << 7) /* Bit 7: Loop Mode Select */
+
+/* UART Control Register 2 */
+
+#define UART_C2_SBK (1 << 0) /* Bit 0: Send Break */
+#define UART_C2_RWU (1 << 1) /* Bit 1: Receiver Wakeup Control */
+#define UART_C2_RE (1 << 2) /* Bit 2: Receiver Enable */
+#define UART_C2_TE (1 << 3) /* Bit 3: Transmitter Enable */
+#define UART_C2_ILIE (1 << 4) /* Bit 4: Idle Line Interruptor Enable */
+#define UART_C2_RIE (1 << 5) /* Bit 5: Receiver Full Interrupt or DMA Transfer Enable */
+#define UART_C2_TCIE (1 << 6) /* Bit 6: Transmission Complete Interrupt Enable */
+#define UART_C2_TIE (1 << 7) /* Bit 7: Transmitter Interrupt or DMA Transfer Enable */
+#define UART_C2_ALLINTS (0xf0)
+
+/* UART Status Register 1 */
+
+#define UART_S1_PF (1 << 0) /* Bit 0: Parity Error Flag */
+#define UART_S1_FE (1 << 1) /* Bit 1: Framing Error Flag */
+#define UART_S1_NF (1 << 2) /* Bit 2: Noise Flag */
+#define UART_S1_OR (1 << 3) /* Bit 3: Receiver Overrun Flag */
+#define UART_S1_IDLE (1 << 4) /* Bit 4: Idle Line Flag */
+#define UART_S1_RDRF (1 << 5) /* Bit 5: Receive Data Register Full Flag */
+#define UART_S1_TC (1 << 6) /* Bit 6: Transmit Complete Flag */
+#define UART_S1_TDRE (1 << 7) /* Bit 7: Transmit Data Register Empty Flag */
+
+/* UART Status Register 2 */
+
+#define UART_S2_RAF (1 << 0) /* Bit 0: Receiver Active Flag */
+#define UART_S2_LBKDE (1 << 1) /* Bit 1: LIN Break Detection Enable */
+#define UART_S2_BRK13 (1 << 2) /* Bit 2: Break Transmit Character Length */
+#define UART_S2_RWUID (1 << 3) /* Bit 3: Receive Wakeup Idle Detect */
+#define UART_S2_RXINV (1 << 4) /* Bit 4: Receive Data Inversion */
+#define UART_S2_MSBF (1 << 5) /* Bit 5: Most Significant Bit First */
+#define UART_S2_RXEDGIF (1 << 6) /* Bit 6: RxD Pin Active Edge Interrupt Flag */
+#define UART_S2_LBKDIF (1 << 7) /* Bit 7: LIN Break Detect Interrupt Flag */
+
+/* UART Control Register 3 */
+
+#define UART_C3_PEIE (1 << 0) /* Bit 0: Parity Error Interrupt Enable */
+#define UART_C3_FEIE (1 << 1) /* Bit 1: Framing Error Interrupt Enable */
+#define UART_C3_NEIE (1 << 2) /* Bit 2: Noise Error Interrupt Enable */
+#define UART_C3_ORIE (1 << 3) /* Bit 3: Overrun Error Interrupt Enable */
+#define UART_C3_TXINV (1 << 4) /* Bit 4: Transmit Data Inversion */
+#define UART_C3_TXDIR (1 << 5) /* Bit 5: Transmitter Pin Data Direction in Single-Wire mode */
+#define UART_C3_T8 (1 << 6) /* Bit 6: Transmit Bit 8 */
+#define UART_C3_R8 (1 << 7) /* Bit 7: Received Bit 8 */
+
+/* UART Data Register: 8-bit data register. */
+/* UART Match Address Registers 1 & 2: 8-bit address registers */
+
+/* UART Control Register 4 */
+
+#define UART_C4_BRFA_SHIFT (0) /* Bits 0-4: Baud Rate Fine Adjust */
+#define UART_C4_BRFA_MASK (31 << UART_C4_BRFA_SHIFT)
+#define UART_C4_M10 (1 << 5) /* Bit 5: 10-bit Mode select */
+#define UART_C4_MAEN2 (1 << 6) /* Bit 6: Match Address Mode Enable 2 */
+#define UART_C4_MAEN1 (1 << 7) /* Bit 7: Match Address Mode Enable 1 */
+
+/* UART Control Register 5 */
+
+ /* Bit 0-4: Reserved */
+#define UART_C5_RDMAS (1 << 5) /* Bit 5: Receiver Full DMA Select */
+ /* Bit 6: Reserved */
+#define UART_C5_TDMAS (1 << 7) /* Bit 7: Transmitter DMA Select */
+
+/* UART Extended Data Register */
+
+ /* Bit 0-5: Reserved */
+#define UART_ED_PARITYE (1 << 6) /* Bit 6: The current received dataword contained
+ * in D and C3[R8] was received with a parity error */
+#define UART_ED_NOISY (1 << 7) /* Bit 7: The current received dataword contained
+ * in D and C3[R8] was received with noise */
+
+/* UART Modem Register */
+
+#define UART_MODEM_TXCTSE (1 << 0) /* Bit 0: Transmitter clear-to-send enable */
+#define UART_MODEM_TXRTSE (1 << 1) /* Bit 1: Transmitter request-to-send enable */
+#define UART_MODEM_TXRTSPOL (1 << 2) /* Bit 2: Transmitter request-to-send polarity */
+#define UART_MODEM_RXRTSE (1 << 3) /* Bit 3: Receiver request-to-send enable */
+ /* Bits 4-7: Reserved */
+
+/* UART Infrared Register */
+
+#define UART_IR_TNP_SHIFT (0) /* Bits 0-1: Transmitter narrow pulse */
+#define UART_IR_TNP_MASK (3 << UART_IR_TNP_SHIFT)
+# define UART_IR_TNP_316THS (0 << UART_IR_TNP_SHIFT) /* 3/16 */
+# define UART_IR_TNP_16TH (1 << UART_IR_TNP_SHIFT) /* 1/16 */
+# define UART_IR_TNP_32ND (2 << UART_IR_TNP_SHIFT) /* 1/32 */
+# define UART_IR_TNP_4TH (3 << UART_IR_TNP_SHIFT) /* 1/4 */
+#define UART_IR_IREN (1 << 2) /* Bit 2: Infrared enable */
+ /* Bits 3-7: Reserved */
+
+/* UART FIFO Parameters */
+
+#define UART_PFIFO_RXFIFOSIZE_SHIFT (0) /* Bits 0-2: Receive FIFO. Buffer Depth */
+#define UART_PFIFO_RXFIFOSIZE_MASK (7 << UART_PFIFO_RXFIFOSIZE_SHIFT)
+# define UART_PFIFO_RXFIFOSIZE_1 (0 << UART_PFIFO_RXFIFOSIZE_SHIFT) /* 1 */
+# define UART_PFIFO_RXFIFOSIZE_4 (1 << UART_PFIFO_RXFIFOSIZE_SHIFT) /* 4 */
+# define UART_PFIFO_RXFIFOSIZE_8 (2 << UART_PFIFO_RXFIFOSIZE_SHIFT) /* 8 */
+# define UART_PFIFO_RXFIFOSIZE_16 (3 << UART_PFIFO_RXFIFOSIZE_SHIFT) /* 16 */
+# define UART_PFIFO_RXFIFOSIZE_32 (4 << UART_PFIFO_RXFIFOSIZE_SHIFT) /* 32 */
+# define UART_PFIFO_RXFIFOSIZE_64 (5 << UART_PFIFO_RXFIFOSIZE_SHIFT) /* 64 */
+# define UART_PFIFO_RXFIFOSIZE_128 (6 << UART_PFIFO_RXFIFOSIZE_SHIFT) /* 128 */
+#define UART_PFIFO_RXFE (1 << 3) /* Bit 3: Receive FIFO Enable */
+#define UART_PFIFO_TXFIFOSIZE_SHIFT (4) /* Bits 4-6: Transmit FIFO. Buffer Depth */
+#define UART_PFIFO_TXFIFOSIZE_MASK (7 << UART_PFIFO_TXFIFOSIZE_SHIFT)
+# define UART_PFIFO_TXFIFOSIZE_1 (0 << UART_PFIFO_TXFIFOSIZE_SHIFT) /* 1 */
+# define UART_PFIFO_TXFIFOSIZE_4 (1 << UART_PFIFO_TXFIFOSIZE_SHIFT) /* 4 */
+# define UART_PFIFO_TXFIFOSIZE_8 (2 << UART_PFIFO_TXFIFOSIZE_SHIFT) /* 8 */
+# define UART_PFIFO_TXFIFOSIZE_16 (3 << UART_PFIFO_TXFIFOSIZE_SHIFT) /* 16 */
+# define UART_PFIFO_TXFIFOSIZE_32 (4 << UART_PFIFO_TXFIFOSIZE_SHIFT) /* 32 */
+# define UART_PFIFO_TXFIFOSIZE_64 (5 << UART_PFIFO_TXFIFOSIZE_SHIFT) /* 64 */
+# define UART_PFIFO_TXFIFOSIZE_128 (6 << UART_PFIFO_TXFIFOSIZE_SHIFT) /* 128 */
+#define UART_PFIFO_TXFE (1 << 7) /* Bit 7: Transmit FIFO Enable */
+
+/* UART FIFO Control Register */
+
+#define UART_CFIFO_RXUFE (1 << 0) /* Bit 0: Receive FIFO Underflow Interrupt Enable */
+#define UART_CFIFO_TXOFE (1 << 1) /* Bit 1: Transmit FIFO Overflow Interrupt Enable */
+ /* Bits 2-5: Reserved */
+#define UART_CFIFO_RXFLUSH (1 << 6) /* Bit 6: Receive FIFO/Buffer Flush */
+#define UART_CFIFO_TXFLUSH (1 << 7) /* Bit 7: Transmit FIFO/Buffer Flush */
+
+/* UART FIFO Status Register */
+
+#define UART_SFIFO_RXUF (1 << 0) /* Bit 0: Receiver Buffer Underflow Flag */
+#define UART_SFIFO_TXOF (1 << 1) /* Bit 1: Transmitter Buffer Overflow Flag */
+ /* Bits 2-5: Reserved */
+#define UART_SFIFO_RXEMPT (1 << 6) /* Bit 6: Receive Buffer/FIFO Empty */
+#define UART_SFIFO_TXEMPT (1 << 7) /* Bit 7: Transmit Buffer/FIFO Empty */
+
+/* UART FIFO Transmit Watermark. 8-bit watermark value. */
+/* UART FIFO Transmit Count. 8-bit count value */
+/* UART FIFO Receive Watermark. 8-bit watermark value. */
+/* UART FIFO Receive Count. 8-bit count value */
+
+/* UART 7816 Control Register */
+
+#define UART_C7816_ISO7816E (1 << 0) /* Bit 0: ISO-7816 Functionality Enabled */
+#define UART_C7816_TTYPE (1 << 1) /* Bit 1: Transfer Type */
+#define UART_C7816_INIT (1 << 2) /* Bit 2: Detect Initial Character */
+#define UART_C7816_ANACK (1 << 3) /* Bit 3: Generate NACK on Error */
+#define UART_C7816_ONACK (1 << 4) /* Bit 4: Generate NACK on Overflow */
+ /* Bits 5-7: Reserved */
+
+/* UART 7816 Interrupt Enable Register */
+
+#define UART_IE7816_RXTE (1 << 0) /* Bit 0: Receive Threshold Exceeded Interrupt Enable */
+#define UART_IE7816_TXTE (1 << 1) /* Bit 1: Transmit Threshold Exceeded Interrupt Enable */
+#define UART_IE7816_GTVE (1 << 2) /* Bit 2: Guard Timer Violated Interrupt Enable */
+ /* Bit 3: Reserved */
+#define UART_IE7816_INITDE (1 << 4) /* Bit 4: Initial Character Detected Interrupt Enable */
+#define UART_IE7816_BWTE (1 << 5) /* Bit 5: Block Wait Timer Interrupt Enable */
+#define UART_IE7816_CWTE (1 << 6) /* Bit 6: Character Wait Timer Interrupt Enable */
+#define UART_IE7816_WTE (1 << 7) /* Bit 7: Wait Timer Interrupt Enable */
+
+/* UART 7816 Interrupt Status Register */
+
+#define UART_IS7816_RXT (1 << 0) /* Bit 0: Receive Threshold Exceeded Interrupt */
+#define UART_IS7816_TXT (1 << 1) /* Bit 1: Transmit Threshold Exceeded Interrupt */
+#define UART_IS7816_GTV (1 << 2) /* Bit 2: Guard Timer Violated Interrupt */
+ /* Bit 3: Reserved */
+#define UART_IS7816_INITD (1 << 4) /* Bit 4: Initial Character Detected Interrupt */
+#define UART_IS7816_BWT (1 << 5) /* Bit 5: Block Wait Timer Interrupt */
+#define UART_IS7816_CWT (1 << 6) /* Bit 6: Character Wait Timer Interrupt */
+#define UART_IS7816_WT (1 << 7) /* Bit 7: Wait Timer Interrupt */
+
+/* UART 7816 Wait Parameter Register. 8-bit Wait Timer Interrupt value. */
+
+/* UART 7816 Wait Parameter Register */
+
+#define UART_WP7816T1_BWI_SHIFT (0) /* Bit 0-3: Block Wait Time Integer(C7816[TTYPE] = 1) */
+#define UART_WP7816T1_BWI_MASK (15 << UART_WP7816T1_BWI_SHIFT)
+#define UART_WP7816T1_CWI_SHIFT (4) /* Bits 4-7: Character Wait Time Integer (C7816[TTYPE] = 1) */
+#define UART_WP7816T1_CWI_MASK (15 << UART_WP7816T1_CWI_SHIFT)
+
+/* UART 7816 Wait N Register. 8-bit Guard Band value. */
+/* UART 7816 Wait FD Register. 8-bit FD Multiplier value. */
+
+/* UART 7816 Error Threshold Register */
+
+#define UART_ET7816_RXTHRESH_SHIFT (0) /* Bit 0-3: Receive NACK Threshold */
+#define UART_ET7816_RXTHRESH_MASK (15 << UART_ET7816_RXTHRESHOLD_SHIFT)
+#define UART_ET7816_TXTHRESH_SHIFT (4) /* Bits 4-7: Transmit NACK Threshold */
+#define UART_ET7816_TXTHRESH_MASK (15 << UART_ET7816_TXTHRESHOLD_MASK)
+
+/* UART 7816 Transmit Length Register. 8-bit Transmit Length value */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KL_KL_UART_H */
diff --git a/nuttx/arch/arm/src/kl/kl_cfmconfig.c b/nuttx/arch/arm/src/kl/kl_cfmconfig.c
new file mode 100644
index 000000000..8135bfe6e
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_cfmconfig.c
@@ -0,0 +1,42 @@
+/* Barely based on "bare metal" sample from Freedom board:
+Copyright (c) 2012-2013 Andrew Payne
+
+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 <stdint.h>
+
+const uint8_t _cfmconfig[16] __attribute__((section(".cfmconfig"))) =
+{
+ 0xFF, /* NV_BACKKEY3: KEY=0xFF */
+ 0xFF, /* NV_BACKKEY2: KEY=0xFF */
+ 0xFF, /* NV_BACKKEY1: KEY=0xFF */
+ 0xFF, /* NV_BACKKEY0: KEY=0xFF */
+ 0xFF, /* NV_BACKKEY7: KEY=0xFF */
+ 0xFF, /* NV_BACKKEY6: KEY=0xFF */
+ 0xFF, /* NV_BACKKEY5: KEY=0xFF */
+ 0xFF, /* NV_BACKKEY4: KEY=0xFF */
+ 0xFF, /* NV_FPROT3: PROT=0xFF */
+ 0xFF, /* NV_FPROT2: PROT=0xFF */
+ 0xFF, /* NV_FPROT1: PROT=0xFF */
+ 0xFF, /* NV_FPROT0: PROT=0xFF */
+ 0x7E, /* NV_FSEC: KEYEN=1,MEEN=3,FSLACC=3,SEC=2 */
+ 0xFF, /* NV_FOPT: ??=1,??=1,FAST_INIT=1,LPBOOT1=1,RESET_PIN_CFG=1,
+ NMI_DIS=1,EZPORT_DIS=1,LPBOOT0=1 */
+ 0xFF,
+ 0xFF
+};
diff --git a/nuttx/arch/arm/src/kl/kl_clockconfig.c b/nuttx/arch/arm/src/kl/kl_clockconfig.c
new file mode 100644
index 000000000..25679243b
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_clockconfig.c
@@ -0,0 +1,275 @@
+/****************************************************************************
+ * arch/arm/src/kl/kl_clockconfig.c
+ * arch/arm/src/chip/kl_clockconfig.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+
+#include "chip.h"
+#include "chip/kl_internal.h"
+#include "chip/kl_mcg.h"
+#include "chip/kl_sim.h"
+#include "chip/kl_osc.h"
+#include "chip/kl_fmc.h"
+#include "chip/kl_llwu.h"
+#include "chip/kl_pinmux.h"
+#include "MKL25Z4.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kl_portclocks
+ *
+ * Description:
+ * Enable all of the port clocks
+ *
+ ****************************************************************************/
+
+#if 0
+static inline void kl_portclocks(void)
+{
+ uint32_t regval;
+
+ /* Enable all of the port clocks */
+
+ regval = getreg32(KL_SIM_SCGC5);
+ regval |= (SIM_SCGC5_PORTA | SIM_SCGC5_PORTB | SIM_SCGC5_PORTC |
+ SIM_SCGC5_PORTD | SIM_SCGC5_PORTE);
+ putreg32(regval, KL_SIM_SCGC5);
+}
+#endif
+
+/****************************************************************************
+ * Name: kl_pllconfig
+ *
+ * Description:
+ * Initialize the PLL using the settings in board.h. This assumes that
+ * the MCG is in default FLL Engaged Internal (FEI mode) out of reset.
+ *
+ ****************************************************************************/
+
+#if 0
+void kl_pllconfig(void)
+{
+ uint32_t regval32;
+ uint8_t regval8;
+
+ /* Enable clock gate to Port A module to enable pin routing (PORTA=1) */
+ regval32 = getreg32(KL_SIM_SCGC5);
+ regval32 |= SIM_SCGC5_PORTA;
+ putreg32(regval32, KL_SIM_SCGC5);
+
+ /* Divide-by-2 for clock 1 and clock 4 (OUTDIV1=1, OUTDIV4=1) */
+ regval32 = SIM_CLKDIV1_OUTDIV1(1) | SIM_CLKDIV1_OUTDIV4(1);
+ putreg32(regval32, KL_SIM_CLKDIV1);
+
+ /* System oscillator drives 32 kHz clock for various peripherals (OSC32KSEL=0) */
+ regval32 = getreg32(KL_SIM_SOPT1);
+ regval32 &= ~(SIM_SOPT1_OSC32KSEL);
+ putreg32(regval32, KL_SIM_SOPT1);
+
+ /* Select PLL as a clock source for various peripherals (PLLFLLSEL=1)
+ Clock source for TPM counter clock is MCGFLLCLK or MCGPLLCLK/2 */
+ regval32 = getreg32(KL_SIM_SOPT2);
+ regval32 |= SIM_SOPT2_PLLFLLSEL;
+ putreg32(regval32, KL_SIM_SOPT2);
+ regval32 = (regval32 & ~(SIM_SOPT2_TPMSRC_OCSERCLK)) | SIM_SOPT2_TPMSRC_MCGCLK;
+ putreg32(regval32, KL_SIM_SOPT2);
+
+ /* PORTA_PCR18: ISF=0,MUX=0 */
+ /* PORTA_PCR19: ISF=0,MUX=0 */
+ regval32 = getreg32(KL_PORTA_PCR18);
+ regval32 = ~(PORT_PCR_ISF | PORT_PCR_MUX_ALT7);
+ putreg32(regval32, KL_PORTA_PCR18);
+ regval32 = getreg32(KL_PORTA_PCR19);
+ regval32 = ~(PORT_PCR_ISF | PORT_PCR_MUX_ALT7);
+ putreg32(regval32, KL_PORTA_PCR19);
+
+ /* Switch to FBE Mode */
+ /* OSC0_CR: ERCLKEN=0,??=0,EREFSTEN=0,??=0,SC2P=0,SC4P=0,SC8P=0,SC16P=0 */
+ putreg8(0, KL_OSC_CR);
+ /* MCG_C2: LOCRE0=0,??=0,RANGE0=2,HGO0=0,EREFS0=1,LP=0,IRCS=0 */
+ //regval8 = (MCG_C2_RANGE_VHIGH | MCG_C2_EREFS);
+ regval8 = MCG_C2_EREFS;
+ putreg8(regval8, KL_MCG_C2);
+ /* MCG_C1: CLKS=2,FRDIV=3,IREFS=0,IRCLKEN=0,IREFSTEN=0 */
+ regval8 = (MCG_C1_CLKS_EXTREF | MCG_C1_FRDIV_R0DIV8);
+ putreg8(regval8, KL_MCG_C1);
+ /* MCG_C4: DMX32=0,DRST_DRS=0 */
+ regval8 = ~(MCG_C4_DMX32 | MCG_C4_DRST_DRS_HIGH);
+ putreg8(regval8, KL_MCG_C4);
+ /* MCG_C5: ??=0,PLLCLKEN0=0,PLLSTEN0=0,PRDIV0=1 */
+ regval8 = MCG_C5_PRDIV(1);
+ putreg8(regval8, KL_MCG_C5);
+ /* MCG_C6: LOLIE0=0,PLLS=0,CME0=0,VDIV0=0 */
+ putreg8(0, KL_MCG_C6);
+
+ /* Check that the source of the FLL reference clock is
+ the external reference clock. */
+ while((getreg8(KL_MCG_S) & MCG_S_IREFST) != 0)
+ ;
+
+ /* Wait until external reference */
+ while((getreg8(KL_MCG_S) & MCG_S_CLKST_MASK) != 8)
+ ;
+
+ /* Switch to PBE mode
+ Select PLL as MCG source (PLLS=1) */
+ putreg8(MCG_C6_PLLS, KL_MCG_C6);
+ /* Wait until PLL locked */
+ while((getreg8(KL_MCG_S) & MCG_S_LOCK) != 0)
+ ;
+
+ /* Switch to PEE mode
+ Select PLL output (CLKS=0)
+ FLL external reference divider (FRDIV=3)
+ External reference clock for FLL (IREFS=0) */
+ putreg8(MCG_C1_FRDIV_R0DIV8, KL_MCG_C1);
+
+ /* Wait until PLL output */
+ while((getreg8(KL_MCG_S) & MCG_S_CLKST_MASK) != 0x0C)
+ ;
+}
+#endif
+
+static void init_clocks(void)
+{
+ // Enable clock gate to Port A module to enable pin routing (PORTA=1)
+ SIM_SCGC5 |= SIM_SCGC5_PORTA_MASK;
+
+ // Divide-by-2 for clock 1 and clock 4 (OUTDIV1=1, OUTDIV4=1)
+ SIM_CLKDIV1 = SIM_CLKDIV1_OUTDIV1(0x01) | SIM_CLKDIV1_OUTDIV4(0x01);
+
+ // System oscillator drives 32 kHz clock for various peripherals (OSC32KSEL=0)
+ SIM_SOPT1 &= ~SIM_SOPT1_OSC32KSEL(0x03);
+
+ // Select PLL as a clock source for various peripherals (PLLFLLSEL=1)
+ // Clock source for TPM counter clock is MCGFLLCLK or MCGPLLCLK/2
+ SIM_SOPT2 |= SIM_SOPT2_PLLFLLSEL_MASK;
+ SIM_SOPT2 = (SIM_SOPT2 & ~(SIM_SOPT2_TPMSRC(0x02))) | SIM_SOPT2_TPMSRC(0x01);
+
+ /* PORTA_PCR18: ISF=0,MUX=0 */
+ /* PORTA_PCR19: ISF=0,MUX=0 */
+ PORTA_PCR18 &= ~((PORT_PCR_ISF_MASK | PORT_PCR_MUX(0x07)));
+ PORTA_PCR19 &= ~((PORT_PCR_ISF_MASK | PORT_PCR_MUX(0x07)));
+ /* Switch to FBE Mode */
+
+ /* OSC0_CR: ERCLKEN=0,??=0,EREFSTEN=0,??=0,SC2P=0,SC4P=0,SC8P=0,SC16P=0 */
+ OSC0_CR = 0;
+ /* MCG_C2: LOCRE0=0,??=0,RANGE0=2,HGO0=0,EREFS0=1,LP=0,IRCS=0 */
+ MCG_C2 = (MCG_C2_RANGE0(0x02) | MCG_C2_EREFS0_MASK);
+ /* MCG_C1: CLKS=2,FRDIV=3,IREFS=0,IRCLKEN=0,IREFSTEN=0 */
+ MCG_C1 = (MCG_C1_CLKS(0x02) | MCG_C1_FRDIV(0x03));
+ /* MCG_C4: DMX32=0,DRST_DRS=0 */
+ MCG_C4 &= ~((MCG_C4_DMX32_MASK | MCG_C4_DRST_DRS(0x03)));
+ /* MCG_C5: ??=0,PLLCLKEN0=0,PLLSTEN0=0,PRDIV0=1 */
+ MCG_C5 = MCG_C5_PRDIV0(0x01);
+ /* MCG_C6: LOLIE0=0,PLLS=0,CME0=0,VDIV0=0 */
+ MCG_C6 = 0;
+
+
+ // Check that the source of the FLL reference clock is
+ // the external reference clock.
+ while((MCG_S & MCG_S_IREFST_MASK) != 0)
+ ;
+
+ while((MCG_S & MCG_S_CLKST_MASK) != 8) // Wait until external reference
+ ;
+
+ // Switch to PBE mode
+ // Select PLL as MCG source (PLLS=1)
+ MCG_C6 = MCG_C6_PLLS_MASK;
+ while((MCG_S & MCG_S_LOCK0_MASK) == 0) // Wait until PLL locked
+ ;
+
+ // Switch to PEE mode
+ // Select PLL output (CLKS=0)
+ // FLL external reference divider (FRDIV=3)
+ // External reference clock for FLL (IREFS=0)
+ MCG_C1 = MCG_C1_FRDIV(0x03);
+ while((MCG_S & MCG_S_CLKST_MASK) != 0x0CU) // Wait until PLL output
+ ;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kl_clockconfig
+ *
+ * Description:
+ * Called to initialize the Kinetis chip. This does whatever setup is
+ * needed to put the MCU in a usable state. This includes the
+ * initialization of clocking using the settings in board.h.
+ *
+ ****************************************************************************/
+
+void kl_clockconfig(void)
+{
+ /* Enable all of the port clocks */
+
+ //kl_portclocks();
+
+ /* Configure the PLL based on settings in the board.h file */
+
+ //kl_pllconfig();
+ init_clocks();
+
+ /* For debugging, we will normally want to enable the trace clock and/or
+ * the FlexBus clock.
+ */
+
+ //kl_traceconfig();
+ //kl_fbconfig();
+}
+
diff --git a/nuttx/arch/arm/src/kl/kl_clockconfig.c_orig b/nuttx/arch/arm/src/kl/kl_clockconfig.c_orig
new file mode 100644
index 000000000..f595f3210
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_clockconfig.c_orig
@@ -0,0 +1,209 @@
+/****************************************************************************
+ * arch/arm/src/kl/kl_clockconfig.c
+ * arch/arm/src/chip/kl_clockconfig.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+
+#include "chip.h"
+#include "chip/kl_internal.h"
+#include "chip/kl_mcg.h"
+#include "chip/kl_sim.h"
+#include "chip/kl_osc.h"
+#include "chip/kl_fmc.h"
+#include "chip/kl_llwu.h"
+#include "chip/kl_pinmux.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kl_portclocks
+ *
+ * Description:
+ * Enable all of the port clocks
+ *
+ ****************************************************************************/
+
+static inline void kl_portclocks(void)
+{
+ uint32_t regval;
+
+ /* Enable all of the port clocks */
+
+ regval = getreg32(KL_SIM_SCGC5);
+ regval |= (SIM_SCGC5_PORTA | SIM_SCGC5_PORTB | SIM_SCGC5_PORTC |
+ SIM_SCGC5_PORTD | SIM_SCGC5_PORTE);
+ putreg32(regval, KL_SIM_SCGC5);
+}
+
+/****************************************************************************
+ * Name: kl_pllconfig
+ *
+ * Description:
+ * Initialize the PLL using the settings in board.h. This assumes that
+ * the MCG is in default FLL Engaged Internal (FEI mode) out of reset.
+ *
+ ****************************************************************************/
+
+void kl_pllconfig(void)
+{
+ uint32_t regval32;
+ uint8_t regval8;
+
+ /* Enable clock gate to Port A module to enable pin routing (PORTA=1) */
+ regval32 = getreg32(KL_SIM_SCGC5);
+ regval32 |= SIM_SCGC5_PORTA;
+ putreg32(regval32, KL_SIM_SCGC5);
+
+ /* Divide-by-2 for clock 1 and clock 4 (OUTDIV1=1, OUTDIV4=1) */
+ regval32 = (SIM_CLKDIV1_OUTDIV1(1) | SIM_CLKDIV1_OUTDIV4(1));
+ putreg32(regval32, KL_SIM_CLKDIV1);
+
+ /* System oscillator drives 32 kHz clock for various peripherals (OSC32KSEL=0) */
+ regval32 = getreg32(KL_SIM_SOPT1);
+ regval32 &= ~(SIM_SOPT1_OSC32KSEL);
+ putreg32(regval32, KL_SIM_SOPT1);
+
+ /* Select PLL as a clock source for various peripherals (PLLFLLSEL=1)
+ Clock source for TPM counter clock is MCGFLLCLK or MCGPLLCLK/2 */
+ regval32 = getreg32(KL_SIM_SOPT2);
+ regval32 |= SIM_SOPT2_PLLFLLSEL;
+ putreg32(regval32, KL_SIM_SOPT2);
+ regval32 = (regval32 & ~(SIM_SOPT2_TPMSRC_OCSERCLK)) | SIM_SOPT2_TPMSRC_MCGCLK;
+ putreg32(regval32, KL_SIM_SOPT2);
+
+ /* PORTA_PCR18: ISF=0,MUX=0 */
+ /* PORTA_PCR19: ISF=0,MUX=0 */
+ regval32 = getreg32(KL_PORTA_PCR18);
+ regval32 = ~(PORT_PCR_ISF | PORT_PCR_MUX_ALT7);
+ putreg32(regval32, KL_PORTA_PCR18);
+ regval32 = getreg32(KL_PORTA_PCR19);
+ regval32 = ~(PORT_PCR_ISF | PORT_PCR_MUX_ALT7);
+ putreg32(regval32, KL_PORTA_PCR19);
+
+ /* Switch to FBE Mode */
+ /* OSC0_CR: ERCLKEN=0,??=0,EREFSTEN=0,??=0,SC2P=0,SC4P=0,SC8P=0,SC16P=0 */
+ putreg8(0, KL_OSC_CR);
+ /* MCG_C2: LOCRE0=0,??=0,RANGE0=2,HGO0=0,EREFS0=1,LP=0,IRCS=0 */
+ regval8 = (MCG_C2_RANGE_VHIGH | MCG_C2_EREFS);
+ putreg8(regval8, KL_MCG_C2);
+ /* MCG_C1: CLKS=2,FRDIV=3,IREFS=0,IRCLKEN=0,IREFSTEN=0 */
+ regval8 = (MCG_C1_CLKS_EXTREF | MCG_C1_FRDIV_R0DIV8);
+ putreg8(regval8, KL_MCG_C1);
+ /* MCG_C4: DMX32=0,DRST_DRS=0 */
+ regval8 = ~(MCG_C4_DMX32 | MCG_C4_DRST_DRS_HIGH);
+ putreg8(regval8, KL_MCG_C4);
+ /* MCG_C5: ??=0,PLLCLKEN0=0,PLLSTEN0=0,PRDIV0=1 */
+ regval8 = MCG_C5_PRDIV(1);
+ putreg8(regval8, KL_MCG_C5);
+ /* MCG_C6: LOLIE0=0,PLLS=0,CME0=0,VDIV0=0 */
+ putreg8(0, KL_MCG_C6);
+
+ /* Check that the source of the FLL reference clock is
+ the external reference clock. */
+ while((getreg8(KL_MCG_S) & MCG_S_IREFST) != 0)
+ ;
+
+ /* Wait until external reference */
+ while((getreg8(KL_MCG_S) & MCG_S_CLKST_MASK) != 8)
+ ;
+
+ /* Switch to PBE mode
+ Select PLL as MCG source (PLLS=1) */
+ putreg8(MCG_C6_PLLS, KL_MCG_C6);
+ /* Wait until PLL locked */
+ while((getreg8(KL_MCG_S) & MCG_S_LOCK) == 0)
+ ;
+
+ /* Switch to PEE mode
+ Select PLL output (CLKS=0)
+ FLL external reference divider (FRDIV=3)
+ External reference clock for FLL (IREFS=0) */
+ putreg8(MCG_C1_FRDIV_R0DIV8, KL_MCG_C1);
+
+ /* Wait until PLL output */
+ while((getreg8(KL_MCG_S) & MCG_S_CLKST_MASK) != 0x0C)
+ ;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kl_clockconfig
+ *
+ * Description:
+ * Called to initialize the Kinetis chip. This does whatever setup is
+ * needed to put the MCU in a usable state. This includes the
+ * initialization of clocking using the settings in board.h.
+ *
+ ****************************************************************************/
+
+void kl_clockconfig(void)
+{
+ /* Enable all of the port clocks */
+
+ //kl_portclocks();
+
+ /* Configure the PLL based on settings in the board.h file */
+
+ kl_pllconfig();
+
+ /* For debugging, we will normally want to enable the trace clock and/or
+ * the FlexBus clock.
+ */
+
+ //kl_traceconfig();
+ //kl_fbconfig();
+}
+
diff --git a/nuttx/arch/arm/src/kl/kl_config.h b/nuttx/arch/arm/src/kl/kl_config.h
new file mode 100644
index 000000000..a85b9b9c8
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_config.h
@@ -0,0 +1,235 @@
+/************************************************************************************
+ * arch/arm/src/kl/kl_config.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KINETISXX_KL_CONFIG_H
+#define __ARCH_ARM_SRC_KINETISXX_KL_CONFIG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/board/board.h>
+
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Configuration *********************************************************************/
+/* Make that no unsupport UARTs are enabled */
+
+#ifndef KL_NISO7816
+# define KL_NISO7816 0
+#endif
+
+#if (KL_NISO7816 + KL_NUART) < 6
+# undef CONFIG_KL_UART5
+# if (KL_NISO7816 + KL_NUART) < 5
+# undef CONFIG_KL_UART4
+# if (KL_NISO7816 + KL_NUART) < 4
+# undef CONFIG_KL_UART3
+# if (KL_NISO7816 + KL_NUART) < 3
+# undef CONFIG_KL_UART2
+# if (KL_NISO7816 + KL_NUART) < 2
+# undef CONFIG_KL_UART1
+# if (KL_NISO7816 + KL_NUART) < 1
+# undef CONFIG_KL_UART0
+# endif
+# endif
+# endif
+# endif
+# endif
+#endif
+
+/* Are any UARTs enabled? */
+
+#undef HAVE_UART_DEVICE
+#if defined(CONFIG_KL_UART0) || defined(CONFIG_KL_UART1) || \
+ defined(CONFIG_KL_UART2) || defined(CONFIG_KL_UART3) || \
+ defined(CONFIG_KL_UART5)
+# define HAVE_UART_DEVICE 1
+#endif
+
+/* Is there a serial console? There should be at most one defined. It could be on
+ * any UARTn, n=0,1,2,3,4,5
+ */
+
+#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_KL_UART0)
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef CONFIG_UART3_SERIAL_CONSOLE
+# undef CONFIG_UART4_SERIAL_CONSOLE
+# undef CONFIG_UART5_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_KL_UART1)
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef CONFIG_UART3_SERIAL_CONSOLE
+# undef CONFIG_UART4_SERIAL_CONSOLE
+# undef CONFIG_UART5_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_KL_UART2)
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART3_SERIAL_CONSOLE
+# undef CONFIG_UART4_SERIAL_CONSOLE
+# undef CONFIG_UART5_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#elif defined(CONFIG_UART3_SERIAL_CONSOLE) && defined(CONFIG_KL_UART3)
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef CONFIG_UART4_SERIAL_CONSOLE
+# undef CONFIG_UART5_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#elif defined(CONFIG_UART4_SERIAL_CONSOLE) && defined(CONFIG_KL_UART4)
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef CONFIG_UART3_SERIAL_CONSOLE
+# undef CONFIG_UART5_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#elif defined(CONFIG_UART5_SERIAL_CONSOLE) && defined(CONFIG_KL_UART5)
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef CONFIG_UART3_SERIAL_CONSOLE
+# undef CONFIG_UART4_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+#else
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef CONFIG_UART3_SERIAL_CONSOLE
+# undef CONFIG_UART4_SERIAL_CONSOLE
+# undef CONFIG_UART5_SERIAL_CONSOLE
+# undef HAVE_SERIAL_CONSOLE
+#endif
+
+/* Check UART flow control (Not yet supported) */
+
+# undef CONFIG_UART0_FLOWCONTROL
+# undef CONFIG_UART1_FLOWCONTROL
+# undef CONFIG_UART2_FLOWCONTROL
+# undef CONFIG_UART3_FLOWCONTROL
+# undef CONFIG_UART4_FLOWCONTROL
+# undef CONFIG_UART5_FLOWCONTROL
+
+/* UART FIFO support is not fully implemented.
+ *
+ * NOTE: UART0 has an 8-byte deep FIFO; the other UARTs have no FIFOs
+ * (1-deep). There appears to be no way to know when the FIFO is not
+ * full (other than reading the FIFO length and comparing the FIFO count).
+ * Hence, the FIFOs are not used in this implementation and, as a result
+ * TDRE indeed mean that the single output buffer is available.
+ *
+ * Performance on UART0 could be improved by enabling the FIFO and by
+ * redesigning all of the FIFO status logic.
+ */
+
+#undef CONFIG_KL_UARTFIFOS
+
+/* UART Default Interrupt Priorities */
+
+#ifndef CONFIG_KL_UART0PRIO
+# define CONFIG_KL_UART0PRIO NVIC_SYSH_PRIORITY_DEFAULT
+#endif
+#ifndef CONFIG_KL_UART1PRIO
+# define CONFIG_KL_UART1PRIO NVIC_SYSH_PRIORITY_DEFAULT
+#endif
+#ifndef CONFIG_KL_UART2PRIO
+# define CONFIG_KL_UART2PRIO NVIC_SYSH_PRIORITY_DEFAULT
+#endif
+#ifndef CONFIG_KL_UART3PRIO
+# define CONFIG_KL_UART3PRIO NVIC_SYSH_PRIORITY_DEFAULT
+#endif
+#ifndef CONFIG_KL_UART4PRIO
+# define CONFIG_KL_UART4PRIO NVIC_SYSH_PRIORITY_DEFAULT
+#endif
+#ifndef CONFIG_KL_UART5PRIO
+# define CONFIG_KL_UART5PRIO NVIC_SYSH_PRIORITY_DEFAULT
+#endif
+
+/* Ethernet controller configuration */
+
+#ifndef CONFIG_ENET_NRXBUFFERS
+# define CONFIG_ENET_NRXBUFFERS 6
+#endif
+#ifndef CONFIG_ENET_NTXBUFFERS
+# define CONFIG_ENET_NTXBUFFERS 2
+#endif
+
+#ifndef CONFIG_ENET_PHYADDR
+# define CONFIG_ENET_PHYADDR 1
+#endif
+
+#ifndef CONFIG_ENET_NETHIFS
+# define CONFIG_ENET_NETHIFS 1
+#endif
+
+/* EMAC Default Interrupt Priorities */
+
+#ifndef CONFIG_KL_EMACTMR_PRIO
+# define CONFIG_KL_EMACTMR_PRIO NVIC_SYSH_PRIORITY_DEFAULT
+#endif
+#ifndef CONFIG_KL_EMACTX_PRIO
+# define CONFIG_KL_EMACTX_PRIO NVIC_SYSH_PRIORITY_DEFAULT
+#endif
+#ifndef CONFIG_KL_EMACRX_PRIO
+# define CONFIG_KL_EMACRX_PRIO NVIC_SYSH_PRIORITY_DEFAULT
+#endif
+#ifndef CONFIG_KL_EMACMISC_PRIO
+# define CONFIG_KL_EMACMISC_PRIO NVIC_SYSH_PRIORITY_DEFAULT
+#endif
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KINETISXX_KL_CONFIG_H */
diff --git a/nuttx/arch/arm/src/kl/kl_dumpgpio.c b/nuttx/arch/arm/src/kl/kl_dumpgpio.c
new file mode 100644
index 000000000..c05569e77
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_dumpgpio.c
@@ -0,0 +1,143 @@
+/****************************************************************************
+ * arch/arm/src/kl/kl_gpio.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <debug.h>
+
+#include "up_arch.h"
+
+#include "chip.h"
+#include "kl_gpio.h"
+
+#ifdef CONFIG_DEBUG
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+/* Port letters for prettier debug output */
+
+#ifdef CONFIG_DEBUG
+static const char g_portchar[KL_GPIO_NPORTS] =
+{
+#if KL_GPIO_NPORTS > 9
+# error "Additional support required for this number of GPIOs"
+#elif KL_GPIO_NPORTS > 8
+ 'A', 'B', 'C', 'D', 'E', 'F', 'G', 'H', 'I'
+#elif KL_GPIO_NPORTS > 7
+ 'A', 'B', 'C', 'D', 'E', 'F', 'G', 'H'
+#elif KL_GPIO_NPORTS > 6
+ 'A', 'B', 'C', 'D', 'E', 'F', 'G'
+#elif KL_GPIO_NPORTS > 5
+ 'A', 'B', 'C', 'D', 'E', 'F'
+#elif KL_GPIO_NPORTS > 4
+ 'A', 'B', 'C', 'D', 'E'
+#elif KL_GPIO_NPORTS > 3
+ 'A', 'B', 'C', 'D'
+#elif KL_GPIO_NPORTS > 2
+ 'A', 'B', 'C'
+#elif KL_GPIO_NPORTS > 1
+ 'A', 'B'
+#elif KL_GPIO_NPORTS > 0
+ 'A'
+#else
+# error "Bad number of GPIOs"
+#endif
+};
+#endif
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: kl_dumpgpio
+ *
+ * Description:
+ * Dump all GPIO registers associated with the provided pin description
+ * along with a descriptive messasge.
+ *
+ ****************************************************************************/
+
+void kl_dumpgpio(gpio_cfgset_t pinset, const char *msg)
+{
+ irqstate_t flags;
+ uintptr_t base;
+ int port;
+
+ /* Decode the port and pin. Use the port number to get the GPIO base
+ * address.
+ */
+
+ port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
+ DEBUGASSERT((unsigned)port <= KL_GPIO_PORTE);
+ base = KL_GPIO_CTRL_BASE(port);
+
+ /* The following requires exclusive access to the GPIO registers */
+
+ flags = irqsave();
+
+ lldbg("GPIO%c pinset: %08x base: %08x -- %s\n",
+ g_portchar[port], pinset, base, msg);
+ lldbg(" PMD: %08x OFFD: %08x DOUT: %08x DMASK: %08x\n",
+ getreg32(base + KL_GPIO_PMD_OFFSET),
+ getreg32(base + KL_GPIO_OFFD_OFFSET),
+ getreg32(base + KL_GPIO_DOUT_OFFSET),
+ getreg32(base + KL_GPIO_DMASK_OFFSET));
+ lldbg(" PIN: %08x DBEN: %08x IMD: %08x IEN: %08x\n",
+ getreg32(base + KL_GPIO_PIN_OFFSET),
+ getreg32(base + KL_GPIO_DBEN_OFFSET),
+ getreg32(base + KL_GPIO_IMD_OFFSET),
+ getreg32(base + KL_GPIO_IEN_OFFSET));
+ lldbg(" ISRC: %08x\n",
+ getreg32(base + KL_GPIO_ISRC_OFFSET));
+
+ irqrestore(flags);
+}
+
+#endif /* CONFIG_DEBUG */
diff --git a/nuttx/arch/arm/src/kl/kl_gpio.c b/nuttx/arch/arm/src/kl/kl_gpio.c
new file mode 100644
index 000000000..4062bd6d9
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_gpio.c
@@ -0,0 +1,309 @@
+/****************************************************************************
+ * arch/arm/src/kl/kl_gpio.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <arch/kl/chip.h>
+
+#include "up_arch.h"
+
+#include "chip.h"
+#include "chip/kl_gpio.h"
+
+#include "kl_gpio.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kl_configgpio
+ *
+ * Description:
+ * Configure a GPIO pin based on bit-encoded description of the pin.
+ * Once it is configured as Alternative (GPIO_ALT|GPIO_CNF_AFPP|...)
+ * function, it must be unconfigured with kl_unconfiggpio() with
+ * the same cfgset first before it can be set to non-alternative function.
+ *
+ * Returns:
+ * OK on success
+ * ERROR on invalid port, or when pin is locked as ALT function.
+ *
+ ****************************************************************************/
+
+int kl_configgpio(gpio_cfgset_t cfgset)
+{
+ uintptr_t base;
+ uint32_t regaddr;
+ uint32_t regval;
+ uint32_t isrc;
+ uint32_t imd;
+ uint32_t ien;
+ uint32_t value;
+ int port;
+ int pin;
+
+ /* Decode the port and pin. Use the port number to get the GPIO base
+ * address.
+ */
+
+ port = (cfgset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
+ pin = (cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
+
+ DEBUGASSERT((unsigned)port <= KL_GPIO_PORTE);
+ base = KL_GPIO_CTRL_BASE(port);
+
+ /* Set the the GPIO PMD register */
+
+ regaddr = base + KL_GPIO_PMD_OFFSET;
+ regval = getreg32(regaddr);
+ regval &= ~GPIO_PMD_MASK(pin);
+
+ switch (cfgset & GPIO_MODE_MASK)
+ {
+ default:
+ case GPIO_INPUT: /* Input */
+ value = GPIO_PMD_INPUT;
+ break;
+
+ case GPIO_OUTPUT: /* Push-pull output */
+ value = GPIO_PMD_OUTPUT;
+ break;
+
+ case GPIO_OPENDRAIN: /* Open drain output */
+ value = GPIO_PMD_OPENDRAIN;
+ break;
+
+ case GPIO_BIDI: /* Quasi bi-directional */
+ value = GPIO_PMD_BIDI;
+ break;
+ }
+
+ regval |= GPIO_PMD(pin, value);
+ putreg32(regval, regaddr);
+
+ /* Check if we need to disable the digital input path */
+
+ regaddr = base + KL_GPIO_OFFD_OFFSET;
+ regval = getreg32(regaddr);
+ regval &= ~GPIO_OFFD(pin);
+
+ if ((cfgset & GPIO_ANALOG) != 0)
+ {
+ regval |= GPIO_OFFD(pin);
+ }
+
+ putreg32(regval, regaddr);
+
+ /* Check if we need to enable debouncing */
+
+ regaddr = base + KL_GPIO_DBEN_OFFSET;
+ regval = getreg32(regaddr);
+ regval &= ~GPIO_DBEN(pin);
+
+ if ((cfgset & GPIO_DEBOUNCE) != 0)
+ {
+ regval |= GPIO_DBEN(pin);
+ }
+
+ putreg32(regval, regaddr);
+
+ /* Configure interrupting pins */
+
+ isrc = getreg32(base + KL_GPIO_ISRC_OFFSET);
+ isrc &= ~GPIO_ISRC(pin);
+
+ imd = getreg32(base + KL_GPIO_IMD_OFFSET);
+ imd &= ~GPIO_IMD(pin);
+
+ ien = getreg32(base + KL_GPIO_IEN_OFFSET);
+ ien &= ~(GPIO_IF_EN(pin) | GPIO_IR_EN(pin));
+
+ switch (cfgset & GPIO_INTERRUPT_MASK)
+ {
+ case GPIO_INTERRUPT_RISING_EDGE:
+ isrc |= GPIO_ISRC(pin);
+ ien |= GPIO_IR_EN(pin);
+ break;
+
+ case GPIO_INTERRUPT_FALLING_EDGE:
+ isrc |= GPIO_ISRC(pin);
+ ien |= GPIO_IF_EN(pin);
+ break;
+
+ case GPIO_INTERRUPT_BOTH_EDGES:
+ isrc |= GPIO_ISRC(pin);
+ ien |= (GPIO_IF_EN(pin) | GPIO_IR_EN(pin));
+ break;
+
+ case GPIO_INTERRUPT_HIGH_LEVEL:
+ isrc |= GPIO_ISRC(pin);
+ imd |= GPIO_IMD(pin);
+ ien |= GPIO_IR_EN(pin);
+ break;
+
+ case GPIO_INTERRUPT_LOW_LEVEL:
+ isrc |= GPIO_ISRC(pin);
+ imd |= GPIO_IMD(pin);
+ ien |= GPIO_IF_EN(pin);
+ break;
+
+ default:
+ break;
+ }
+
+ putreg32(ien, base + KL_GPIO_IEN_OFFSET);
+ putreg32(imd, base + KL_GPIO_IMD_OFFSET);
+ putreg32(isrc, base + KL_GPIO_ISRC_OFFSET);
+
+ /* If the pin is an output, set the initial output value */
+
+ if ((cfgset & GPIO_MODE_MASK) == GPIO_OUTPUT)
+ {
+ kl_gpiowrite(cfgset, (cfgset & GPIO_OUTPUT_SET) != 0);
+ }
+
+ return 0;
+}
+
+/****************************************************************************
+ * Name: kl_gpiowrite
+ *
+ * Description:
+ * Write one or zero to the selected GPIO pin
+ *
+ ****************************************************************************/
+
+void kl_gpiowrite(gpio_cfgset_t pinset, bool value)
+{
+#ifndef KL_LOW
+ irqstate_t flags;
+ uintptr_t base;
+#endif
+ int port;
+ int pin;
+
+ /* Decode the port and pin. Use the port number to get the GPIO base
+ * address.
+ */
+
+ port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
+ pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
+
+ DEBUGASSERT((unsigned)port <= KL_GPIO_PORTE);
+
+ /* Only the low density K25Z100/120 chips support bit-band access to GPIO
+ * pins.
+ */
+
+#ifdef KL_LOW
+ putreg32((uint32_t)value, KL_PORT_PDIO(port, pin));
+#else
+ /* Get the base address of the GPIO port registers */
+
+ base = KL_GPIO_CTRL_BASE(port);
+
+ /* Disable interrupts -- the following operations must be atomic */
+
+ flags = irqsave();
+
+ /* Allow writing only to the selected pin in the DOUT register */
+
+ putreg32(~(1 << pin), base + KL_GPIO_DMASK_OFFSET);
+
+ /* Set the pin to the selected value and re-enable interrupts */
+
+ putreg32(((uint32_t)value << pin), base + KL_GPIO_DOUT_OFFSET);
+ irqrestore(flags);
+#endif
+}
+
+/****************************************************************************
+ * Name: kl_gpioread
+ *
+ * Description:
+ * Read one or zero from the selected GPIO pin
+ *
+ ****************************************************************************/
+
+bool kl_gpioread(gpio_cfgset_t pinset)
+{
+#ifndef KL_LOW
+ uintptr_t base;
+#endif
+ int port;
+ int pin;
+
+ /* Decode the port and pin. Use the port number to get the GPIO base
+ * address.
+ */
+
+ port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
+ pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
+
+ DEBUGASSERT((unsigned)port <= KL_GPIO_PORTE);
+
+ /* Only the low density K25Z100/120 chips support bit-band access to GPIO
+ * pins.
+ */
+
+#ifdef KL_LOW
+ return (getreg32(KL_PORT_PDIO(port, pin)) & PORT_MASK) != 0;
+#else
+ /* Get the base address of the GPIO port registers */
+
+ base = KL_GPIO_CTRL_BASE(port);
+
+ /* Return the state of the selected pin */
+
+ return (getreg32(base + KL_GPIO_PIN_OFFSET) & (1 << pin)) != 0;
+#endif
+}
diff --git a/nuttx/arch/arm/src/kl/kl_gpio.h b/nuttx/arch/arm/src/kl/kl_gpio.h
new file mode 100644
index 000000000..02cb0643a
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_gpio.h
@@ -0,0 +1,259 @@
+/****************************************************************************
+ * arch/arm/src/kl/kl_gpio.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_KINETIS_GPIO_H
+#define __ARCH_ARM_SRC_KL_KINETIS_GPIO_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+# include <stdbool.h>
+#endif
+
+#include <nuttx/irq.h>
+
+#include "chip.h"
+#include "chip/kl_gpio.h"
+
+/****************************************************************************
+ * Pre-processor Declarations
+ ****************************************************************************/
+
+/* Bit-encoded input to kl_configgpio() */
+
+/* 16-bit Encoding:
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * MMAD III. VPPP BBBB
+ */
+
+/* GPIO mode:
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * MM.. .... .... ....
+ */
+
+#define GPIO_MODE_SHIFT (14) /* Bits 14-15: GPIO mode */
+#define GPIO_MODE_MASK (3 << GPIO_MODE_SHIFT)
+# define GPIO_INPUT (0 << GPIO_MODE_SHIFT) /* Input */
+# define GPIO_OUTPUT (1 << GPIO_MODE_SHIFT) /* Push-pull output */
+# define GPIO_OPENDRAIN (2 << GPIO_MODE_SHIFT) /* Open drain output */
+# define GPIO_BIDI (3 << GPIO_MODE_SHIFT) /* Quasi bi-directional */
+
+/* GPIO analog: If the pin is an analog input, then it would be necessary to
+ * disable the digital input
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * ..A. .... .... ....
+ */
+
+#define GPIO_ANALOG (1 << 13) /* Bit 13: Disable digital input */
+
+/* De-bounce enable:
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * ...D .... .... ....
+ */
+
+#define GPIO_DEBOUNCE (1 << 12) /* Bit 12: Debounce enable */
+
+/* Interrupt Controls:
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * .... III. .... ....
+ */
+
+#define GPIO_INTERRUPT_SHIFT (9) /* Bits 9-11: Interrupt controls */
+#define GPIO_INTERRUPT_MASK (7 << GPIO_INTERRUPT_SHIFT)
+# define GPIO_INTERRUPT_NONE (0 << GPIO_INTERRUPT_SHIFT)
+# define GPIO_INTERRUPT_RISING_EDGE (1 << GPIO_INTERRUPT_SHIFT)
+# define GPIO_INTERRUPT_FALLING_EDGE (2 << GPIO_INTERRUPT_SHIFT)
+# define GPIO_INTERRUPT_BOTH_EDGES (3 << GPIO_INTERRUPT_SHIFT)
+# define GPIO_INTERRUPT_HIGH_LEVEL (4 << GPIO_INTERRUPT_SHIFT)
+# define GPIO_INTERRUPT_LOW_LEVEL (5 << GPIO_INTERRUPT_SHIFT)
+
+/* If the pin is a GPIO digital output, then this identifies the initial output value.
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * .... .... V... ....
+ */
+
+#define GPIO_OUTPUT_SET (1 << 7) /* Bit 7: If output, inital value of output */
+#define GPIO_OUTPUT_CLEAR (0)
+
+/* This identifies the GPIO port:
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * .... .... .PPP ....
+ */
+
+#define GPIO_PORT_SHIFT 4 /* Bit 4-6: Port number */
+#define GPIO_PORT_MASK (7 << GPIO_PORT_SHIFT)
+# define GPIO_PORTA (0 << GPIO_PORT_SHIFT) /* GPIOA */
+# define GPIO_PORTB (1 << GPIO_PORT_SHIFT) /* GPIOB */
+# define GPIO_PORTC (2 << GPIO_PORT_SHIFT) /* GPIOC */
+# define GPIO_PORTD (3 << GPIO_PORT_SHIFT) /* GPIOD */
+# define GPIO_PORTE (4 << GPIO_PORT_SHIFT) /* GPIOE */
+#
+
+/* This identifies the bit in the port:
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * .... .... .... BBBB
+ */
+
+#define GPIO_PIN_SHIFT 0 /* Bits 0-3: GPIO number: 0-15 */
+#define GPIO_PIN_MASK (15 << GPIO_PIN_SHIFT)
+# define GPIO_PIN0 (0 << GPIO_PIN_SHIFT)
+# define GPIO_PIN1 (1 << GPIO_PIN_SHIFT)
+# define GPIO_PIN2 (2 << GPIO_PIN_SHIFT)
+# define GPIO_PIN3 (3 << GPIO_PIN_SHIFT)
+# define GPIO_PIN4 (4 << GPIO_PIN_SHIFT)
+# define GPIO_PIN5 (5 << GPIO_PIN_SHIFT)
+# define GPIO_PIN6 (6 << GPIO_PIN_SHIFT)
+# define GPIO_PIN7 (7 << GPIO_PIN_SHIFT)
+# define GPIO_PIN8 (8 << GPIO_PIN_SHIFT)
+# define GPIO_PIN9 (9 << GPIO_PIN_SHIFT)
+# define GPIO_PIN10 (10 << GPIO_PIN_SHIFT)
+# define GPIO_PIN11 (11 << GPIO_PIN_SHIFT)
+# define GPIO_PIN12 (12 << GPIO_PIN_SHIFT)
+# define GPIO_PIN13 (13 << GPIO_PIN_SHIFT)
+# define GPIO_PIN14 (14 << GPIO_PIN_SHIFT)
+# define GPIO_PIN15 (15 << GPIO_PIN_SHIFT)
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+typedef uint16_t gpio_cfgset_t;
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kl_configgpio
+ *
+ * Description:
+ * Configure a GPIO pin based on bit-encoded description of the pin.
+ * Once it is configured as Alternative (GPIO_ALT|GPIO_CNF_AFPP|...)
+ * function, it must be unconfigured with kl_unconfiggpio() with
+ * the same cfgset first before it can be set to non-alternative function.
+ *
+ * Returns:
+ * OK on success
+ * ERROR on invalid port, or when pin is locked as ALT function.
+ *
+ ****************************************************************************/
+
+int kl_configgpio(gpio_cfgset_t cfgset);
+
+/****************************************************************************
+ * Name: kl_gpiowrite
+ *
+ * Description:
+ * Write one or zero to the selected GPIO pin
+ *
+ ****************************************************************************/
+
+void kl_gpiowrite(gpio_cfgset_t pinset, bool value);
+
+/****************************************************************************
+ * Name: kl_gpioread
+ *
+ * Description:
+ * Read one or zero from the selected GPIO pin
+ *
+ ****************************************************************************/
+
+bool kl_gpioread(gpio_cfgset_t pinset);
+
+/****************************************************************************
+ * Function: kl_dumpgpio
+ *
+ * Description:
+ * Dump all GPIO registers associated with the provided pin description
+ * along with a descriptive messasge.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG
+void kl_dumpgpio(gpio_cfgset_t pinset, const char *msg);
+#else
+# define kl_dumpgpio(p,m)
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_KL_KINETIS_GPIO_H */
diff --git a/nuttx/arch/arm/src/kl/kl_idle.c b/nuttx/arch/arm/src/kl/kl_idle.c
new file mode 100644
index 000000000..3cc865f55
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_idle.c
@@ -0,0 +1,187 @@
+/****************************************************************************
+ * arch/arm/src/stm32/kl_idle.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <arch/board/board.h>
+#include <nuttx/config.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/power/pm.h>
+
+#include <arch/irq.h>
+
+#include "chip.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Does the board support an IDLE LED to indicate that the board is in the
+ * IDLE state?
+ */
+
+#if defined(CONFIG_ARCH_LEDS) && defined(LED_IDLE)
+# define BEGIN_IDLE() up_ledon(LED_IDLE)
+# define END_IDLE() up_ledoff(LED_IDLE)
+#else
+# define BEGIN_IDLE()
+# define END_IDLE()
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_idlepm
+ *
+ * Description:
+ * Perform IDLE state power management.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static void up_idlepm(void)
+{
+ static enum pm_state_e oldstate = PM_NORMAL;
+ enum pm_state_e newstate;
+ irqstate_t flags;
+ int ret;
+
+ /* Decide, which power saving level can be obtained */
+
+ newstate = pm_checkstate();
+
+ /* Check for state changes */
+
+ if (newstate != oldstate)
+ {
+ flags = irqsave();
+
+ /* Perform board-specific, state-dependent logic here */
+
+ llvdbg("newstate= %d oldstate=%d\n", newstate, oldstate);
+
+ /* Then force the global state change */
+
+ ret = pm_changestate(newstate);
+ if (ret < 0)
+ {
+ /* The new state change failed, revert to the preceding state */
+
+ (void)pm_changestate(oldstate);
+ }
+ else
+ {
+ /* Save the new state */
+
+ oldstate = newstate;
+ }
+
+ /* MCU-specific power management logic */
+
+ switch (newstate)
+ {
+ case PM_NORMAL:
+ break;
+
+ case PM_IDLE:
+ break;
+
+ case PM_STANDBY:
+ kl_pmstop(true);
+ break;
+
+ case PM_SLEEP:
+ (void)kl_pmstandby();
+ break;
+
+ default:
+ break;
+ }
+
+ irqrestore(flags);
+ }
+}
+#else
+# define up_idlepm()
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_idle
+ *
+ * Description:
+ * up_idle() is the logic that will be executed when their is no other
+ * ready-to-run task. This is processor idle time and will continue until
+ * some interrupt occurs to cause a context switch from the idle task.
+ *
+ * Processing in this state may be processor-specific. e.g., this is where
+ * power management operations might be performed.
+ *
+ ****************************************************************************/
+
+void up_idle(void)
+{
+#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS)
+ /* If the system is idle and there are no timer interrupts, then process
+ * "fake" timer interrupts. Hopefully, something will wake up.
+ */
+
+ sched_process_timer();
+#else
+
+ /* Perform IDLE mode power management */
+
+ up_idlepm();
+
+ /* Sleep until an interrupt occurs to save power. */
+
+ BEGIN_IDLE();
+ asm("WFI");
+ END_IDLE();
+#endif
+}
diff --git a/nuttx/arch/arm/src/kl/kl_irq.c b/nuttx/arch/arm/src/kl/kl_irq.c
new file mode 100644
index 000000000..e4fe27e91
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_irq.c
@@ -0,0 +1,435 @@
+/****************************************************************************
+ * arch/arm/src/stm32/kl_irq.c
+ * arch/arm/src/chip/kl_irq.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <arch/irq.h>
+
+#include "nvic.h"
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+#include "kl_irq.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Get a 32-bit version of the default priority */
+
+#define DEFPRIORITY32 \
+ (NVIC_SYSH_PRIORITY_DEFAULT << 24 | NVIC_SYSH_PRIORITY_DEFAULT << 16 |\
+ NVIC_SYSH_PRIORITY_DEFAULT << 8 | NVIC_SYSH_PRIORITY_DEFAULT)
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+volatile uint32_t *current_regs;
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kl_dumpnvic
+ *
+ * Description:
+ * Dump some interesting NVIC registers
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_DEBUG_IRQ) && defined (CONFIG_DEBUG)
+static void kl_dumpnvic(const char *msg, int irq)
+{
+ irqstate_t flags;
+
+ flags = irqsave();
+
+ slldbg("NVIC (%s, irq=%d):\n", msg, irq);
+ slldbg(" ISER: %08x ICER: %08x\n",
+ getreg32(ARMV6M_NVIC_ISER), getreg32(ARMV6M_NVIC_ICER));
+ slldbg(" ISPR: %08x ICPR: %08x\n",
+ getreg32(ARMV6M_NVIC_ISPR), getreg32(ARMV6M_NVIC_ICPR));
+ slldbg(" IRQ PRIO: %08x %08x %08x %08x\n",
+ getreg32(ARMV6M_NVIC_IPR0), getreg32(ARMV6M_NVIC_IPR1),
+ getreg32(ARMV6M_NVIC_IPR2), getreg32(ARMV6M_NVIC_IPR3));
+ slldbg(" %08x %08x %08x %08x\n",
+ getreg32(ARMV6M_NVIC_IPR4), getreg32(ARMV6M_NVIC_IPR5),
+ getreg32(ARMV6M_NVIC_IPR6), getreg32(ARMV6M_NVIC_IPR7));
+
+ slldbg("SYSCON:\n");
+ slldbg(" CPUID: %08x\n",
+ getreg32(ARMV6M_SYSCON_CPUID));
+ slldbg(" ICSR: %08x AIRCR: %08x\n",
+ getreg32(ARMV6M_SYSCON_ICSR), getreg32(ARMV6M_SYSCON_AIRCR));
+ slldbg(" SCR: %08x CCR: %08x\n",
+ getreg32(ARMV6M_SYSCON_SCR), getreg32(ARMV6M_SYSCON_CCR));
+ slldbg(" SHPR2: %08x SHPR3: %08x\n",
+ getreg32(ARMV6M_SYSCON_SHPR2), getreg32(ARMV6M_SYSCON_SHPR3));
+
+ irqrestore(flags);
+}
+
+#else
+# define kl_dumpnvic(msg, irq)
+#endif
+
+/****************************************************************************
+ * Name: kl_nmi, kl_busfault, kl_usagefault, kl_pendsv,
+ * kl_dbgmonitor, kl_pendsv, kl_reserved
+ *
+ * Description:
+ * Handlers for various execptions. None are handled and all are fatal
+ * error conditions. The only advantage these provided over the default
+ * unexpected interrupt handler is that they provide a diagnostic output.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG
+static int kl_nmi(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! NMI received\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+
+static int kl_pendsv(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! PendSV received\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+
+static int kl_reserved(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! Reserved interrupt\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+#endif
+
+/****************************************************************************
+ * Name: kl_prioritize_syscall
+ *
+ * Description:
+ * Set the priority of an exception. This function may be needed
+ * internally even if support for prioritized interrupts is not enabled.
+ *
+ ****************************************************************************/
+
+static inline void kl_prioritize_syscall(int priority)
+{
+ uint32_t regval;
+
+ /* SVCALL is system handler 11 */
+
+ regval = getreg32(ARMV6M_SYSCON_SHPR2);
+ regval &= ~SYSCON_SHPR2_PRI_11_MASK;
+ regval |= (priority << SYSCON_SHPR2_PRI_11_SHIFT);
+ putreg32(regval, ARMV6M_SYSCON_SHPR2);
+}
+
+/****************************************************************************
+ * Name: kl_clrpend
+ *
+ * Description:
+ * Clear a pending interrupt at the NVIC.
+ *
+ ****************************************************************************/
+
+static inline void kl_clrpend(int irq)
+{
+ /* This will be called on each interrupt exit whether the interrupt can be
+ * enambled or not. So this assertion is necessarily lame.
+ */
+
+ DEBUGASSERT((unsigned)irq < NR_IRQS);
+
+ /* Check for an external interrupt */
+
+ if (irq >= KL_IRQ_INTERRUPT && irq < KL_IRQ_INTERRUPT + 32)
+ {
+ /* Set the appropriate bit in the ISER register to enable the
+ * interrupt
+ */
+
+ putreg32((1 << (irq - KL_IRQ_INTERRUPT)), ARMV6M_NVIC_ICPR);
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_irqinitialize
+ ****************************************************************************/
+
+void up_irqinitialize(void)
+{
+ uint32_t regaddr;
+ int i;
+
+ /* Disable all interrupts */
+
+ putreg32(0xffffffff, ARMV6M_NVIC_ICER);
+
+ /* Set all interrupts (and exceptions) to the default priority */
+
+ putreg32(DEFPRIORITY32, ARMV6M_SYSCON_SHPR2);
+ putreg32(DEFPRIORITY32, ARMV6M_SYSCON_SHPR3);
+
+ /* Now set all of the interrupt lines to the default priority */
+
+ for (i = 0; i < 8; i++)
+ {
+ regaddr = ARMV6M_NVIC_IPR(i);
+ putreg32(DEFPRIORITY32, regaddr);
+ }
+
+ /* currents_regs is non-NULL only while processing an interrupt */
+
+ current_regs = NULL;
+
+ /* Attach the SVCall and Hard Fault exception handlers. The SVCall
+ * exception is used for performing context switches; The Hard Fault
+ * must also be caught because a SVCall may show up as a Hard Fault
+ * under certain conditions.
+ */
+
+ irq_attach(KL_IRQ_SVCALL, up_svcall);
+ irq_attach(KL_IRQ_HARDFAULT, up_hardfault);
+
+ /* Set the priority of the SVCall interrupt */
+
+#ifdef CONFIG_ARCH_IRQPRIO
+/* up_prioritize_irq(KL_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); */
+#endif
+ kl_prioritize_syscall(NVIC_SYSH_SVCALL_PRIORITY);
+
+ /* Attach all other processor exceptions (except reset and sys tick) */
+
+#ifdef CONFIG_DEBUG
+ irq_attach(KL_IRQ_NMI, kl_nmi);
+ irq_attach(KL_IRQ_PENDSV, kl_pendsv);
+ irq_attach(KL_IRQ_RESERVED, kl_reserved);
+#endif
+
+ kl_dumpnvic("initial", NR_IRQS);
+
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+
+ /* And finally, enable interrupts */
+
+ irqenable();
+#endif
+}
+
+/****************************************************************************
+ * Name: up_disable_irq
+ *
+ * Description:
+ * Disable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_disable_irq(int irq)
+{
+ /* This will be called on each interrupt (via up_maskack_irq()) whether
+ * the interrupt can be disabled or not. So this assertion is necessarily
+ * lame.
+ */
+
+ DEBUGASSERT((unsigned)irq < NR_IRQS);
+
+ /* Check for an external interrupt */
+
+ if (irq >= KL_IRQ_INTERRUPT && irq < KL_IRQ_INTERRUPT + 32)
+ {
+ /* Set the appropriate bit in the ICER register to disable the
+ * interrupt
+ */
+
+ putreg32((1 << (irq - KL_IRQ_INTERRUPT)), ARMV6M_NVIC_ICER);
+ }
+
+ /* Handle processor exceptions. Only SysTick can be disabled */
+
+ else if (irq == KL_IRQ_SYSTICK)
+ {
+ modifyreg32(ARMV6M_SYSTICK_CSR, SYSTICK_CSR_ENABLE, 0);
+ }
+
+ kl_dumpnvic("disable", irq);
+}
+
+/****************************************************************************
+ * Name: up_enable_irq
+ *
+ * Description:
+ * Enable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_enable_irq(int irq)
+{
+ /* This will be called on each interrupt exit whether the interrupt can be
+ * enambled or not. So this assertion is necessarily lame.
+ */
+
+ DEBUGASSERT((unsigned)irq < NR_IRQS);
+
+ /* Check for external interrupt */
+
+ if (irq >= KL_IRQ_INTERRUPT && irq < KL_IRQ_INTERRUPT + 32)
+ {
+ /* Set the appropriate bit in the ISER register to enable the
+ * interrupt
+ */
+
+ putreg32((1 << (irq - KL_IRQ_INTERRUPT)), ARMV6M_NVIC_ISER);
+ }
+
+ /* Handle processor exceptions. Only SysTick can be disabled */
+
+ else if (irq == KL_IRQ_SYSTICK)
+ {
+ modifyreg32(ARMV6M_SYSTICK_CSR, 0, SYSTICK_CSR_ENABLE);
+ }
+
+ kl_dumpnvic("enable", irq);
+}
+
+/****************************************************************************
+ * Name: up_maskack_irq
+ *
+ * Description:
+ * Mask the IRQ and acknowledge it
+ *
+ ****************************************************************************/
+
+void up_maskack_irq(int irq)
+{
+ up_disable_irq(irq);
+ kl_clrpend(irq);
+}
+
+/****************************************************************************
+ * Name: up_prioritize_irq
+ *
+ * Description:
+ * Set the priority of an IRQ.
+ *
+ * Since this API is not supported on all architectures, it should be
+ * avoided in common implementations where possible.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_IRQPRIO
+int up_prioritize_irq(int irq, int priority)
+{
+ uint32_t regaddr;
+ uint32_t regval;
+ int shift;
+
+ DEBUGASSERT(irq == KL_IRQ_SVCALL ||
+ irq == KL_IRQ_PENDSV ||
+ irq == KL_IRQ_SYSTICK ||
+ (irq >= KL_IRQ_INTERRUPT && irq < NR_IRQS));
+ DEBUGASSERT(priority >= NVIC_SYSH_DISABLE_PRIORITY &&
+ priority <= NVIC_SYSH_PRIORITY_MIN);
+
+ /* Check for external interrupt */
+
+ if (irq >= KL_IRQ_INTERRUPT && irq < KL_IRQ_INTERRUPT + 32)
+ {
+ /* ARMV6M_NVIC_IPR() maps register IPR0-IPR7 with four settings per
+ * register.
+ */
+
+ regaddr = ARMV6M_NVIC_IPR(irq >> 2);
+ shift = (irq & 3) << 3;
+ }
+
+ /* Handle processor exceptions. Only SVCall, PendSV, and SysTick can be
+ * reprioritized. And we will not permit modification of SVCall through
+ * this function.
+ */
+
+ else if (irq == KL_IRQ_PENDSV)
+ {
+ regaddr = ARMV6M_SYSCON_SHPR2;
+ shift = SYSCON_SHPR3_PRI_14_SHIFT;
+ }
+ else if (irq == KL_IRQ_SYSTICK)
+ {
+ regaddr = ARMV6M_SYSCON_SHPR2;
+ shift = SYSCON_SHPR3_PRI_15_SHIFT;
+ }
+ else
+ {
+ return ERROR;
+ }
+
+ /* Set the priority */
+
+ regval = getreg32(regaddr);
+ regval &= ~((uint32_t)0xff << shift);
+ regval |= ((uint32_t)priority << shift);
+ putreg32(regval, regaddr);
+
+ kl_dumpnvic("prioritize", irq);
+ return OK;
+}
+#endif
diff --git a/nuttx/arch/arm/src/kl/kl_irq.h b/nuttx/arch/arm/src/kl/kl_irq.h
new file mode 100644
index 000000000..089cd60bd
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_irq.h
@@ -0,0 +1,65 @@
+/************************************************************************************
+ * arch/arm/src/kl/kl_irq.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_KINETIS_IRQ_H
+#define __ARCH_ARM_SRC_KL_KINETIS_IRQ_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KL_KINETIS_IRQ_H */
diff --git a/nuttx/arch/arm/src/kl/kl_led.c b/nuttx/arch/arm/src/kl/kl_led.c
new file mode 100644
index 000000000..3f2c36f02
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_led.c
@@ -0,0 +1,28 @@
+void blueled(int on)
+{
+ volatile unsigned int *SIM_COPC = ((volatile unsigned int *)0x40048100);
+ volatile unsigned int *SIM_SCGC5 = ((volatile unsigned int *)0x40048038);
+ volatile unsigned int *PORTD_PCR1 = ((volatile unsigned int *)0x4004C004);
+ volatile unsigned int *GPIOD_PSOR = ((volatile unsigned int *)0x400FF0C4);
+ volatile unsigned int *GPIOD_PCOR = ((volatile unsigned int *)0x400FF0C8);
+ volatile unsigned int *GPIOD_PDDR = ((volatile unsigned int *)0x400FF0D4);
+
+ /*acassis: disable SIM_COP*/
+ *SIM_COPC = 0;
+
+ /* enable clocks for PORTD */
+ *SIM_SCGC5 = 0x1000;
+
+ /* set D1 to GPIO */
+ *PORTD_PCR1 = 0x100;
+
+ /* set D1 DDR to output */
+ *GPIOD_PDDR |= 2;
+
+ if(on)
+ *GPIOD_PCOR = 2;
+ else
+ *GPIOD_PSOR = 2;
+
+}
+
diff --git a/nuttx/arch/arm/src/kl/kl_lowputc.c b/nuttx/arch/arm/src/kl/kl_lowputc.c
new file mode 100644
index 000000000..d19eba1de
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_lowputc.c
@@ -0,0 +1,403 @@
+/**************************************************************************
+ * arch/arm/src/kl/kl_lowputc.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ **************************************************************************/
+
+/**************************************************************************
+ * Included Files
+ **************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+
+#include <arch/irq.h>
+#include <arch/board/board.h>
+
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "kl_config.h"
+//#include "kl_lowputc.h"
+//#include "chip/kl_internal.h"
+#include "chip/kl_uart.h"
+#include "chip/kl_sim.h"
+#include "chip/kl_port.h"
+#include "chip/kl_uart.h"
+#include "chip/kl_pinmux.h"
+
+
+/**************************************************************************
+ * Private Definitions
+ **************************************************************************/
+
+/* Select UART parameters for the selected console */
+
+# define CONSOLE_BASE KL_UART0_BASE
+# define CONSOLE_FREQ 48000000
+# define CONSOLE_BAUD CONFIG_UART0_BAUD
+# define CONSOLE_BITS CONFIG_UART0_BITS
+# define CONSOLE_PARITY CONFIG_UART0_PARITY
+
+/**************************************************************************
+ * Private Types
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Function Prototypes
+ **************************************************************************/
+
+/**************************************************************************
+ * Global Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Variables
+ **************************************************************************/
+
+/* This array maps an encoded FIFO depth (index) to the actual size of the
+ * FIFO (indexed value). NOTE: That there is no 8th value.
+ */
+
+#ifdef CONFIG_KL_UARTFIFOS
+static uint8_t g_sizemap[8] = {1, 4, 8, 16, 32, 64, 128, 0};
+#endif
+
+/**************************************************************************
+ * Private Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Public Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Name: up_lowputc
+ *
+ * Description:
+ * Output one byte on the serial console
+ *
+ **************************************************************************/
+
+void kl_lowputc(char ch)
+{
+#if defined HAVE_UART_DEVICE && defined HAVE_SERIAL_CONSOLE
+#ifdef CONFIG_KL_UARTFIFOS
+ /* Wait until there is space in the TX FIFO: Read the number of bytes
+ * currently in the FIFO and compare that to the size of the FIFO. If
+ * there are fewer bytes in the FIFO than the size of the FIFO, then we
+ * are able to transmit.
+ */
+
+# error "Missing logic"
+#else
+ /* Wait until the transmit data register is "empty" (TDRE). This state
+ * depends on the TX watermark setting and may not mean that the transmit
+ * buffer is truly empty. It just means that we can now add another
+ * characterto the transmit buffer without exceeding the watermark.
+ *
+ * NOTE: UART0 has an 8-byte deep FIFO; the other UARTs have no FIFOs
+ * (1-deep). There appears to be no way to know when the FIFO is not
+ * full (other than reading the FIFO length and comparing the FIFO count).
+ * Hence, the FIFOs are not used in this implementation and, as a result
+ * TDRE indeed mean that the single output buffer is available.
+ *
+ * Performance on UART0 could be improved by enabling the FIFO and by
+ * redesigning all of the FIFO status logic.
+ */
+
+ while ((getreg8(CONSOLE_BASE+KL_UART_S1_OFFSET) & UART_S1_TDRE) == 0);
+
+#endif
+
+ /* Then write the character to the UART data register */
+
+ putreg8((uint8_t)ch, CONSOLE_BASE+KL_UART_D_OFFSET);
+
+#endif
+}
+
+/**************************************************************************
+ * Name: kl_lowsetup
+ *
+ * Description:
+ * This performs basic initialization of the UART used for the serial
+ * console. Its purpose is to get the console output availabe as soon
+ * as possible.
+ *
+ **************************************************************************/
+void kl_lowsetup(void)
+{
+ uint32_t regval;
+ uint8_t regval8;
+
+ //regval = getreg32(KL_SIM_SOPT2);
+ //regval |= SIM_SOPT2_PLLFLLSEL | SIM_SOPT2_UART0SRC_MCGCLK ;
+ //putreg32(regval, KL_SIM_SOPT2);
+
+ regval = getreg32(KL_SIM_SCGC5);
+ regval |= SIM_SCGC5_PORTA;
+ putreg32(regval, KL_SIM_SCGC5);
+
+ regval = getreg32(KL_SIM_SCGC4);
+ regval |= SIM_SCGC4_UART0;
+ putreg32(regval, KL_SIM_SCGC4);
+
+ regval = getreg32(KL_SIM_SOPT2);
+ regval &= ~(SIM_SOPT2_UART0SRC_MASK);
+ putreg32(regval, KL_SIM_SOPT2);
+
+ regval = getreg32(KL_SIM_SOPT2);
+ regval |= SIM_SOPT2_UART0SRC_MCGCLK;
+ putreg32(regval, KL_SIM_SOPT2);
+
+ putreg32((PORT_PCR_MUX_ALT2), KL_PORTA_PCR1);
+ putreg32((PORT_PCR_MUX_ALT2), KL_PORTA_PCR2);
+
+ /* Disable UART before changing registers */
+ putreg8(0, KL_UART0_C2);
+ putreg8(0, KL_UART0_C1);
+ putreg8(0, KL_UART0_C3);
+ putreg8(0, KL_UART0_S2);
+
+ // Set the baud rate divisor
+ #define CORE_CLOCK 48000000
+ #define OVER_SAMPLE 16
+ uint16_t divisor = (CORE_CLOCK / OVER_SAMPLE) / CONSOLE_BAUD;
+ regval8 = OVER_SAMPLE - 1;
+ putreg8(regval8, KL_UART0_C4);
+
+ regval8 = (divisor >> 8) & UARTLP_BDH_SBR_MASK;
+ putreg8(regval8, KL_UART0_BDH);
+
+ regval8 = (divisor & UARTLP_BDL_SBR_MASK);
+ putreg8(regval8, KL_UART0_BDL);
+
+ /* Enable UART before changing registers */
+ regval8 = getreg8(KL_UART0_C2);
+ regval8 |= (UART_C2_RE | UART_C2_TE);
+ putreg8(regval8, KL_UART0_C2);
+
+ /* Configure the console (only) now. Other UARTs will be configured
+ * when the serial driver is opened.
+ */
+
+//#if defined(HAVE_SERIAL_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
+
+// kl_uartconfigure(CONSOLE_BASE, CONSOLE_BAUD, CONSOLE_FREQ,
+// CONSOLE_PARITY, CONSOLE_BITS);
+//#endif
+}
+
+/******************************************************************************
+ * Name: kl_uartreset
+ *
+ * Description:
+ * Reset a UART.
+ *
+ ******************************************************************************/
+
+#ifdef HAVE_UART_DEVICE
+void kl_uartreset(uintptr_t uart_base)
+{
+ uint8_t regval;
+
+ /* Just disable the transmitter and receiver */
+
+ regval = getreg8(uart_base+KL_UART_C2_OFFSET);
+ regval &= ~(UART_C2_RE|UART_C2_TE);
+ putreg8(regval, uart_base+KL_UART_C2_OFFSET);
+}
+#endif
+
+/******************************************************************************
+ * Name: kl_uartconfigure
+ *
+ * Description:
+ * Configure a UART as a RS-232 UART.
+ *
+ ******************************************************************************/
+
+#ifdef HAVE_UART_DEVICE
+void kl_uartconfigure(uintptr_t uart_base, uint32_t baud,
+ uint32_t clock, unsigned int parity,
+ unsigned int nbits)
+{
+ uint32_t sbr;
+ uint32_t brfa;
+ uint32_t tmp;
+ uint8_t regval;
+#ifdef CONFIG_KL_UARTFIFOS
+ unsigned int depth;
+#endif
+
+ /* Disable the transmitter and receiver throughout the reconfiguration */
+
+ regval = getreg8(uart_base+KL_UART_C2_OFFSET);
+ regval &= ~(UART_C2_RE|UART_C2_TE);
+ putreg8(regval, uart_base+KL_UART_C2_OFFSET);
+
+ /* Configure number of bits, stop bits and parity */
+
+ regval = 0;
+
+ /* Check for odd parity */
+
+ if (parity == 1)
+ {
+ regval |= (UART_C1_PE|UART_C1_PT); /* Enable + odd parity type */
+ }
+
+ /* Check for even parity */
+
+ else if (parity == 2)
+ {
+ regval |= UART_C1_PE; /* Enable (even parity default) */
+ }
+
+ /* The only other option is no parity */
+
+ else
+ {
+ DEBUGASSERT(parity == 0);
+ }
+
+ /* Check for 9-bit operation */
+
+ if (nbits == 9)
+ {
+ regval |= UART_C1_M;
+ }
+
+ /* The only other option is 8-bit operation */
+
+ else
+ {
+ DEBUGASSERT(nbits == 8);
+ }
+
+ putreg8(regval, uart_base+KL_UART_C1_OFFSET);
+
+ /* Calculate baud settings (truncating) */
+
+ sbr = clock / (baud << 4);
+ DEBUGASSERT(sbr < 0x2000);
+
+ /* Save the new baud divisor, retaining other bits in the UARTx_BDH
+ * register.
+ */
+
+ regval = getreg8(uart_base+KL_UART_BDH_OFFSET) & UART_BDH_SBR_MASK;
+ tmp = sbr >> 8;
+ regval |= (((uint8_t)tmp) << UART_BDH_SBR_SHIFT) & UART_BDH_SBR_MASK;
+ putreg8(regval, uart_base+KL_UART_BDH_OFFSET);
+
+ regval = sbr & 0xff;
+ putreg8(regval, uart_base+KL_UART_BDL_OFFSET);
+
+ /* Calculate a fractional divider to get closer to the requested baud.
+ * The fractional divider, BRFA, is a 5 bit fractional value that is
+ * logically added to the SBR:
+ *
+ * UART baud rate = clock / (16 × (SBR + BRFD))
+ *
+ * The BRFA the remainder. This will be a non-negative value since the SBR
+ * was calculated by truncation.
+ */
+
+ tmp = clock - (sbr * (baud << 4));
+ brfa = (tmp << 5) / (baud << 4);
+
+ /* Set the BRFA field (retaining other bits in the UARTx_C4 register) */
+
+ regval = getreg8(uart_base+KL_UART_C4_OFFSET) & UART_C4_BRFA_MASK;
+ regval |= ((uint8_t)brfa << UART_C4_BRFA_SHIFT) & UART_C4_BRFA_MASK;
+ putreg8(regval, uart_base+KL_UART_C4_OFFSET);
+
+ /* Set the FIFO watermarks.
+ *
+ * NOTE: UART0 has an 8-byte deep FIFO; the other UARTs have no FIFOs
+ * (1-deep). There appears to be no way to know when the FIFO is not
+ * full (other than reading the FIFO length and comparing the FIFO count).
+ * Hence, the FIFOs are not used in this implementation and, as a result
+ * TDRE indeed mean that the single output buffer is available.
+ *
+ * Performance on UART0 could be improved by enabling the FIFO and by
+ * redesigning all of the FIFO status logic.
+ */
+
+#ifdef CONFIG_KL_UARTFIFOS
+ depth = g_sizemap[(regval & UART_PFIFO_RXFIFOSIZE_MASK) >> UART_PFIFO_RXFIFOSIZE_SHIFT];
+ if (depth > 1)
+ {
+ depth = (3 * depth) >> 2;
+ }
+ putreg8(depth , uart_base+KL_UART_RWFIFO_OFFSET);
+
+ depth = g_sizemap[(regval & UART_PFIFO_TXFIFOSIZE_MASK) >> UART_PFIFO_TXFIFOSIZE_SHIFT];
+ if (depth > 3)
+ {
+ depth = (depth >> 2);
+ }
+ putreg8(depth, uart_base+KL_UART_TWFIFO_OFFSET);
+
+ /* Enable RX and TX FIFOs */
+
+ putreg8(UART_PFIFO_RXFE | UART_PFIFO_TXFE, uart_base+KL_UART_PFIFO_OFFSET);
+#else
+ /* Otherwise, disable the FIFOs. Then the FIFOs are disable, the effective
+ * FIFO depth is 1. So set the watermarks as follows:
+ *
+ * TWFIFO[TXWATER] = 0: TDRE will be set when the number of queued bytes
+ * (1 in this case) is less than or equal to 0.
+ * RWFIFO[RXWATER] = 1: RDRF will be set when the number of queued bytes
+ * (1 in this case) is greater than or equal to 1.
+ *
+ * Set the watermarks to one/zero and disable the FIFOs
+ */
+
+ putreg8(1, uart_base+KL_UART_RWFIFO_OFFSET);
+ putreg8(0, uart_base+KL_UART_TWFIFO_OFFSET);
+ putreg8(0, uart_base+KL_UART_PFIFO_OFFSET);
+#endif
+
+ /* Now we can (re-)enable the transmitter and receiver */
+
+ regval = getreg8(uart_base+KL_UART_C2_OFFSET);
+ regval |= (UART_C2_RE | UART_C2_TE);
+ putreg8(regval, uart_base+KL_UART_C2_OFFSET);
+}
+#endif
+
+
+
diff --git a/nuttx/arch/arm/src/kl/kl_lowputc.h b/nuttx/arch/arm/src/kl/kl_lowputc.h
new file mode 100644
index 000000000..b30544e0f
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_lowputc.h
@@ -0,0 +1,125 @@
+/************************************************************************************
+ * arch/arm/src/kl/kl_lowputc.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_KINETIS_LOWPUTC_H
+#define __ARCH_ARM_SRC_KL_KINETIS_LOWPUTC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include "kl_config.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: kl_lowsetup
+ *
+ * Description:
+ * Called at the very beginning of _start. Performs low level initialization.
+ *
+ ************************************************************************************/
+
+void kl_lowsetup(void);
+
+/****************************************************************************
+ * Name: kl_setbaud
+ *
+ * Description:
+ * Set the BAUD divxisor for the selected UART
+ *
+ * Mode DIV_X_EN DIV_X_ONE Divider X BRD (Baud rate equation)
+ * -------------------------------------------------------------
+ * 0 Disable 0 B A UART_CLK / [16 * (A+2)]
+ * 1 Enable 0 B A UART_CLK / [(B+1) * (A+2)] , B must >= 8
+ * 2 Enable 1 Don't care A UART_CLK / (A+2), A must >=3
+ *
+ * Here we assume that the default clock source for the UART modules is
+ * the external high speed crystal.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_UART
+void kl_setbaud(uintptr_t base, uint32_t baud);
+#endif
+
+/****************************************************************************
+ * Name: kl_lowputc
+ *
+ * Description:
+ * Output one character to the UART using a simple polling method.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_SERIAL_CONSOLE
+void kl_lowputc(uint32_t ch);
+#endif
+
+void kl_uartconfigure(uintptr_t uart_base, uint32_t baud,
+ uint32_t clock, unsigned int parity,
+ unsigned int nbits);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_KL_KINETIS_LOWPUTC_H */
diff --git a/nuttx/arch/arm/src/kl/kl_serial.c b/nuttx/arch/arm/src/kl/kl_serial.c
new file mode 100644
index 000000000..1a110ae90
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_serial.c
@@ -0,0 +1,1347 @@
+/****************************************************************************
+ * arch/mips/src/kl/kl_serial.c
+ *
+ * Copyright (C) 2013-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <unistd.h>
+#include <semaphore.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <nuttx/serial/serial.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+#include "os_internal.h"
+
+#include "kl_config.h"
+#include "kl_lowputc.h"
+#include "chip.h"
+#include "chip/kl_uart.h"
+//#include "kl_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Some sanity checks *******************************************************/
+/* Is there at least one UART enabled and configured as a RS-232 device? */
+
+#ifndef HAVE_UART_DEVICE
+# warning "No UARTs enabled"
+#endif
+
+/* If we are not using the serial driver for the console, then we still must
+ * provide some minimal implementation of up_putc.
+ */
+
+#ifdef USE_SERIALDRIVER
+
+/* Which UART with be tty0/console and which tty1-4? The console will always
+ * be ttyS0. If there is no console then will use the lowest numbered UART.
+ */
+
+/* First pick the console and ttys0. This could be any of UART0-5 */
+
+#if defined(CONFIG_UART0_SERIAL_CONSOLE)
+# define CONSOLE_DEV g_uart0port /* UART0 is console */
+# define TTYS0_DEV g_uart0port /* UART0 is ttyS0 */
+# define UART0_ASSIGNED 1
+#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
+# define CONSOLE_DEV g_uart1port /* UART1 is console */
+# define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */
+# define UART1_ASSIGNED 1
+#elif defined(CONFIG_UART2_SERIAL_CONSOLE)
+# define CONSOLE_DEV g_uart2port /* UART2 is console */
+# define TTYS0_DEV g_uart2port /* UART2 is ttyS0 */
+# define UART2_ASSIGNED 1
+#elif defined(CONFIG_UART3_SERIAL_CONSOLE)
+# define CONSOLE_DEV g_uart3port /* UART3 is console */
+# define TTYS0_DEV g_uart3port /* UART3 is ttyS0 */
+# define UART3_ASSIGNED 1
+#elif defined(CONFIG_UART4_SERIAL_CONSOLE)
+# define CONSOLE_DEV g_uart4port /* UART4 is console */
+# define TTYS0_DEV g_uart4port /* UART4 is ttyS0 */
+# define UART4_ASSIGNED 1
+#elif defined(CONFIG_UART5_SERIAL_CONSOLE)
+# define CONSOLE_DEV g_uart5port /* UART5 is console */
+# define TTYS5_DEV g_uart5port /* UART5 is ttyS0 */
+#else
+# undef CONSOLE_DEV /* No console */
+# if defined(CONFIG_KL_UART0)
+# define TTYS0_DEV g_uart0port /* UART0 is ttyS0 */
+# define UART0_ASSIGNED 1
+# elif defined(CONFIG_KL_UART1)
+# define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */
+# define UART1_ASSIGNED 1
+# elif defined(CONFIG_KL_UART2)
+# define TTYS0_DEV g_uart2port /* UART2 is ttyS0 */
+# define UART2_ASSIGNED 1
+# elif defined(CONFIG_KL_UART3)
+# define TTYS0_DEV g_uart3port /* UART3 is ttyS0 */
+# define UART3_ASSIGNED 1
+# elif defined(CONFIG_KL_UART4)
+# define TTYS0_DEV g_uart4port /* UART4 is ttyS0 */
+# define UART4_ASSIGNED 1
+# elif defined(CONFIG_KL_UART5)
+# define TTYS0_DEV g_uart5port /* UART5 is ttyS0 */
+# define UART5_ASSIGNED 1
+# endif
+#endif
+
+/* Pick ttys1. This could be any of UART0-5 excluding the console UART. */
+
+#if defined(CONFIG_KL_UART0) && !defined(UART0_ASSIGNED)
+# define TTYS1_DEV g_uart0port /* UART0 is ttyS1 */
+# define UART0_ASSIGNED 1
+#elif defined(CONFIG_KL_UART1) && !defined(UART1_ASSIGNED)
+# define TTYS1_DEV g_uart1port /* UART1 is ttyS1 */
+# define UART1_ASSIGNED 1
+#elif defined(CONFIG_KL_UART2) && !defined(UART2_ASSIGNED)
+# define TTYS1_DEV g_uart2port /* UART2 is ttyS1 */
+# define UART2_ASSIGNED 1
+#elif defined(CONFIG_KL_UART3) && !defined(UART3_ASSIGNED)
+# define TTYS1_DEV g_uart3port /* UART3 is ttyS1 */
+# define UART3_ASSIGNED 1
+#elif defined(CONFIG_KL_UART4) && !defined(UART4_ASSIGNED)
+# define TTYS1_DEV g_uart4port /* UART4 is ttyS1 */
+# define UART4_ASSIGNED 1
+#elif defined(CONFIG_KL_UART5) && !defined(UART5_ASSIGNED)
+# define TTYS1_DEV g_uart5port /* UART5 is ttyS1 */
+# define UART5_ASSIGNED 1
+#endif
+
+/* Pick ttys2. This could be one of UART1-5. It can't be UART0 because that
+ * was either assigned as ttyS0 or ttys1. One of UART 1-5 could also be the
+ * console.
+ */
+
+#if defined(CONFIG_KL_UART1) && !defined(UART1_ASSIGNED)
+# define TTYS2_DEV g_uart1port /* UART1 is ttyS2 */
+# define UART1_ASSIGNED 1
+#elif defined(CONFIG_KL_UART2) && !defined(UART2_ASSIGNED)
+# define TTYS2_DEV g_uart2port /* UART2 is ttyS2 */
+# define UART2_ASSIGNED 1
+#elif defined(CONFIG_KL_UART3) && !defined(UART3_ASSIGNED)
+# define TTYS2_DEV g_uart3port /* UART3 is ttyS2 */
+# define UART3_ASSIGNED 1
+#elif defined(CONFIG_KL_UART4) && !defined(UART4_ASSIGNED)
+# define TTYS2_DEV g_uart4port /* UART4 is ttyS2 */
+# define UART4_ASSIGNED 1
+#elif defined(CONFIG_KL_UART5) && !defined(UART5_ASSIGNED)
+# define TTYS2_DEV g_uart5port /* UART5 is ttyS2 */
+# define UART5_ASSIGNED 1
+#endif
+
+/* Pick ttys3. This could be one of UART2-5. It can't be UART0-1 because
+ * those have already been assigned to ttsyS0, 1, or 2. One of
+ * UART 2-5 could also be the console.
+ */
+
+#if defined(CONFIG_KL_UART2) && !defined(UART2_ASSIGNED)
+# define TTYS3_DEV g_uart2port /* UART2 is ttyS3 */
+# define UART2_ASSIGNED 1
+#elif defined(CONFIG_KL_UART3) && !defined(UART3_ASSIGNED)
+# define TTYS3_DEV g_uart3port /* UART3 is ttyS3 */
+# define UART3_ASSIGNED 1
+#elif defined(CONFIG_KL_UART4) && !defined(UART4_ASSIGNED)
+# define TTYS3_DEV g_uart4port /* UART4 is ttyS3 */
+# define UART4_ASSIGNED 1
+#elif defined(CONFIG_KL_UART5) && !defined(UART5_ASSIGNED)
+# define TTYS3_DEV g_uart5port /* UART5 is ttyS3 */
+# define UART5_ASSIGNED 1
+#endif
+
+/* Pick ttys4. This could be one of UART3-5. It can't be UART0-2 because
+ * those have already been assigned to ttsyS0, 1, 2 or 3. One of
+ * UART 3-5 could also be the console.
+ */
+
+#if defined(CONFIG_KL_UART3) && !defined(UART3_ASSIGNED)
+# define TTYS4_DEV g_uart3port /* UART3 is ttyS4 */
+# define UART3_ASSIGNED 1
+#elif defined(CONFIG_KL_UART4) && !defined(UART4_ASSIGNED)
+# define TTYS4_DEV g_uart4port /* UART4 is ttyS4 */
+# define UART4_ASSIGNED 1
+#elif defined(CONFIG_KL_UART5) && !defined(UART5_ASSIGNED)
+# define TTYS4_DEV g_uart5port /* UART5 is ttyS4 */
+# define UART5_ASSIGNED 1
+#endif
+
+/* Pick ttys5. This could be one of UART4-5. It can't be UART0-3 because
+ * those have already been assigned to ttsyS0, 1, 2, 3 or 4. One of
+ * UART 4-5 could also be the console.
+ */
+
+#if defined(CONFIG_KL_UART4) && !defined(UART4_ASSIGNED)
+# define TTYS5_DEV g_uart4port /* UART4 is ttyS5 */
+# define UART4_ASSIGNED 1
+#elif defined(CONFIG_KL_UART5) && !defined(UART5_ASSIGNED)
+# define TTYS5_DEV g_uart5port /* UART5 is ttyS5 */
+# define UART5_ASSIGNED 1
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct up_dev_s
+{
+ uintptr_t uartbase; /* Base address of UART registers */
+ uint32_t baud; /* Configured baud */
+ uint32_t clock; /* Clocking frequency of the UART module */
+#ifdef CONFIG_DEBUG
+ uint8_t irqe; /* Error IRQ associated with this UART (for enable) */
+#endif
+ uint8_t irqs; /* Status IRQ associated with this UART (for enable) */
+ uint8_t irqprio; /* Interrupt priority */
+ uint8_t ie; /* Interrupts enabled */
+ uint8_t parity; /* 0=none, 1=odd, 2=even */
+ uint8_t bits; /* Number of bits (8 or 9) */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int up_setup(struct uart_dev_s *dev);
+static void up_shutdown(struct uart_dev_s *dev);
+static int up_attach(struct uart_dev_s *dev);
+static void up_detach(struct uart_dev_s *dev);
+#ifdef CONFIG_DEBUG
+static int up_interrupte(int irq, void *context);
+#endif
+static int up_interrupts(int irq, void *context);
+static int up_ioctl(struct file *filep, int cmd, unsigned long arg);
+static int up_receive(struct uart_dev_s *dev, uint32_t *status);
+static void up_rxint(struct uart_dev_s *dev, bool enable);
+static bool up_rxavailable(struct uart_dev_s *dev);
+static void up_send(struct uart_dev_s *dev, int ch);
+static void up_txint(struct uart_dev_s *dev, bool enable);
+static bool up_txready(struct uart_dev_s *dev);
+#ifdef CONFIG_KL_UARTFIFOS
+static bool up_txempty(struct uart_dev_s *dev);
+#endif
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+static const struct uart_ops_s g_uart_ops =
+{
+ .setup = up_setup,
+ .shutdown = up_shutdown,
+ .attach = up_attach,
+ .detach = up_detach,
+ .ioctl = up_ioctl,
+ .receive = up_receive,
+ .rxint = up_rxint,
+ .rxavailable = up_rxavailable,
+ .send = up_send,
+ .txint = up_txint,
+ .txready = up_txready,
+#ifdef CONFIG_KL_UARTFIFOS
+ .txempty = up_txempty,
+#else
+ .txempty = up_txready,
+#endif
+};
+
+/* I/O buffers */
+
+#ifdef CONFIG_KL_UART0
+static char g_uart0rxbuffer[CONFIG_UART0_RXBUFSIZE];
+static char g_uart0txbuffer[CONFIG_UART0_TXBUFSIZE];
+#endif
+#ifdef CONFIG_KL_UART1
+static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE];
+static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE];
+#endif
+#ifdef CONFIG_KL_UART2
+static char g_uart2rxbuffer[CONFIG_UART2_RXBUFSIZE];
+static char g_uart2txbuffer[CONFIG_UART2_TXBUFSIZE];
+#endif
+#ifdef CONFIG_KL_UART3
+static char g_uart3rxbuffer[CONFIG_UART3_RXBUFSIZE];
+static char g_uart3txbuffer[CONFIG_UART3_TXBUFSIZE];
+#endif
+#ifdef CONFIG_KL_UART4
+static char g_uart4rxbuffer[CONFIG_UART4_RXBUFSIZE];
+static char g_uart4txbuffer[CONFIG_UART4_TXBUFSIZE];
+#endif
+#ifdef CONFIG_KL_UART5
+static char g_uart5rxbuffer[CONFIG_UART5_RXBUFSIZE];
+static char g_uart5txbuffer[CONFIG_UART5_TXBUFSIZE];
+#endif
+
+/* This describes the state of the Kinetis UART0 port. */
+
+#ifdef CONFIG_KL_UART0
+static struct up_dev_s g_uart0priv =
+{
+ .uartbase = KL_UART0_BASE,
+ .clock = BOARD_CORECLK_FREQ,
+ .baud = CONFIG_UART0_BAUD,
+ .irqprio = CONFIG_KL_UART0PRIO,
+ .parity = CONFIG_UART0_PARITY,
+ .bits = CONFIG_UART0_BITS,
+};
+
+static uart_dev_t g_uart0port =
+{
+ .recv =
+ {
+ .size = CONFIG_UART0_RXBUFSIZE,
+ .buffer = g_uart0rxbuffer,
+ },
+ .xmit =
+ {
+ .size = CONFIG_UART0_TXBUFSIZE,
+ .buffer = g_uart0txbuffer,
+ },
+ .ops = &g_uart_ops,
+ .priv = &g_uart0priv,
+};
+#endif
+
+/* This describes the state of the Kinetis UART1 port. */
+
+#ifdef CONFIG_KL_UART1
+static struct up_dev_s g_uart1priv =
+{
+ .uartbase = KL_UART1_BASE,
+ .clock = BOARD_CORECLK_FREQ,
+ .baud = CONFIG_UART1_BAUD,
+#ifdef CONFIG_DEBUG
+ .irqe = KL_IRQ_UART1E,
+#endif
+ .irqs = KL_IRQ_UART1S,
+ .irqprio = CONFIG_KL_UART1PRIO,
+ .parity = CONFIG_UART1_PARITY,
+ .bits = CONFIG_UART1_BITS,
+};
+
+static uart_dev_t g_uart1port =
+{
+ .recv =
+ {
+ .size = CONFIG_UART1_RXBUFSIZE,
+ .buffer = g_uart1rxbuffer,
+ },
+ .xmit =
+ {
+ .size = CONFIG_UART1_TXBUFSIZE,
+ .buffer = g_uart1txbuffer,
+ },
+ .ops = &g_uart_ops,
+ .priv = &g_uart1priv,
+};
+#endif
+
+/* This describes the state of the Kinetis UART2 port. */
+
+#ifdef CONFIG_KL_UART2
+static struct up_dev_s g_uart2priv =
+{
+ .uartbase = KL_UART2_BASE,
+ .clock = BOARD_BUS_FREQ,
+ .baud = CONFIG_UART2_BAUD,
+#ifdef CONFIG_DEBUG
+ .irqe = KL_IRQ_UART2E,
+#endif
+ .irqs = KL_IRQ_UART2S,
+ .irqprio = CONFIG_KL_UART2PRIO,
+ .parity = CONFIG_UART2_PARITY,
+ .bits = CONFIG_UART2_BITS,
+};
+
+static uart_dev_t g_uart2port =
+{
+ .recv =
+ {
+ .size = CONFIG_UART2_RXBUFSIZE,
+ .buffer = g_uart2rxbuffer,
+ },
+ .xmit =
+ {
+ .size = CONFIG_UART2_TXBUFSIZE,
+ .buffer = g_uart2txbuffer,
+ },
+ .ops = &g_uart_ops,
+ .priv = &g_uart2priv,
+};
+#endif
+
+/* This describes the state of the Kinetis UART3 port. */
+
+#ifdef CONFIG_KL_UART3
+static struct up_dev_s g_uart3priv =
+{
+ .uartbase = KL_UART3_BASE,
+ .clock = BOARD_BUS_FREQ,
+ .baud = CONFIG_UART3_BAUD,
+#ifdef CONFIG_DEBUG
+ .irqe = KL_IRQ_UART3E,
+#endif
+ .irqs = KL_IRQ_UART3S,
+ .irqprio = CONFIG_KL_UART3PRIO,
+ .parity = CONFIG_UART3_PARITY,
+ .bits = CONFIG_UART3_BITS,
+};
+
+static uart_dev_t g_uart3port =
+{
+ .recv =
+ {
+ .size = CONFIG_UART3_RXBUFSIZE,
+ .buffer = g_uart3rxbuffer,
+ },
+ .xmit =
+ {
+ .size = CONFIG_UART3_TXBUFSIZE,
+ .buffer = g_uart3txbuffer,
+ },
+ .ops = &g_uart_ops,
+ .priv = &g_uart3priv,
+};
+#endif
+
+/* This describes the state of the Kinetis UART4 port. */
+
+#ifdef CONFIG_KL_UART4
+static struct up_dev_s g_uart4priv =
+{
+ .uartbase = KL_UART4_BASE,
+ .clock = BOARD_BUS_FREQ,
+ .baud = CONFIG_UART4_BAUD,
+#ifdef CONFIG_DEBUG
+ .irqe = KL_IRQ_UART4E,
+#endif
+ .irqs = KL_IRQ_UART4S,
+ .irqprio = CONFIG_KL_UART4PRIO,
+ .parity = CONFIG_UART4_PARITY,
+ .bits = CONFIG_UART4_BITS,
+};
+
+static uart_dev_t g_uart4port =
+{
+ .recv =
+ {
+ .size = CONFIG_UART4_RXBUFSIZE,
+ .buffer = g_uart4rxbuffer,
+ },
+ .xmit =
+ {
+ .size = CONFIG_UART4_TXBUFSIZE,
+ .buffer = g_uart4txbuffer,
+ },
+ .ops = &g_uart_ops,
+ .priv = &g_uart4priv,
+};
+#endif
+
+/* This describes the state of the Kinetis UART5 port. */
+
+#ifdef CONFIG_KL_UART5
+static struct up_dev_s g_uart5priv =
+{
+ .uartbase = KL_UART5_BASE,
+ .clock = BOARD_BUS_FREQ,
+ .baud = CONFIG_UART5_BAUD,
+#ifdef CONFIG_DEBUG
+ .irqe = KL_IRQ_UART5E,
+#endif
+ .irqs = KL_IRQ_UART5S,
+ .irqprio = CONFIG_KL_UART5PRIO,
+ .parity = CONFIG_UART5_PARITY,
+ .bits = CONFIG_UART5_BITS,
+};
+
+static uart_dev_t g_uart5port =
+{
+ .recv =
+ {
+ .size = CONFIG_UART5_RXBUFSIZE,
+ .buffer = g_uart5rxbuffer,
+ },
+ .xmit =
+ {
+ .size = CONFIG_UART5_TXBUFSIZE,
+ .buffer = g_uart5txbuffer,
+ },
+ .ops = &g_uart_ops,
+ .priv = &g_uart5priv,
+};
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_serialin
+ ****************************************************************************/
+
+static inline uint8_t up_serialin(struct up_dev_s *priv, int offset)
+{
+ return getreg8(priv->uartbase + offset);
+}
+
+/****************************************************************************
+ * Name: up_serialout
+ ****************************************************************************/
+
+static inline void up_serialout(struct up_dev_s *priv, int offset, uint8_t value)
+{
+ putreg8(value, priv->uartbase + offset);
+}
+
+/****************************************************************************
+ * Name: up_setuartint
+ ****************************************************************************/
+
+static void up_setuartint(struct up_dev_s *priv)
+{
+ irqstate_t flags;
+ uint8_t regval;
+
+ /* Re-enable/re-disable interrupts corresponding to the state of bits in ie */
+
+ flags = irqsave();
+ regval = up_serialin(priv, KL_UART_C2_OFFSET);
+ regval &= ~UART_C2_ALLINTS;
+ regval |= priv->ie;
+ up_serialout(priv, KL_UART_C2_OFFSET, regval);
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: up_restoreuartint
+ ****************************************************************************/
+
+static void up_restoreuartint(struct up_dev_s *priv, uint8_t ie)
+{
+ irqstate_t flags;
+
+ /* Re-enable/re-disable interrupts corresponding to the state of bits in ie */
+
+ flags = irqsave();
+ priv->ie = ie & UART_C2_ALLINTS;
+ up_setuartint(priv);
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: up_disableuartint
+ ****************************************************************************/
+
+static void up_disableuartint(struct up_dev_s *priv, uint8_t *ie)
+{
+ irqstate_t flags;
+
+ flags = irqsave();
+ if (ie)
+ {
+ *ie = priv->ie;
+ }
+
+ up_restoreuartint(priv, 0);
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: up_setup
+ *
+ * Description:
+ * Configure the UART baud, bits, parity, etc. This method is called the
+ * first time that the serial port is opened.
+ *
+ ****************************************************************************/
+
+static int up_setup(struct uart_dev_s *dev)
+{
+#ifndef CONFIG_SUPPRESS_UART_CONFIG
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+
+ /* Configure the UART as an RS-232 UART */
+
+ kl_uartconfigure(priv->uartbase, priv->baud, priv->clock,
+ priv->parity, priv->bits);
+#endif
+
+ /* Make sure that all interrupts are disabled */
+
+ up_restoreuartint(priv, 0);
+
+ /* Set up the interrupt priority */
+
+ up_prioritize_irq(priv->irqs, priv->irqprio);
+#ifdef CONFIG_DEBUG
+ up_prioritize_irq(priv->irqe, priv->irqprio);
+#endif
+ return OK;
+}
+
+/****************************************************************************
+ * Name: up_shutdown
+ *
+ * Description:
+ * Disable the UART. This method is called when the serial
+ * port is closed
+ *
+ ****************************************************************************/
+
+static void up_shutdown(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+
+ /* Disable interrupts */
+
+ up_restoreuartint(priv, 0);
+
+ /* Reset hardware and disable Rx and Tx */
+
+ kl_uartreset(priv->uartbase);
+}
+
+/****************************************************************************
+ * Name: up_attach
+ *
+ * Description:
+ * Configure the UART to operation in interrupt driven mode. This method is
+ * called when the serial port is opened. Normally, this is just after the
+ * the setup() method is called, however, the serial console may operate in
+ * a non-interrupt driven mode during the boot phase.
+ *
+ * RX and TX interrupts are not enabled when by the attach method (unless the
+ * hardware supports multiple levels of interrupt enabling). The RX and TX
+ * interrupts are not enabled until the txint() and rxint() methods are called.
+ *
+ ****************************************************************************/
+
+static int up_attach(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ int ret;
+
+ /* Attach and enable the IRQ(s). The interrupts are (probably) still
+ * disabled in the C2 register.
+ */
+
+ ret = irq_attach(priv->irqs, up_interrupts);
+#ifdef CONFIG_DEBUG
+ if (ret == OK)
+ {
+ ret = irq_attach(priv->irqe, up_interrupte);
+ }
+#endif
+
+ if (ret == OK)
+ {
+#ifdef CONFIG_DEBUG
+ up_enable_irq(priv->irqe);
+#endif
+ up_enable_irq(priv->irqs);
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: up_detach
+ *
+ * Description:
+ * Detach UART interrupts. This method is called when the serial port is
+ * closed normally just before the shutdown method is called. The exception
+ * is the serial console which is never shutdown.
+ *
+ ****************************************************************************/
+
+static void up_detach(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+
+ /* Disable interrupts */
+
+ up_restoreuartint(priv, 0);
+#ifdef CONFIG_DEBUG
+ up_disable_irq(priv->irqe);
+#endif
+ up_disable_irq(priv->irqs);
+
+ /* Detach from the interrupt(s) */
+
+ irq_detach(priv->irqs);
+#ifdef CONFIG_DEBUG
+ irq_detach(priv->irqe);
+#endif
+}
+
+/****************************************************************************
+ * Name: up_interrupte
+ *
+ * Description:
+ * This is the UART error interrupt handler. It will be invoked when an
+ * interrupt received on the 'irq'
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG
+static int up_interrupte(int irq, void *context)
+{
+ struct uart_dev_s *dev = NULL;
+ struct up_dev_s *priv;
+ uint8_t regval;
+
+#ifdef CONFIG_KL_UART0
+ if (g_uart0priv.irqe == irq)
+ {
+ dev = &g_uart0port;
+ }
+ else
+#endif
+#ifdef CONFIG_KL_UART1
+ if (g_uart1priv.irqe == irq)
+ {
+ dev = &g_uart1port;
+ }
+ else
+#endif
+#ifdef CONFIG_KL_UART2
+ if (g_uart2priv.irqe == irq)
+ {
+ dev = &g_uart2port;
+ }
+ else
+#endif
+#ifdef CONFIG_KL_UART3
+ if (g_uart3priv.irqe == irq)
+ {
+ dev = &g_uart3port;
+ }
+ else
+#endif
+#ifdef CONFIG_KL_UART4
+ if (g_uart4priv.irqe == irq)
+ {
+ dev = &g_uart4port;
+ }
+ else
+#endif
+#ifdef CONFIG_KL_UART5
+ if (g_uart5priv.irqe == irq)
+ {
+ dev = &g_uart5port;
+ }
+ else
+#endif
+ {
+ PANIC(OSERR_INTERNAL);
+ }
+ priv = (struct up_dev_s*)dev->priv;
+ DEBUGASSERT(priv);
+
+ /* Handle error interrupts. This interrupt may be caused by:
+ *
+ * FE: Framing error. To clear FE, read S1 with FE set and then read the
+ * UART data register (D).
+ * NF: Noise flag. To clear NF, read S1 and then read the UART data
+ * register (D).
+ * PF: Parity error flag. To clear PF, read S1 and then read the UART data
+ * register (D).
+ */
+
+ regval = up_serialin(priv, KL_UART_S1_OFFSET);
+ lldbg("S1: %02x\n", regval);
+ regval = up_serialin(priv, KL_UART_D_OFFSET);
+ return OK;
+}
+#endif /* CONFIG_DEBUG */
+
+/****************************************************************************
+ * Name: up_interrupts
+ *
+ * Description:
+ * This is the UART status interrupt handler. It will be invoked when an
+ * interrupt received on the 'irq' It should call uart_transmitchars or
+ * uart_receivechar to perform the appropriate data transfers. The
+ * interrupt handling logic must be able to map the 'irq' number into the
+ * approprite uart_dev_s structure in order to call these functions.
+ *
+ ****************************************************************************/
+
+static int up_interrupts(int irq, void *context)
+{
+ struct uart_dev_s *dev = NULL;
+ struct up_dev_s *priv;
+ int passes;
+#ifdef CONFIG_KL_UARTFIFOS
+ unsigned int count;
+#else
+ uint8_t s1;
+#endif
+ bool handled;
+
+#ifdef CONFIG_KL_UART0
+ if (g_uart0priv.irqs == irq)
+ {
+ dev = &g_uart0port;
+ }
+ else
+#endif
+#ifdef CONFIG_KL_UART1
+ if (g_uart1priv.irqs == irq)
+ {
+ dev = &g_uart1port;
+ }
+ else
+#endif
+#ifdef CONFIG_KL_UART2
+ if (g_uart2priv.irqs == irq)
+ {
+ dev = &g_uart2port;
+ }
+ else
+#endif
+#ifdef CONFIG_KL_UART3
+ if (g_uart3priv.irqs == irq)
+ {
+ dev = &g_uart3port;
+ }
+ else
+#endif
+#ifdef CONFIG_KL_UART4
+ if (g_uart4priv.irqs == irq)
+ {
+ dev = &g_uart4port;
+ }
+ else
+#endif
+#ifdef CONFIG_KL_UART5
+ if (g_uart5priv.irq == irqs)
+ {
+ dev = &g_uart5port;
+ }
+ else
+#endif
+ {
+ PANIC(OSERR_INTERNAL);
+ }
+ priv = (struct up_dev_s*)dev->priv;
+ DEBUGASSERT(priv);
+
+ /* Loop until there are no characters to be transferred or,
+ * until we have been looping for a long time.
+ */
+
+ handled = true;
+ for (passes = 0; passes < 256 && handled; passes++)
+ {
+ handled = false;
+
+ /* Read status register 1 */
+
+#ifndef CONFIG_KL_UARTFIFOS
+ s1 = up_serialin(priv, KL_UART_S1_OFFSET);
+#endif
+
+ /* Handle incoming, receive bytes */
+
+#ifdef CONFIG_KL_UARTFIFOS
+ /* Check the count of bytes in the RX FIFO */
+
+ count = up_serialin(priv, KL_UART_RCFIFO_OFFSET);
+ if (count > 0)
+#else
+ /* Check if the receive data register is full (RDRF). NOTE: If
+ * FIFOS are enabled, this does not mean that the the FIFO is full,
+ * rather, it means that the the number of bytes in the RX FIFO has
+ * exceeded the watermark setting. There may actually be RX data
+ * available!
+ *
+ * The RDRF status indication is cleared when the data is read from
+ * the RX data register.
+ */
+
+ if ((s1 & UART_S1_RDRF) != 0)
+#endif
+ {
+ /* Process incoming bytes */
+
+ uart_recvchars(dev);
+ handled = true;
+ }
+
+ /* Handle outgoing, transmit bytes */
+
+#ifdef CONFIG_KL_UARTFIFOS
+ /* Read the number of bytes currently in the FIFO and compare that to
+ * the size of the FIFO. If there are fewer bytes in the FIFO than
+ * the size of the FIFO, then we are able to transmit.
+ */
+
+# error "Missing logic"
+#else
+ /* Check if the transmit data register is "empty." NOTE: If FIFOS
+ * are enabled, this does not mean that the the FIFO is empty, rather,
+ * it means that the the number of bytes in the TX FIFO is below the
+ * watermark setting. There could actually be space for additional TX
+ * data.
+ *
+ * The TDRE status indication is cleared when the data is written to
+ * the TX data register.
+ */
+
+ if ((s1 & UART_S1_TDRE) != 0)
+#endif
+ {
+ /* Process outgoing bytes */
+
+ uart_xmitchars(dev);
+ handled = true;
+ }
+ }
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: up_ioctl
+ *
+ * Description:
+ * All ioctl calls will be routed through this method
+ *
+ ****************************************************************************/
+
+static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
+{
+#if 0 /* Reserved for future growth */
+ struct inode *inode;
+ struct uart_dev_s *dev;
+ struct up_dev_s *priv;
+ int ret = OK;
+
+ DEBUGASSERT(filep, filep->f_inode);
+ inode = filep->f_inode;
+ dev = inode->i_private;
+
+ DEBUGASSERT(dev, dev->priv)
+ priv = (struct up_dev_s*)dev->priv;
+
+ switch (cmd)
+ {
+ case xxx: /* Add commands here */
+ break;
+
+ default:
+ ret = -ENOTTY;
+ break;
+ }
+
+ return ret;
+#else
+ return -ENOTTY;
+#endif
+}
+
+/****************************************************************************
+ * Name: up_receive
+ *
+ * Description:
+ * Called (usually) from the interrupt level to receive one
+ * character from the UART. Error bits associated with the
+ * receipt are provided in the return 'status'.
+ *
+ ****************************************************************************/
+
+static int up_receive(struct uart_dev_s *dev, uint32_t *status)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ uint8_t s1;
+
+ /* Get error status information:
+ *
+ * FE: Framing error. To clear FE, read S1 with FE set and then read
+ * read UART data register (D).
+ * NF: Noise flag. To clear NF, read S1 and then read the UART data
+ * register (D).
+ * PF: Parity error flag. To clear PF, read S1 and then read the UART
+ * data register (D).
+ */
+
+ s1 = up_serialin(priv, KL_UART_S1_OFFSET);
+
+ /* Return status information */
+
+ if (status)
+ {
+ *status = (uint32_t)s1;
+ }
+
+ /* Then return the actual received byte. Reading S1 then D clears all
+ * RX errors.
+ */
+
+ return (int)up_serialin(priv, KL_UART_D_OFFSET);
+}
+
+/****************************************************************************
+ * Name: up_rxint
+ *
+ * Description:
+ * Call to enable or disable RX interrupts
+ *
+ ****************************************************************************/
+
+static void up_rxint(struct uart_dev_s *dev, bool enable)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ irqstate_t flags;
+
+ flags = irqsave();
+ if (enable)
+ {
+ /* Receive an interrupt when their is anything in the Rx data register (or an Rx
+ * timeout occurs).
+ */
+
+#ifndef CONFIG_SUPPRESS_SERIAL_INTS
+ priv->ie |= UART_C2_RIE;
+ up_setuartint(priv);
+#endif
+ }
+ else
+ {
+#ifdef CONFIG_DEBUG
+# warning "Revisit: How are errors enabled?"
+ priv->ie |= UART_C2_RIE;
+#else
+ priv->ie |= UART_C2_RIE;
+#endif
+ up_setuartint(priv);
+ }
+
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: up_rxavailable
+ *
+ * Description:
+ * Return true if the receive register is not empty
+ *
+ ****************************************************************************/
+
+static bool up_rxavailable(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+#ifdef CONFIG_KL_UARTFIFOS
+ unsigned int count;
+
+ /* Return true if there are any bytes in the RX FIFO */
+
+ count = up_serialin(priv, KL_UART_RCFIFO_OFFSET);
+ return count > 0;
+#else
+ /* Return true if the receive data register is full (RDRF). NOTE: If
+ * FIFOS are enabled, this does not mean that the the FIFO is full,
+ * rather, it means that the the number of bytes in the RX FIFO has
+ * exceeded the watermark setting. There may actually be RX data
+ * available!
+ */
+
+ return (up_serialin(priv, KL_UART_S1_OFFSET) & UART_S1_RDRF) != 0;
+#endif
+}
+
+/****************************************************************************
+ * Name: up_send
+ *
+ * Description:
+ * This method will send one byte on the UART.
+ *
+ ****************************************************************************/
+
+static void up_send(struct uart_dev_s *dev, int ch)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ up_serialout(priv, KL_UART_D_OFFSET, (uint8_t)ch);
+}
+
+/****************************************************************************
+ * Name: up_txint
+ *
+ * Description:
+ * Call to enable or disable TX interrupts
+ *
+ ****************************************************************************/
+
+static void up_txint(struct uart_dev_s *dev, bool enable)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ irqstate_t flags;
+
+ flags = irqsave();
+ if (enable)
+ {
+ /* Enable the TX interrupt */
+
+#ifndef CONFIG_SUPPRESS_SERIAL_INTS
+ priv->ie |= UART_C2_TIE;
+ up_setuartint(priv);
+
+ /* Fake a TX interrupt here by just calling uart_xmitchars() with
+ * interrupts disabled (note this may recurse).
+ */
+
+ uart_xmitchars(dev);
+#endif
+ }
+ else
+ {
+ /* Disable the TX interrupt */
+
+ priv->ie &= ~UART_C2_TIE;
+ up_setuartint(priv);
+ }
+
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: up_txready
+ *
+ * Description:
+ * Return true if the tranmsit data register is empty
+ *
+ ****************************************************************************/
+
+static bool up_txready(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+
+#ifdef CONFIG_KL_UARTFIFOS
+ /* Read the number of bytes currently in the FIFO and compare that to the
+ * size of the FIFO. If there are fewer bytes in the FIFO than the size
+ * of the FIFO, then we are able to transmit.
+ */
+
+# error "Missing logic"
+#else
+ /* Return true if the transmit data register is "empty." NOTE: If
+ * FIFOS are enabled, this does not mean that the the FIFO is empty,
+ * rather, it means that the the number of bytes in the TX FIFO is
+ * below the watermark setting. There may actually be space for
+ * additional TX data.
+ */
+
+ return (up_serialin(priv, KL_UART_S1_OFFSET) & UART_S1_TDRE) != 0;
+#endif
+}
+
+/****************************************************************************
+ * Name: up_txempty
+ *
+ * Description:
+ * Return true if the tranmsit data register is empty
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KL_UARTFIFOS
+static bool up_txempty(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+
+ /* Return true if the transmit buffer/fifo is "empty." */
+
+ return (up_serialin(priv, KL_UART_SFIFO_OFFSET) & UART_SFIFO_TXEMPT) != 0;
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_earlyserialinit
+ *
+ * Description:
+ * Performs the low level UART initialization early in debug so that the
+ * serial console will be available during bootup. This must be called
+ * before up_serialinit. NOTE: This function depends on GPIO pin
+ * configuration performed in up_consoleinit() and main clock iniialization
+ * performed in up_clkinitialize().
+ *
+ ****************************************************************************/
+
+void up_earlyserialinit(void)
+{
+ /* Disable interrupts from all UARTS. The console is enabled in
+ * pic32mx_consoleinit()
+ */
+
+ up_restoreuartint(TTYS0_DEV.priv, 0);
+#ifdef TTYS1_DEV
+ up_restoreuartint(TTYS1_DEV.priv, 0);
+#endif
+#ifdef TTYS2_DEV
+ up_restoreuartint(TTYS2_DEV.priv, 0);
+#endif
+#ifdef TTYS3_DEV
+ up_restoreuartint(TTYS3_DEV.priv, 0);
+#endif
+#ifdef TTYS4_DEV
+ up_restoreuartint(TTYS4_DEV.priv, 0);
+#endif
+#ifdef TTYS5_DEV
+ up_restoreuartint(TTYS5_DEV.priv, 0);
+#endif
+
+ /* Configuration whichever one is the console */
+
+#ifdef HAVE_SERIAL_CONSOLE
+ CONSOLE_DEV.isconsole = true;
+ up_setup(&CONSOLE_DEV);
+#endif
+}
+
+/****************************************************************************
+ * Name: up_serialinit
+ *
+ * Description:
+ * Register serial console and serial ports. This assumes
+ * that up_earlyserialinit was called previously.
+ *
+ ****************************************************************************/
+
+void up_serialinit(void)
+{
+ /* Register the console */
+
+#ifdef HAVE_SERIAL_CONSOLE
+ (void)uart_register("/dev/console", &CONSOLE_DEV);
+#endif
+
+ /* Register all UARTs */
+
+ (void)uart_register("/dev/ttyS0", &TTYS0_DEV);
+#ifdef TTYS1_DEV
+ (void)uart_register("/dev/ttyS1", &TTYS1_DEV);
+#endif
+#ifdef TTYS2_DEV
+ (void)uart_register("/dev/ttyS2", &TTYS2_DEV);
+#endif
+#ifdef TTYS3_DEV
+ (void)uart_register("/dev/ttyS3", &TTYS3_DEV);
+#endif
+#ifdef TTYS4_DEV
+ (void)uart_register("/dev/ttyS4", &TTYS4_DEV);
+#endif
+#ifdef TTYS5_DEV
+ (void)uart_register("/dev/ttyS5", &TTYS5_DEV);
+#endif
+}
+
+/****************************************************************************
+ * Name: up_putc
+ *
+ * Description:
+ * Provide priority, low-level access to support OS debug writes
+ *
+ ****************************************************************************/
+
+int up_putc(int ch)
+{
+#ifdef HAVE_SERIAL_CONSOLE
+ struct up_dev_s *priv = (struct up_dev_s*)CONSOLE_DEV.priv;
+ uint8_t ie;
+
+ up_disableuartint(priv, &ie);
+
+ /* Check for LF */
+
+ if (ch == '\n')
+ {
+ /* Add CR */
+
+ kl_lowputc('\r');
+ }
+
+ kl_lowputc(ch);
+ up_restoreuartint(priv, ie);
+#endif
+ return ch;
+}
+
+#else /* USE_SERIALDRIVER */
+
+/****************************************************************************
+ * Name: up_putc
+ *
+ * Description:
+ * Provide priority, low-level access to support OS debug writes
+ *
+ ****************************************************************************/
+
+int up_putc(int ch)
+{
+#ifdef HAVE_SERIAL_CONSOLE
+ /* Check for LF */
+
+ if (ch == '\n')
+ {
+ /* Add CR */
+
+ kl_lowputc('\r');
+ }
+
+ kl_lowputc(ch);
+#endif
+ return ch;
+}
+
+#endif /* USE_SERIALDRIVER */
+
diff --git a/nuttx/arch/arm/src/kl/kl_start.c b/nuttx/arch/arm/src/kl/kl_start.c
new file mode 100644
index 000000000..7857cc01a
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_start.c
@@ -0,0 +1,199 @@
+/****************************************************************************
+ * arch/arm/src/kl/kl_start.c
+ * arch/arm/src/chip/kl_start.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/init.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+
+#include "kl_config.h"
+#include "kl_lowputc.h"
+//#include "kl_clockconfig.h"
+#include "kl_userspace.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Memory Map:
+ *
+ * 0x0000:0000 - Beginning of FLASH. Address of exception vectors.
+ * 0x0001:ffff - End of flash (assuming 128KB of FLASH)
+ * 0x2000:0000 - Start of SRAM and start of .data (_sdata)
+ * - End of .data (_edata) abd start of .bss (_sbss)
+ * - End of .bss (_ebss) and bottom of idle stack
+ * - _ebss + CONFIG_IDLETHREAD_STACKSIZE = end of idle stack,
+ * start of heap
+ * 0x2000:3fff - End of SRAM and end of heap (assuming 16KB of SRAM)
+ */
+
+#define IDLE_STACK ((uint32_t)&_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
+#define HEAP_BASE ((uint32_t)&_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+const uint32_t g_idle_topstack = HEAP_BASE;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: showprogress
+ *
+ * Description:
+ * Print a character on the UART to show boot status.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_DEBUG) && defined(HAVE_SERIAL_CONSOLE)
+# define showprogress(c) kl_lowputc((uint32_t)c)
+#else
+# define showprogress(c)
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+void iprintf(const char *string)
+{
+ while(*string != NULL)
+ kl_lowputc((char) *string++);
+}
+
+/****************************************************************************
+ * Name: _start
+ *
+ * Description:
+ * This is the reset entry point.
+ *
+ ****************************************************************************/
+
+void __start(void)
+{
+ const uint32_t *src;
+ uint32_t *dest, i=0;
+ volatile unsigned int *SIM_COPC = ((volatile unsigned int *)0x40048100);
+
+ /*acassis: disable SIM_COP*/
+ *SIM_COPC = 0;
+
+ /* Configure the uart so that we can get debug output as soon as possible */
+
+ kl_clockconfig();
+ kl_lowsetup();
+ //uart_init();
+ showprogress('A');
+
+ /* Blink blue LED to indicate we are here */
+ //for (; ; i++)
+ // blueled(i & 0x10000);
+
+ /* Clear .bss. We'll do this inline (vs. calling memset) just to be
+ * certain that there are no issues with the state of global variables.
+ */
+
+ for (dest = &_sbss; dest < &_ebss; )
+ {
+ *dest++ = 0;
+ }
+ showprogress('B');
+
+ /* Move the intialized data section from his temporary holding spot in
+ * FLASH into the correct place in SRAM. The correct place in SRAM is
+ * give by _sdata and _edata. The temporary location is in FLASH at the
+ * end of all of the other read-only data (.text, .rodata) at _eronly.
+ */
+
+ for (src = &_eronly, dest = &_sdata; dest < &_edata; )
+ {
+ *dest++ = *src++;
+ }
+ showprogress('C');
+
+ /* Perform early serial initialization */
+
+#ifdef USE_EARLYSERIALINIT
+ up_earlyserialinit();
+#endif
+ showprogress('D');
+
+ /* For the case of the separate user-/kernel-space build, perform whatever
+ * platform specific initialization of the user memory is required.
+ * Normally this just means initializing the user space .data and .bss
+ * segments.
+ */
+
+#ifdef CONFIG_NUTTX_KERNEL
+ kl_userspace();
+ showprogress('E');
+#endif
+
+ /* Initialize onboard resources */
+
+ kl_boardinitialize();
+ showprogress('F');
+
+ /* Then start NuttX */
+
+ //iprintf("\r\nWelcome to NuttX!\r\n");
+
+ //showprogress('\r');
+ //showprogress('\n');
+
+ iprintf("\r\n\r\n");
+
+ os_start();
+
+ /* Shoulnd't get here */
+
+ for(;;);
+}
+
diff --git a/nuttx/arch/arm/src/kl/kl_timerisr.c b/nuttx/arch/arm/src/kl/kl_timerisr.c
new file mode 100644
index 000000000..4a868a252
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_timerisr.c
@@ -0,0 +1,249 @@
+/****************************************************************************
+ * arch/arm/src/kl/kl_timerisr.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <time.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include "nvic.h"
+#include "clock_internal.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "chip.h"
+#include "chip/kl_clk.h"
+#include "chip/kl_gcr.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Get the frequency of the selected clock source */
+
+#if defined(CONFIG_KL_SYSTICK_CORECLK)
+# define SYSTICK_CLOCK BOARD_HCLK_FREQUENCY /* Core clock */
+#elif defined(CONFIG_KL_SYSTICK_XTALHI)
+# define SYSTICK_CLOCK BOARD_XTALHI_FREQUENCY /* High speed XTAL clock */
+#elif defined(CONFIG_KL_SYSTICK_XTALLO)
+# define SYSTICK_CLOCK BOARD_XTALLO_FREQUENCY /* Low speed XTAL clock */
+#elif defined(CONFIG_KL_SYSTICK_XTALHId2)
+# define SYSTICK_CLOCK (BOARD_XTALHI_FREQUENCY/2) /* High speed XTAL clock/2 */
+#elif defined(CONFIG_KL_SYSTICK_HCLKd2)
+# define SYSTICK_CLOCK (BOARD_HCLK_FREQUENCY/2) /* HCLK/2 */
+#elif defined(CONFIG_KL_SYSTICK_INTHId2)
+# define SYSTICK_CLOCK (KL_INTHI_FREQUENCY/2) /* Internal high speed clock/2 */
+#endif
+
+/* The desired timer interrupt frequency is provided by the definition
+ * CLK_TCK (see include/time.h). CLK_TCK defines the desired number of
+ * system clock ticks per second. That value is a user configurable setting
+ * that defaults to 100 (100 ticks per second = 10 MS interval).
+ *
+ * Then, for example, if the external high speed crystal is the SysTick
+ * clock source and BOARD_XTALHI_FREQUENCY is 12MHz and CLK_TCK is 100, then
+ * the reload value would be:
+ *
+ * SYSTICK_RELOAD = (12,000,000 / 100) - 1
+ * = 119,999
+ * = 0x1d4bf
+ *
+ * Which fits within the maximum 14-bit reload value.
+ */
+
+#define SYSTICK_RELOAD ((SYSTICK_CLOCK / CLK_TCK) - 1)
+
+/* The size of the reload field is 24 bits. Verify that the reload value
+ * will fit in the reload register.
+ */
+
+#if SYSTICK_RELOAD > 0x00ffffff
+# error SYSTICK_RELOAD exceeds the range of the RELOAD register
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kl_unlock
+ *
+ * Description:
+ * Unlock registers
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KL_SYSTICK_CORECLK
+static inline void kl_unlock(void)
+{
+ putreg32(0x59, KL_GCR_REGWRPROT);
+ putreg32(0x16, KL_GCR_REGWRPROT);
+ putreg32(0x88, KL_GCR_REGWRPROT);
+}
+#endif
+
+/****************************************************************************
+ * Name: kl_clock
+ *
+ * Description:
+ * Lok registers
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KL_SYSTICK_CORECLK
+static inline void kl_lock(void)
+{
+ putreg32(0, KL_GCR_REGWRPROT);
+}
+#endif
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: up_timerisr
+ *
+ * Description:
+ * The timer ISR will perform a variety of services for various portions
+ * of the systems.
+ *
+ ****************************************************************************/
+
+int up_timerisr(int irq, uint32_t *regs)
+{
+ /* Process timer interrupt */
+
+ sched_process_timer();
+ return 0;
+}
+
+/****************************************************************************
+ * Function: up_timerinit
+ *
+ * Description:
+ * This function is called during start-up to initialize
+ * the timer interrupt.
+ *
+ ****************************************************************************/
+
+void up_timerinit(void)
+{
+ uint32_t regval;
+
+ /* Configure the SysTick clock source. This is only necessary if we are not
+ * using the Cortex-M0 core clock as the frequency source.
+ */
+
+#ifndef CONFIG_KL_SYSTICK_CORECLK
+
+ /* This field is write protected and must be unlocked */
+
+ kl_unlock();
+
+ /* Read the CLKSEL0 register and set the STCLK_S field appropriately */
+
+ regval = getreg32(KL_CLK_CLKSEL0);
+ regval &= ~CLK_CLKSEL0_STCLK_S_MASK;
+#if defined(CONFIG_KL_SYSTICK_XTALHI)
+ regval |= CLK_CLKSEL0_STCLK_S_XTALHI; /* High speed XTAL clock */
+#elif defined(CONFIG_KL_SYSTICK_XTALLO)
+ regval |= CLK_CLKSEL0_STCLK_S_XTALLO; /* Low speed XTAL clock */
+#elif defined(CONFIG_KL_SYSTICK_XTALHId2)
+ regval |= CLK_CLKSEL0_STCLK_S_XTALDIV2; /* High speed XTAL clock/2 */
+#elif defined(CONFIG_KL_SYSTICK_HCLKd2)
+ regval |= CLK_CLKSEL0_STCLK_S_HCLKDIV2; /* HCLK/2 */
+#elif defined(CONFIG_KL_SYSTICK_INTHId2)
+ regval |= CLK_CLKSEL0_STCLK_S_INTDIV2; /* Internal high speed clock/2 */
+#endif
+ putreg32(regval, KL_CLK_CLKSEL0);
+
+ /* Re-lock the register */
+
+ kl_lock();
+#endif
+
+ /* Set the SysTick interrupt to the default priority */
+
+ regval = getreg32(ARMV6M_SYSCON_SHPR3);
+ regval &= ~SYSCON_SHPR3_PRI_15_MASK;
+ regval |= (NVIC_SYSH_PRIORITY_DEFAULT << SYSCON_SHPR3_PRI_15_SHIFT);
+ putreg32(regval, ARMV6M_SYSCON_SHPR3);
+
+ /* Configure SysTick to interrupt at the requested rate */
+
+ putreg32(SYSTICK_RELOAD, ARMV6M_SYSTICK_RVR);
+
+ /* Attach the timer interrupt vector */
+
+ (void)irq_attach(KL_IRQ_SYSTICK, (xcpt_t)up_timerisr);
+
+ /* Enable SysTick interrupts. We need to select the core clock here if
+ * we are not using one of the alternative clock sources above.
+ */
+
+#ifdef CONFIG_KL_SYSTICK_CORECLK
+ putreg32((SYSTICK_CSR_CLKSOURCE | SYSTICK_CSR_TICKINT | SYSTICK_CSR_ENABLE),
+ ARMV6M_SYSTICK_CSR);
+#else
+ putreg32((SYSTICK_CSR_TICKINT | SYSTICK_CSR_ENABLE), ARMV6M_SYSTICK_CSR);
+#endif
+
+ /* And enable the timer interrupt */
+
+ up_enable_irq(KL_IRQ_SYSTICK);
+}
diff --git a/nuttx/arch/arm/src/kl/kl_userspace.c b/nuttx/arch/arm/src/kl/kl_userspace.c
new file mode 100644
index 000000000..00d0f5338
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_userspace.c
@@ -0,0 +1,114 @@
+/****************************************************************************
+ * arch/arm/src/kl/kl_userspace.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <assert.h>
+
+#include <nuttx/userspace.h>
+
+#include "kl_userspace.h"
+
+#ifdef CONFIG_NUTTX_KERNEL
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kl_userspace
+ *
+ * Description:
+ * For the case of the separate user-/kernel-space build, perform whatever
+ * platform specific initialization of the user memory is required.
+ * Normally this just means initializing the user space .data and .bss
+ * segments.
+ *
+ ****************************************************************************/
+
+void kl_userspace(void)
+{
+ uint8_t *src;
+ uint8_t *dest;
+ uint8_t *end;
+
+ /* Clear all of user-space .bss */
+
+ DEBUGASSERT(USERSPACE->us_bssstart != 0 && USERSPACE->us_bssend != 0 &&
+ USERSPACE->us_bssstart <= USERSPACE->us_bssend);
+
+ dest = (uint8_t*)USERSPACE->us_bssstart;
+ end = (uint8_t*)USERSPACE->us_bssend;
+
+ while (dest != end)
+ {
+ *dest++ = 0;
+ }
+
+ /* Initialize all of user-space .data */
+
+ DEBUGASSERT(USERSPACE->us_datasource != 0 &&
+ USERSPACE->us_datastart != 0 && USERSPACE->us_dataend != 0 &&
+ USERSPACE->us_datastart <= USERSPACE->us_dataend);
+
+ src = (uint8_t*)USERSPACE->us_datasource;
+ dest = (uint8_t*)USERSPACE->us_datastart;
+ end = (uint8_t*)USERSPACE->us_dataend;
+
+ while (dest != end)
+ {
+ *dest++ = *src++;
+ }
+}
+
+#endif /* CONFIG_NUTTX_KERNEL */
+
diff --git a/nuttx/arch/arm/src/kl/kl_userspace.h b/nuttx/arch/arm/src/kl/kl_userspace.h
new file mode 100644
index 000000000..c92dfe2b0
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/kl_userspace.h
@@ -0,0 +1,76 @@
+/************************************************************************************
+ * arch/arm/src/kl/kl_userspace.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_KINETIS_USERSPACE_H
+#define __ARCH_ARM_SRC_KL_KINETIS_USERSPACE_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/****************************************************************************
+ * Name: kl_userspace
+ *
+ * Description:
+ * For the case of the separate user-/kernel-space build, perform whatever
+ * platform specific initialization of the user memory is required.
+ * Normally this just means initializing the user space .data and .bss
+ * segments.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NUTTX_KERNEL
+void kl_userspace(void);
+#endif
+
+#endif /* __ARCH_ARM_SRC_KL_KINETIS_USERSPACE_H */