summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-08-10 17:54:00 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-08-10 17:54:00 +0000
commit01e2672b46e5aa9a495440451563e27bab88384b (patch)
tree724ac240481e7f2dffd6fc2e3aef6d43401a9543
parenta6fa3d53832c8b63039def4987a34da152486f24 (diff)
downloadpx4-nuttx-01e2672b46e5aa9a495440451563e27bab88384b.tar.gz
px4-nuttx-01e2672b46e5aa9a495440451563e27bab88384b.tar.bz2
px4-nuttx-01e2672b46e5aa9a495440451563e27bab88384b.zip
Add Kinetis FLASH and FlexBUS header files
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3863 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/src/kinetis/kinetis_flexbus.h213
-rw-r--r--nuttx/arch/arm/src/kinetis/kinetis_fmc.h389
-rw-r--r--nuttx/arch/arm/src/kinetis/kinetis_ftfl.h159
-rw-r--r--nuttx/arch/arm/src/kinetis/kinetis_memorymap.h8
-rw-r--r--nuttx/arch/arm/src/kinetis/kinetis_rtc.h195
5 files changed, 879 insertions, 85 deletions
diff --git a/nuttx/arch/arm/src/kinetis/kinetis_flexbus.h b/nuttx/arch/arm/src/kinetis/kinetis_flexbus.h
new file mode 100644
index 000000000..8fddfeff9
--- /dev/null
+++ b/nuttx/arch/arm/src/kinetis/kinetis_flexbus.h
@@ -0,0 +1,213 @@
+/************************************************************************************
+ * arch/arm/src/kinetis/kinetis_flexbus.h
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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_FLEXBUS_H
+#define __ARCH_ARM_SRC_KINETIS_KINETIS_FLEXBUS_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register Offsets *****************************************************************/
+
+#define KINETIS_FB_CS_OFFSET(n) (0x0000+(12*(n)))
+#define KINETIS_FB_CSAR_OFFSET 0x0000 /* Chip select n address register */
+#define KINETIS_FB_CSMR_OFFSET 0x0004 /* Chip select n mask register */
+#define KINETIS_FB_CSCR_OFFSET 0x0008 /* Chip select n control register */
+
+#define KINETIS_FB_CSAR0_OFFSET 0x0000 /* Chip select 0 address register */
+#define KINETIS_FB_CSMR0_OFFSET 0x0004 /* Chip select 0 mask register */
+#define KINETIS_FB_CSCR0_OFFSET 0x0008 /* Chip select 0 control register */
+
+#define KINETIS_FB_CSAR1_OFFSET 0x000c /* Chip select 1 address register */
+#define KINETIS_FB_CSMR1_OFFSET 0x0010 /* Chip select 1 mask register */
+#define KINETIS_FB_CSCR1_OFFSET 0x0014 /* Chip select 1 control register */
+
+#define KINETIS_FB_CSAR2_OFFSET 0x0018 /* Chip select 2 address register */
+#define KINETIS_FB_CSMR2_OFFSET 0x001c /* Chip select 2 mask register */
+#define KINETIS_FB_CSCR2_OFFSET 0x0020 /* Chip select 2 control register */
+
+#define KINETIS_FB_CSAR3_OFFSET 0x0024 /* Chip select 3 address register */
+#define KINETIS_FB_CSMR3_OFFSET 0x0028 /* Chip select 3 mask register */
+#define KINETIS_FB_CSCR3_OFFSET 0x002c /* Chip select 3 control register */
+
+#define KINETIS_FB_CSAR4_OFFSET 0x0030 /* Chip select 4 address register */
+#define KINETIS_FB_CSMR4_OFFSET 0x0034 /* Chip select 4 mask register */
+#define KINETIS_FB_CSCR4_OFFSET 0x0038 /* Chip select 4 control register */
+
+#define KINETIS_FB_CSAR5_OFFSET 0x003c /* Chip select 5 address register */
+#define KINETIS_FB_CSMR5_OFFSET 0x0040 /* Chip select 5 mask register */
+#define KINETIS_FB_CSCR5_OFFSET 0x0044 /* Chip select 5 control register */
+
+#define KINETIS_FB_CSPMCR_OFFSET 0x0060 /* Chip select port multiplexing control register */
+
+/* Register Addresses ***************************************************************/
+# define 0x4000c000 /* FlexBus */
+
+#define KINETIS_FB_CS_BASE(n) (KINETIS_FLEXBUS_BASE+KINETIS_FB_CS_OFFSET(n))
+#define KINETIS_FB_CSAR(n) (KINETIS_FB_CS_BASE(n)+KINETIS_FB_CSAR_OFFSET)
+#define KINETIS_FB_CSMR(n) (KINETIS_FB_CS_BASE(n)+KINETIS_FB_CSMR_OFFSET)
+#define KINETIS_FB_CSCR(n) (KINETIS_FB_CS_BASE(n)+KINETIS_FB_CSCR_OFFSET)
+
+#define KINETIS_FB_CSAR0 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSAR0_OFFSET)
+#define KINETIS_FB_CSMR0 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSMR0_OFFSET)
+#define KINETIS_FB_CSCR0 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSCR0_OFFSET)
+
+#define KINETIS_FB_CSAR1 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSAR1_OFFSET)
+#define KINETIS_FB_CSMR1 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSMR1_OFFSET)
+#define KINETIS_FB_CSCR1 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSCR1_OFFSET)
+
+#define KINETIS_FB_CSAR2 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSAR2_OFFSET)
+#define KINETIS_FB_CSMR2 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSMR2_OFFSET)
+#define KINETIS_FB_CSCR2 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSCR2_OFFSET)
+
+#define KINETIS_FB_CSAR3 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSAR3_OFFSET)
+#define KINETIS_FB_CSMR3 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSMR3_OFFSET)
+#define KINETIS_FB_CSCR3 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSCR3_OFFSET)
+
+#define KINETIS_FB_CSAR4 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSAR4_OFFSET)
+#define KINETIS_FB_CSMR4 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSMR4_OFFSET)
+#define KINETIS_FB_CSCR4 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSCR4_OFFSET)
+
+#define KINETIS_FB_CSAR5 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSAR5_OFFSET)
+#define KINETIS_FB_CSMR5 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSMR5_OFFSET)
+#define KINETIS_FB_CSCR5 (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSCR5_OFFSET)
+
+#define KINETIS_FB_CSPMCR (KINETIS_FLEXBUS_BASE+KINETIS_FB_CSPMCR_OFFSET)
+
+/* Register Bit Definitions *********************************************************/
+
+/* Chip select address register (32-bit) */
+
+#define FB_CSAR_BA_SHIFT (16) /* Bits 16-31: Base address */
+#define FB_CSAR_BA_MASK (0xffff << FB_CSAR_BA_SHIFT)
+ /* Bits 0-15: Reserved */
+
+/* Chip select mask register (32-bit) */
+
+#define FB_CSMR_V (1 << 0) /* Bit 0: Valid */
+ /* Bits 1-7: Reserved */
+#define FB_CSMR_WP (1 << 8) /* Bit 8: Write protect
+ /* Bits 9-15: Reserved */
+#define FB_CSMR_BAM_SHIFT (16) /* Bits 16-31: Base address mask */
+#define FB_CSMR_BAM_MASK (0xffff << FB_CSMR_BAM_SHIFT)
+
+/* Chip select control register (32-bit) */
+ /* Bits 0-1: Reserved */
+#define FB_CSCR_BSTW (1 << 3) /* Bit 3: Burst-write enable */
+#define FB_CSCR_BSTR (1 << 4) /* Bit 4: Burst-read enable */
+#define FB_CSCR_BEM (1 << 5) /* Bit 5: Byte-enable mode */
+#define FB_CSCR_PS_SHIFT (6) /* Bits 6-7: Port size */
+#define FB_CSCR_PS_MASK (3 << FB_CSCR_PS_SHIFT)
+# define FB_CSCR_PS_32BIT (0 << FB_CSCR_PS_SHIFT) /* 32-bit port size */
+# define FB_CSCR_PS_8BIT (1 << FB_CSCR_PS_SHIFT) /* 8-bit port size */
+# define FB_CSCR_PS_16BIT (2 << FB_CSCR_PS_SHIFT) /* 16-bit port size */
+#define FB_CSCR_AA (1 << 8) /* Bit 8: Auto-acknowledge enable */
+#define FB_CSCR_BLS (1 << 9) /* Bit 9: Byte-lane shift */
+#define FB_CSCR_WS_SHIFT (10) /* Bits 19-15: Wait states */
+#define FB_CSCR_WS_SHIFT (10) /* Bits 19-15: Wait states */
+#define FB_CSCR_WRAH_SHIFT (16) /* Bits 16-17: Write address hold or deselect */
+#define FB_CSCR_WRAH_MASK (3 << FB_CSCR_WRAH_SHIFT)
+# define FB_CSCR_WRAH_HOLD1 (0 << FB_CSCR_WRAH_SHIFT) /* Hold one cycle after FB_CSn */
+# define FB_CSCR_WRAH_HOLD2 (1 << FB_CSCR_WRAH_SHIFT) /* Hold two cycles after FB_CSn */
+# define FB_CSCR_WRAH_HOLD3 (2 << FB_CSCR_WRAH_SHIFT) /* Hold three cycles after FB_CSn */
+# define FB_CSCR_WRAH_HOLD4 (3 << FB_CSCR_WRAH_SHIFT) /* Hold four cycles after FB_CSn */
+#define FB_CSCR_RDAH_SHIFT (18) /* Bits 18-19: Read address hold or deselect */
+#define FB_CSCR_RDAH_MASK (3 << FB_CSCR_RDAH_SHIFT)
+# define FB_CSCR_RDAH_10CYCLES (0 << FB_CSCR_RDAH_SHIFT) /* AA=0:1 cycle else 0 cycles */
+# define FB_CSCR_RDAH_21CYCLES (1 << FB_CSCR_RDAH_SHIFT) /* AA=0:2 cycles else 1 cycle */
+# define FB_CSCR_RDAH_32CYCLES (2 << FB_CSCR_RDAH_SHIFT) /* AA=0:3 cycles else 2 cycles */
+# define FB_CSCR_RDAH_43CYCLES (3 << FB_CSCR_RDAH_SHIFT) /* AA=0:4 cycles else 3 cycles */
+#define FB_CSCR_ASET_SHIFT (20) /* Bits 20-21: Address setup */
+#define FB_CSCR_ASET_MASK (3 << FB_CSCR_ASET_SHIFT)
+# define FB_CSCR_ASET_1STRISING (0 << FB_CSCR_ASET_SHIFT) /* Assert CR on first rising clock edge */
+# define FB_CSCR_ASET_2NDRISING (1 << FB_CSCR_ASET_SHIFT) /* Assert CR on second rising clock edge */
+# define FB_CSCR_ASET_3RDRISING (2 << FB_CSCR_ASET_SHIFT) /* Assert CR on third rising clock edge */
+# define FB_CSCR_ASET_4thRISING (3 << FB_CSCR_ASET_SHIFT) /* Assert CR on fourth rising clock edge */
+#define FB_CSCR_EXTS (1 << 22) /* Bit 22: Extended address latch enable */
+#define FB_CSCR_SWSEN (1 << 23) /* Bit 23: Secondary wait state enable */
+ /* Bits 24-25: Reserved */
+#define FB_CSCR_SWS_SHIFT (26) /* Bits 26-31: Secondary wait states */
+#define FB_CSCR_SWS_MASK (0x3f << FB_CSCR_SWS_SHIFT)
+
+/* Chip select port multiplexing control register (32-bit) */
+ /* Bits 0-11: Reserved */
+#define FB_CSPMCR_GROUP5_SHIFT (12) /* Bits 12-15: FlexBus signal group 5 multiplex control */
+#define FB_CSPMCR_GROUP5_MASK (15 << FB_CSPMCR_GROUP5_SHIFT)
+# define FB_CSPMCR_GROUP5_TA (0 << FB_CSPMCR_GROUP5_SHIFT) /* FB_TA */
+# define FB_CSPMCR_GROUP5_CS3 (1 << FB_CSPMCR_GROUP5_SHIFT) /* FB_CS3 */
+# define FB_CSPMCR_GROUP5_BE70 (2 << FB_CSPMCR_GROUP5_SHIFT) /* FB_BE_7_0 */
+#define FB_CSPMCR_GROUP4_SHIFT (16) /* Bits 16-19: FlexBus signal group 4 multiplex control */
+#define FB_CSPMCR_GROUP4_MASK (15 << FB_CSPMCR_GROUP4_SHIFT)
+# define FB_CSPMCR_GROUP4_TBST (0 << FB_CSPMCR_GROUP4_SHIFT) /* FB_TBST */
+# define FB_CSPMCR_GROUP4_CS2 (1 << FB_CSPMCR_GROUP4_SHIFT) /* FB_CS2 */
+# define FB_CSPMCR_GROUP4_BE158 (2 << FB_CSPMCR_GROUP4_SHIFT) /* FB_BE_15_8 */
+#define FB_CSPMCR_GROUP3_SHIFT (20) /* Bits 29-23: FlexBus signal group 3 multiplex control */
+#define FB_CSPMCR_GROUP3_MASK (15 << FB_CSPMCR_GROUP3_SHIFT)
+# define FB_CSPMCR_GROUP3_CS5 (0 << FB_CSPMCR_GROUP3_SHIFT) /* FB_CS5 */
+# define FB_CSPMCR_GROUP3_TSIZ1 (1 << FB_CSPMCR_GROUP3_SHIFT) /* FB_TSIZ1 */
+# define FB_CSPMCR_GROUP3_BE2316 (2 << FB_CSPMCR_GROUP3_SHIFT) /* FB_BE_23_16 */
+#define FB_CSPMCR_GROUP2_SHIFT (24) /* Bits 24-27: FlexBus signal group 2 multiplex control */
+#define FB_CSPMCR_GROUP2_MASK (15 << FB_CSPMCR_GROUP2_SHIFT)
+# define FB_CSPMCR_GROUP2_CS4 (0 << FB_CSPMCR_GROUP2_SHIFT) /* FB_CS4 */
+# define FB_CSPMCR_GROUP2_TSIZ0 (1 << FB_CSPMCR_GROUP2_SHIFT) /* FB_TSIZ0 */
+# define FB_CSPMCR_GROUP2_BE3124 (2 << FB_CSPMCR_GROUP2_SHIFT) /* FB_BE_31_24 */
+#define FB_CSPMCR_GROUP1_SHIFT (28) /* Bits 28-31: FlexBus signal group 1 multiplex control */
+#define FB_CSPMCR_GROUP1_MASK (15 << FB_CSPMCR_GROUP1_MASK)
+# define FB_CSPMCR_GROUP1_ALE (0 << FB_CSPMCR_GROUP1_MASK) /* FB_ALE */
+# define FB_CSPMCR_GROUP1_CS1 (1 << FB_CSPMCR_GROUP1_MASK) /* FB_CS1 */
+# define FB_CSPMCR_GROUP1_TS (2 << FB_CSPMCR_GROUP1_MASK) /* FB_TS */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KINETIS_KINETIS_FLEXBUS_H */
diff --git a/nuttx/arch/arm/src/kinetis/kinetis_fmc.h b/nuttx/arch/arm/src/kinetis/kinetis_fmc.h
new file mode 100644
index 000000000..2a318e3de
--- /dev/null
+++ b/nuttx/arch/arm/src/kinetis/kinetis_fmc.h
@@ -0,0 +1,389 @@
+/************************************************************************************
+ * arch/arm/src/kinetis/kinetis_fmc.h
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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_FMC_H
+#define __ARCH_ARM_SRC_KINETIS_KINETIS_FMC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register Offsets *****************************************************************/
+
+#define KINETIS_FMC_PFAPR_OFFSET 0x0000 /* Flash Access Protection Register */
+#define KINETIS_FMC_PFB0CR_OFFSET 0x0004 /* Flash Bank 0 Control Register */
+#define KINETIS_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 KINETIS_FMC_TAGVD_OFFSET(w,s) (0x100+((w)<<5)+((s)<<2))
+
+#define KINETIS_FMC_TAGVDW0S0_OFFSET 0x0100 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW0S1_OFFSET 0x0104 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW0S2_OFFSET 0x0108 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW0S3_OFFSET 0x010c /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW0S4_OFFSET 0x0110 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW0S5_OFFSET 0x0114 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW0S6_OFFSET 0x0118 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW0S7_OFFSET 0x011c /* Cache Directory Storage */
+
+#define KINETIS_FMC_TAGVDW1S0_OFFSET 0x0120 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW1S1_OFFSET 0x0124 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW1S2_OFFSET 0x0128 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW1S3_OFFSET 0x012c /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW1S4_OFFSET 0x0130 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW1S5_OFFSET 0x0134 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW1S6_OFFSET 0x0138 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW1S7_OFFSET 0x013c /* Cache Directory Storage */
+
+#define KINETIS_FMC_TAGVDW2S0_OFFSET 0x0140 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW2S1_OFFSET 0x0144 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW2S2_OFFSET 0x0148 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW2S3_OFFSET 0x014c /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW2S4_OFFSET 0x0150 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW2S5_OFFSET 0x0154 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW2S6_OFFSET 0x0158 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW2S7_OFFSET 0x015c /* Cache Directory Storage */
+
+#define KINETIS_FMC_TAGVDW3S0_OFFSET 0x0160 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW3S1_OFFSET 0x0164 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW3S2_OFFSET 0x0168 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW3S3_OFFSET 0x016c /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW3S4_OFFSET 0x0170 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW3S5_OFFSET 0x0174 /* Cache Directory Storage */
+#define KINETIS_FMC_TAGVDW3S6_OFFSET 0x0178 /* Cache Directory Storage */
+#define KINETIS_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 KINETIS_FMC_DATAU_OFFSET(w,s) (0x200+((w)<<6)+((s)<<2))
+#define KINETIS_FMC_DATAL_OFFSET(w,s) (0x204+((w)<<6)+((s)<<2))
+
+#define KINETIS_FMC_DATAW0S0U_OFFSET 0x0200 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW0S0L_OFFSET 0x0204 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW0S1U_OFFSET 0x0208 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW0S1L_OFFSET 0x020c /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW0S2U_OFFSET 0x0210 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW0S2L_OFFSET 0x0214 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW0S3U_OFFSET 0x0218 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW0S3L_OFFSET 0x021c /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW0S4U_OFFSET 0x0220 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW0S4L_OFFSET 0x0224 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW0S5U_OFFSET 0x0228 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW0S5L_OFFSET 0x022c /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW0S6U_OFFSET 0x0230 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW0S6L_OFFSET 0x0234 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW0S7U_OFFSET 0x0238 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW0S7L_OFFSET 0x023c /* Cache Data Storage (lower word) */
+
+#define KINETIS_FMC_DATAW1S0U_OFFSET 0x0240 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW1S0L_OFFSET 0x0244 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW1S1U_OFFSET 0x0248 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW1S1L_OFFSET 0x024c /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW1S2U_OFFSET 0x0250 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW1S2L_OFFSET 0x0254 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW1S3U_OFFSET 0x0258 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW1S3L_OFFSET 0x025c /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW1S4U_OFFSET 0x0260 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW1S4L_OFFSET 0x0264 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW1S5U_OFFSET 0x0268 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW1S5L_OFFSET 0x026c /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW1S6U_OFFSET 0x0270 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW1S6L_OFFSET 0x0274 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW1S7U_OFFSET 0x0278 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW1S7L_OFFSET 0x027c /* Cache Data Storage (lower word) */
+
+#define KINETIS_FMC_DATAW2S0U_OFFSET 0x0280 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW2S0L_OFFSET 0x0284 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW2S1U_OFFSET 0x0288 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW2S1L_OFFSET 0x028c /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW2S2U_OFFSET 0x0290 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW2S2L_OFFSET 0x0294 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW2S3U_OFFSET 0x0298 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW2S3L_OFFSET 0x029c /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW2S4U_OFFSET 0x02a0 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW2S4L_OFFSET 0x02a4 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW2S5U_OFFSET 0x02a8 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW2S5L_OFFSET 0x02ac /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW2S6U_OFFSET 0x02b0 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW2S6L_OFFSET 0x02b4 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW2S7U_OFFSET 0x02b8 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW2S7L_OFFSET 0x02bc /* Cache Data Storage (lower word) */
+
+#define KINETIS_FMC_DATAW3S0U_OFFSET 0x02c0 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW3S0L_OFFSET 0x02c4 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW3S1U_OFFSET 0x02c8 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW3S1L_OFFSET 0x02cc /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW3S2U_OFFSET 0x02d0 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW3S2L_OFFSET 0x02d4 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW3S3U_OFFSET 0x02d8 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW3S3L_OFFSET 0x02dc /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW3S4U_OFFSET 0x02e0 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW3S4L_OFFSET 0x02e4 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW3S5U_OFFSET 0x02e8 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW3S5L_OFFSET 0x02ec /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW3S6U_OFFSET 0x02f0 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW3S6L_OFFSET 0x02f4 /* Cache Data Storage (lower word) */
+#define KINETIS_FMC_DATAW3S7U_OFFSET 0x02f8 /* Cache Data Storage (upper word) */
+#define KINETIS_FMC_DATAW3S7L_OFFSET 0x02fc /* Cache Data Storage (lower word) */
+
+/* Register Addresses ***************************************************************/
+
+#define KINETIS_FMC_PFAPR (KINETIS_FMC_BASE+KINETIS_FMC_PFAPR_OFFSET)
+#define KINETIS_FMC_PFB0CR (KINETIS_FMC_BASE+KINETIS_FMC_PFB0CR_OFFSET)
+#define KINETIS_FMC_PFB1CR (KINETIS_FMC_BASE+KINETIS_FMC_PFB1CR_OFFSET)
+
+/* Cache Directory Storage for way=w and set=s, w=0..3, s=0..7 */
+
+#define KINETIS_FMC_TAGVD(w,s) (KINETIS_FMC_BASE+KINETIS_FMC_TAGVD_OFFSET(w,s))
+
+#define KINETIS_FMC_TAGVDW0S0 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW0S0_OFFSET)
+#define KINETIS_FMC_TAGVDW0S1 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW0S1_OFFSET)
+#define KINETIS_FMC_TAGVDW0S2 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW0S2_OFFSET)
+#define KINETIS_FMC_TAGVDW0S3 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW0S3_OFFSET)
+#define KINETIS_FMC_TAGVDW0S4 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW0S4_OFFSET)
+#define KINETIS_FMC_TAGVDW0S5 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW0S5_OFFSET)
+#define KINETIS_FMC_TAGVDW0S6 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW0S6_OFFSET)
+#define KINETIS_FMC_TAGVDW0S7 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW0S7_OFFSET)
+
+#define KINETIS_FMC_TAGVDW1S0 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW1S0_OFFSET)
+#define KINETIS_FMC_TAGVDW1S1 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW1S1_OFFSET)
+#define KINETIS_FMC_TAGVDW1S2 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW1S2_OFFSET)
+#define KINETIS_FMC_TAGVDW1S3 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW1S3_OFFSET)
+#define KINETIS_FMC_TAGVDW1S4 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW1S4_OFFSET)
+#define KINETIS_FMC_TAGVDW1S5 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW1S5_OFFSET)
+#define KINETIS_FMC_TAGVDW1S6 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW1S6_OFFSET)
+#define KINETIS_FMC_TAGVDW1S7 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW1S7_OFFSET)
+
+#define KINETIS_FMC_TAGVDW2S0 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW2S0_OFFSET)
+#define KINETIS_FMC_TAGVDW2S1 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW2S1_OFFSET)
+#define KINETIS_FMC_TAGVDW2S2 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW2S2_OFFSET)
+#define KINETIS_FMC_TAGVDW2S3 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW2S3_OFFSET)
+#define KINETIS_FMC_TAGVDW2S4 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW2S4_OFFSET)
+#define KINETIS_FMC_TAGVDW2S5 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW2S5_OFFSET)
+#define KINETIS_FMC_TAGVDW2S6 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW2S6_OFFSET)
+#define KINETIS_FMC_TAGVDW2S7 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW2S7_OFFSET)
+
+#define KINETIS_FMC_TAGVDW3S0 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW3S0_OFFSET)
+#define KINETIS_FMC_TAGVDW3S1 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW3S1_OFFSET)
+#define KINETIS_FMC_TAGVDW3S2 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW3S2_OFFSET)
+#define KINETIS_FMC_TAGVDW3S3 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW3S3_OFFSET)
+#define KINETIS_FMC_TAGVDW3S4 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW3S4_OFFSET)
+#define KINETIS_FMC_TAGVDW3S5 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW3S5_OFFSET)
+#define KINETIS_FMC_TAGVDW3S6 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW3S6_OFFSET)
+#define KINETIS_FMC_TAGVDW3S7 (KINETIS_FMC_BASE+KINETIS_FMC_TAGVDW3S7_OFFSET)
+
+/* Cache Data Storage (upper and lower) for way=w and set=s, w=0..3, s=0..7 */
+
+#define KINETIS_FMC_DATAU(w,s) (KINETIS_FMC_BASE+KINETIS_FMC_DATAU_OFFSET(w,s))
+#define KINETIS_FMC_DATAL(w,s) (KINETIS_FMC_BASE+KINETIS_FMC_DATAL_OFFSET(w,s))
+
+#define KINETIS_FMC_DATAW0S0U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S0U_OFFSET)
+#define KINETIS_FMC_DATAW0S0L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S0L_OFFSET)
+#define KINETIS_FMC_DATAW0S1U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S1U_OFFSET)
+#define KINETIS_FMC_DATAW0S1L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S1L_OFFSET)
+#define KINETIS_FMC_DATAW0S2U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S2U_OFFSET)
+#define KINETIS_FMC_DATAW0S2L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S2L_OFFSET)
+#define KINETIS_FMC_DATAW0S3U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S3U_OFFSET)
+#define KINETIS_FMC_DATAW0S3L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S3L_OFFSET)
+#define KINETIS_FMC_DATAW0S4U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S4U_OFFSET)
+#define KINETIS_FMC_DATAW0S4L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S4L_OFFSET)
+#define KINETIS_FMC_DATAW0S5U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S5U_OFFSET)
+#define KINETIS_FMC_DATAW0S5L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S5L_OFFSET)
+#define KINETIS_FMC_DATAW0S6U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S6U_OFFSET)
+#define KINETIS_FMC_DATAW0S6L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S6L_OFFSET)
+#define KINETIS_FMC_DATAW0S7U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S7U_OFFSET)
+#define KINETIS_FMC_DATAW0S7L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW0S7L_OFFSET)
+
+#define KINETIS_FMC_DATAW1S0U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S0U_OFFSET)
+#define KINETIS_FMC_DATAW1S0L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S0L_OFFSET)
+#define KINETIS_FMC_DATAW1S1U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S1U_OFFSET)
+#define KINETIS_FMC_DATAW1S1L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S1L_OFFSET)
+#define KINETIS_FMC_DATAW1S2U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S2U_OFFSET)
+#define KINETIS_FMC_DATAW1S2L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S2L_OFFSET)
+#define KINETIS_FMC_DATAW1S3U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S3U_OFFSET)
+#define KINETIS_FMC_DATAW1S3L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S3L_OFFSET)
+#define KINETIS_FMC_DATAW1S4U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S4U_OFFSET)
+#define KINETIS_FMC_DATAW1S4L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S4L_OFFSET)
+#define KINETIS_FMC_DATAW1S5U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S5U_OFFSET)
+#define KINETIS_FMC_DATAW1S5L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S5L_OFFSET)
+#define KINETIS_FMC_DATAW1S6U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S6U_OFFSET)
+#define KINETIS_FMC_DATAW1S6L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S6L_OFFSET)
+#define KINETIS_FMC_DATAW1S7U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S7U_OFFSET)
+#define KINETIS_FMC_DATAW1S7L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW1S7L_OFFSET)
+
+#define KINETIS_FMC_DATAW2S0U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S0U_OFFSET)
+#define KINETIS_FMC_DATAW2S0L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S0L_OFFSET)
+#define KINETIS_FMC_DATAW2S1U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S1U_OFFSET)
+#define KINETIS_FMC_DATAW2S1L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S1L_OFFSET)
+#define KINETIS_FMC_DATAW2S2U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S2U_OFFSET)
+#define KINETIS_FMC_DATAW2S2L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S2L_OFFSET)
+#define KINETIS_FMC_DATAW2S3U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S3U_OFFSET)
+#define KINETIS_FMC_DATAW2S3L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S3L_OFFSET)
+#define KINETIS_FMC_DATAW2S4U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S4U_OFFSET)
+#define KINETIS_FMC_DATAW2S4L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S4L_OFFSET)
+#define KINETIS_FMC_DATAW2S5U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S5U_OFFSET)
+#define KINETIS_FMC_DATAW2S5L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S5L_OFFSET)
+#define KINETIS_FMC_DATAW2S6U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S6U_OFFSET)
+#define KINETIS_FMC_DATAW2S6L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S6L_OFFSET)
+#define KINETIS_FMC_DATAW2S7U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S7U_OFFSET)
+#define KINETIS_FMC_DATAW2S7L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW2S7L_OFFSET)
+
+#define KINETIS_FMC_DATAW3S0U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S0U_OFFSET)
+#define KINETIS_FMC_DATAW3S0L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S0L_OFFSET)
+#define KINETIS_FMC_DATAW3S1U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S1U_OFFSET)
+#define KINETIS_FMC_DATAW3S1L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S1L_OFFSET)
+#define KINETIS_FMC_DATAW3S2U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S2U_OFFSET)
+#define KINETIS_FMC_DATAW3S2L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S2L_OFFSET)
+#define KINETIS_FMC_DATAW3S3U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S3U_OFFSET)
+#define KINETIS_FMC_DATAW3S3L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S3L_OFFSET)
+#define KINETIS_FMC_DATAW3S4U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S4U_OFFSET)
+#define KINETIS_FMC_DATAW3S4L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S4L_OFFSET)
+#define KINETIS_FMC_DATAW3S5U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S5U_OFFSET)
+#define KINETIS_FMC_DATAW3S5L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S5L_OFFSET)
+#define KINETIS_FMC_DATAW3S6U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S6U_OFFSET)
+#define KINETIS_FMC_DATAW3S6L (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S6L_OFFSET)
+#define KINETIS_FMC_DATAW3S7U (KINETIS_FMC_BASE+KINETIS_FMC_DATAW3S7U_OFFSET)
+#define KINETIS_FMC_DATAW3S7L (KINETIS_FMC_BASE+KINETIS_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_KINETIS_KINETIS_FMC_H */
diff --git a/nuttx/arch/arm/src/kinetis/kinetis_ftfl.h b/nuttx/arch/arm/src/kinetis/kinetis_ftfl.h
new file mode 100644
index 000000000..27746ab02
--- /dev/null
+++ b/nuttx/arch/arm/src/kinetis/kinetis_ftfl.h
@@ -0,0 +1,159 @@
+/************************************************************************************
+ * arch/arm/src/kinetis/kinetis_ftfl.h
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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_FTFL_H
+#define __ARCH_ARM_SRC_KINETIS_KINETIS_FTFL_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register Offsets *****************************************************************/
+
+#define KINETIS_FTFL_FSTAT_OFFSET 0x0000 /* Flash Status Register */
+#define KINETIS_FTFL_FCNFG_OFFSET 0x0001 /* Flash Configuration Register */
+#define KINETIS_FTFL_FSEC_OFFSET 0x0002 /* Flash Security Register */
+#define KINETIS_FTFL_FOPT_OFFSET 0x0003 /* Flash Option Register */
+
+#define KINETIS_FTFL_FCCOB3_OFFSET 0x0004 /* Flash Common Command Object Registers */
+#define KINETIS_FTFL_FCCOB2_OFFSET 0x0005 /* Flash Common Command Object Registers */
+#define KINETIS_FTFL_FCCOB1_OFFSET 0x0006 /* Flash Common Command Object Registers */
+#define KINETIS_FTFL_FCCOB0_OFFSET 0x0007 /* Flash Common Command Object Registers */
+#define KINETIS_FTFL_FCCOB7_OFFSET 0x0008 /* Flash Common Command Object Registers */
+#define KINETIS_FTFL_FCCOB6_OFFSET 0x0009 /* Flash Common Command Object Registers */
+#define KINETIS_FTFL_FCCOB5_OFFSET 0x000a /* Flash Common Command Object Registers */
+#define KINETIS_FTFL_FCCOB4_OFFSET 0x000b /* Flash Common Command Object Registers */
+#define KINETIS_FTFL_FCCOBB_OFFSET 0x000c /* Flash Common Command Object Registers */
+#define KINETIS_FTFL_FCCOBA_OFFSET 0x000d /* Flash Common Command Object Registers */
+#define KINETIS_FTFL_FCCOB9_OFFSET 0x000e /* Flash Common Command Object Registers */
+#define KINETIS_FTFL_FCCOB8_OFFSET 0x000f /* Flash Common Command Object Registers */
+#define KINETIS_FTFL_FPROT3_OFFSET 0x0010 /* Program Flash Protection Registers */
+#define KINETIS_FTFL_FPROT2_OFFSET 0x0011 /* Program Flash Protection Registers */
+#define KINETIS_FTFL_FPROT1_OFFSET 0x0012 /* Program Flash Protection Registers */
+#define KINETIS_FTFL_FPROT0_OFFSET 0x0013 /* Program Flash Protection Registers */
+#define KINETIS_FTFL_FEPROT_OFFSET 0x0016 /* EEPROM Protection Register */
+#define KINETIS_FTFL_FDPROT_OFFSET 0x0017 /* Data Flash Protection Register */
+
+/* Register Addresses ***************************************************************/
+
+#define KINETIS_FTFL_FSTAT (KINETIS_FTFL_BASE+KINETIS_FTFL_FSTAT_OFFSET)
+#define KINETIS_FTFL_FCNFG (KINETIS_FTFL_BASE+KINETIS_FTFL_FCNFG_OFFSET)
+#define KINETIS_FTFL_FSEC (KINETIS_FTFL_BASE+KINETIS_FTFL_FSEC_OFFSET)
+#define KINETIS_FTFL_FOPT (KINETIS_FTFL_BASE+KINETIS_FTFL_FOPT_OFFSET)
+#define KINETIS_FTFL_FCCOB3 (KINETIS_FTFL_BASE+KINETIS_FTFL_FCCOB3_OFFSET)
+#define KINETIS_FTFL_FCCOB2 (KINETIS_FTFL_BASE+KINETIS_FTFL_FCCOB2_OFFSET)
+#define KINETIS_FTFL_FCCOB1 (KINETIS_FTFL_BASE+KINETIS_FTFL_FCCOB1_OFFSET)
+#define KINETIS_FTFL_FCCOB0 (KINETIS_FTFL_BASE+KINETIS_FTFL_FCCOB0_OFFSET)
+#define KINETIS_FTFL_FCCOB7 (KINETIS_FTFL_BASE+KINETIS_FTFL_FCCOB7_OFFSET)
+#define KINETIS_FTFL_FCCOB6 (KINETIS_FTFL_BASE+KINETIS_FTFL_FCCOB6_OFFSET)
+#define KINETIS_FTFL_FCCOB5 (KINETIS_FTFL_BASE+KINETIS_FTFL_FCCOB5_OFFSET)
+#define KINETIS_FTFL_FCCOB4 (KINETIS_FTFL_BASE+KINETIS_FTFL_FCCOB4_OFFSET)
+#define KINETIS_FTFL_FCCOBB (KINETIS_FTFL_BASE+KINETIS_FTFL_FCCOBB_OFFSET)
+#define KINETIS_FTFL_FCCOBA (KINETIS_FTFL_BASE+KINETIS_FTFL_FCCOBA_OFFSET)
+#define KINETIS_FTFL_FCCOB9 (KINETIS_FTFL_BASE+KINETIS_FTFL_FCCOB9_OFFSET)
+#define KINETIS_FTFL_FCCOB8 (KINETIS_FTFL_BASE+KINETIS_FTFL_FCCOB8_OFFSET)
+#define KINETIS_FTFL_FPROT3 (KINETIS_FTFL_BASE+KINETIS_FTFL_FPROT3_OFFSET)
+#define KINETIS_FTFL_FPROT2 (KINETIS_FTFL_BASE+KINETIS_FTFL_FPROT2_OFFSET)
+#define KINETIS_FTFL_FPROT1 (KINETIS_FTFL_BASE+KINETIS_FTFL_FPROT1_OFFSET)
+#define KINETIS_FTFL_FPROT0 (KINETIS_FTFL_BASE+KINETIS_FTFL_FPROT0_OFFSET)
+#define KINETIS_FTFL_FEPROT (KINETIS_FTFL_BASE+KINETIS_FTFL_FEPROT_OFFSET)
+#define KINETIS_FTFL_FDPROT (KINETIS_FTFL_BASE+KINETIS_FTFL_FDPROT_OFFSET)
+
+/* Register Bit Definitions *********************************************************/
+
+/* Flash Status Register */
+
+#define FTFL_FSTAT_MGSTAT0 (1 << 0) /* Bit 0: Memory Controller Command Completion Status Flag */
+ /* Bits 1-3: Reserved */
+#define FTFL_FSTAT_FPVIOL (1 << 4) /* Bit 4: Flash Protection Violation Flag */
+#define FTFL_FSTAT_ACCERR (1 << 5) /* Bit 5: Flash Access Error Flag */
+#define FTFL_FSTAT_RDCOLERR (1 << 6) /* Bit 6: FTFL Read Collision Error Flag */
+#define FTFL_FSTAT_CCIF (1 << 7) /* Bit 7: Command Complete Interrupt Flag */
+
+/* Flash Configuration Register */
+
+#define FTFL_FCNFG_EEERDY (1 << 0) /* Bit 0: FEEPROM backup data copied to FlexRAM */
+#define FTFL_FCNFG_RAMRDY (1 << 1) /* Bit 1: RAM Ready */
+#define FTFL_FCNFG_PFLSH (1 << 2) /* Bit 2: FTFL configuration */
+#define FTFL_FCNFG_SWAP (1 << 3) /* Bit 3: Swap */
+#define FTFL_FCNFG_ERSSUSP (1 << 4) /* Bit 4: Erase Suspend */
+#define FTFL_FCNFG_ERSAREQ (1 << 5) /* Bit 5: Erase All Request */
+#define FTFL_FCNFG_RDCOLLIE (1 << 6) /* Bit 6: Read Collision Error Interrupt Enable */
+#define FTFL_FCNFG_CCIE (1 << 7) /* Bit 7: Command Complete Interrupt Enable */
+
+/* Flash Security Register */
+
+#define FTFL_FSEC_SEC_SHIFT (0) /* Bits 0-1: Flash Security */
+#define FTFL_FSEC_SEC_MASK (3 << FTFL_FSEC_SEC_SHIFT)
+# define FTFL_FSEC_SEC_SECURE (0 << FTFL_FSEC_SEC_SHIFT) /* 00,01,11: status is secure */
+# define FTFL_FSEC_SEC_UNSECURE (2 << FTFL_FSEC_SEC_SHIFT) /* 10: status is insecure */
+#define FTFL_FSEC_FSLACC_SHIFT (2) /* Bits 2-3: Freescale Failure Analysis Access Code */
+#define FTFL_FSEC_FSLACC_MASK (3 << FTFL_FSEC_FSLACC_SHIFT)
+# define FTFL_FSEC_FSLACC_GRANTED (0 << FTFL_FSEC_FSLACC_SHIFT) /* 00 or 11: Access granted */
+# define FTFL_FSEC_FSLACC_DENIED (1 << FTFL_FSEC_FSLACC_SHIFT) /* 01 or 10: Access denied */
+#define FTFL_FSEC_MEEN_SHIFT (4) /* Bits 4-5: Mass Erase Enable Bits */
+#define FTFL_FSEC_MEEN_MASK (3 << FTFL_FSEC_MEEN_SHIFT)
+# define FTFL_FSEC_MEEN_ENABLED (0 << FTFL_FSEC_MEEN_SHIFT) /* All values are enabled */
+#define FTFL_FSEC_KEYEN_SHIFT (6) /* Bits 6-7: Backdoor Key Security Enable */
+#define FTFL_FSEC_KEYEN_MASK (3 << FTFL_FSEC_KEYEN_SHIFT)
+# define FTFL_FSEC_KEYEN_DISABLED (1 << FTFL_FSEC_KEYEN_SHIFT) /* All values are disabled */
+
+/* Flash Option Register (32-bits, see Chip Configuration details) */
+/* Flash Common Command Object Registers (8-bit flash command data) */
+/* Program Flash Protection Registers (8-bit flash protection data) */
+/* EEPROM Protection Register (8-bit eeprom protection data) */
+/* Data Flash Protection Register (8-bit data flash protection data) */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KINETIS_KINETIS_FTFL_H */
diff --git a/nuttx/arch/arm/src/kinetis/kinetis_memorymap.h b/nuttx/arch/arm/src/kinetis/kinetis_memorymap.h
index ef4480fff..ae7466818 100644
--- a/nuttx/arch/arm/src/kinetis/kinetis_memorymap.h
+++ b/nuttx/arch/arm/src/kinetis/kinetis_memorymap.h
@@ -101,8 +101,8 @@
# define KINETIS_DMADESC_BASE 0x40009000 /* DMA controller transfer control descriptors */
# define KINETIS_FLEXBUS_BASE 0x4000c000 /* FlexBus */
# define KINETIS_MPU_BASE 0x4000d000 /* MPU */
-# define KINETIS_FLASHC_BASE 0x4001f000 /* Flash memory controller */
-# define KINETIS_FLASH_BASE 0x40020000 /* Flash memory */
+# define KINETIS_FMC_BASE 0x4001f000 /* Flash memory controller */
+# define KINETIS_FTFL_BASE 0x40020000 /* Flash memory */
# define KINETIS_DMAMUX0_BASE 0x40021000 /* DMA channel mutiplexer 0 */
# define KINETIS_FLEXCAN0_BASE 0x40024000 /* FlexCAN 0 */
# define KINETIS_SPI0_BASE 0x4002c000 /* SPI 0 */
@@ -232,8 +232,8 @@
# define KINETIS_DMADESC_BASE 0x40009000 /* DMA controller transfer control descriptors */
# define KINETIS_FLEXBUS_BASE 0x4000c000 /* FlexBus */
# define KINETIS_MPU_BASE 0x4000d000 /* MPU */
-# define KINETIS_FLASHC_BASE 0x4001f000 /* Flash memory controller */
-# define KINETIS_FLASH_BASE 0x40020000 /* Flash memory */
+# define KINETIS_FMC_BASE 0x4001f000 /* Flash memory controller */
+# define KINETIS_FTFL_BASE 0x40020000 /* Flash memory */
# define KINETIS_DMAMUX0_BASE 0x40021000 /* DMA channel mutiplexer 0 */
# define KINETIS_FLEXCAN0_BASE 0x40024000 /* FlexCAN 0 */
# define KINETIS_SPI0_BASE 0x4002c000 /* DSPI 0 */
diff --git a/nuttx/arch/arm/src/kinetis/kinetis_rtc.h b/nuttx/arch/arm/src/kinetis/kinetis_rtc.h
index 9b12d81ef..8c97bd00e 100644
--- a/nuttx/arch/arm/src/kinetis/kinetis_rtc.h
+++ b/nuttx/arch/arm/src/kinetis/kinetis_rtc.h
@@ -50,29 +50,39 @@
/* Register Offsets *****************************************************************/
-#define KINETIS_RTC_TSR_OFFSET 0x0000 /* RTC Time Seconds Register */
-#define KINETIS_RTC_TPR_OFFSET 0x0004 /* RTC Time Prescaler Register */
-#define KINETIS_RTC_TAR_OFFSET 0x0008 /* RTC Time Alarm Register */
-#define KINETIS_RTC_TCR_OFFSET 0x000c /* RTC Time Compensation Register */
-#define KINETIS_RTC_CR_OFFSET 0x0010 /* RTC Control Register */
-#define KINETIS_RTC_SR_OFFSET 0x0014 /* RTC Status Register */
-#define KINETIS_RTC_LR_OFFSET 0x0018 /* RTC Lock Register */
-#define KINETIS_RTC_IER_OFFSET 0x001c /* RTC Interrupt Enable Register */
-#define KINETIS_RTC_WAR_OFFSET 0x0800 /* RTC Write Access Register */
-#define KINETIS_RTC_RAR_OFFSET 0x0804 /* RTC Read Access Register */
+#define KINETIS_RTC_TSR_OFFSET 0x0000 /* RTC Time Seconds Register */
+#define KINETIS_RTC_TPR_OFFSET 0x0004 /* RTC Time Prescaler Register */
+#define KINETIS_RTC_TAR_OFFSET 0x0008 /* RTC Time Alarm Register */
+#define KINETIS_RTC_TCR_OFFSET 0x000c /* RTC Time Compensation Register */
+#define KINETIS_RTC_CR_OFFSET 0x0010 /* RTC Control Register */
+#define KINETIS_RTC_SR_OFFSET 0x0014 /* RTC Status Register */
+#define KINETIS_RTC_LR_OFFSET 0x0018 /* RTC Lock Register */
+#ifdef KINETIS_K40
+# define KINETIS_RTC_IER_OFFSET 0x001c /* RTC Interrupt Enable Register (K40) */
+#endif
+#ifdef KINETIS_K60
+# define KINETIS_RTC_CCR_OFFSET 0x001c /* RTC Chip Configuration Register (K60) */
+#endif
+#define KINETIS_RTC_WAR_OFFSET 0x0800 /* RTC Write Access Register */
+#define KINETIS_RTC_RAR_OFFSET 0x0804 /* RTC Read Access Register */
/* Register Addresses ***************************************************************/
-#define KINETIS_RTC_TSR (KINETIS_RTC_BASE+KINETIS_RTC_TSR_OFFSET)
-#define KINETIS_RTC_TPR (KINETIS_RTC_BASE+KINETIS_RTC_TPR_OFFSET)
-#define KINETIS_RTC_TAR (KINETIS_RTC_BASE+KINETIS_RTC_TAR_OFFSET)
-#define KINETIS_RTC_TCR (KINETIS_RTC_BASE+KINETIS_RTC_TCR_OFFSET)
-#define KINETIS_RTC_CR (KINETIS_RTC_BASE+KINETIS_RTC_CR_OFFSET)
-#define KINETIS_RTC_SR (KINETIS_RTC_BASE+KINETIS_RTC_SR_OFFSET)
-#define KINETIS_RTC_LR (KINETIS_RTC_BASE+KINETIS_RTC_LR_OFFSET)
-#define KINETIS_RTC_IER (KINETIS_RTC_BASE+KINETIS_RTC_IER_OFFSET)
-#define KINETIS_RTC_WAR (KINETIS_RTC_BASE+KINETIS_RTC_WAR_OFFSET)
-#define KINETIS_RTC_RAR (KINETIS_RTC_BASE+KINETIS_RTC_RAR_OFFSET)
+#define KINETIS_RTC_TSR (KINETIS_RTC_BASE+KINETIS_RTC_TSR_OFFSET)
+#define KINETIS_RTC_TPR (KINETIS_RTC_BASE+KINETIS_RTC_TPR_OFFSET)
+#define KINETIS_RTC_TAR (KINETIS_RTC_BASE+KINETIS_RTC_TAR_OFFSET)
+#define KINETIS_RTC_TCR (KINETIS_RTC_BASE+KINETIS_RTC_TCR_OFFSET)
+#define KINETIS_RTC_CR (KINETIS_RTC_BASE+KINETIS_RTC_CR_OFFSET)
+#define KINETIS_RTC_SR (KINETIS_RTC_BASE+KINETIS_RTC_SR_OFFSET)
+#define KINETIS_RTC_LR (KINETIS_RTC_BASE+KINETIS_RTC_LR_OFFSET)
+#ifdef KINETIS_K40
+# define KINETIS_RTC_IER (KINETIS_RTC_BASE+KINETIS_RTC_IER_OFFSET)
+#endif
+#ifdef KINETIS_K60
+# define KINETIS_CCR_IER (KINETIS_RTC_BASE+KINETIS_RTC_CCR_OFFSET)
+#endif
+#define KINETIS_RTC_WAR (KINETIS_RTC_BASE+KINETIS_RTC_WAR_OFFSET)
+#define KINETIS_RTC_RAR (KINETIS_RTC_BASE+KINETIS_RTC_RAR_OFFSET)
/* Register Bit Definitions *********************************************************/
@@ -80,81 +90,104 @@
/* RTC Time Prescaler Register */
-#define RTC_TPR_SHIFT (0) /* Bits 0-15: Time Prescaler Register */
-#define RTC_TPR_MASK (0xffff << RTC_TPR_SHIFT)
- /* Bits 16-31: Reserved */
+#define RTC_TPR_SHIFT (0) /* Bits 0-15: Time Prescaler Register */
+#define RTC_TPR_MASK (0xffff << RTC_TPR_SHIFT)
+ /* Bits 16-31: Reserved */
/* RTC Time Alarm Register (32-bits of time alarm) */
/* RTC Time Compensation Register (32-bits) */
-#define RTC_TCR_TCR_SHIFT (0) /* Bits 0-7: Time Compensation Register */
-#define RTC_TCR_TCR_MASK (0xff << RTC_TCR_CIR_MASK)
-#define RTC_TCR_CIR_SHIFT (8) /* Bits 8-15: Compensation Interval Register */
-#define RTC_TCR_CIR_MASK (0xff << RTC_TCR_CIR_SHIFT)
-#define RTC_TCR_TCV_SHIFT (16) /* Bits 16-23: Time Compensation Value */
-#define RTC_TCR_TCV_MASK (0xff << RTC_TCR_TCV_SHIFT)
-#define RTC_TCR_CIC_SHIFT (24) /* Bits 24-31: Compensation Interval Counter */
-#define RTC_TCR_CIC_MASK (0xff << RTC_TCR_CIC_SHIFT)
+#define RTC_TCR_TCR_SHIFT (0) /* Bits 0-7: Time Compensation Register */
+#define RTC_TCR_TCR_MASK (0xff << RTC_TCR_CIR_MASK)
+#define RTC_TCR_CIR_SHIFT (8) /* Bits 8-15: Compensation Interval Register */
+#define RTC_TCR_CIR_MASK (0xff << RTC_TCR_CIR_SHIFT)
+#define RTC_TCR_TCV_SHIFT (16) /* Bits 16-23: Time Compensation Value */
+#define RTC_TCR_TCV_MASK (0xff << RTC_TCR_TCV_SHIFT)
+#define RTC_TCR_CIC_SHIFT (24) /* Bits 24-31: Compensation Interval Counter */
+#define RTC_TCR_CIC_MASK (0xff << RTC_TCR_CIC_SHIFT)
/* RTC Control Register (32-bits) */
-#define RTC_CR_SWR (1 << 0) /* Bit 0: Software Reset */
-#define RTC_CR_WPE (1 << 1) /* Bit 1: Wakeup Pin Enable */
-#define RTC_CR_SUP (1 << 2) /* Bit 2: Supervisor Access */
-#define RTC_CR_UM (1 << 3) /* Bit 3: Update Mode */
- /* Bits 4-7: Reserved */
-#define RTC_CR_OSCE (1 << 8) /* Bit 8: Oscillator Enable */
-#define RTC_CR_CLKO (1 << 9) /* Bit 9: Clock Output */
-#define RTC_CR_SC16P (1 << 10) /* Bit 10: Oscillator 16pF load configure */
-#define RTC_CR_SC8P (1 << 11) /* Bit 11: Oscillator 8pF load configure */
-#define RTC_CR_SC4P (1 << 12) /* Bit 12: Oscillator 4pF load configure */
-#define RTC_CR_SC2P (1 << 13) /* Bit 13: Oscillator 2pF load configure */
- /* Bits 14-31: Reserved */
+#define RTC_CR_SWR (1 << 0) /* Bit 0: Software Reset */
+#define RTC_CR_WPE (1 << 1) /* Bit 1: Wakeup Pin Enable */
+#define RTC_CR_SUP (1 << 2) /* Bit 2: Supervisor Access */
+#define RTC_CR_UM (1 << 3) /* Bit 3: Update Mode */
+ /* Bits 4-7: Reserved */
+#define RTC_CR_OSCE (1 << 8) /* Bit 8: Oscillator Enable */
+#define RTC_CR_CLKO (1 << 9) /* Bit 9: Clock Output */
+#define RTC_CR_SC16P (1 << 10) /* Bit 10: Oscillator 16pF load configure */
+#define RTC_CR_SC8P (1 << 11) /* Bit 11: Oscillator 8pF load configure */
+#define RTC_CR_SC4P (1 << 12) /* Bit 12: Oscillator 4pF load configure */
+#define RTC_CR_SC2P (1 << 13) /* Bit 13: Oscillator 2pF load configure */
+ /* Bits 14-31: Reserved */
/* RTC Status Register (32-bits) */
-#define RTC_SR_TIF (1 << 0) /* Bit 0: Time Invalid Flag */
-#define RTC_SR_TOF (1 << 1) /* Bit 1: Time Overflow Flag */
- /* Bit 3: Reserved */
-#define RTC_SR_TAF (1 << 2) /* Bit 2: Time Alarm Flag */
-#define RTC_SR_TCE (1 << 4) /* Bit 4: Time Counter Enable */
- /* Bits 5-31: Reserved */
+#define RTC_SR_TIF (1 << 0) /* Bit 0: Time Invalid Flag */
+#define RTC_SR_TOF (1 << 1) /* Bit 1: Time Overflow Flag */
+ /* Bit 3: Reserved */
+#define RTC_SR_TAF (1 << 2) /* Bit 2: Time Alarm Flag */
+#define RTC_SR_TCE (1 << 4) /* Bit 4: Time Counter Enable */
+ /* Bits 5-31: Reserved */
/* RTC Lock Register (32-bits) */
- /* Bits 0-2: Reserved */
-#define RTC_LR_TCL (1 << 3) /* Bit 3: Time Compensation Lock */
-#define RTC_LR_CRL (1 << 4) /* Bit 4: Control Register Lock */
-#define RTC_LR_SRL (1 << 5) /* Bit 5: Status Register Lock */
-#define RTC_LR_LRL (1 << 6) /* Bit 6: Lock Register Lock */
- /* Bits 7-31: Reserved */
-/* RTC Interrupt Enable Register (32-bits) */
-
-#define RTC_IER_TIIE (1 << 0) /* Bit 0: Time Invalid Interrupt Enable */
-#define RTC_IER_TOIE (1 << 1) /* Bit 1: Time Overflow Interrupt Enable */
-#define RTC_IER_TAIE (1 << 2) /* Bit 2: Time Alarm Interrupt Enable */
- /* Bit 3: Reserved */
-#define RTC_IER_TSIE (1 << 4) /* Bit 4: Time Seconds Interrupt Enable */
- /* Bits 5-31: Reserved */
+ /* Bits 0-2: Reserved */
+#define RTC_LR_TCL (1 << 3) /* Bit 3: Time Compensation Lock */
+#define RTC_LR_CRL (1 << 4) /* Bit 4: Control Register Lock */
+#define RTC_LR_SRL (1 << 5) /* Bit 5: Status Register Lock */
+#ifdef KINETIS_K40
+# define RTC_LR_LRL (1 << 6) /* Bit 6: Lock Register Lock (K40) */
+#endif
+ /* Bits 7-31: Reserved */
+/* RTC Interrupt Enable Register (32-bits, K40) */
+
+#ifdef KINETIS_K40
+# define RTC_IER_TIIE (1 << 0) /* Bit 0: Time Invalid Interrupt Enable */
+# define RTC_IER_TOIE (1 << 1) /* Bit 1: Time Overflow Interrupt Enable */
+# define RTC_IER_TAIE (1 << 2) /* Bit 2: Time Alarm Interrupt Enable */
+ /* Bit 3: Reserved */
+# define RTC_IER_TSIE (1 << 4) /* Bit 4: Time Seconds Interrupt Enable */
+ /* Bits 5-31: Reserved */
+#endif
+
+/* RTC Chip Configuration Register (32-bits,K60) */
+
+#ifdef KINETIS_K60
+# define RTC_CCR_CONFIG_SHIFT (0) /* Bits 0-7: Chip Configuration */
+# define RTC_CCR_CONFIG_MASK (0xff << RTC_CCR_CONFIG_SHIFT)
+ /* Bits 8-31: Reserved */
+#endif
+
/* RTC Write Access Register (32-bits) */
-#define RTC_WAR_TSRW (1 << 0) /* Bit 0: Time Seconds Register Write */
-#define RTC_WAR_TPRW (1 << 1) /* Bit 1: Time Prescaler Register Write */
-#define RTC_WAR_TARW (1 << 2) /* Bit 2: Time Alarm Register Write */
-#define RTC_WAR_TCRW (1 << 3) /* Bit 3: Time Compensation Register Write */
-#define RTC_WAR_CRW (1 << 4) /* Bit 4: Control Register Write */
-#define RTC_WAR_SRW (1 << 5) /* Bit 5: Status Register Write */
-#define RTC_WAR_LRW (1 << 6) /* Bit 6: Lock Register Write */
-#define RTC_WAR_IERW (1 << 7) /* Bit 7: Interrupt Enable Register Write */
- /* Bits 8-31: Reserved */
+#define RTC_WAR_TSRW (1 << 0) /* Bit 0: Time Seconds Register Write */
+#define RTC_WAR_TPRW (1 << 1) /* Bit 1: Time Prescaler Register Write */
+#define RTC_WAR_TARW (1 << 2) /* Bit 2: Time Alarm Register Write */
+#define RTC_WAR_TCRW (1 << 3) /* Bit 3: Time Compensation Register Write */
+#define RTC_WAR_CRW (1 << 4) /* Bit 4: Control Register Write */
+#define RTC_WAR_SRW (1 << 5) /* Bit 5: Status Register Write */
+#define RTC_WAR_LRW (1 << 6) /* Bit 6: Lock Register Write */
+#ifdef KINETIS_K40
+# define RTC_WAR_IERW (1 << 7) /* Bit 7: Interrupt Enable Register Write */
+#endif
+#ifdef KINETIS_K60
+# define RTC_WAR_CCRW (1 << 7) /* Bit 7: Chip Config Register Write */
+#endif
+ /* Bits 8-31: Reserved */
/* RTC Read Access Register */
-#define RTC_RAR_TSRR (1 << 0) /* Bit 0: Time Seconds Register Read */
-#define RTC_RAR_TPRR (1 << 1) /* Bit 1: Time Prescaler Register Read */
-#define RTC_RAR_TARR (1 << 2) /* Bit 2: Time Alarm Register Read */
-#define RTC_RAR_TCRR (1 << 3) /* Bit 3: Time Compensation Register Read */
-#define RTC_RAR_CRR (1 << 4) /* Bit 4: Control Register Read */
-#define RTC_RAR_SRR (1 << 5) /* Bit 5: Status Register Read */
-#define RTC_RAR_LRR (1 << 6) /* Bit 6: Lock Register Read */
-#define RTC_RAR_IERR (1 << 7) /* Bit 7: Interrupt Enable Register Read */
- /* Bits 8-31: Reserved */
+#define RTC_RAR_TSRR (1 << 0) /* Bit 0: Time Seconds Register Read */
+#define RTC_RAR_TPRR (1 << 1) /* Bit 1: Time Prescaler Register Read */
+#define RTC_RAR_TARR (1 << 2) /* Bit 2: Time Alarm Register Read */
+#define RTC_RAR_TCRR (1 << 3) /* Bit 3: Time Compensation Register Read */
+#define RTC_RAR_CRR (1 << 4) /* Bit 4: Control Register Read */
+#define RTC_RAR_SRR (1 << 5) /* Bit 5: Status Register Read */
+#define RTC_RAR_LRR (1 << 6) /* Bit 6: Lock Register Read */
+#ifdef KINETIS_K40
+# define RTC_RAR_IERR (1 << 7) /* Bit 7: Interrupt Enable Register Read */
+#endif
+#ifdef KINETIS_K60
+# define RTC_RAR_CCRR (1 << 7) /* Bit 7: Chip Config Register Read */
+#endif
+ /* Bits 8-31: Reserved */
/************************************************************************************
* Public Types