summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-06-06 17:39:39 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-06-06 17:39:39 +0200
commitf42a335d690257ffb9daf310c7782c601c12935a (patch)
treec86a5b67e4676dc77b7daba6a224170cf4b96693 /nuttx/arch
parent39fab7664fe6bbbff78d01f291b05957666f3ffc (diff)
parent303cf6c26e2f96c1909ca977b8ce86b0b761b444 (diff)
downloadpx4-nuttx-f42a335d690257ffb9daf310c7782c601c12935a.tar.gz
px4-nuttx-f42a335d690257ffb9daf310c7782c601c12935a.tar.bz2
px4-nuttx-f42a335d690257ffb9daf310c7782c601c12935a.zip
Merge branch 'master' of http://git.code.sf.net/p/nuttx/git into integration
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/src/sam34/Kconfig5
-rw-r--r--nuttx/arch/arm/src/sam34/Make.defs9
-rw-r--r--nuttx/arch/arm/src/sam34/chip/sam3u_eefc.h (renamed from nuttx/arch/arm/src/sam34/chip/sam_eefc.h)8
-rw-r--r--nuttx/arch/arm/src/sam34/chip/sam3u_supc.h (renamed from nuttx/arch/arm/src/sam34/chip/sam_supc.h)8
-rw-r--r--nuttx/arch/arm/src/sam34/chip/sam4l_flashcalw.h349
-rw-r--r--nuttx/arch/arm/src/sam34/chip/sam4l_gpio.h500
-rw-r--r--nuttx/arch/arm/src/sam34/chip/sam4l_memorymap.h2
-rw-r--r--nuttx/arch/arm/src/sam34/chip/sam4l_pm.h351
-rw-r--r--nuttx/arch/arm/src/sam34/sam3u_clockconfig.c (renamed from nuttx/arch/arm/src/sam34/sam_clockconfig.c)7
-rw-r--r--nuttx/arch/arm/src/sam34/sam4l_clockconfig.c571
-rw-r--r--nuttx/arch/arm/src/sam34/sam4l_gpio.c18
-rw-r--r--nuttx/arch/arm/src/sam34/sam4l_periphclks.c272
-rw-r--r--nuttx/arch/arm/src/sam34/sam4l_periphclks.h349
-rw-r--r--nuttx/arch/arm/src/sam34/sam_clockconfig.h7
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_flashc.h4
15 files changed, 2319 insertions, 141 deletions
diff --git a/nuttx/arch/arm/src/sam34/Kconfig b/nuttx/arch/arm/src/sam34/Kconfig
index 3991798a7..b26dec659 100644
--- a/nuttx/arch/arm/src/sam34/Kconfig
+++ b/nuttx/arch/arm/src/sam34/Kconfig
@@ -141,6 +141,11 @@ config ARCH_CHIP_SAM4S
menu "AT91SAM3 Peripheral Support"
+config SAM_PICOCACHE
+ bool "PICOCACHE"
+ depends on ARCH_CHIP_SAM4L
+ default y
+
config SAM34_DMA
bool "DMA"
default n
diff --git a/nuttx/arch/arm/src/sam34/Make.defs b/nuttx/arch/arm/src/sam34/Make.defs
index 683751bb5..6f192960f 100644
--- a/nuttx/arch/arm/src/sam34/Make.defs
+++ b/nuttx/arch/arm/src/sam34/Make.defs
@@ -77,16 +77,15 @@ endif
# Required SAM3/4 files
CHIP_ASRCS =
-CHIP_CSRCS = sam_allocateheap.c sam_clockconfig.c sam_gpioirq.c
-CHIP_CSRCS += sam_irq.c sam_lowputc.c sam_serial.c sam_start.c
-CHIP_CSRCS += sam_timerisr.c
+CHIP_CSRCS = sam_allocateheap.c sam_gpioirq.c sam_irq.c sam_lowputc.c
+CHIP_CSRCS += sam_serial.c sam_start.c sam_timerisr.c
# Configuration-dependent SAM3/4 files
ifeq ($(CONFIG_ARCH_CHIP_SAM4L),y)
-CHIP_CSRCS += sam4l_gpio.c
+CHIP_CSRCS += sam4l_clockconfig.c sam4l_periphclks.c sam4l_gpio.c
else
-CHIP_CSRCS += sam3u_gpio.c
+CHIP_CSRCS += sam3u_clockconfig.c sam3u_gpio.c
endif
ifeq ($(CONFIG_NUTTX_KERNEL),y)
diff --git a/nuttx/arch/arm/src/sam34/chip/sam_eefc.h b/nuttx/arch/arm/src/sam34/chip/sam3u_eefc.h
index 546b6334c..05ffad19b 100644
--- a/nuttx/arch/arm/src/sam34/chip/sam_eefc.h
+++ b/nuttx/arch/arm/src/sam34/chip/sam3u_eefc.h
@@ -1,5 +1,5 @@
/****************************************************************************************
- * arch/arm/src/sam34/chip/sam_eefc.h
+ * arch/arm/src/sam34/chip/sam3u_eefc.h
*
* Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -33,8 +33,8 @@
*
****************************************************************************************/
-#ifndef __ARCH_ARM_SRC_SAM34_CHIP_SAM_EEFC_H
-#define __ARCH_ARM_SRC_SAM34_CHIP_SAM_EEFC_H
+#ifndef __ARCH_ARM_SRC_SAM34_CHIP_SAM3U_EEFC_H
+#define __ARCH_ARM_SRC_SAM34_CHIP_SAM3U_EEFC_H
/****************************************************************************************
* Included Files
@@ -117,4 +117,4 @@
* Public Functions
****************************************************************************************/
-#endif /* __ARCH_ARM_SRC_SAM34_CHIP_SAM_EEFC_H */
+#endif /* __ARCH_ARM_SRC_SAM34_CHIP_SAM3U_EEFC_H */
diff --git a/nuttx/arch/arm/src/sam34/chip/sam_supc.h b/nuttx/arch/arm/src/sam34/chip/sam3u_supc.h
index 1be920d0d..88f9452d8 100644
--- a/nuttx/arch/arm/src/sam34/chip/sam_supc.h
+++ b/nuttx/arch/arm/src/sam34/chip/sam3u_supc.h
@@ -1,5 +1,5 @@
/****************************************************************************************
- * arch/arm/src/sam34/chip/sam_supc.h
+ * arch/arm/src/sam34/chip/sam3u_supc.h
*
* Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -33,8 +33,8 @@
*
****************************************************************************************/
-#ifndef __ARCH_ARM_SRC_SAM34_CHIP_SAM_SUPC_H
-#define __ARCH_ARM_SRC_SAM34_CHIP_SAM_SUPC_H
+#ifndef __ARCH_ARM_SRC_SAM34_CHIP_SAM3U_SUPC_H
+#define __ARCH_ARM_SRC_SAM34_CHIP_SAM3U_SUPC_H
/****************************************************************************************
* Included Files
@@ -161,4 +161,4 @@
* Public Functions
****************************************************************************************/
-#endif /* __ARCH_ARM_SRC_SAM34_CHIP_SAM_SUPC_H */
+#endif /* __ARCH_ARM_SRC_SAM34_CHIP_SAM3U_SUPC_H */
diff --git a/nuttx/arch/arm/src/sam34/chip/sam4l_flashcalw.h b/nuttx/arch/arm/src/sam34/chip/sam4l_flashcalw.h
new file mode 100644
index 000000000..d2503aa18
--- /dev/null
+++ b/nuttx/arch/arm/src/sam34/chip/sam4l_flashcalw.h
@@ -0,0 +1,349 @@
+/************************************************************************************
+ * arch/avr/src/sam34/sam4l_flashcalw.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * This file is derived from nuttx/arch/avr/src/at32uc3/at32uc3_flashc.h.
+ *
+ * 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_SAM34_CHIP_SAM4L_FLASHCALW_H
+#define __ARCH_ARM_SRC_SAM34_CHIP_SAM4L_FLASHCALW_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/sam_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+/* Relative to SAM_FLASHCALW_BASE */
+
+#define SAM_FLASHCALW_FCR_OFFSET 0x0000 /* Flash Control Register */
+#define SAM_FLASHCALW_FCMD_OFFSET 0x0004 /* Flash Command Register */
+#define SAM_FLASHCALW_FSR_OFFSET 0x0008 /* Flash Status Register */
+#define SAM_FLASHCALW_FPR_OFFSET 0x000c /* Flash Parameter Register */
+#define SAM_FLASHCALW_FVR_OFFSET 0x0010 /* Flash Version Register */
+#define SAM_FLASHCALW_FGPFRHI_OFFSET 0x0014 /* Flash General Purpose Fuse Register Hi */
+#define SAM_FLASHCALW_FGPFRLO_OFFSET 0x0018 /* Flash General Purpose Fuse Register Lo */
+
+/* Relative to SAM_PICOCACHE_BASE */
+
+#define SAM_PICOCACHE_CTRL_OFFSET 0x0008 /* PicoCache Control Register */
+#define SAM_PICOCACHE_SR_OFFSET 0x000c /* PicoCache Status Register */
+#define SAM_PICOCACHE_MAINT0_OFFSET 0x0020 /* PicoCache Maintenance Register 0 */
+#define SAM_PICOCACHE_MAINT1_OFFSET 0x0024 /* PicoCache Maintenance Register 1 */
+#define SAM_PICOCACHE_MCFG_OFFSET 0x0028 /* PicoCache Monitor Configuration Register */
+#define SAM_PICOCACHE_MEN_OFFSET 0x002c /* PicoCache Monitor Enable Register */
+#define SAM_PICOCACHE_MCTRL_OFFSET 0x0030 /* PicoCache Monitor Control Register */
+#define SAM_PICOCACHE_MSR_OFFSET 0x0034 /* PicoCache Monitor Status Register */
+#define SAM_PICOCACHE_PVR_OFFSET 0x00fc /* Version Register */
+
+/* Register Addresses ***************************************************************/
+
+#define SAM_FLASHCALW_FCR (SAM_FLASHCALW_BASE+SAM_FLASHCALW_FCR_OFFSET)
+#define SAM_FLASHCALW_FCMD (SAM_FLASHCALW_BASE+SAM_FLASHCALW_FCMD_OFFSET)
+#define SAM_FLASHCALW_FSR (SAM_FLASHCALW_BASE+SAM_FLASHCALW_FSR_OFFSET)
+#define SAM_FLASHCALW_FPR (SAM_FLASHCALW_BASE+SAM_FLASHCALW_FPR_OFFSET)
+#define SAM_FLASHCALW_FSR (SAM_FLASHCALW_BASE+SAM_FLASHCALW_FSR_OFFSET)
+#define SAM_FLASHCALW_FGPFRHI (SAM_FLASHCALW_BASE+SAM_FLASHCALW_FGPFRHI_OFFSET)
+#define SAM_FLASHCALW_FGPFRLO (SAM_FLASHCALW_BASE+SAM_FLASHCALW_FGPFRLO_OFFSET)
+
+#define SAM_PICOCACHE_CTRL (SAM_PICOCACHE_BASE+SAM_PICOCACHE_CTRL_OFFSET)
+#define SAM_PICOCACHE_SR (SAM_PICOCACHE_BASE+SAM_PICOCACHE_SR_OFFSET)
+#define SAM_PICOCACHE_MAINT0 (SAM_PICOCACHE_BASE+SAM_PICOCACHE_MAINT0_OFFSET)
+#define SAM_PICOCACHE_MAINT1 (SAM_PICOCACHE_BASE+SAM_PICOCACHE_MAINT1_OFFSET)
+#define SAM_PICOCACHE_MCFG (SAM_PICOCACHE_BASE+SAM_PICOCACHE_MCFG_OFFSET)
+#define SAM_PICOCACHE_MEN (SAM_PICOCACHE_BASE+SAM_PICOCACHE_MEN_OFFSET)
+#define SAM_PICOCACHE_MCTRL (SAM_PICOCACHE_BASE+SAM_PICOCACHE_MCTRL_OFFSET)
+#define SAM_PICOCACHE_MSR (SAM_PICOCACHE_BASE+SAM_PICOCACHE_MSR_OFFSET)
+#define SAM_PICOCACHE_PVR (SAM_PICOCACHE_BASE+SAM_PICOCACHE_PVR_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Flash Control Register */
+
+#define FLASHCALW_FCR_FRDY (1 << 0) /* Bit 0: Flash Ready Interrupt Enable */
+#define FLASHCALW_FCR_LOCKE (1 << 2) /* Bit 2: Lock Error Interrupt Enable */
+#define FLASHCALW_FCR_PROGE (1 << 3) /* Bit 3: Programming Error Interrupt Enable */
+#define FLASHCALW_FCR_ECCE (1 << 4) /* Bit 4: ECC Error Interrupt Enable */
+#define FLASHCALW_FCR_FWS (1 << 6) /* Bit 6: Flash Wait State */
+#define FLASHCALW_FCR_WS1OPT (1 << 7) /* Bit 7: Wait State 1 Optimization */
+
+/* Flash Command Register */
+
+#define FLASHCALW_FCMD_CMD_SHIFT (0) /* Bits 0-5: Command */
+#define FLASHCALW_FCMD_CMD_MASK (0x3f << FLASHCALW_FCMD_CMD_SHIFT)
+# define FLASHCALW_FCMD_CMD_NOP (0 << FLASHCALW_FCMD_CMD_SHIFT) /* No operation */
+# define FLASHCALW_FCMD_CMD_WP (1 << FLASHCALW_FCMD_CMD_SHIFT) /* Write Page */
+# define FLASHCALW_FCMD_CMD_EP (2 << FLASHCALW_FCMD_CMD_SHIFT) /* Erase Page */
+# define FLASHCALW_FCMD_CMD_CPB (3 << FLASHCALW_FCMD_CMD_SHIFT) /* Clear Page Buffer */
+# define FLASHCALW_FCMD_CMD_LP (4 << FLASHCALW_FCMD_CMD_SHIFT) /* Lock region containing given Page */
+# define FLASHCALW_FCMD_CMD_UP (5 << FLASHCALW_FCMD_CMD_SHIFT) /* Unlock region containing given Page */
+# define FLASHCALW_FCMD_CMD_EA (6 << FLASHCALW_FCMD_CMD_SHIFT) /* Erase All */
+# define FLASHCALW_FCMD_CMD_WGPB (7 << FLASHCALW_FCMD_CMD_SHIFT) /* Write General-Purpose Fuse Bit */
+# define FLASHCALW_FCMD_CMD_EGPB (8 << FLASHCALW_FCMD_CMD_SHIFT) /* Erase General-Purpose Fuse Bit */
+# define FLASHCALW_FCMD_CMD_SSB (9 << FLASHCALW_FCMD_CMD_SHIFT) /* Set Security Fuses */
+# define FLASHCALW_FCMD_CMD_PGPFB (10 << FLASHCALW_FCMD_CMD_SHIFT) /* Program GP Fuse Byte */
+# define FLASHCALW_FCMD_CMD_EAGPF (11 << FLASHCALW_FCMD_CMD_SHIFT) /* Erase All GPFuses */
+# define FLASHCALW_FCMD_CMD_QPR (12 << FLASHCALW_FCMD_CMD_SHIFT) /* Quick Page Read */
+# define FLASHCALW_FCMD_CMD_WUP (13 << FLASHCALW_FCMD_CMD_SHIFT) /* Write User Page */
+# define FLASHCALW_FCMD_CMD_EUP (14 << FLASHCALW_FCMD_CMD_SHIFT) /* Erase User Page */
+# define FLASHCALW_FCMD_CMD_QPRUP (15 << FLASHCALW_FCMD_CMD_SHIFT) /* Quick Page Read User Page */
+# define FLASHCALW_FCMD_CMD_HSEN (16 << FLASHCALW_FCMD_CMD_SHIFT) /* High Speed Mode Enable */
+# define FLASHCALW_FCMD_CMD_HSDIS (17 << FLASHCALW_FCMD_CMD_SHIFT) /* High Speed Mode Disable */
+#define FLASHCALW_FCMD_PAGEN_SHIFT (8) /* Bits 8-23: Page number */
+#define FLASHCALW_FCMD_PAGEN_MASK (0xffff << FLASHCALW_FCMD_PAGEN_SHIFT)
+#define FLASHCALW_FCMD_KEY_SHIFT (14) /* Bits 24-31: Write protection key */
+#define FLASHCALW_FCMD_KEY_MASK (0xff << FLASHCALW_FCMD_KEY_SHIFT)
+
+/* Flash Status Register */
+
+#define FLASHCALW_FSR_FRDY (1 << 0) /* Bit 0: Flash Ready Status */
+#define FLASHCALW_FSR_LOCKE (1 << 2) /* Bit 2: Lock Error Status */
+#define FLASHCALW_FSR_PROGE (1 << 3) /* Bit 3: Programming Error Status */
+#define FLASHCALW_FSR_SECURITY (1 << 4) /* Bit 4: Security Bit Status */
+#define FLASHCALW_FSR_QPRR (1 << 5) /* Bit 5: Quick Page Read Result */
+#define FLASHCALW_FSR_HSMODE (1 << 6) /* Bit 6: High-Speed Mode */
+#define FLASHCALW_FSR_ECCERR_SHIFT (8) /* Bits 8-0: ECC Error Status */
+#define FLASHCALW_FSR_ECCERR_MASK (3 << FLASHCALW_FSR_ECCERR_SHIFT)
+#define FLASHCALW_FSR_LOCK(n) (1 << ((n)+16)
+#define FLASHCALW_FSR_LOCK0 (1 << 16) /* Bit 16: Lock Region 0 Lock Status */
+#define FLASHCALW_FSR_LOCK1 (1 << 17) /* Bit 17: Lock Region 1 Lock Status */
+#define FLASHCALW_FSR_LOCK2 (1 << 18) /* Bit 18: Lock Region 2 Lock Status */
+#define FLASHCALW_FSR_LOCK3 (1 << 19) /* Bit 19: Lock Region 3 Lock Status */
+#define FLASHCALW_FSR_LOCK4 (1 << 20) /* Bit 20: Lock Region 4 Lock Status */
+#define FLASHCALW_FSR_LOCK5 (1 << 21) /* Bit 21: Lock Region 5 Lock Status */
+#define FLASHCALW_FSR_LOCK6 (1 << 22) /* Bit 22: Lock Region 6 Lock Status */
+#define FLASHCALW_FSR_LOCK7 (1 << 23) /* Bit 23: Lock Region 7 Lock Status */
+#define FLASHCALW_FSR_LOCK8 (1 << 24) /* Bit 24: Lock Region 8 Lock Status */
+#define FLASHCALW_FSR_LOCK9 (1 << 25) /* Bit 25: Lock Region 9 Lock Status */
+#define FLASHCALW_FSR_LOCK10 (1 << 26) /* Bit 26: Lock Region 10 Lock Status */
+#define FLASHCALW_FSR_LOCK11 (1 << 27) /* Bit 27: Lock Region 11 Lock Status */
+#define FLASHCALW_FSR_LOCK12 (1 << 28) /* Bit 28: Lock Region 12 Lock Status */
+#define FLASHCALW_FSR_LOCK13 (1 << 29) /* Bit 29: Lock Region 13 Lock Status */
+#define FLASHCALW_FSR_LOCK14 (1 << 30) /* Bit 30: Lock Region 14 Lock Status */
+#define FLASHCALW_FSR_LOCK15 (1 << 31) /* Bit 31: Lock Region 15 Lock Status */
+
+/* Flash Parameter Register */
+#define FLASHCALW_FPR_
+
+#define FLASHCALW_FPR_FSZ_SHIFT (0) /* Bits 0-3: Flash Size */
+#define FLASHCALW_FPR_FSZ_MASK (15 << FLASHCALW_FPR_FSZ_SHIFT)
+# define FLASHCALW_FPR_FSZ_4KB (0 << FLASHCALW_FPR_FSZ_SHIFT) /* 4 Kbytes */
+# define FLASHCALW_FPR_FSZ_8KB (1 << FLASHCALW_FPR_FSZ_SHIFT) /* 8 Kbytes */
+# define FLASHCALW_FPR_FSZ_16KB (2 << FLASHCALW_FPR_FSZ_SHIFT) /* 16 Kbytes */
+# define FLASHCALW_FPR_FSZ_32KB (3 << FLASHCALW_FPR_FSZ_SHIFT) /* 32 Kbytes */
+# define FLASHCALW_FPR_FSZ_48KB (4 << FLASHCALW_FPR_FSZ_SHIFT) /* 48 Kbytes */
+# define FLASHCALW_FPR_FSZ_64KB (5 << FLASHCALW_FPR_FSZ_SHIFT) /* 64 Kbytes */
+# define FLASHCALW_FPR_FSZ_96KB (6 << FLASHCALW_FPR_FSZ_SHIFT) /* 96 Kbytes */
+# define FLASHCALW_FPR_FSZ_128KB (7 << FLASHCALW_FPR_FSZ_SHIFT) /* 128 Kbytes */
+# define FLASHCALW_FPR_FSZ_192KB (8 << FLASHCALW_FPR_FSZ_SHIFT) /* 192 Kbytes */
+# define FLASHCALW_FPR_FSZ_256KB (9 << FLASHCALW_FPR_FSZ_SHIFT) /* 256 Kbytes */
+# define FLASHCALW_FPR_FSZ_384KB (10 << FLASHCALW_FPR_FSZ_SHIFT) /* 384 Kbytes */
+# define FLASHCALW_FPR_FSZ_512KB (11 << FLASHCALW_FPR_FSZ_SHIFT) /* 512 Kbytes */
+# define FLASHCALW_FPR_FSZ_768KB (12 << FLASHCALW_FPR_FSZ_SHIFT) /* 768 Kbytes */
+# define FLASHCALW_FPR_FSZ_1MB (13 << FLASHCALW_FPR_FSZ_SHIFT) /* 1024 Kbytes */
+# define FLASHCALW_FPR_FSZ_2MB (14 << FLASHCALW_FPR_FSZ_SHIFT) /* 2048 Kbytes */
+#define FLASHCALW_FPR_PSZ_SHIFT (8) /* Bits 8-9: Page Size */
+#define FLASHCALW_FPR_PSZ_MASK (7 << FLASHCALW_FPR_PSZ_SHIFT)
+# define FLASHCALW_FPR_PSZ_32KB (0 << FLASHCALW_FPR_PSZ_SHIFT) /* 32 Kbytes */
+# define FLASHCALW_FPR_PSZ_64KB (1 << FLASHCALW_FPR_PSZ_SHIFT) /* 64 Kbytes */
+# define FLASHCALW_FPR_PSZ_128KB (2 << FLASHCALW_FPR_PSZ_SHIFT) /* 128 Kbytes */
+# define FLASHCALW_FPR_PSZ_256KB (3 << FLASHCALW_FPR_PSZ_SHIFT) /* 256 Kbytes */
+# define FLASHCALW_FPR_PSZ_512KGB (4 << FLASHCALW_FPR_PSZ_SHIFT) /* 512 Kbytes */
+# define FLASHCALW_FPR_PSZ_1MB (5 << FLASHCALW_FPR_PSZ_SHIFT) /* 1024 Kbytes */
+# define FLASHCALW_FPR_PSZ_2MB (6 << FLASHCALW_FPR_PSZ_SHIFT) /* 2048 Kbytes */
+# define FLASHCALW_FPR_PSZ_4MB (7 << FLASHCALW_FPR_PSZ_SHIFT) /* 4096 Kbytes */
+
+/* Flash Version Register */
+
+#define FLASHCALW_FVR_VERSION_SHIFT (0) /* Bits 0-11: Version Number */
+#define FLASHCALW_FVR_VERSION_MASK (0xfff << FLASHCALW_FVR_VERSION_SHIFT)
+#define FLASHCALW_FVR_VARIANT_SHIFT (16) /* Bits 16-19: Variant Number */
+#define FLASHCALW_FVR_VARIANT_MASK (15 << FLASHCALW_FVR_VARIANT_SHIFT)
+
+/* Flash General Purpose Fuse Register Hi */
+
+#define FLASHCALW_FGPFRHI(n) (1 << ((n)-32))
+#define FLASHCALW_FGPFRHI32 (1 << 0) /* Bit 0: General Purpose Fuse 32 */
+#define FLASHCALW_FGPFRHI33 (1 << 1) /* Bit 1: General Purpose Fuse 33 */
+#define FLASHCALW_FGPFRHI34 (1 << 2) /* Bit 2: General Purpose Fuse 34 */
+#define FLASHCALW_FGPFRHI35 (1 << 3) /* Bit 3: General Purpose Fuse 35 */
+#define FLASHCALW_FGPFRHI36 (1 << 4) /* Bit 4: General Purpose Fuse 36 */
+#define FLASHCALW_FGPFRHI37 (1 << 5) /* Bit 5: General Purpose Fuse 37 */
+#define FLASHCALW_FGPFRHI38 (1 << 6) /* Bit 6: General Purpose Fuse 38 */
+#define FLASHCALW_FGPFRHI39 (1 << 7) /* Bit 7: General Purpose Fuse 39 */
+#define FLASHCALW_FGPFRHI40 (1 << 8) /* Bit 8: General Purpose Fuse 40 */
+#define FLASHCALW_FGPFRHI41 (1 << 9) /* Bit 9: General Purpose Fuse 41 */
+#define FLASHCALW_FGPFRHI42 (1 << 10) /* Bit 10: General Purpose Fuse 42 */
+#define FLASHCALW_FGPFRHI43 (1 << 11) /* Bit 11: General Purpose Fuse 43 */
+#define FLASHCALW_FGPFRHI44 (1 << 12) /* Bit 12: General Purpose Fuse 44 */
+#define FLASHCALW_FGPFRHI45 (1 << 13) /* Bit 13: General Purpose Fuse 45 */
+#define FLASHCALW_FGPFRHI46 (1 << 14) /* Bit 14: General Purpose Fuse 46 */
+#define FLASHCALW_FGPFRHI47 (1 << 15) /* Bit 15: General Purpose Fuse 47 */
+#define FLASHCALW_FGPFRHI48 (1 << 16) /* Bit 16: General Purpose Fuse 48 */
+#define FLASHCALW_FGPFRHI49 (1 << 17) /* Bit 17: General Purpose Fuse 49 */
+#define FLASHCALW_FGPFRHI50 (1 << 18) /* Bit 18: General Purpose Fuse 50 */
+#define FLASHCALW_FGPFRHI51 (1 << 19) /* Bit 19: General Purpose Fuse 51 */
+#define FLASHCALW_FGPFRHI52 (1 << 20) /* Bit 20: General Purpose Fuse 52 */
+#define FLASHCALW_FGPFRHI53 (1 << 21) /* Bit 21: General Purpose Fuse 53 */
+#define FLASHCALW_FGPFRHI54 (1 << 22) /* Bit 22: General Purpose Fuse 54 */
+#define FLASHCALW_FGPFRHI55 (1 << 23) /* Bit 23: General Purpose Fuse 55 */
+#define FLASHCALW_FGPFRHI56 (1 << 24) /* Bit 24: General Purpose Fuse 56 */
+#define FLASHCALW_FGPFRHI57 (1 << 25) /* Bit 25: General Purpose Fuse 57 */
+#define FLASHCALW_FGPFRHI58 (1 << 26) /* Bit 26: General Purpose Fuse 58 */
+#define FLASHCALW_FGPFRHI59 (1 << 27) /* Bit 27: General Purpose Fuse 59 */
+#define FLASHCALW_FGPFRHI60 (1 << 28) /* Bit 28: General Purpose Fuse 60 */
+#define FLASHCALW_FGPFRHI61 (1 << 29) /* Bit 29: General Purpose Fuse 61 */
+#define FLASHCALW_FGPFRHI62 (1 << 30) /* Bit 30: General Purpose Fuse 62 */
+#define FLASHCALW_FGPFRHI63 (1 << 31) /* Bit 31: General Purpose Fuse 63 */
+
+/* Flash General Purpose Fuse Register Lo */
+
+#define FLASHCALW_FGPFRLO(n) (1 << (n))
+#define FLASHCALW_FGPFRLO00 (1 << 0) /* Bit 0: General Purpose Fuse 00 */
+#define FLASHCALW_FGPFRLO01 (1 << 1) /* Bit 1: General Purpose Fuse 01 */
+#define FLASHCALW_FGPFRLO02 (1 << 2) /* Bit 2: General Purpose Fuse 02 */
+#define FLASHCALW_FGPFRLO03 (1 << 3) /* Bit 3: General Purpose Fuse 03 */
+#define FLASHCALW_FGPFRLO04 (1 << 4) /* Bit 4: General Purpose Fuse 04 */
+#define FLASHCALW_FGPFRLO05 (1 << 5) /* Bit 5: General Purpose Fuse 05 */
+#define FLASHCALW_FGPFRLO06 (1 << 6) /* Bit 6: General Purpose Fuse 06 */
+#define FLASHCALW_FGPFRLO07 (1 << 7) /* Bit 7: General Purpose Fuse 07 */
+#define FLASHCALW_FGPFRLO08 (1 << 8) /* Bit 8: General Purpose Fuse 08 */
+#define FLASHCALW_FGPFRLO09 (1 << 9) /* Bit 9: General Purpose Fuse 09 */
+#define FLASHCALW_FGPFRLO10 (1 << 10) /* Bit 10: General Purpose Fuse 10 */
+#define FLASHCALW_FGPFRLO11 (1 << 11) /* Bit 11: General Purpose Fuse 11 */
+#define FLASHCALW_FGPFRLO12 (1 << 12) /* Bit 12: General Purpose Fuse 12 */
+#define FLASHCALW_FGPFRLO13 (1 << 13) /* Bit 13: General Purpose Fuse 13 */
+#define FLASHCALW_FGPFRLO14 (1 << 14) /* Bit 14: General Purpose Fuse 14 */
+#define FLASHCALW_FGPFRLO15 (1 << 15) /* Bit 15: General Purpose Fuse 15 */
+#define FLASHCALW_FGPFRLO16 (1 << 16) /* Bit 16: General Purpose Fuse 16 */
+#define FLASHCALW_FGPFRLO17 (1 << 17) /* Bit 17: General Purpose Fuse 17 */
+#define FLASHCALW_FGPFRLO18 (1 << 18) /* Bit 18: General Purpose Fuse 18 */
+#define FLASHCALW_FGPFRLO19 (1 << 19) /* Bit 19: General Purpose Fuse 19 */
+#define FLASHCALW_FGPFRLO20 (1 << 20) /* Bit 20: General Purpose Fuse 20 */
+#define FLASHCALW_FGPFRLO21 (1 << 21) /* Bit 21: General Purpose Fuse 21 */
+#define FLASHCALW_FGPFRLO22 (1 << 22) /* Bit 22: General Purpose Fuse 22 */
+#define FLASHCALW_FGPFRLO23 (1 << 23) /* Bit 23: General Purpose Fuse 23 */
+#define FLASHCALW_FGPFRLO24 (1 << 24) /* Bit 24: General Purpose Fuse 24 */
+#define FLASHCALW_FGPFRLO25 (1 << 25) /* Bit 25: General Purpose Fuse 25 */
+#define FLASHCALW_FGPFRLO26 (1 << 26) /* Bit 26: General Purpose Fuse 26 */
+#define FLASHCALW_FGPFRLO27 (1 << 27) /* Bit 27: General Purpose Fuse 27 */
+#define FLASHCALW_FGPFRLO28 (1 << 28) /* Bit 28: General Purpose Fuse 28 */
+#define FLASHCALW_FGPFRLO29 (1 << 29) /* Bit 29: General Purpose Fuse 29 */
+#define FLASHCALW_FGPFRLO30 (1 << 30) /* Bit 30: General Purpose Fuse 30 */
+#define FLASHCALW_FGPFRLO31 (1 << 31) /* Bit 31: General Purpose Fuse 31 */
+
+/* PicoCache Control Register */
+
+#define PICOCACHE_CTRL_CEN (1 << 0) /* Bit 0: Cache Enable */
+
+/* PicoCache Status Register */
+
+#define PICOCACHE_SR_CSTS (1 << 0) /* Bit 0: Cache Controller Status */
+
+/* PicoCache Maintenance Register 0 */
+
+#define PICOCACHE_MAINT0_INVALL (1 << 0) /* Bit 0: Cache Controller Invalidate All */
+
+/* PicoCache Maintenance Register 1 */
+
+#define PICOCACHE_MAINT1_INDEX_SHIFT (4) /* Bits 4-7: Invalidate Index */
+#define PICOCACHE_MAINT1_INDEX_MASK (15 << PICOCACHE_MAINT1_INDEX_SHIFT)
+
+/* PicoCache Monitor Configuration Register */
+
+#define PICOCACHE_MCFG_MODE_SHIFT (0) /* Bits 0-1: Cache Controller Monitor Counter Mode */
+#define PICOCACHE_MCFG_MODE_MASK (3 << PICOCACHE_MCFG_MODE_SHIFT)
+# define PICOCACHE_MCFG_MODE_CYCLE (0 << PICOCACHE_MCFG_MODE_SHIFT) /* CYCLE_COUNT cycle counter */
+# define PICOCACHE_MCFG_MODE_IHIT (1 << PICOCACHE_MCFG_MODE_SHIFT) /* IHIT_COUNT instruction hit counter */
+# define PICOCACHE_MCFG_MODE_DHIT (2 << PICOCACHE_MCFG_MODE_SHIFT) /* DHIT_COUNT data hit counter */
+
+/* PicoCache Monitor Enable Register */
+
+#define PICOCACHE_MEN_MENABLE (1 << 0) /* Bit 0: Monitor Enable */
+
+/* PicoCache Monitor Control Register */
+
+#define PICOCACHE_MCTRL_SWRST (1 << 0) /* Bit 0: Monitor Software Reset */
+
+/* PicoCache Monitor Status Register (32-bit event count) */
+
+/* Version Register */
+
+#define PICOCACHE_PVR_VERSION_SHIFT (0) /* Bits 0-11: Version Number */
+#define PICOCACHE_PVR_VERSION_MASK (0xfff << PICOCACHE_PVR_FVR_VERSION_SHIFT)
+#define PICOCACHE_PVR_MFN_SHIFT (16) /* Bits 16-19: MFN */
+#define PICOCACHE_PVR_MFN_MASK (15 << PICOCACHE_PVR_FVR_MFN_SHIFT)
+
+/* Flash Command Set ****************************************************************/
+
+#define FLASH_CMD_NOP 0 /* No operation */
+#define FLASH_CMD_WP 1 /* Write Page */
+#define FLASH_CMD_EP 2 /* Erase Page */
+#define FLASH_CMD_CPB 3 /* Clear Page Buffer */
+#define FLASH_CMD_LP 4 /* Lock region containing given Page */
+#define FLASH_CMD_UP 5 /* Unlock region containing given Page */
+#define FLASH_CMD_EA 6 /* Erase All */
+#define FLASH_CMD_WGPB 7 /* Write General-Purpose Fuse Bit */
+#define FLASH_CMD_EGPB 8 /* Erase General-Purpose Fuse Bit */
+#define FLASH_CMD_SSB 9 /* Set Security Fuses */
+#define FLASH_CMD_PGPFB 10 /* Program GP Fuse Byte */
+#define FLASH_CMD_EAGPF 11 /* Erase All GPFuses */
+#define FLASH_CMD_QPR 12 /* Quick Page Read */
+#define FLASH_CMD_WUP 13 /* Write User Page */
+#define FLASH_CMD_EUP 14 /* Erase User Page */
+#define FLASH_CMD_QPRUP 15 /* Quick Page Read User Page */
+#define FLASH_CMD_HSEN 16 /* High Speed Mode Enable */
+#define FLASH_CMD_HSDIS 17 /* High Speed Mode Disable */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_SAM34_CHIP_SAM4L_FLASHCALW_H */
+
diff --git a/nuttx/arch/arm/src/sam34/chip/sam4l_gpio.h b/nuttx/arch/arm/src/sam34/chip/sam4l_gpio.h
index 4927ab706..cf5631da3 100644
--- a/nuttx/arch/arm/src/sam34/chip/sam4l_gpio.h
+++ b/nuttx/arch/arm/src/sam34/chip/sam4l_gpio.h
@@ -94,8 +94,6 @@
#define SAM_GPIO_OVRC_OFFSET 0x0058 /* Output Value Register Clear */
#define SAM_GPIO_OVRT_OFFSET 0x005c /* Output Value Register Toggle */
-/* Pin Value Register Read (4 registers)*/
-
#define SAM_GPIO_PVR_OFFSET 0x0060 /* Pin Value Register Read */
/* {PUER, PDER} Selected Function
@@ -108,7 +106,7 @@
#define SAM_GPIO_PUER_OFFSET 0x0070 /* Pull-up Enable Register Read/Write */
#define SAM_GPIO_PUERS_OFFSET 0x0074 /* Pull-up Enable Register Set */
-#define SAM_GPIO_PUERC_OFFSET 0x0078 /* Pull-up Enable Register Clear*/
+#define SAM_GPIO_PUERC_OFFSET 0x0078 /* Pull-up Enable Register Clear */
#define SAM_GPIO_PUERT_OFFSET 0x007c /* Pull-up Enable Register Toggle */
#define SAM_GPIO_PDER_OFFSET 0x0080 /* Pull-down Enable Register Read/Write */
@@ -144,13 +142,8 @@
#define SAM_GPIO_GFERC_OFFSET 0x00c8 /* Glitch Filter Enable Register Clear */
#define SAM_GPIO_GFERT_OFFSET 0x00cc /* Glitch Filter Enable Register Toggle */
-/* Interrupt Flag Register Read (2 registers)*/
-
#define SAM_GPIO_IFR_OFFSET 0x00d0 /* Interrupt Flag Register 0 Read */
-
-/* Interrupt Flag Register Clear (2 registers)*/
-
-#define SAM_GPIO_IFRC _OFFSET 0x00d8 /* Interrupt Flag Register 0 Clear */
+#define SAM_GPIO_IFRC_OFFSET 0x00d8 /* Interrupt Flag Register 0 Clear */
/* {ODCR1, ODCR0} Output drive strength
*
@@ -188,107 +181,398 @@
#define SAM_GPIO_PARAMETER_OFFSET 0x01f8 /* Parameter Register Read */
#define SAM_GPIO_VERSION_OFFSET 0x01fc /* Version Register Read */
+/* GPIO port offsets and addresses ******************************************************/
+
+#define SAM_GPIOA 0
+#define SAM_GPIOB 1
+#define SAM_GPIOC 2
+
+#define SAM_GPIO_PORTSIZE 0x200
+#define SAM_GPION_OFFSET(n) ((n) << 9)
+#define SAM_GPION_BASE(n) (SAM_GPIO_BASE+SAM_GPION_OFFSET(n))
+#define SAM_GPIOA_BASE SAM_GPION_BASE(SAM_GPIOA)
+#define SAM_GPIOB_BASE SAM_GPION_BASE(SAM_GPIOB)
+#define SAM_GPIOC_BASE SAM_GPION_BASE(SAM_GPIOC)
+
/* GPIO register adresses ***************************************************************/
-#define SAM_GPIO_GPER (SAM_GPIO_BASE+SAM_GPIO_GPER_OFFSET)
-#define SAM_GPIO_GPERS (SAM_GPIO_BASE+SAM_GPIO_GPERS_OFFSET)
-#define SAM_GPIO_GPERC (SAM_GPIO_BASE+SAM_GPIO_GPERC_OFFSET)
-#define SAM_GPIO_GPERT (SAM_GPIO_BASE+SAM_GPIO_GPERT_OFFSET)
-
-#define SAM_GPIO_PMR0 (SAM_GPIO_BASE+SAM_GPIO_PMR0_OFFSET)
-#define SAM_GPIO_PMR0S (SAM_GPIO_BASE+SAM_GPIO_PMR0S_OFFSET)
-#define SAM_GPIO_PMR0C (SAM_GPIO_BASE+SAM_GPIO_PMR0C_OFFSET)
-#define SAM_GPIO_PMR0T (SAM_GPIO_BASE+SAM_GPIO_PMR0T_OFFSET_
-
-#define SAM_GPIO_PMR1 (SAM_GPIO_BASE+SAM_GPIO_PMR1_OFFSET)
-#define SAM_GPIO_PMR1S (SAM_GPIO_BASE+SAM_GPIO_PMR1S_OFFSET)
-#define SAM_GPIO_PMR1C (SAM_GPIO_BASE+SAM_GPIO_PMR1C_OFFSET)
-#define SAM_GPIO_PMR1T (SAM_GPIO_BASE+SAM_GPIO_PMR1T_OFFSET)
-
-#define SAM_GPIO_PMR2 (SAM_GPIO_BASE+SAM_GPIO_PMR2_OFFSET)
-#define SAM_GPIO_PMR2S (SAM_GPIO_BASE+SAM_GPIO_PMR2S_OFFSET)
-#define SAM_GPIO_PMR2C (SAM_GPIO_BASE+SAM_GPIO_PMR2C_OFFSET)
-#define SAM_GPIO_PMR2T (SAM_GPIO_BASE+SAM_GPIO_PMR2T_OFFSET)
-
-#define SAM_GPIO_ODER (SAM_GPIO_BASE+SAM_GPIO_ODER_OFFSET)
-#define SAM_GPIO_ODERS (SAM_GPIO_BASE+SAM_GPIO_ODERS_OFFSET)
-#define SAM_GPIO_ODERC (SAM_GPIO_BASE+SAM_GPIO_ODERC_OFFSET)
-#define SAM_GPIO_ODERT (SAM_GPIO_BASE+SAM_GPIO_ODERT_OFFSET)
-
-#define SAM_GPIO_OVR (SAM_GPIO_BASE+SAM_GPIO_OVR_OFFSET)
-#define SAM_GPIO_OVRS (SAM_GPIO_BASE+SAM_GPIO_OVRS_OFFSET)
-#define SAM_GPIO_OVRC (SAM_GPIO_BASE+SAM_GPIO_OVRC_OFFSET)
-#define SAM_GPIO_OVRT (SAM_GPIO_BASE+SAM_GPIO_OVRT_OFFSET)
-
-/* Pin Value Register Read (4 registers)*/
-
-#define SAM_GPIO_PVR (SAM_GPIO_BASE+SAM_GPIO_PVR_OFFSET)
-
-#define SAM_GPIO_PUER (SAM_GPIO_BASE+SAM_GPIO_PUER_OFFSET)
-#define SAM_GPIO_PUERS (SAM_GPIO_BASE+SAM_GPIO_PUERS_OFFSET)
-#define SAM_GPIO_PUERC (SAM_GPIO_BASE+SAM_GPIO_PUERC_OFFSET)
-#define SAM_GPIO_PUERT (SAM_GPIO_BASE+SAM_GPIO_PUERT_OFFSET)
-
-#define SAM_GPIO_PDER (SAM_GPIO_BASE+SAM_GPIO_PDER_OFFSET)
-#define SAM_GPIO_PDERS (SAM_GPIO_BASE+SAM_GPIO_PDERS_OFFSET)
-#define SAM_GPIO_PDERC (SAM_GPIO_BASE+SAM_GPIO_PDERC_OFFSET)
-#define SAM_GPIO_PDERT (SAM_GPIO_BASE+SAM_GPIO_PDERT_OFFSET)
-
-#define SAM_GPIO_IER (SAM_GPIO_BASE+SAM_GPIO_IER_OFFSET)
-#define SAM_GPIO_IERS (SAM_GPIO_BASE+SAM_GPIO_IERS_OFFSET)
-#define SAM_GPIO_IERC (SAM_GPIO_BASE+SAM_GPIO_IERC_OFFSET)
-#define SAM_GPIO_IERT (SAM_GPIO_BASE+SAM_GPIO_IERT_OFFSET)
-
-#define SAM_GPIO_IMR0 (SAM_GPIO_BASE+SAM_GPIO_IMR0_OFFSET)
-#define SAM_GPIO_IMR0S (SAM_GPIO_BASE+SAM_GPIO_IMR0S_OFFSET)
-#define SAM_GPIO_IMR0C (SAM_GPIO_BASE+SAM_GPIO_IMR0C_OFFSET)
-#define SAM_GPIO_IMR0T (SAM_GPIO_BASE+SAM_GPIO_IMR0T_OFFSET)
-
-#define SAM_GPIO_IMR1 (SAM_GPIO_BASE+SAM_GPIO_IMR1_OFFSET)
-#define SAM_GPIO_IMR1S (SAM_GPIO_BASE+SAM_GPIO_IMR1S_OFFSET)
-#define SAM_GPIO_IMR1C (SAM_GPIO_BASE+SAM_GPIO_IMR1C_OFFSET)
-#define SAM_GPIO_IMR1T (SAM_GPIO_BASE+SAM_GPIO_IMR1T_OFFSET)
-
-#define SAM_GPIO_GFER (SAM_GPIO_BASE+SAM_GPIO_GFER_OFFSET)
-#define SAM_GPIO_GFERS (SAM_GPIO_BASE+SAM_GPIO_GFERS_OFFSET)
-#define SAM_GPIO_GFERC (SAM_GPIO_BASE+SAM_GPIO_GFERC_OFFSET)
-#define SAM_GPIO_GFERT (SAM_GPIO_BASE+SAM_GPIO_GFERT_OFFSET)
-
-/* Interrupt Flag Register Read */
-
-#define SAM_GPIO_IFR (SAM_GPIO_BASE+SAM_GPIO_IFR_OFFSET)
-
-/* Interrupt Flag Register Clear */
-
-#define SAM_GPIO_IFRC (SAM_GPIO_BASE+SAM_GPIO_IFRC_OFFSET)
-
-#define SAM_GPIO_ODCR0 (SAM_GPIO_BASE+SAM_GPIO_ODCR0_OFFSET)
-#define SAM_GPIO_ODCR0S (SAM_GPIO_BASE+SAM_GPIO_ODCR0S_OFFSET)
-#define SAM_GPIO_ODCR0C (SAM_GPIO_BASE+SAM_GPIO_ODCR0C_OFFSET)
-#define SAM_GPIO_ODCR0T (SAM_GPIO_BASE+SAM_GPIO_ODCR0T_OFFSET)
-
-#define SAM_GPIO_ODCR1 (SAM_GPIO_BASE+SAM_GPIO_ODCR1_OFFSET)
-#define SAM_GPIO_ODCR1S (SAM_GPIO_BASE+SAM_GPIO_ODCR1S_OFFSET)
-#define SAM_GPIO_ODCR1C (SAM_GPIO_BASE+SAM_GPIO_ODCR1C_OFFSET)
-#define SAM_GPIO_ODCR1T (SAM_GPIO_BASE+SAM_GPIO_ODCR1T_OFFSET)
-
-#define SAM_GPIO_OSRR0 (SAM_GPIO_BASE+SAM_GPIO_OSRR0_OFFSET)
-#define SAM_GPIO_OSRR0S (SAM_GPIO_BASE+SAM_GPIO_OSRR0S_OFFSET)
-#define SAM_GPIO_OSRR0C (SAM_GPIO_BASE+SAM_GPIO_OSRR0C_OFFSET)
-#define SAM_GPIO_OSRR0T (SAM_GPIO_BASE+SAM_GPIO_OSRR0T_OFFSET)
-
-#define SAM_GPIO_STER (SAM_GPIO_BASE+SAM_GPIO_STER_OFFSET)
-#define SAM_GPIO_STERS (SAM_GPIO_BASE+SAM_GPIO_STERS_OFFSET)
-#define SAM_GPIO_STERC (SAM_GPIO_BASE+SAM_GPIO_STERC_OFFSET)
-#define SAM_GPIO_STERT (SAM_GPIO_BASE+SAM_GPIO_STERT_OFFSET)
-
-#define SAM_GPIO_EVER (SAM_GPIO_BASE+SAM_GPIO_EVER_OFFSET)
-#define SAM_GPIO_EVERS (SAM_GPIO_BASE+SAM_GPIO_EVERS_OFFSET)
-#define SAM_GPIO_EVERC (SAM_GPIO_BASE+SAM_GPIO_EVERC_OFFSET)
-#define SAM_GPIO_EVERT (SAM_GPIO_BASE+SAM_GPIO_EVERT_OFFSET)
-
-#define SAM_GPIO_PARAMETER (SAM_GPIO_BASE+SAM_GPIO_PARAMETER_OFFSET)
-#define SAM_GPIO_VERSION (SAM_GPIO_BASE+SAM_GPIO_VERSION_OFFSET)
+#define SAM_GPIO_GPER(n) (SAM_GPION_BASE(n)+SAM_GPIO_GPER_OFFSET)
+#define SAM_GPIO_GPERS(n) (SAM_GPION_BASE(n)+SAM_GPIO_GPERS_OFFSET)
+#define SAM_GPIO_GPERC(n) (SAM_GPION_BASE(n)+SAM_GPIO_GPERC_OFFSET)
+#define SAM_GPIO_GPERT(n) (SAM_GPION_BASE(n)+SAM_GPIO_GPERT_OFFSET)
+
+#define SAM_GPIO_PMR0(n) (SAM_GPION_BASE(n)+SAM_GPIO_PMR0_OFFSET)
+#define SAM_GPIO_PMR0S(n) (SAM_GPION_BASE(n)+SAM_GPIO_PMR0S_OFFSET)
+#define SAM_GPIO_PMR0C(n) (SAM_GPION_BASE(n)+SAM_GPIO_PMR0C_OFFSET)
+#define SAM_GPIO_PMR0T(n) (SAM_GPION_BASE(n)+SAM_GPIO_PMR0T_OFFSET_
+
+#define SAM_GPIO_PMR1(n) (SAM_GPION_BASE(n)+SAM_GPIO_PMR1_OFFSET)
+#define SAM_GPIO_PMR1S(n) (SAM_GPION_BASE(n)+SAM_GPIO_PMR1S_OFFSET)
+#define SAM_GPIO_PMR1C(n) (SAM_GPION_BASE(n)+SAM_GPIO_PMR1C_OFFSET)
+#define SAM_GPIO_PMR1T(n) (SAM_GPION_BASE(n)+SAM_GPIO_PMR1T_OFFSET)
+
+#define SAM_GPIO_PMR2(n) (SAM_GPION_BASE(n)+SAM_GPIO_PMR2_OFFSET)
+#define SAM_GPIO_PMR2S(n) (SAM_GPION_BASE(n)+SAM_GPIO_PMR2S_OFFSET)
+#define SAM_GPIO_PMR2C(n) (SAM_GPION_BASE(n)+SAM_GPIO_PMR2C_OFFSET)
+#define SAM_GPIO_PMR2T(n) (SAM_GPION_BASE(n)+SAM_GPIO_PMR2T_OFFSET)
+
+#define SAM_GPIO_ODER(n) (SAM_GPION_BASE(n)+SAM_GPIO_ODER_OFFSET)
+#define SAM_GPIO_ODERS(n) (SAM_GPION_BASE(n)+SAM_GPIO_ODERS_OFFSET)
+#define SAM_GPIO_ODERC(n) (SAM_GPION_BASE(n)+SAM_GPIO_ODERC_OFFSET)
+#define SAM_GPIO_ODERT(n) (SAM_GPION_BASE(n)+SAM_GPIO_ODERT_OFFSET)
+
+#define SAM_GPIO_OVR(n) (SAM_GPION_BASE(n)+SAM_GPIO_OVR_OFFSET)
+#define SAM_GPIO_OVRS(n) (SAM_GPION_BASE(n)+SAM_GPIO_OVRS_OFFSET)
+#define SAM_GPIO_OVRC(n) (SAM_GPION_BASE(n)+SAM_GPIO_OVRC_OFFSET)
+#define SAM_GPIO_OVRT(n) (SAM_GPION_BASE(n)+SAM_GPIO_OVRT_OFFSET)
+
+#define SAM_GPIO_PVR(n) (SAM_GPION_BASE(n)+SAM_GPIO_PVR_OFFSET)
+
+#define SAM_GPIO_PUER(n) (SAM_GPION_BASE(n)+SAM_GPIO_PUER_OFFSET)
+#define SAM_GPIO_PUERS(n) (SAM_GPION_BASE(n)+SAM_GPIO_PUERS_OFFSET)
+#define SAM_GPIO_PUERC(n) (SAM_GPION_BASE(n)+SAM_GPIO_PUERC_OFFSET)
+#define SAM_GPIO_PUERT(n) (SAM_GPION_BASE(n)+SAM_GPIO_PUERT_OFFSET)
+
+#define SAM_GPIO_PDER(n) (SAM_GPION_BASE(n)+SAM_GPIO_PDER_OFFSET)
+#define SAM_GPIO_PDERS(n) (SAM_GPION_BASE(n)+SAM_GPIO_PDERS_OFFSET)
+#define SAM_GPIO_PDERC(n) (SAM_GPION_BASE(n)+SAM_GPIO_PDERC_OFFSET)
+#define SAM_GPIO_PDERT(n) (SAM_GPION_BASE(n)+SAM_GPIO_PDERT_OFFSET)
+
+#define SAM_GPIO_IER(n) (SAM_GPION_BASE(n)+SAM_GPIO_IER_OFFSET)
+#define SAM_GPIO_IERS(n) (SAM_GPION_BASE(n)+SAM_GPIO_IERS_OFFSET)
+#define SAM_GPIO_IERC(n) (SAM_GPION_BASE(n)+SAM_GPIO_IERC_OFFSET)
+#define SAM_GPIO_IERT(n) (SAM_GPION_BASE(n)+SAM_GPIO_IERT_OFFSET)
+
+#define SAM_GPIO_IMR0(n) (SAM_GPION_BASE(n)+SAM_GPIO_IMR0_OFFSET)
+#define SAM_GPIO_IMR0S(n) (SAM_GPION_BASE(n)+SAM_GPIO_IMR0S_OFFSET)
+#define SAM_GPIO_IMR0C(n) (SAM_GPION_BASE(n)+SAM_GPIO_IMR0C_OFFSET)
+#define SAM_GPIO_IMR0T(n) (SAM_GPION_BASE(n)+SAM_GPIO_IMR0T_OFFSET)
+
+#define SAM_GPIO_IMR1(n) (SAM_GPION_BASE(n)+SAM_GPIO_IMR1_OFFSET)
+#define SAM_GPIO_IMR1S(n) (SAM_GPION_BASE(n)+SAM_GPIO_IMR1S_OFFSET)
+#define SAM_GPIO_IMR1C(n) (SAM_GPION_BASE(n)+SAM_GPIO_IMR1C_OFFSET)
+#define SAM_GPIO_IMR1T(n) (SAM_GPION_BASE(n)+SAM_GPIO_IMR1T_OFFSET)
+
+#define SAM_GPIO_GFER(n) (SAM_GPION_BASE(n)+SAM_GPIO_GFER_OFFSET)
+#define SAM_GPIO_GFERS(n) (SAM_GPION_BASE(n)+SAM_GPIO_GFERS_OFFSET)
+#define SAM_GPIO_GFERC(n) (SAM_GPION_BASE(n)+SAM_GPIO_GFERC_OFFSET)
+#define SAM_GPIO_GFERT(n) (SAM_GPION_BASE(n)+SAM_GPIO_GFERT_OFFSET)
+
+#define SAM_GPIO_IFR(n) (SAM_GPION_BASE(n)+SAM_GPIO_IFR_OFFSET)
+#define SAM_GPIO_IFRC(n) (SAM_GPION_BASE(n)+SAM_GPIO_IFRC_OFFSET)
+
+#define SAM_GPIO_ODCR0(n) (SAM_GPION_BASE(n)+SAM_GPIO_ODCR0_OFFSET)
+#define SAM_GPIO_ODCR0S(n) (SAM_GPION_BASE(n)+SAM_GPIO_ODCR0S_OFFSET)
+#define SAM_GPIO_ODCR0C(n) (SAM_GPION_BASE(n)+SAM_GPIO_ODCR0C_OFFSET)
+#define SAM_GPIO_ODCR0T(n) (SAM_GPION_BASE(n)+SAM_GPIO_ODCR0T_OFFSET)
+
+#define SAM_GPIO_ODCR1(n) (SAM_GPION_BASE(n)+SAM_GPIO_ODCR1_OFFSET)
+#define SAM_GPIO_ODCR1S(n) (SAM_GPION_BASE(n)+SAM_GPIO_ODCR1S_OFFSET)
+#define SAM_GPIO_ODCR1C(n) (SAM_GPION_BASE(n)+SAM_GPIO_ODCR1C_OFFSET)
+#define SAM_GPIO_ODCR1T(n) (SAM_GPION_BASE(n)+SAM_GPIO_ODCR1T_OFFSET)
+
+#define SAM_GPIO_OSRR0(n) (SAM_GPION_BASE(n)+SAM_GPIO_OSRR0_OFFSET)
+#define SAM_GPIO_OSRR0S(n) (SAM_GPION_BASE(n)+SAM_GPIO_OSRR0S_OFFSET)
+#define SAM_GPIO_OSRR0C(n) (SAM_GPION_BASE(n)+SAM_GPIO_OSRR0C_OFFSET)
+#define SAM_GPIO_OSRR0T(n) (SAM_GPION_BASE(n)+SAM_GPIO_OSRR0T_OFFSET)
+
+#define SAM_GPIO_STER(n) (SAM_GPION_BASE(n)+SAM_GPIO_STER_OFFSET)
+#define SAM_GPIO_STERS(n) (SAM_GPION_BASE(n)+SAM_GPIO_STERS_OFFSET)
+#define SAM_GPIO_STERC(n) (SAM_GPION_BASE(n)+SAM_GPIO_STERC_OFFSET)
+#define SAM_GPIO_STERT(n) (SAM_GPION_BASE(n)+SAM_GPIO_STERT_OFFSET)
+
+#define SAM_GPIO_EVER(n) (SAM_GPION_BASE(n)+SAM_GPIO_EVER_OFFSET)
+#define SAM_GPIO_EVERS(n) (SAM_GPION_BASE(n)+SAM_GPIO_EVERS_OFFSET)
+#define SAM_GPIO_EVERC(n) (SAM_GPION_BASE(n)+SAM_GPIO_EVERC_OFFSET)
+#define SAM_GPIO_EVERT(n) (SAM_GPION_BASE(n)+SAM_GPIO_EVERT_OFFSET)
+
+#define SAM_GPIO_PARAMETER(n) (SAM_GPION_BASE(n)+SAM_GPIO_PARAMETER_OFFSET)
+#define SAM_GPIO_VERSION (n) (SAM_GPION_BASE(n)+SAM_GPIO_VERSION_OFFSET)
+
+/* GPIO PORTA register adresses *********************************************************/
+
+#define SAM_GPIOA_GPER (SAM_GPIOA_BASE+SAM_GPIO_GPER_OFFSET)
+#define SAM_GPIOA_GPERS (SAM_GPIOA_BASE+SAM_GPIO_GPERS_OFFSET)
+#define SAM_GPIOA_GPERC (SAM_GPIOA_BASE+SAM_GPIO_GPERC_OFFSET)
+#define SAM_GPIOA_GPERT (SAM_GPIOA_BASE+SAM_GPIO_GPERT_OFFSET)
+
+#define SAM_GPIOA_PMR0 (SAM_GPIOA_BASE+SAM_GPIO_PMR0_OFFSET)
+#define SAM_GPIOA_PMR0S (SAM_GPIOA_BASE+SAM_GPIO_PMR0S_OFFSET)
+#define SAM_GPIOA_PMR0C (SAM_GPIOA_BASE+SAM_GPIO_PMR0C_OFFSET)
+#define SAM_GPIOA_PMR0T (SAM_GPIOA_BASE+SAM_GPIO_PMR0T_OFFSET_
+
+#define SAM_GPIOA_PMR1 (SAM_GPIOA_BASE+SAM_GPIO_PMR1_OFFSET)
+#define SAM_GPIOA_PMR1S (SAM_GPIOA_BASE+SAM_GPIO_PMR1S_OFFSET)
+#define SAM_GPIOA_PMR1C (SAM_GPIOA_BASE+SAM_GPIO_PMR1C_OFFSET)
+#define SAM_GPIOA_PMR1T (SAM_GPIOA_BASE+SAM_GPIO_PMR1T_OFFSET)
+
+#define SAM_GPIOA_PMR2 (SAM_GPIOA_BASE+SAM_GPIO_PMR2_OFFSET)
+#define SAM_GPIOA_PMR2S (SAM_GPIOA_BASE+SAM_GPIO_PMR2S_OFFSET)
+#define SAM_GPIOA_PMR2C (SAM_GPIOA_BASE+SAM_GPIO_PMR2C_OFFSET)
+#define SAM_GPIOA_PMR2T (SAM_GPIOA_BASE+SAM_GPIO_PMR2T_OFFSET)
+
+#define SAM_GPIOA_ODER (SAM_GPIOA_BASE+SAM_GPIO_ODER_OFFSET)
+#define SAM_GPIOA_ODERS (SAM_GPIOA_BASE+SAM_GPIO_ODERS_OFFSET)
+#define SAM_GPIOA_ODERC (SAM_GPIOA_BASE+SAM_GPIO_ODERC_OFFSET)
+#define SAM_GPIOA_ODERT (SAM_GPIOA_BASE+SAM_GPIO_ODERT_OFFSET)
+
+#define SAM_GPIOA_OVR (SAM_GPIOA_BASE+SAM_GPIO_OVR_OFFSET)
+#define SAM_GPIOA_OVRS (SAM_GPIOA_BASE+SAM_GPIO_OVRS_OFFSET)
+#define SAM_GPIOA_OVRC (SAM_GPIOA_BASE+SAM_GPIO_OVRC_OFFSET)
+#define SAM_GPIOA_OVRT (SAM_GPIOA_BASE+SAM_GPIO_OVRT_OFFSET)
+
+#define SAM_GPIOA_PVR (SAM_GPIOA_BASE+SAM_GPIO_PVR_OFFSET)
+
+#define SAM_GPIOA_PUER (SAM_GPIOA_BASE+SAM_GPIO_PUER_OFFSET)
+#define SAM_GPIOA_PUERS (SAM_GPIOA_BASE+SAM_GPIO_PUERS_OFFSET)
+#define SAM_GPIOA_PUERC (SAM_GPIOA_BASE+SAM_GPIO_PUERC_OFFSET)
+#define SAM_GPIOA_PUERT (SAM_GPIOA_BASE+SAM_GPIO_PUERT_OFFSET)
+
+#define SAM_GPIOA_PDER (SAM_GPIOA_BASE+SAM_GPIO_PDER_OFFSET)
+#define SAM_GPIOA_PDERS (SAM_GPIOA_BASE+SAM_GPIO_PDERS_OFFSET)
+#define SAM_GPIOA_PDERC (SAM_GPIOA_BASE+SAM_GPIO_PDERC_OFFSET)
+#define SAM_GPIOA_PDERT (SAM_GPIOA_BASE+SAM_GPIO_PDERT_OFFSET)
+
+#define SAM_GPIOA_IER (SAM_GPIOA_BASE+SAM_GPIO_IER_OFFSET)
+#define SAM_GPIOA_IERS (SAM_GPIOA_BASE+SAM_GPIO_IERS_OFFSET)
+#define SAM_GPIOA_IERC (SAM_GPIOA_BASE+SAM_GPIO_IERC_OFFSET)
+#define SAM_GPIOA_IERT (SAM_GPIOA_BASE+SAM_GPIO_IERT_OFFSET)
+
+#define SAM_GPIOA_IMR0 (SAM_GPIOA_BASE+SAM_GPIO_IMR0_OFFSET)
+#define SAM_GPIOA_IMR0S (SAM_GPIOA_BASE+SAM_GPIO_IMR0S_OFFSET)
+#define SAM_GPIOA_IMR0C (SAM_GPIOA_BASE+SAM_GPIO_IMR0C_OFFSET)
+#define SAM_GPIOA_IMR0T (SAM_GPIOA_BASE+SAM_GPIO_IMR0T_OFFSET)
+
+#define SAM_GPIOA_IMR1 (SAM_GPIOA_BASE+SAM_GPIO_IMR1_OFFSET)
+#define SAM_GPIOA_IMR1S (SAM_GPIOA_BASE+SAM_GPIO_IMR1S_OFFSET)
+#define SAM_GPIOA_IMR1C (SAM_GPIOA_BASE+SAM_GPIO_IMR1C_OFFSET)
+#define SAM_GPIOA_IMR1T (SAM_GPIOA_BASE+SAM_GPIO_IMR1T_OFFSET)
+
+#define SAM_GPIOA_GFER (SAM_GPIOA_BASE+SAM_GPIO_GFER_OFFSET)
+#define SAM_GPIOA_GFERS (SAM_GPIOA_BASE+SAM_GPIO_GFERS_OFFSET)
+#define SAM_GPIOA_GFERC (SAM_GPIOA_BASE+SAM_GPIO_GFERC_OFFSET)
+#define SAM_GPIOA_GFERT (SAM_GPIOA_BASE+SAM_GPIO_GFERT_OFFSET)
+
+#define SAM_GPIOA_IFR (SAM_GPIOA_BASE+SAM_GPIO_IFR_OFFSET)
+#define SAM_GPIOA_IFRC (SAM_GPIOA_BASE+SAM_GPIO_IFRC_OFFSET)
+
+#define SAM_GPIOA_ODCR0 (SAM_GPIOA_BASE+SAM_GPIO_ODCR0_OFFSET)
+#define SAM_GPIOA_ODCR0S (SAM_GPIOA_BASE+SAM_GPIO_ODCR0S_OFFSET)
+#define SAM_GPIOA_ODCR0C (SAM_GPIOA_BASE+SAM_GPIO_ODCR0C_OFFSET)
+#define SAM_GPIOA_ODCR0T (SAM_GPIOA_BASE+SAM_GPIO_ODCR0T_OFFSET)
+
+#define SAM_GPIOA_ODCR1 (SAM_GPIOA_BASE+SAM_GPIO_ODCR1_OFFSET)
+#define SAM_GPIOA_ODCR1S (SAM_GPIOA_BASE+SAM_GPIO_ODCR1S_OFFSET)
+#define SAM_GPIOA_ODCR1C (SAM_GPIOA_BASE+SAM_GPIO_ODCR1C_OFFSET)
+#define SAM_GPIOA_ODCR1T (SAM_GPIOA_BASE+SAM_GPIO_ODCR1T_OFFSET)
+
+#define SAM_GPIOA_OSRR0 (SAM_GPIOA_BASE+SAM_GPIO_OSRR0_OFFSET)
+#define SAM_GPIOA_OSRR0S (SAM_GPIOA_BASE+SAM_GPIO_OSRR0S_OFFSET)
+#define SAM_GPIOA_OSRR0C (SAM_GPIOA_BASE+SAM_GPIO_OSRR0C_OFFSET)
+#define SAM_GPIOA_OSRR0T (SAM_GPIOA_BASE+SAM_GPIO_OSRR0T_OFFSET)
+
+#define SAM_GPIOA_STER (SAM_GPIOA_BASE+SAM_GPIO_STER_OFFSET)
+#define SAM_GPIOA_STERS (SAM_GPIOA_BASE+SAM_GPIO_STERS_OFFSET)
+#define SAM_GPIOA_STERC (SAM_GPIOA_BASE+SAM_GPIO_STERC_OFFSET)
+#define SAM_GPIOA_STERT (SAM_GPIOA_BASE+SAM_GPIO_STERT_OFFSET)
+
+#define SAM_GPIOA_EVER (SAM_GPIOA_BASE+SAM_GPIO_EVER_OFFSET)
+#define SAM_GPIOA_EVERS (SAM_GPIOA_BASE+SAM_GPIO_EVERS_OFFSET)
+#define SAM_GPIOA_EVERC (SAM_GPIOA_BASE+SAM_GPIO_EVERC_OFFSET)
+#define SAM_GPIOA_EVERT (SAM_GPIOA_BASE+SAM_GPIO_EVERT_OFFSET)
+
+#define SAM_GPIOA_PARAMETER (SAM_GPIOA_BASE+SAM_GPIO_PARAMETER_OFFSET)
+#define SAM_GPIOA_VERSION (SAM_GPIOA_BASE+SAM_GPIO_VERSION_OFFSET)
+
+/* GPIO PORTB register adresses *********************************************************/
+
+#define SAM_GPIOB_GPER (SAM_GPIOB_BASE+SAM_GPIO_GPER_OFFSET)
+#define SAM_GPIOB_GPERS (SAM_GPIOB_BASE+SAM_GPIO_GPERS_OFFSET)
+#define SAM_GPIOB_GPERC (SAM_GPIOB_BASE+SAM_GPIO_GPERC_OFFSET)
+#define SAM_GPIOB_GPERT (SAM_GPIOB_BASE+SAM_GPIO_GPERT_OFFSET)
+
+#define SAM_GPIOB_PMR0 (SAM_GPIOB_BASE+SAM_GPIO_PMR0_OFFSET)
+#define SAM_GPIOB_PMR0S (SAM_GPIOB_BASE+SAM_GPIO_PMR0S_OFFSET)
+#define SAM_GPIOB_PMR0C (SAM_GPIOB_BASE+SAM_GPIO_PMR0C_OFFSET)
+#define SAM_GPIOB_PMR0T (SAM_GPIOB_BASE+SAM_GPIO_PMR0T_OFFSET_
+
+#define SAM_GPIOB_PMR1 (SAM_GPIOB_BASE+SAM_GPIO_PMR1_OFFSET)
+#define SAM_GPIOB_PMR1S (SAM_GPIOB_BASE+SAM_GPIO_PMR1S_OFFSET)
+#define SAM_GPIOB_PMR1C (SAM_GPIOB_BASE+SAM_GPIO_PMR1C_OFFSET)
+#define SAM_GPIOB_PMR1T (SAM_GPIOB_BASE+SAM_GPIO_PMR1T_OFFSET)
+
+#define SAM_GPIOB_PMR2 (SAM_GPIOB_BASE+SAM_GPIO_PMR2_OFFSET)
+#define SAM_GPIOB_PMR2S (SAM_GPIOB_BASE+SAM_GPIO_PMR2S_OFFSET)
+#define SAM_GPIOB_PMR2C (SAM_GPIOB_BASE+SAM_GPIO_PMR2C_OFFSET)
+#define SAM_GPIOB_PMR2T (SAM_GPIOB_BASE+SAM_GPIO_PMR2T_OFFSET)
+
+#define SAM_GPIOB_ODER (SAM_GPIOB_BASE+SAM_GPIO_ODER_OFFSET)
+#define SAM_GPIOB_ODERS (SAM_GPIOB_BASE+SAM_GPIO_ODERS_OFFSET)
+#define SAM_GPIOB_ODERC (SAM_GPIOB_BASE+SAM_GPIO_ODERC_OFFSET)
+#define SAM_GPIOB_ODERT (SAM_GPIOB_BASE+SAM_GPIO_ODERT_OFFSET)
+
+#define SAM_GPIOB_OVR (SAM_GPIOB_BASE+SAM_GPIO_OVR_OFFSET)
+#define SAM_GPIOB_OVRS (SAM_GPIOB_BASE+SAM_GPIO_OVRS_OFFSET)
+#define SAM_GPIOB_OVRC (SAM_GPIOB_BASE+SAM_GPIO_OVRC_OFFSET)
+#define SAM_GPIOB_OVRT (SAM_GPIOB_BASE+SAM_GPIO_OVRT_OFFSET)
+
+#define SAM_GPIOB_PVR (SAM_GPIOB_BASE+SAM_GPIO_PVR_OFFSET)
+
+#define SAM_GPIOB_PUER (SAM_GPIOB_BASE+SAM_GPIO_PUER_OFFSET)
+#define SAM_GPIOB_PUERS (SAM_GPIOB_BASE+SAM_GPIO_PUERS_OFFSET)
+#define SAM_GPIOB_PUERC (SAM_GPIOB_BASE+SAM_GPIO_PUERC_OFFSET)
+#define SAM_GPIOB_PUERT (SAM_GPIOB_BASE+SAM_GPIO_PUERT_OFFSET)
+
+#define SAM_GPIOB_PDER (SAM_GPIOB_BASE+SAM_GPIO_PDER_OFFSET)
+#define SAM_GPIOB_PDERS (SAM_GPIOB_BASE+SAM_GPIO_PDERS_OFFSET)
+#define SAM_GPIOB_PDERC (SAM_GPIOB_BASE+SAM_GPIO_PDERC_OFFSET)
+#define SAM_GPIOB_PDERT (SAM_GPIOB_BASE+SAM_GPIO_PDERT_OFFSET)
+
+#define SAM_GPIOB_IER (SAM_GPIOB_BASE+SAM_GPIO_IER_OFFSET)
+#define SAM_GPIOB_IERS (SAM_GPIOB_BASE+SAM_GPIO_IERS_OFFSET)
+#define SAM_GPIOB_IERC (SAM_GPIOB_BASE+SAM_GPIO_IERC_OFFSET)
+#define SAM_GPIOB_IERT (SAM_GPIOB_BASE+SAM_GPIO_IERT_OFFSET)
+
+#define SAM_GPIOB_IMR0 (SAM_GPIOB_BASE+SAM_GPIO_IMR0_OFFSET)
+#define SAM_GPIOB_IMR0S (SAM_GPIOB_BASE+SAM_GPIO_IMR0S_OFFSET)
+#define SAM_GPIOB_IMR0C (SAM_GPIOB_BASE+SAM_GPIO_IMR0C_OFFSET)
+#define SAM_GPIOB_IMR0T (SAM_GPIOB_BASE+SAM_GPIO_IMR0T_OFFSET)
+
+#define SAM_GPIOB_IMR1 (SAM_GPIOB_BASE+SAM_GPIO_IMR1_OFFSET)
+#define SAM_GPIOB_IMR1S (SAM_GPIOB_BASE+SAM_GPIO_IMR1S_OFFSET)
+#define SAM_GPIOB_IMR1C (SAM_GPIOB_BASE+SAM_GPIO_IMR1C_OFFSET)
+#define SAM_GPIOB_IMR1T (SAM_GPIOB_BASE+SAM_GPIO_IMR1T_OFFSET)
+
+#define SAM_GPIOB_GFER (SAM_GPIOB_BASE+SAM_GPIO_GFER_OFFSET)
+#define SAM_GPIOB_GFERS (SAM_GPIOB_BASE+SAM_GPIO_GFERS_OFFSET)
+#define SAM_GPIOB_GFERC (SAM_GPIOB_BASE+SAM_GPIO_GFERC_OFFSET)
+#define SAM_GPIOB_GFERT (SAM_GPIOB_BASE+SAM_GPIO_GFERT_OFFSET)
+
+#define SAM_GPIOB_IFR (SAM_GPIOB_BASE+SAM_GPIO_IFR_OFFSET)
+#define SAM_GPIOB_IFRC (SAM_GPIOB_BASE+SAM_GPIO_IFRC_OFFSET)
+
+#define SAM_GPIOB_ODCR0 (SAM_GPIOB_BASE+SAM_GPIO_ODCR0_OFFSET)
+#define SAM_GPIOB_ODCR0S (SAM_GPIOB_BASE+SAM_GPIO_ODCR0S_OFFSET)
+#define SAM_GPIOB_ODCR0C (SAM_GPIOB_BASE+SAM_GPIO_ODCR0C_OFFSET)
+#define SAM_GPIOB_ODCR0T (SAM_GPIOB_BASE+SAM_GPIO_ODCR0T_OFFSET)
+
+#define SAM_GPIOB_ODCR1 (SAM_GPIOB_BASE+SAM_GPIO_ODCR1_OFFSET)
+#define SAM_GPIOB_ODCR1S (SAM_GPIOB_BASE+SAM_GPIO_ODCR1S_OFFSET)
+#define SAM_GPIOB_ODCR1C (SAM_GPIOB_BASE+SAM_GPIO_ODCR1C_OFFSET)
+#define SAM_GPIOB_ODCR1T (SAM_GPIOB_BASE+SAM_GPIO_ODCR1T_OFFSET)
+
+#define SAM_GPIOB_OSRR0 (SAM_GPIOB_BASE+SAM_GPIO_OSRR0_OFFSET)
+#define SAM_GPIOB_OSRR0S (SAM_GPIOB_BASE+SAM_GPIO_OSRR0S_OFFSET)
+#define SAM_GPIOB_OSRR0C (SAM_GPIOB_BASE+SAM_GPIO_OSRR0C_OFFSET)
+#define SAM_GPIOB_OSRR0T (SAM_GPIOB_BASE+SAM_GPIO_OSRR0T_OFFSET)
+
+#define SAM_GPIOB_STER (SAM_GPIOB_BASE+SAM_GPIO_STER_OFFSET)
+#define SAM_GPIOB_STERS (SAM_GPIOB_BASE+SAM_GPIO_STERS_OFFSET)
+#define SAM_GPIOB_STERC (SAM_GPIOB_BASE+SAM_GPIO_STERC_OFFSET)
+#define SAM_GPIOB_STERT (SAM_GPIOB_BASE+SAM_GPIO_STERT_OFFSET)
+
+#define SAM_GPIOB_EVER (SAM_GPIOB_BASE+SAM_GPIO_EVER_OFFSET)
+#define SAM_GPIOB_EVERS (SAM_GPIOB_BASE+SAM_GPIO_EVERS_OFFSET)
+#define SAM_GPIOB_EVERC (SAM_GPIOB_BASE+SAM_GPIO_EVERC_OFFSET)
+#define SAM_GPIOB_EVERT (SAM_GPIOB_BASE+SAM_GPIO_EVERT_OFFSET)
+
+#define SAM_GPIOB_PARAMETER (SAM_GPIOB_BASE+SAM_GPIO_PARAMETER_OFFSET)
+#define SAM_GPIOB_VERSION (SAM_GPIOB_BASE+SAM_GPIO_VERSION_OFFSET)
+
+/* GPIO PORTC register adresses *********************************************************/
+
+#define SAM_GPIOC_GPER (SAM_GPIOC_BASE+SAM_GPIO_GPER_OFFSET)
+#define SAM_GPIOC_GPERS (SAM_GPIOC_BASE+SAM_GPIO_GPERS_OFFSET)
+#define SAM_GPIOC_GPERC (SAM_GPIOC_BASE+SAM_GPIO_GPERC_OFFSET)
+#define SAM_GPIOC_GPERT (SAM_GPIOC_BASE+SAM_GPIO_GPERT_OFFSET)
+
+#define SAM_GPIOC_PMR0 (SAM_GPIOC_BASE+SAM_GPIO_PMR0_OFFSET)
+#define SAM_GPIOC_PMR0S (SAM_GPIOC_BASE+SAM_GPIO_PMR0S_OFFSET)
+#define SAM_GPIOC_PMR0C (SAM_GPIOC_BASE+SAM_GPIO_PMR0C_OFFSET)
+#define SAM_GPIOC_PMR0T (SAM_GPIOC_BASE+SAM_GPIO_PMR0T_OFFSET_
+
+#define SAM_GPIOC_PMR1 (SAM_GPIOC_BASE+SAM_GPIO_PMR1_OFFSET)
+#define SAM_GPIOC_PMR1S (SAM_GPIOC_BASE+SAM_GPIO_PMR1S_OFFSET)
+#define SAM_GPIOC_PMR1C (SAM_GPIOC_BASE+SAM_GPIO_PMR1C_OFFSET)
+#define SAM_GPIOC_PMR1T (SAM_GPIOC_BASE+SAM_GPIO_PMR1T_OFFSET)
+
+#define SAM_GPIOC_PMR2 (SAM_GPIOC_BASE+SAM_GPIO_PMR2_OFFSET)
+#define SAM_GPIOC_PMR2S (SAM_GPIOC_BASE+SAM_GPIO_PMR2S_OFFSET)
+#define SAM_GPIOC_PMR2C (SAM_GPIOC_BASE+SAM_GPIO_PMR2C_OFFSET)
+#define SAM_GPIOC_PMR2T (SAM_GPIOC_BASE+SAM_GPIO_PMR2T_OFFSET)
+
+#define SAM_GPIOC_ODER (SAM_GPIOC_BASE+SAM_GPIO_ODER_OFFSET)
+#define SAM_GPIOC_ODERS (SAM_GPIOC_BASE+SAM_GPIO_ODERS_OFFSET)
+#define SAM_GPIOC_ODERC (SAM_GPIOC_BASE+SAM_GPIO_ODERC_OFFSET)
+#define SAM_GPIOC_ODERT (SAM_GPIOC_BASE+SAM_GPIO_ODERT_OFFSET)
+
+#define SAM_GPIOC_OVR (SAM_GPIOC_BASE+SAM_GPIO_OVR_OFFSET)
+#define SAM_GPIOC_OVRS (SAM_GPIOC_BASE+SAM_GPIO_OVRS_OFFSET)
+#define SAM_GPIOC_OVRC (SAM_GPIOC_BASE+SAM_GPIO_OVRC_OFFSET)
+#define SAM_GPIOC_OVRT (SAM_GPIOC_BASE+SAM_GPIO_OVRT_OFFSET)
+
+#define SAM_GPIOC_PVR (SAM_GPIOC_BASE+SAM_GPIO_PVR_OFFSET)
+
+#define SAM_GPIOC_PUER (SAM_GPIOC_BASE+SAM_GPIO_PUER_OFFSET)
+#define SAM_GPIOC_PUERS (SAM_GPIOC_BASE+SAM_GPIO_PUERS_OFFSET)
+#define SAM_GPIOC_PUERC (SAM_GPIOC_BASE+SAM_GPIO_PUERC_OFFSET)
+#define SAM_GPIOC_PUERT (SAM_GPIOC_BASE+SAM_GPIO_PUERT_OFFSET)
+
+#define SAM_GPIOC_PDER (SAM_GPIOC_BASE+SAM_GPIO_PDER_OFFSET)
+#define SAM_GPIOC_PDERS (SAM_GPIOC_BASE+SAM_GPIO_PDERS_OFFSET)
+#define SAM_GPIOC_PDERC (SAM_GPIOC_BASE+SAM_GPIO_PDERC_OFFSET)
+#define SAM_GPIOC_PDERT (SAM_GPIOC_BASE+SAM_GPIO_PDERT_OFFSET)
+
+#define SAM_GPIOC_IER (SAM_GPIOC_BASE+SAM_GPIO_IER_OFFSET)
+#define SAM_GPIOC_IERS (SAM_GPIOC_BASE+SAM_GPIO_IERS_OFFSET)
+#define SAM_GPIOC_IERC (SAM_GPIOC_BASE+SAM_GPIO_IERC_OFFSET)
+#define SAM_GPIOC_IERT (SAM_GPIOC_BASE+SAM_GPIO_IERT_OFFSET)
+
+#define SAM_GPIOC_IMR0 (SAM_GPIOC_BASE+SAM_GPIO_IMR0_OFFSET)
+#define SAM_GPIOC_IMR0S (SAM_GPIOC_BASE+SAM_GPIO_IMR0S_OFFSET)
+#define SAM_GPIOC_IMR0C (SAM_GPIOC_BASE+SAM_GPIO_IMR0C_OFFSET)
+#define SAM_GPIOC_IMR0T (SAM_GPIOC_BASE+SAM_GPIO_IMR0T_OFFSET)
+
+#define SAM_GPIOC_IMR1 (SAM_GPIOC_BASE+SAM_GPIO_IMR1_OFFSET)
+#define SAM_GPIOC_IMR1S (SAM_GPIOC_BASE+SAM_GPIO_IMR1S_OFFSET)
+#define SAM_GPIOC_IMR1C (SAM_GPIOC_BASE+SAM_GPIO_IMR1C_OFFSET)
+#define SAM_GPIOC_IMR1T (SAM_GPIOC_BASE+SAM_GPIO_IMR1T_OFFSET)
+
+#define SAM_GPIOC_GFER (SAM_GPIOC_BASE+SAM_GPIO_GFER_OFFSET)
+#define SAM_GPIOC_GFERS (SAM_GPIOC_BASE+SAM_GPIO_GFERS_OFFSET)
+#define SAM_GPIOC_GFERC (SAM_GPIOC_BASE+SAM_GPIO_GFERC_OFFSET)
+#define SAM_GPIOC_GFERT (SAM_GPIOC_BASE+SAM_GPIO_GFERT_OFFSET)
+
+#define SAM_GPIOC_IFR (SAM_GPIOC_BASE+SAM_GPIO_IFR_OFFSET)
+#define SAM_GPIOC_IFRC (SAM_GPIOC_BASE+SAM_GPIO_IFRC_OFFSET)
+
+#define SAM_GPIOC_ODCR0 (SAM_GPIOC_BASE+SAM_GPIO_ODCR0_OFFSET)
+#define SAM_GPIOC_ODCR0S (SAM_GPIOC_BASE+SAM_GPIO_ODCR0S_OFFSET)
+#define SAM_GPIOC_ODCR0C (SAM_GPIOC_BASE+SAM_GPIO_ODCR0C_OFFSET)
+#define SAM_GPIOC_ODCR0T (SAM_GPIOC_BASE+SAM_GPIO_ODCR0T_OFFSET)
+
+#define SAM_GPIOC_ODCR1 (SAM_GPIOC_BASE+SAM_GPIO_ODCR1_OFFSET)
+#define SAM_GPIOC_ODCR1S (SAM_GPIOC_BASE+SAM_GPIO_ODCR1S_OFFSET)
+#define SAM_GPIOC_ODCR1C (SAM_GPIOC_BASE+SAM_GPIO_ODCR1C_OFFSET)
+#define SAM_GPIOC_ODCR1T (SAM_GPIOC_BASE+SAM_GPIO_ODCR1T_OFFSET)
+
+#define SAM_GPIOC_OSRR0 (SAM_GPIOC_BASE+SAM_GPIO_OSRR0_OFFSET)
+#define SAM_GPIOC_OSRR0S (SAM_GPIOC_BASE+SAM_GPIO_OSRR0S_OFFSET)
+#define SAM_GPIOC_OSRR0C (SAM_GPIOC_BASE+SAM_GPIO_OSRR0C_OFFSET)
+#define SAM_GPIOC_OSRR0T (SAM_GPIOC_BASE+SAM_GPIO_OSRR0T_OFFSET)
+
+#define SAM_GPIOC_STER (SAM_GPIOC_BASE+SAM_GPIO_STER_OFFSET)
+#define SAM_GPIOC_STERS (SAM_GPIOC_BASE+SAM_GPIO_STERS_OFFSET)
+#define SAM_GPIOC_STERC (SAM_GPIOC_BASE+SAM_GPIO_STERC_OFFSET)
+#define SAM_GPIOC_STERT (SAM_GPIOC_BASE+SAM_GPIO_STERT_OFFSET)
+
+#define SAM_GPIOC_EVER (SAM_GPIOC_BASE+SAM_GPIO_EVER_OFFSET)
+#define SAM_GPIOC_EVERS (SAM_GPIOC_BASE+SAM_GPIO_EVERS_OFFSET)
+#define SAM_GPIOC_EVERC (SAM_GPIOC_BASE+SAM_GPIO_EVERC_OFFSET)
+#define SAM_GPIOC_EVERT (SAM_GPIOC_BASE+SAM_GPIO_EVERT_OFFSET)
+
+#define SAM_GPIOC_PARAMETER (SAM_GPIOC_BASE+SAM_GPIO_PARAMETER_OFFSET)
+#define SAM_GPIOC_VERSION (SAM_GPIOC_BASE+SAM_GPIO_VERSION_OFFSET)
/* GPIO register bit definitions ********************************************************/
diff --git a/nuttx/arch/arm/src/sam34/chip/sam4l_memorymap.h b/nuttx/arch/arm/src/sam34/chip/sam4l_memorymap.h
index 0a3acdcc2..c85e6b4b8 100644
--- a/nuttx/arch/arm/src/sam34/chip/sam4l_memorymap.h
+++ b/nuttx/arch/arm/src/sam34/chip/sam4l_memorymap.h
@@ -109,7 +109,7 @@
#define SAM_FLASHCALW_BASE 0x400a0000 /* 0x400a0000-0x400a03ff: FLASHCALW */
#define SAM_PICOCACHE_BASE 0x400a0400 /* 0x400a0400-0x400a0fff: PICOCACHE */
-#define SAM_HMATRIX_BASE 0x400a1000 /* 0x400a1000-0x400a1fff: PICOCACHE */
+#define SAM_HMATRIX_BASE 0x400a1000 /* 0x400a1000-0x400a1fff: HMATRIX */
#define SAM_PDCA_BASE 0x400a2000 /* 0x400a2000-0x400a2fff: Peripheral DMA Controller */
#define SAM_SMAP_BASE 0x400a3000 /* 0x400a3000-0x400a3fff: SMAP */
#define SAM_CRCCU_BASE 0x400a4000 /* 0x400a4000-0x400a4fff: CRC Calculation Unit */
diff --git a/nuttx/arch/arm/src/sam34/chip/sam4l_pm.h b/nuttx/arch/arm/src/sam34/chip/sam4l_pm.h
new file mode 100644
index 000000000..ba78b3a95
--- /dev/null
+++ b/nuttx/arch/arm/src/sam34/chip/sam4l_pm.h
@@ -0,0 +1,351 @@
+/************************************************************************************
+ * arch/avr/src/sam34/sam4l_pm.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * This file is derived from nuttx/arch/avr/src/at32uc3/at32uc3_pm.h.
+ *
+ * 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_SAM34_CHIP_SAM4L_PM_H
+#define __ARCH_ARM_SRC_SAM34_CHIP_SAM4L_PM_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/sam_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define SAM_PM_MCCTRL_OFFSET 0x0000 /* Main Clock Control Register */
+#define SAM_PM_CPUSEL_OFFSET 0x0004 /* CPU Clock Select Register */
+#define SAM_PM_PBASEL_OFFSET 0x000c /* PBA Clock Select Register */
+#define SAM_PM_PBBSEL_OFFSET 0x0010 /* PBB Clock Select Register */
+#define SAM_PM_PBCSEL_OFFSET 0x0014 /* PBC Clock Select Register */
+#define SAM_PM_PBDSEL_OFFSET 0x0018 /* PBD Clock Select Register */
+#define SAM_PM_CPUMASK_OFFSET 0x0020 /* CPU Mask Register */
+#define SAM_PM_HSBMASK_OFFSET 0x0024 /* HSB Mask Register */
+#define SAM_PM_PBAMASK_OFFSET 0x0028 /* PBA Mask Register */
+#define SAM_PM_PBBMASK_OFFSET 0x002c /* PBB Mask Register */
+#define SAM_PM_PBCMASK_OFFSET 0x0030 /* PBC Mask Register */
+#define SAM_PM_PBDMASK_OFFSET 0x0034 /* PBD Mask Register */
+#define SAM_PM_PBADIVMASK_OFFSET 0x0040 /* PBA Divided Mask */
+#define SAM_PM_CFDCTRL_OFFSET 0x0054 /* Clock Failure Detector Control */
+#define SAM_PM_UNLOCK_OFFSET 0x0058 /* Unlock Register */
+#define SAM_PM_IER_OFFSET 0x00c0 /* Interrupt Enable Register */
+#define SAM_PM_IDR_OFFSET 0x00c4 /* Interrupt Disable Register */
+#define SAM_PM_IMR_OFFSET 0x00c8 /* Interrupt Mask Register */
+#define SAM_PM_ISR_OFFSET 0x00cc /* Interrupt Status Register */
+#define SAM_PM_ICR_OFFSET 0x00d0 /* Interrupt Clear Register */
+#define SAM_PM_SR_OFFSET 0x00d4 /* Status Register Register */
+#define SAM_PM_PPCR_OFFSET 0x0160 /* Peripheral Power Control Register */
+#define SAM_PM_RCAUSE_OFFSET 0x0180 /* Reset Cause Register */
+#define SAM_PM_WCAUSE_OFFSET 0x0184 /* Wake Cause Register */
+#define SAM_PM_AWEN_OFFSET 0x0188 /* Asynchronous Wake Up Enable Register */
+#define SAM_PM_PROTCTRL_OFFSET 0x018c /* Protection Control Register */
+#define SAM_PM_FASTSLEEP_OFFSET 0x0194 /* Fast Sleep Register */
+#define SAM_PM_CONFIG_OFFSET 0x03f8 /* Configuration Register */
+#define SAM_PM_VERSION_OFFSET 0x03fc /* Version Register */
+
+/* Register Addresses ***************************************************************/
+
+#define SAM_PM_MCCTRL (SAM_PM_BASE+SAM_PM_MCCTRL_OFFSET)
+#define SAM_PM_CPUSEL (SAM_PM_BASE+SAM_PM_CPUSEL_OFFSET)
+#define SAM_PM_PBASEL (SAM_PM_BASE+SAM_PM_PBASEL_OFFSET)
+#define SAM_PM_PBBSEL (SAM_PM_BASE+SAM_PM_PBBSEL_OFFSET)
+#define SAM_PM_PBCSEL (SAM_PM_BASE+SAM_PM_PBCSEL_OFFSET)
+#define SAM_PM_PBDSEL (SAM_PM_BASE+SAM_PM_PBDSEL_OFFSET)
+#define SAM_PM_CPUMASK (SAM_PM_BASE+SAM_PM_CPUMASK_OFFSET)
+#define SAM_PM_HSBMASK (SAM_PM_BASE+SAM_PM_HSBMASK_OFFSET)
+#define SAM_PM_PBAMASK (SAM_PM_BASE+SAM_PM_PBAMASK_OFFSET)
+#define SAM_PM_PBBMASK (SAM_PM_BASE+SAM_PM_PBBMASK_OFFSET)
+#define SAM_PM_PBCMASK (SAM_PM_BASE+SAM_PM_PBCMASK_OFFSET)
+#define SAM_PM_PBDMASK (SAM_PM_BASE+SAM_PM_PBDMASK_OFFSET)
+#define SAM_PM_PBADIVMASK (SAM_PM_BASE+SAM_PM_PBADIVMASK_OFFSET)
+#define SAM_PM_CFDCTRL (SAM_PM_BASE+SAM_PM_CFDCTRL_OFFSET)
+#define SAM_PM_UNLOCK (SAM_PM_BASE+SAM_PM_UNLOCK_OFFSET)
+#define SAM_PM_IER (SAM_PM_BASE+SAM_PM_IER_OFFSET)
+#define SAM_PM_IDR (SAM_PM_BASE+SAM_PM_IDR_OFFSET)
+#define SAM_PM_IMR (SAM_PM_BASE+SAM_PM_IMR_OFFSET)
+#define SAM_PM_ISR (SAM_PM_BASE+SAM_PM_ISR_OFFSET)
+#define SAM_PM_ICR (SAM_PM_BASE+SAM_PM_ICR_OFFSET)
+#define SAM_PM_SR (SAM_PM_BASE+SAM_PM_SR_OFFSET)
+#define SAM_PM_PPCR (SAM_PM_BASE+SAM_PM_PPCR_OFFSET)
+#define SAM_PM_RCAUSE (SAM_PM_BASE+SAM_PM_RCAUSE_OFFSET)
+#define SAM_PM_WCAUSE (SAM_PM_BASE+SAM_PM_WCAUSE_OFFSET)
+#define SAM_PM_AWEN (SAM_PM_BASE+SAM_PM_AWEN_OFFSET)
+#define SAM_PM_PROTCTRL (SAM_PM_BASE+SAM_PM_PROTCTRL_OFFSET)
+#define SAM_PM_FASTSLEEP (SAM_PM_BASE+SAM_PM_FASTSLEEP_OFFSET)
+#define SAM_PM_CONFIG (SAM_PM_BASE+SAM_PM_CONFIG_OFFSET)
+#define SAM_PM_VERSION (SAM_PM_BASE+SAM_PM_VERSION_OFFSET)
+
+/* Register Bit-field Definitions ***************************************************/
+
+/* Main Clock Control Register Bit-field Definitions */
+
+#define PM_MCCTRL_MCSEL_SHIFT (0) /* Bits 0-2: Main Clock Select */
+#define PM_MCCTRL_MCSEL_MASK (7 << PM_MCCTRL_MCSEL_SHIFT)
+# define PM_MCCTRL_MCSEL_RCSYS (0 << PM_MCCTRL_MCSEL_SHIFT) /* System RC oscillator */
+# define PM_MCCTRL_MCSEL_OSC0 (1 << PM_MCCTRL_MCSEL_SHIFT) /* Oscillator0 */
+# define PM_MCCTRL_MCSEL_PLL (2 << PM_MCCTRL_MCSEL_SHIFT) /* PLL */
+# define PM_MCCTRL_MCSEL_DFLL (3 << PM_MCCTRL_MCSEL_SHIFT) /* DFLL */
+# define PM_MCCTRL_MCSEL_RC80M (4 << PM_MCCTRL_MCSEL_SHIFT) /* 80MHz RC oscillator */
+# define PM_MCCTRL_MCSEL_RCFAST (5 << PM_MCCTRL_MCSEL_SHIFT) /* 4/8/12 MHz RC oscillator */
+# define PM_MCCTRL_MCSEL_RC1M (6 << PM_MCCTRL_MCSEL_SHIFT) /* 1 MHz RC oscillator */
+
+/* CPU Clock Select Register Bit-field Definitions */
+
+#define PM_CPUSEL_SHIFT (0) /* Bits 0-2: CPU Clock Select */
+#define PM_CPUSEL_MASK (7 << PM_CPUSEL_SHIFT)
+# define PM_CPUSEL(n) ((n) << PM_CPUSEL_SHIFT)
+#define PM_CPUSEL_DIV (1 << 7) /* Bit 7: CPU Division */
+
+/* PBA/PBB/PBC/PBD Clock Select Register Bit-field Definitions */
+
+#define PM_PBSEL_SHIFT (0) /* Bits 0-2: PBx Clock Select */
+#define PM_PBSEL_MASK (7 << PM_PBSEL_SHIFT)
+# define PM_PBSEL(n) ((n) << PM_PBSEL_SHIFT)
+#define PM_PBSEL_DIV (1 << 7) /* Bit 7: PBx Division */
+
+/* CPU Mask Register Bit-field Definitions */
+
+#define PM_CPUMASK_OCD (1 << 0) /* Bit 0: OCD */
+
+/* HSB Mask Register Bit-field Definitions */
+
+#define PM_HSBMASK_PDCA (1 << 0) /* Bit 0: PDCA */
+#define PM_HSBMASK_FLASHCALW (1 << 1) /* Bit 1: FLASHCALW */
+#define PM_HSBMASK_HRAMC1 (1 << 2) /* Bit 2: HRAMC1 (picoCache RAM) */
+#define PM_HSBMASK_USBC (1 << 3) /* Bit 3: USBC */
+#define PM_HSBMASK_CRCCU (1 << 4) /* Bit 4: CRCCU */
+#define PM_HSBMASK_APBA (1 << 5) /* Bit 5: APBA bridge */
+#define PM_HSBMASK_APBB (1 << 6) /* Bit 5: APBB bridge */
+#define PM_HSBMASK_APBC (1 << 7) /* Bit 5: APBC bridge */
+#define PM_HSBMASK_APBD (1 << 8) /* Bit 5: APBD bridge */
+#define PM_HSBMASK_AESA (1 << 9) /* Bit 5: AESA */
+
+/* PBA Mask Register Bit-field Definitions */
+
+#define PM_PBAMASK_IISC (1 << 0) /* Bit 0: IISC */
+#define PM_PBAMASK_SPI (1 << 1) /* Bit 1: SPI */
+#define PM_PBAMASK_TC0 (1 << 2) /* Bit 2: TC0 */
+#define PM_PBAMASK_TC1 (1 << 3) /* Bit 3: TC1 */
+#define PM_PBAMASK_TWIM0 (1 << 4) /* Bit 4: TWIM0 */
+#define PM_PBAMASK_TWIS0 (1 << 5) /* Bit 5: TWIS0 */
+#define PM_PBAMASK_TWIM1 (1 << 6) /* Bit 6: TWIM1 */
+#define PM_PBAMASK_TWIS1 (1 << 7) /* Bit 7: TWIS1 */
+#define PM_PBAMASK_USART0 (1 << 8) /* Bit 8: USART0 */
+#define PM_PBAMASK_USART1 (1 << 9) /* Bit 9: USART1 */
+#define PM_PBAMASK_USART2 (1 << 10) /* Bit 10: USART2 */
+#define PM_PBAMASK_USART3 (1 << 11) /* Bit 11: USART3 */
+#define PM_PBAMASK_ADCIFE (1 << 12) /* Bit 12: ADCIFE */
+#define PM_PBAMASK_DACC (1 << 13) /* Bit 13: DACC */
+#define PM_PBAMASK_ACIFC (1 << 14) /* Bit 14: ACIFC */
+#define PM_PBAMASK_GLOC (1 << 15) /* Bit 15: GLOC */
+#define PM_PBAMASK_ABDACB (1 << 16) /* Bit 16: ABDACB */
+#define PM_PBAMASK_TRNG (1 << 17) /* Bit 17: TRNG */
+#define PM_PBAMASK_PARC (1 << 18) /* Bit 18: PARC */
+#define PM_PBAMASK_CATB (1 << 19) /* Bit 19: CATB */
+#define PM_PBAMASK_TWIM2 (1 << 21) /* Bit 21: TWIM2 */
+#define PM_PBAMASK_TWIM3 (1 << 22) /* Bit 22: TWIM3 */
+#define PM_PBAMASK_LCDCA (1 << 23) /* Bit 23: LCDCA*/
+
+/* These are the PBMA peripherals that use divided clocks enabled in the
+ * PBADIVMASK register.
+ */
+
+#define PM_PBAMASK_TIMERS (PM_PBAMASK_TC0 | PM_PBAMASK_TC1)
+#define PM_PBAMASK_UARTS (PM_PBAMASK_USART0 | PM_PBAMASK_USART1 | \
+ PM_PBAMASK_USART2 | PM_PBAMASK_USART3)
+
+/* PBB Mask Register Bit-field Definitions */
+
+#define PM_PBBMASK_FLASHCALW (1 << 0) /* Bit 0: FLASHCALW */
+#define PM_PBBMASK_HRAMC1 (1 << 1) /* Bit 1: HRAMC1 */
+#define PM_PBBMASK_HMATRIX (1 << 2) /* Bit 2: HMATRIX */
+#define PM_PBBMASK_PDCA (1 << 3) /* Bit 3: PDCA */
+#define PM_PBBMASK_CRCCU (1 << 4) /* Bit 4: CRCCU */
+#define PM_PBBMASK_USBC (1 << 5) /* Bit 5: USBC */
+#define PM_PBBMASK_PEVC (1 << 6) /* Bit 6: PEVC */
+
+/* PBC Mask Register Bit-field Definitions */
+
+#define PM_PBCMASK_PM (1 << 0) /* Bit 0: PM */
+#define PM_PBCMASK_CHIPID (1 << 1) /* Bit 1: CHIPID */
+#define PM_PBCMASK_SCIF (1 << 2) /* Bit 2: SCIF */
+#define PM_PBCMASK_FREQM (1 << 3) /* Bit 3: FREQM */
+#define PM_PBCMASK_GPIO (1 << 4) /* Bit 4: GPIO */
+
+/* PBD Mask Register Bit-field Definitions */
+
+#define PM_PBDMASK_BPM (1 << 0) /* Bit 0: BPM */
+#define PM_PBDMASK_BSCIF (1 << 1) /* Bit 1: BSCIF */
+#define PM_PBDMASK_AST (1 << 2) /* Bit 2: AST */
+#define PM_PBDMASK_WDT (1 << 3) /* Bit 3: WDT */
+#define PM_PBDMASK_EIC (1 << 4) /* Bit 4: EIC */
+#define PM_PBDMASK_PICOUART (1 << 5) /* Bit 5: PICOUART */
+
+/* PBA Divided Mask */
+
+#define PM_PBADIVMASK_TIMER_CLOCK2 (1 << 0) /* Bit 0: TIMER_CLOCK2 (TC0-1) */
+#define PM_PBADIVMASK_CLK_USART (1 << 2) /* Bit 2: CLK_USART/DIV (USART0-3) */
+#define PM_PBADIVMASK_TIMER_CLOCK3 (1 << 2) /* Bit 2: TIMER_CLOCK3 (TC0-1) */
+#define PM_PBADIVMASK_TIMER_CLOCK4 (1 << 4) /* Bit 4: TIMER_CLOCK4 (TC0-1) */
+#define PM_PBADIVMASK_TIMER_CLOCK5 (1 << 6) /* Bit 5: TIMER_CLOCK5 (TC0-1) */
+
+#define PM_PBADIVMASK_TIMER_CLOCKS \
+ (PM_PBADIVMASK_TIMER_CLOCK2 | PM_PBADIVMASK_TIMER_CLOCK3 | \
+ PM_PBADIVMASK_TIMER_CLOCK4 | PM_PBADIVMASK_TIMER_CLOCK5)
+
+/* Clock Failure Detector Control */
+
+#define PM_CFDCTRL_CFDEN (1 << 0) /* Bit 0: Clock Failure Detection Enable */
+#define PM_CFDCTRL_SFV (1 << 31) /* Bit 31: Store Final Value */
+
+/* Unlock Register */
+
+#define PM_UNLOCK_ADDR_SHIFT (0) /* Bits 0-9: Unlock Address */
+#define PM_UNLOCK_ADDR_MASK (0x3ff << PM_UNLOCK_ADDR_SHIFT)
+# define PM_UNLOCK_ADDR(n) ((n) << PM_UNLOCK_ADDR_SHIFT)
+#define PM_UNLOCK_KEY_SHIFT (24) /* Bits 24-31: Unlock Key */
+#define PM_UNLOCK_KEY_MASK (0xff << PM_UNLOCK_KEY_SHIFT)
+# define PM_UNLOCK_KEY(n) ((n) << PM_UNLOCK_KEY_SHIFT)
+
+/* Interrupt Enable Register Bit-field Definitions */
+/* Interrupt Disable Register Bit-field Definitions */
+/* Interrupt Mask Register Bit-field Definitions */
+/* Interrupt Status Register Bit-field Definitions */
+/* Interrupt Clear Register Bit-field Definitions */
+/* Status Register Register */
+
+#define PM_INT_CFD (1 << 0) /* Bit 0: CFD */
+#define PM_INT_CKRDY (1 << 5) /* Bit 5: CKRDY */
+#define PM_INT_WAKE (1 << 8) /* Bit 8: WAKE */
+
+/* Peripheral Power Control Register */
+
+#define PM_PPCR_RSTPUN (1 << 0) /* Bit 0: Reset Pullup */
+#define PM_PPCR_CATBRCMASK (1 << 1) /* Bit 1: CAT Request Clock Mask */
+#define PM_PPCR_ACIFCRCMASK (1 << 2) /* Bit 2: ACIFC Request Clock Mask */
+#define PM_PPCR_ASTRCMASK (1 << 3) /* Bit 3: AST Request Clock Mask */
+#define PM_PPCR_TWIS0RCMASK (1 << 4) /* Bit 4: TWIS0 Request Clock Mask */
+#define PM_PPCR_TWIS1RCMASK (1 << 5) /* Bit 5: TWIS1 Request Clock Mask */
+#define PM_PPCR_PEVCRCMASK (1 << 6) /* Bit 6: PEVC Request Clock Mask */
+#define PM_PPCR_ADCIFERCMASK (1 << 7) /* Bit 7: ADCIFE Request Clock Mask */
+#define PM_PPCR_VREGRCMASK (1 << 8) /* Bit 8: VREG Request Clock Mask */
+#define PM_PPCR_FWBGREF (1 << 9) /* Bit 9: Flash Wait BGREF */
+#define PM_PPCR_FWBOD18 (1 << 10) /* Bit 10: Flash Wait BOD18 */
+
+/* Reset Cause Register */
+
+#define PM_RCAUSE_POR (1 << 0) /* Bit 0: Power-on Reset */
+#define PM_RCAUSE_BOD (1 << 1) /* Bit 1: Brown-out Reset */
+#define PM_RCAUSE_EXT (1 << 2) /* Bit 2: External Reset Pin */
+#define PM_RCAUSE_WDT (1 << 3) /* Bit 3: Watchdog Reset */
+#define PM_RCAUSE_BKUP (1 << 6) /* Bit 6: Backup reset */
+#define PM_RCAUSE_OCDRST (1 << 8) /* Bit 8: OCD Reset */
+#define PM_RCAUSE_POR33 (1 << 10) /* Bit 10: Power-on 3.3v Reset */
+#define PM_RCAUSE_BOD33 (1 << 13) /* Bit 13: Brown-out 3.3v Reset */
+
+/* Wake Cause Register */
+
+#define PM_WCAUSE_TWIS0 (1 << 0) /* Bit 0: 0 TWI Slave 0 */
+#define PM_WCAUSE_TWIS1 (1 << 1) /* Bit 1: 1 TWI Slave 1 */
+#define PM_WCAUSE_USBC (1 << 2) /* Bit 2: 2 USBC */
+#define PM_WCAUSE_PSOK (1 << 3) /* Bit 3: 3 PSOK */
+#define PM_WCAUSE_BOD18 (1 << 4) /* Bit 4: 4 BOD18 IRQ */
+#define PM_WCAUSE_BOD33 (1 << 5) /* Bit 5: 5 BOD33 IRQ */
+#define PM_WCAUSE_PICOUART (1 << 6) /* Bit 6: 6 PICOUART */
+#define PM_WCAUSE_LCDCA (1 << 7) /* Bit 7: 7 LCDCA */
+#define PM_WCAUSE_EIC (1 << 16) /* Bit 16: 16 EIC */
+#define PM_WCAUSE_AST (1 << 17) /* Bit 17: 17 AST */
+
+/* Asynchronous Wake Up Enable Register Bit-field Definitions */
+
+#define PM_AWEN_TWIS0 (1 << 0) /* Bit 0: TWI Slave 0 */
+#define PM_AWEN_TWIS1 (1 << 1) /* Bit 1: TWI Slave 1 */
+#define PM_AWEN_USBC (1 << 2) /* Bit 2: USBC */
+#define PM_AWEN_PSOK (1 << 3) /* Bit 3: PSOK */
+#define PM_AWEN_BOD18 (1 << 4) /* Bit 4: BOD18 IRQ */
+#define PM_AWEN_BOD33 (1 << 5) /* Bit 5: BOD33 IRQ */
+#define PM_AWEN_PICOUART (1 << 6) /* Bit 6: PICOUART */
+#define PM_AWEN_LCDCA (1 << 7) /* Bit 7: LCDCA */
+
+/* Protection Control Register */
+
+/* Fast Sleep Register */
+#define PM_FASTSLEEP_
+#define PM_FASTSLEEP_OSC (1 << 0) /* Bit 0: Oscillator */
+#define PM_FASTSLEEP_PLL (1 << 0) /* Bit 0: PLL */
+#define PM_FASTSLEEP_FASTRCOSC_SHIFT (0) /* Bits 0-9: FASTRCOSC */
+#define PM_FASTSLEEP_FASTRCOSC_MASK (31 << PM_FASTSLEEP_FASTRCOSC_SHIFT)
+# define PM_FASTSLEEP_RC80 (1 << PM_FASTSLEEP_FASTRCOSC_SHIFT)
+# define PM_FASTSLEEP_RCFAST (2 << PM_FASTSLEEP_FASTRCOSC_SHIFT)
+# define PM_FASTSLEEP_RC1M (4 << PM_FASTSLEEP_FASTRCOSC_SHIFT)
+#define PM_FASTSLEEP_DFLL (1 << 0) /* Bit 0: DFLL */
+
+/* Configuration Register */
+
+#define PM_CONFIG_PBA (1 << 0) /* Bit 0: APBA Implemented */
+#define PM_CONFIG_PBB (1 << 1) /* Bit 1: APBB Implemented */
+#define PM_CONFIG_PBC (1 << 2) /* Bit 2: APBC Implemented */
+#define PM_CONFIG_PBD (1 << 3) /* Bit 3: APBD Implemented */
+#define PM_CONFIG_HSBPEVC (1 << 7) /* Bit 7: HSB PEVC Clock Implemented */
+
+/* Version Register */
+
+#define PM_VERSION_SHIFT (0) /* Bits 0-11: Version Number */
+#define PM_VERSION_MASK (0xfff << PM_VERSION_VERSION_SHIFT)
+#define PM_VERSION_VARIANT_SHIFT (16) /* Bits 16-19: Variant Number */
+#define PM_VERSION_VARIANT_MASK (15 << PM_VERSION_VARIANT_SHIFT)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_SAM34_CHIP_SAM4L_PM_H */
+
diff --git a/nuttx/arch/arm/src/sam34/sam_clockconfig.c b/nuttx/arch/arm/src/sam34/sam3u_clockconfig.c
index 8a3988a40..374e4868a 100644
--- a/nuttx/arch/arm/src/sam34/sam_clockconfig.c
+++ b/nuttx/arch/arm/src/sam34/sam3u_clockconfig.c
@@ -1,6 +1,5 @@
/****************************************************************************
- * arch/arm/src/sam34/sam_clockconfig.c
- * arch/arm/src/chip/sam_clockconfig.c
+ * arch/arm/src/chip/sam3u_clockconfig.c
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -51,9 +50,9 @@
#include "sam_clockconfig.h"
#include "chip/sam_pmc.h"
-#include "chip/sam_eefc.h"
+#include "chip/sam3u_eefc.h"
#include "chip/sam_wdt.h"
-#include "chip/sam_supc.h"
+#include "chip/sam3u_supc.h"
#include "chip/sam_matrix.h"
/****************************************************************************
diff --git a/nuttx/arch/arm/src/sam34/sam4l_clockconfig.c b/nuttx/arch/arm/src/sam34/sam4l_clockconfig.c
new file mode 100644
index 000000000..2857c7fb1
--- /dev/null
+++ b/nuttx/arch/arm/src/sam34/sam4l_clockconfig.c
@@ -0,0 +1,571 @@
+/****************************************************************************
+ * arch/avr/src/sam34/sam4l_clockconfig.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * This file is derived from nuttx/arch/avr/src/at32uc3/at32uc3_clkinit.c
+ *
+ * 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/irq.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+
+#include "up_internal.h"
+#include "chip/sam4l_pm.h"
+#include "chip/sam4l_flashcalw.h"
+
+#include "sam_clockconfig.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+#if defined(SAM_CLOCK_OSC0) || \
+ (defined (SAM_CLOCK_PLL0) && defined(SAM_CLOCK_PLL0_OSC0)) || \
+ (defined (SAM_CLOCK_PLL1) && defined(SAM_CLOCK_PLL1_OSC0))
+# define NEED_OSC0
+#endif
+
+#if defined(SAM_CLOCK_OSC1) || \
+ (defined (SAM_CLOCK_PLL0) && defined(SAM_CLOCK_PLL0_OSC1)) || \
+ (defined (SAM_CLOCK_PLL1) && defined(SAM_CLOCK_PLL1_OSC1))
+# define NEED_OSC1
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_picocache
+ *
+ * Description:
+ * Initialiaze the PICOCACHE.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SAM_PICOCACHE
+static inline void sam_picocache(void)
+{
+ /* Enable clocking to the PICOCACHE */
+
+ sam_hsb_enableperipheral(PM_HSBMASK_HRAMC1);
+ sam_pbb_enableperipheral(PM_PBBMASK_HRAMC1);
+
+ /* Enable the PICOCACHE and wait for it to become ready */
+
+ putreg32(PICOCACHE_CTRL_CEN, SAM_PICOCACHE_CTRL);
+ while ((getreg32(SAM_PICOCACHE_SR) & PICOCACHE_SR_CSTS) == 0);
+}
+#else
+# define sam_picocache()
+#endif
+
+/****************************************************************************
+ * Name: sam_enableosc32
+ *
+ * Description:
+ * Initialiaze the 32KHz oscillator. This oscillator is used by the RTC
+ * logic to provide the sysem timer.
+ *
+ ****************************************************************************/
+
+#ifdef SAM_CLOCK_OSC32
+static inline void sam_enableosc32(void)
+{
+ uint32_t regval;
+
+ /* Select the 32KHz oscillator crystal */
+
+ regval = getreg32(SAM_PM_OSCCTRL32);
+ regval &= ~PM_OSCCTRL32_MODE_MASK;
+ regval |= PM_OSCCTRL32_MODE_XTAL;
+ putreg32(regval, SAM_PM_OSCCTRL32);
+
+ /* Enable the 32-kHz clock */
+
+ regval = getreg32(SAM_PM_OSCCTRL32);
+ regval &= ~PM_OSCCTRL32_STARTUP_MASK;
+ regval |= PM_OSCCTRL32_EN|(SAM_OSC32STARTUP << PM_OSCCTRL32_STARTUP_SHIFT);
+ putreg32(regval, SAM_PM_OSCCTRL32);
+}
+#endif
+
+/****************************************************************************
+ * Name: sam_enableosc0
+ *
+ * Description:
+ * Initialiaze OSC0 settings per the definitions in the board.h file.
+ *
+ ****************************************************************************/
+
+#ifdef NEED_OSC0
+static inline void sam_enableosc0(void)
+{
+ uint32_t regval;
+
+ /* Enable OSC0 in the correct crystal mode by setting the mode value in OSCCTRL0 */
+
+ regval = getreg32(SAM_PM_OSCCTRL0);
+ regval &= ~PM_OSCCTRL_MODE_MASK;
+#if SAM_FOSC0 < 900000
+ regval |= PM_OSCCTRL_MODE_XTALp9; /* Crystal XIN 0.4-0.9MHz */
+#elif SAM_FOSC0 < 3000000
+ regval |= PM_OSCCTRL_MODE_XTAL3; /* Crystal XIN 0.9-3.0MHz */
+#elif SAM_FOSC0 < 8000000
+ regval |= PM_OSCCTRL_MODE_XTAL8; /* Crystal XIN 3.0-8.0MHz */
+#else
+ regval |= PM_OSCCTRL_MODE_XTALHI; /* Crystal XIN above 8.0MHz */
+#endif
+ putreg32(regval, SAM_PM_OSCCTRL0);
+
+ /* Enable OSC0 using the startup time provided in board.h. This startup time
+ * is critical and depends on the characteristics of the crystal.
+ */
+
+ regval = getreg32(SAM_PM_OSCCTRL0);
+ regval &= ~PM_OSCCTRL_STARTUP_MASK;
+ regval |= (SAM_OSC0STARTUP << PM_OSCCTRL_STARTUP_SHIFT);
+ putreg32(regval, SAM_PM_OSCCTRL0);
+
+ /* Enable OSC0 */
+
+ regval = getreg32(SAM_PM_MCCTRL);
+ regval |= PM_MCCTRL_OSC0EN;
+ putreg32(regval, SAM_PM_MCCTRL);
+
+ /* Wait for OSC0 to be ready */
+
+ while ((getreg32(SAM_PM_POSCSR) & PM_POSCSR_OSC0RDY) == 0);
+}
+#endif
+
+/****************************************************************************
+ * Name: sam_enableosc1
+ *
+ * Description:
+ * Initialiaze OSC0 settings per the definitions in the board.h file.
+ *
+ ****************************************************************************/
+
+#ifdef NEED_OSC1
+static inline void sam_enableosc1(void)
+{
+ uint32_t regval;
+
+ /* Enable OSC1 in the correct crystal mode by setting the mode value in OSCCTRL1 */
+
+ regval = getreg32(SAM_PM_OSCCTRL1);
+ regval &= ~PM_OSCCTRL_MODE_MASK;
+#if SAM_FOSC1 < 900000
+ regval |= PM_OSCCTRL_MODE_XTALp9; /* Crystal XIN 0.4-0.9MHz */
+#elif SAM_FOSC1 < 3000000
+ regval |= PM_OSCCTRL_MODE_XTAL3; /* Crystal XIN 0.9-3.0MHz */
+#elif SAM_FOSC1 < 8000000
+ regval |= PM_OSCCTRL_MODE_XTAL8; /* Crystal XIN 3.0-8.0MHz */
+#else
+ regval |= PM_OSCCTRL_MODE_XTALHI; /* Crystal XIN above 8.0MHz */
+#endif
+ putreg32(regval, SAM_PM_OSCCTRL1);
+
+ /* Enable OSC1 using the startup time provided in board.h. This startup time
+ * is critical and depends on the characteristics of the crystal.
+ */
+
+ regval = getreg32(SAM_PM_OSCCTRL1);
+ regval &= ~PM_OSCCTRL_STARTUP_MASK;
+ regval |= (SAM_OSC1STARTUP << PM_OSCCTRL_STARTUP_SHIFT);
+ putreg32(regval, SAM_PM_OSCCTRL1);
+
+ /* Enable OSC1 */
+
+ regval = getreg32(SAM_PM_MCCTRL);
+ regval |= PM_MCCTRL_OSC1EN;
+ putreg32(regval, SAM_PM_MCCTRL);
+
+ /* Wait for OSC1 to be ready */
+
+ while ((getreg32(SAM_PM_POSCSR) & PM_POSCSR_OSC1RDY) == 0);
+}
+#endif
+
+/****************************************************************************
+ * Name: sam_enablepll0
+ *
+ * Description:
+ * Initialiaze PLL0 settings per the definitions in the board.h file.
+ *
+ ****************************************************************************/
+
+#ifdef SAM_CLOCK_PLL0
+static inline void sam_enablepll0(void)
+{
+ /* Setup PLL0 */
+
+ regval = (SAM_PLL0_DIV << PM_PLL_PLLDIV_SHIFT) | (SAM_PLL0_MUL << PM_PLL_PLLMUL_SHIFT) | (16 << PM_PLL_PLLCOUNT_SHIFT)
+
+ /* Select PLL0/1 oscillator */
+
+#if SAM_CLOCK_PLL_OSC1
+ regval |= PM_PLL_PLLOSC;
+#endif
+
+ putreg32(regval, SAM_PM_PLL0);
+
+ /* Set PLL0 options */
+
+ regval = getreg32(SAM_PM_PLL0);
+ regval &= ~PM_PLL_PLLOPT_MASK
+#if SAM_PLL0_FREQ < 160000000
+ regval |= PM_PLL_PLLOPT_VCO;
+#endif
+#if SAM_PLL0_DIV2 != 0
+ regval |= PM_PLL_PLLOPT_XTRADIV;
+#endif
+#if SAM_PLL0_WBWM != 0
+ regval |= PM_PLL_PLLOPT_WBWDIS;
+#endif
+ putreg32(regval, SAM_PM_PLL0)
+
+ /* Enable PLL0 */
+
+ regval = getreg32(SAM_PM_PLL0);
+ regval |= PM_PLL_PLLEN;
+ putreg32(regval, SAM_PM_PLL0)
+
+ /* Wait for PLL0 locked. */
+
+ while ((getreg32(SAM_PM_POSCSR) & PM_POSCSR_LOCK0) == 0);
+}
+#endif
+
+/****************************************************************************
+ * Name: sam_enablepll1
+ *
+ * Description:
+ * Initialiaze PLL1 settings per the definitions in the board.h file.
+ *
+ ****************************************************************************/
+
+#ifdef SAM_CLOCK_PLL1
+static inline void sam_enablepll1(void)
+{
+ /* Setup PLL1 */
+
+ regval = (SAM_PLL1_DIV << PM_PLL_PLLDIV_SHIFT) | (SAM_PLL1_MUL << PM_PLL_PLLMUL_SHIFT) | (16 << PM_PLL_PLLCOUNT_SHIFT)
+
+ /* Select PLL0/1 oscillator */
+
+#if SAM_CLOCK_PLL_OSC1
+ regval |= PM_PLL_PLLOSC;
+#endif
+
+ putreg32(regval, SAM_PM_PLL1);
+
+ /* Set PLL1 options */
+
+ regval = getreg32(SAM_PM_PLL1);
+ regval &= ~PM_PLL_PLLOPT_MASK
+#if SAM_PLL1_FREQ < 160000000
+ regval |= PM_PLL_PLLOPT_VCO;
+#endif
+#if SAM_PLL1_DIV2 != 0
+ regval |= PM_PLL_PLLOPT_XTRADIV;
+#endif
+#if SAM_PLL1_WBWM != 0
+ regval |= PM_PLL_PLLOPT_WBWDIS;
+#endif
+ putreg32(regval, SAM_PM_PLL1)
+
+ /* Enable PLL1 */
+
+ regval = getreg32(SAM_PM_PLL1);
+ regval |= PM_PLL_PLLEN;
+ putreg32(regval, SAM_PM_PLL1)
+
+ /* Wait for PLL1 locked. */
+
+ while ((getreg32(SAM_PM_POSCSR) & PM_POSCSR_LOCK1) == 0);
+}
+#endif
+
+/****************************************************************************
+ * Name: sam_setdividers
+ *
+ * Description:
+ * Configure derived clocks.
+ *
+ ****************************************************************************/
+
+static inline void sam_setdividers(uint32_t cpudiv, uint32_t pbadiv,
+ uint32_t pbbdiv, uint32_t pbcdiv,
+ uint32_t pbddiv)
+{
+ irqstate_t flags;
+ uint32_t cpusel = 0;
+ uint32_t pbasel = 0;
+ uint32_t pbbsel = 0;
+ uint32_t pbcsel = 0;
+ uint32_t pbdsel = 0;
+
+ /* Get the register setting for each divider value */
+
+ if (cpudiv > 0)
+ {
+ cpusel = (PM_CPUSEL(cpudiv - 1)) | PM_CPUSEL_DIV;
+ }
+
+ if (pbadiv > 0)
+ {
+ pbasel = (PM_PBSEL(pbadiv - 1)) | PM_PBSEL_DIV;
+ }
+
+ if (pbbdiv > 0)
+ {
+ pbbsel = (PM_PBSEL(pbbdiv - 1)) | PM_PBSEL_DIV;
+ }
+
+ if (pbcdiv > 0)
+ {
+ pbcsel = (PM_PBSEL(pbcdiv - 1)) | PM_PBSEL_DIV;
+ }
+
+ if (pbddiv > 0)
+ {
+ pbdsel = (PM_PBSEL(pbddiv - 1)) | PM_PBSEL_DIV;
+ }
+
+ /* Then set the divider values. The following operations need to be atomic
+ * for the unlock-write sequeuences.
+ */
+
+ flags = irqsave();
+
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_CPUSEL_OFFSET), SAM_PM_UNLOCK);
+ putreg32(cpusel, SAM_PM_CPUSEL);
+
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_PBASEL_OFFSET), SAM_PM_UNLOCK);
+ putreg32(pbasel, SAM_PM_PBASEL);
+
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_PBBSEL_OFFSET), SAM_PM_UNLOCK);
+ putreg32(pbbsel, SAM_PM_PBBSEL);
+
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_PBCSEL_OFFSET), SAM_PM_UNLOCK);
+ putreg32(pbcsel, SAM_PM_PBCSEL);
+
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_PBDSEL_OFFSET), SAM_PM_UNLOCK);
+ putreg32(pbdsel, SAM_PM_PBDSEL);
+
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: sam_fws
+ *
+ * Description:
+ * Setup FLASH wait states.
+ *
+ ****************************************************************************/
+
+static void sam_fws(uint32_t cpuclock)
+{
+ uint32_t regval;
+
+ regval = getreg32(SAM_FLASHCALW_FCR);
+ if (cpuclock > SAM_FLASHCALW_FWS0_MAXFREQ)
+ {
+ regval |= FLASHCALW_FCR_FWS;
+ }
+ else
+ {
+ regval &= ~FLASHCALW_FCR_FWS;
+ }
+
+ putreg32(regval, SAM_FLASHCALW_FCR);
+}
+
+/****************************************************************************
+ * Name: sam_mainclk
+ *
+ * Description:
+ * Select the main clock.
+ *
+ ****************************************************************************/
+
+static inline void sam_mainclk(uint32_t mcsel)
+{
+ uint32_t regval;
+
+ regval = getreg32(SAM_PM_MCCTRL);
+ regval &= ~PM_MCCTRL_MCSEL_MASK;
+ regval |= mcsel;
+ putreg32(regval, SAM_PM_MCCTRL);
+}
+
+/****************************************************************************
+ * Name: sam_usbclock
+ *
+ * Description:
+ * Setup the USBB GCLK.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_USBDEV
+static inline void sam_usbclock(void)
+{
+ uint32_t regval = 0;
+
+#if defined(SAM_CLOCK_USB_PLL0) || defined(SAM_CLOCK_USB_PLL1)
+ regval |= PM_GCCTRL_PLLSEL;
+#endif
+#if defined(SAM_CLOCK_USB_OSC1) || defined(SAM_CLOCK_USB_PLL1)
+ regval |= PM_GCCTRL_OSCSEL;
+#endif
+#if SAM_CLOCK_USB_DIV > 0
+
+
+ u_avr32_pm_gcctrl.GCCTRL.diven = diven;
+ u_avr32_pm_gcctrl.GCCTRL.div = div;
+#endif
+ putreg32(regval, SAM_PM_GCCTRL(SAM_PM_GCLK_USBB))
+
+ /* Enable USB GCLK */
+
+ regval = getreg32(SAM_PM_GCCTRL(SAM_PM_GCLK_USBB))
+ regval |= PM_GCCTRL_CEN;
+ putreg32(regval, SAM_PM_GCCTRL(SAM_PM_GCLK_USBB))
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_clockconfig
+ *
+ * Description:
+ * Called to initialize the SAM3/4. This does whatever setup is needed to
+ * put the SoC in a usable state. This includes the initialization of
+ * clocking using the settings in board.h.
+ *
+ ****************************************************************************/
+
+void sam_clockconfig(void)
+{
+ /* Enable clocking to the PICOCACHE */
+
+ sam_picocache();
+
+ /* Configure dividers derived clocks. These divider definitions must be
+ * provided in the board.h header file.
+ */
+
+ sam_setdividers(BOARD_SYSCLK_CPU_DIV, BOARD_SYSCLK_PBA_DIV,
+ BOARD_SYSCLK_PBB_DIV, BOARD_SYSCLK_PBC_DIV,
+ BOARD_SYSCLK_PBD_DIV);
+
+#ifdef SAM_CLOCK_OSC32
+ /* Enable the 32KHz oscillator (need by the RTC module) */
+
+ sam_enableosc32();
+#endif
+
+#ifdef NEED_OSC0
+ /* Enable OSC0 using the settings in board.h */
+
+ sam_enableosc0();
+
+ /* Set up FLASH wait states */
+
+ sam_fws(SAM_FOSC0);
+
+ /* Then switch the main clock to OSC0 */
+
+ sam_mainclk(PM_MCCTRL_MCSEL_OSC0);
+#endif
+
+#ifdef NEED_OSC1
+ /* Enable OSC1 using the settings in board.h */
+
+ sam_enableosc1();
+#endif
+
+#ifdef SAM_CLOCK_PLL0
+ /* Enable PLL0 using the settings in board.h */
+
+ sam_enablepll0();
+
+ /* Set up FLASH wait states */
+
+ sam_fws(SAM_CPU_CLOCK);
+
+ /* Then switch the main clock to PLL0 */
+
+ sam_mainclk(PM_MCCTRL_MCSEL_PLL0);
+#endif
+
+#ifdef SAM_CLOCK_PLL1
+ /* Enable PLL1 using the settings in board.h */
+
+ sam_enablepll1();
+#endif
+
+ /* Set up the USBB GCLK */
+
+#ifdef CONFIG_USBDEV
+ void sam_usbclock();
+#endif
+}
diff --git a/nuttx/arch/arm/src/sam34/sam4l_gpio.c b/nuttx/arch/arm/src/sam34/sam4l_gpio.c
index 88f3d02cb..977e91e60 100644
--- a/nuttx/arch/arm/src/sam34/sam4l_gpio.c
+++ b/nuttx/arch/arm/src/sam34/sam4l_gpio.c
@@ -105,6 +105,8 @@ static inline int sam_gpiopin(gpio_pinset_t cfgset)
*
* Description:
* Configure a GPIO input pin based on bit-encoded description of the pin.
+ * This function serves the dual role of putting all pins into a known,
+ * initial state. Hence, it is overkill for what really needs to be done.
*
****************************************************************************/
@@ -200,10 +202,10 @@ static inline int sam_configinterrupt(uintptr_t base, uint32_t pin,
* falling edges.
*/
- ret = sam_configinput(base, pin, cfgset)
- if (ret = OK)
+ ret = sam_configinput(base, pin, cfgset);
+ if (ret == OK)
{
- /* Disable rising and falling edge interrupts as requested
+ /* Disable rising and falling edge interrupts as requested
* {IMR1, IMR0} Interrupt Mode
*
* 00 Pin Change <-- We already have this
@@ -214,13 +216,13 @@ static inline int sam_configinterrupt(uintptr_t base, uint32_t pin,
gpio_pinset_t edges = cfgset & GPIO_INT_MASK;
- if (eges = GPIO_INT_RISING)
+ if (edges == GPIO_INT_RISING)
{
/* Rising only.. disable interrrupts on the falling edge */
putreg32(pin, base + SAM_GPIO_IMR0S_OFFSET);
}
- else if (edges = GPIO_INT_FALLING)
+ else if (edges == GPIO_INT_FALLING)
{
/* Falling only.. disable interrrupts on the rising edge */
@@ -363,7 +365,7 @@ static inline int sam_configperiph(uintptr_t base, uint32_t pin,
case _GPIO_FUNCC: /* Function C 010 */
putreg32(pin, base + SAM_GPIO_PMR1S_OFFSET);
break;
-
+
case _GPIO_FUNCE: /* Function E 100 */
putreg32(pin, base + SAM_GPIO_PMR2S_OFFSET);
break;
@@ -397,13 +399,13 @@ static inline int sam_configperiph(uintptr_t base, uint32_t pin,
*/
edges = cfgset & GPIO_INT_MASK;
- if (eges = GPIO_INT_RISING)
+ if (edges == GPIO_INT_RISING)
{
/* Rising only.. disable interrrupts on the falling edge */
putreg32(pin, base + SAM_GPIO_IMR0S_OFFSET);
}
- else if (edges = GPIO_INT_FALLING)
+ else if (edges == GPIO_INT_FALLING)
{
/* Falling only.. disable interrrupts on the rising edge */
diff --git a/nuttx/arch/arm/src/sam34/sam4l_periphclks.c b/nuttx/arch/arm/src/sam34/sam4l_periphclks.c
new file mode 100644
index 000000000..abd766695
--- /dev/null
+++ b/nuttx/arch/arm/src/sam34/sam4l_periphclks.c
@@ -0,0 +1,272 @@
+/****************************************************************************
+ * arch/avr/src/sam34/sam4l_periphclks.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * This file is derived from nuttx/arch/avr/src/at32uc3/at32uc3_clkinit.c
+ *
+ * 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/irq.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+
+#include "up_internal.h"
+#include "chip/sam4l_pm.h"
+
+#include "sam4l_periphclks.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_modifyperipheral
+ *
+ * Description:
+ * This is a convenience function that is intended to be used to enable
+ * or disable peripheral module clocking.
+ *
+ ****************************************************************************/
+
+void sam_modifyperipheral(uintptr_t regaddr, uint32_t clrbits, uint32_t setbits)
+{
+ irqstate_t flags;
+ uint32_t regval;
+
+ /* Make sure that the following operations are atomic */
+
+ flags = irqsave();
+
+ /* Enable/disabling clocking */
+
+ regval = getreg32(regaddr);
+ regval &= ~clrbits;
+ regval |= setbits;
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(regaddr - SAM_PM_BASE), SAM_PM_UNLOCK);
+ putreg32(regval, regaddr);
+
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: sam_pba_modifydivmask
+ *
+ * Description:
+ * This is a convenience function that is intended to be used to modify
+ * bits in the PBA divided clock (DIVMASK) register.
+ *
+ ****************************************************************************/
+
+void sam_pba_modifydivmask(uint32_t clrbits, uint32_t setbits)
+{
+ irqstate_t flags;
+ uint32_t regval;
+
+ /* Make sure that the following operations are atomic */
+
+ flags = irqsave();
+
+ /* Modify the PBA DIVMASK */
+
+ regval = getreg32(SAM_PM_PBADIVMASK);
+ regval &= ~clrbits;
+ regval |= setbits;
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_PBADIVMASK_OFFSET), SAM_PM_UNLOCK);
+ putreg32(regval, SAM_PM_PBADIVMASK);
+
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: sam_pba_enableperipheral
+ *
+ * Description:
+ * This is a convenience function to enable a peripheral on the APBA
+ * bridge.
+ *
+ ****************************************************************************/
+
+void sam_pba_enableperipheral(uint32_t bitset)
+{
+ irqstate_t flags;
+
+ /* The following operations must be atomic */
+
+ flags = irqsave();
+
+ /* Enable the APBA bridge if necessary */
+
+ if (getreg32(SAM_PM_PBAMASK) == 0)
+ {
+ sam_hsb_enableperipheral(PM_HSBMASK_APBA);
+ }
+
+ irqrestore(flags);
+
+ /* Enable the module */
+
+ sam_enableperipheral(SAM_PM_PBAMASK, bitset);
+}
+
+/****************************************************************************
+ * Name: sam_pba_disableperipheral
+ *
+ * Description:
+ * This is a convenience function to disable a peripheral on the APBA
+ * bridge.
+ *
+ ****************************************************************************/
+
+void sam_pba_disableperipheral(uint32_t bitset)
+{
+ irqstate_t flags;
+
+ /* Disable clocking to the module */
+
+ sam_disableperipheral(SAM_PM_PBAMASK, bitset);
+
+ /* Disable the APBA bridge if possible */
+
+ flags = irqsave();
+
+ if (getreg32(SAM_PM_PBAMASK) == 0)
+ {
+ sam_hsb_disableperipheral(PM_HSBMASK_APBA);
+ }
+
+ /* Disable PBA UART divided clock if none of the UARTS are in use */
+
+ if ((getreg32(SAM_PM_PBAMASK) & PM_PBAMASK_UARTS) == 0)
+ {
+ sam_pba_disabledivmask(PM_PBADIVMASK_CLK_USART);
+ }
+
+ /* Disable PBA TIMER divided clocks if none of the UARTS are in use */
+
+ if ((getreg32(SAM_PM_PBAMASK) & PM_PBAMASK_TIMERS) == 0)
+ {
+ sam_pba_disabledivmask(PM_PBADIVMASK_TIMER_CLOCKS);
+ }
+
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: sam_pbb_enableperipheral
+ *
+ * Description:
+ * This is a convenience function to enable a peripheral on the APBB
+ * bridge.
+ *
+ ****************************************************************************/
+
+void sam_pbb_enableperipheral(uint32_t bitset)
+{
+ irqstate_t flags;
+
+ /* The following operations must be atomic */
+
+ flags = irqsave();
+
+ /* Enable the APBB bridge if necessary */
+
+ if (getreg32(SAM_PM_PBBMASK) == 0)
+ {
+ sam_hsb_enableperipheral(PM_HSBMASK_APBB);
+ }
+
+ irqrestore(flags);
+
+ /* Enable the module */
+
+ sam_enableperipheral(SAM_PM_PBBMASK, bitset);
+}
+
+/****************************************************************************
+ * Name: sam_pbb_disableperipheral
+ *
+ * Description:
+ * This is a convenience function to disable a peripheral on the APBA
+ * bridge.
+ *
+ ****************************************************************************/
+
+void sam_pbb_disableperipheral(uint32_t bitset)
+{
+ irqstate_t flags;
+
+ /* Disable clocking to the peripheral module */
+
+ sam_disableperipheral(SAM_PM_PBBMASK, bitset);
+
+ /* Disable the APBB bridge if possible */
+
+ flags = irqsave();
+
+ if (getreg32(SAM_PM_PBBMASK) == 0)
+ {
+ sam_hsb_disableperipheral(PM_HSBMASK_APBB);
+ }
+
+ irqrestore(flags);
+}
diff --git a/nuttx/arch/arm/src/sam34/sam4l_periphclks.h b/nuttx/arch/arm/src/sam34/sam4l_periphclks.h
new file mode 100644
index 000000000..895556e5d
--- /dev/null
+++ b/nuttx/arch/arm/src/sam34/sam4l_periphclks.h
@@ -0,0 +1,349 @@
+/************************************************************************************
+ * arch/arm/src/sam34/sam4l_periphclks.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_SAM34_SAM4L_PERIPHCLKS_H
+#define __ARCH_ARM_SRC_SAM34_SAM4L_PERIPHCLKS_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* SAM4L helper macros */
+
+#define sam_enableperipheral(a,s) sam_modifyperipheral(a,0,s)
+#define sam_disableperipheral(a,s) sam_modifyperipheral(a,s,0)
+
+#define sam_cpu_enableperipheral(s) sam_enableperipheral(SAM_PM_CPUMASK,s)
+#define sam_hsb_enableperipheral(s) sam_enableperipheral(SAM_PM_HSBMASK,s)
+#define sam_pbc_enableperipheral(s) sam_enableperipheral(SAM_PM_PBCMASK,s)
+#define sam_pbd_enableperipheral(s) sam_enableperipheral(SAM_PM_PBDMASK,s)
+
+#define sam_cpu_disableperipheral(s) sam_disableperipheral(SAM_PM_CPUMASK,s)
+#define sam_hsb_disableperipheral(s) sam_disableperipheral(SAM_PM_HSBMASK,s)
+#define sam_pbc_enableperipheral(s) sam_enableperipheral(SAM_PM_PBCMASK,s)
+#define sam_pbd_enableperipheral(s) sam_enableperipheral(SAM_PM_PBDMASK,s)
+
+#define sam_pba_enabledivmask(s) sam_pba_modifydivmask(0,s)
+#define sam_pba_disabledivmask(s) sam_pba_modifydivmask(s,0)
+
+/* Macros to enable clocking to individual peripherals */
+
+#define sam_aesa_enableclk() sam_hsb_enableperipheral(PM_HSBMASK_AESA)
+#define sam_iisc_enableclk() sam_pba_enableperipheral(PM_PBAMASK_IISC)
+#define sam_spi_enableclk() sam_pba_enableperipheral(PM_PBAMASK_SPI)
+
+#define sam_tc0_enableclk() \
+ do { \
+ sam_pba_enableperipheral(PM_PBAMASK_TC0); \
+ sam_pba_enabledivmask(PM_PBADIVMASK_TIMER_CLOCKS); \
+ } while (0)
+
+#define sam_tc1_enableclk() \
+ do { \
+ sam_pba_enableperipheral(PM_PBAMASK_TC1); \
+ sam_pba_enabledivmask(PM_PBADIVMASK_TIMER_CLOCKS); \
+ } while (0)
+
+#define sam_twim0_enableclk() sam_pba_enableperipheral(PM_PBAMASK_TWIM0)
+#define sam_twis0_enableclk() sam_pba_enableperipheral(PM_PBAMASK_TWIS0)
+#define sam_twim1_enableclk() sam_pba_enableperipheral(PM_PBAMASK_TWIM1)
+#define sam_twis1_enableclk() sam_pba_enableperipheral(PM_PBAMASK_TWIS1)
+
+#define sam_usart0_enableclk() \
+ do { \
+ sam_pba_enableperipheral(PM_PBAMASK_USART0); \
+ sam_pba_enabledivmask(PBA_DIVMASK_CLK_USART); \
+ } while (0)
+
+#define sam_usart1_enableclk() \
+ do { \
+ sam_pba_enableperipheral(PM_PBAMASK_USART1); \
+ sam_pba_enabledivmask(PBA_DIVMASK_CLK_USART); \
+ } while (0)
+
+#define sam_usart2_enableclk() \
+ do { \
+ sam_pba_enableperipheral(PM_PBAMASK_USART2); \
+ sam_pba_enabledivmask(PBA_DIVMASK_CLK_USART); \
+ } while (0)
+
+#define sam_usart3_enableclk() \
+ do { \
+ sam_pba_enableperipheral(PM_PBAMASK_USART3); \
+ sam_pba_enabledivmask(PBA_DIVMASK_CLK_USART); \
+ } while (0)
+
+#define sam_adcife_enableclk() sam_pba_enableperipheral(PM_PBAMASK_ADCIFE)
+#define sam_dacc_enableclk() sam_pba_enableperipheral(PM_PBAMASK_DACC)
+#define sam_acifc_enableclk() sam_pba_enableperipheral(PM_PBAMASK_ACIFC)
+#define sam_gloc_enableclk() sam_pba_enableperipheral(PM_PBAMASK_GLOC)
+#define sam_abdacb_enableclk() sam_pba_enableperipheral(PM_PBAMASK_ABDACB)
+#define sam_trng_enableclk() sam_pba_enableperipheral(PM_PBAMASK_TRNG)
+#define sam_parc_enableclk() sam_pba_enableperipheral(PM_PBAMASK_PARC)
+#define sam_catb_enableclk() sam_pba_enableperipheral(PM_PBAMASK_CATB)
+#define sam_twim2_enableclk() sam_pba_enableperipheral(PM_PBAMASK_TWIM2)
+#define sam_twim3_enableclk() sam_pba_enableperipheral(PM_PBAMASK_TWIM3)
+#define sam_lcdca_enableclk() sam_pba_enableperipheral(PM_PBAMASK_LCDCA)
+
+#define sam_flashcalw_enableclk() \
+ do { \
+ sam_hsb_enableperipheral(PM_HSBMASK_FLASHCALW); \
+ sam_pbb_enableperipheral(PM_PBBMASK_FLASHCALW); \
+ } while (0)
+
+#define sam_picocache_enableclk() \
+ do { \
+ sam_hsb_enableperipheral(PM_HSBMASK_HRAMC1); \
+ sam_pbb_enableperipheral(PM_PBBMASK_HRAMC1); \
+ } while (0)
+
+#define sam_hmatrix_enableclk() sam_pbb_enableperipheral(PM_PBBMASK_HMATRIX)
+
+#define sam_pdca_enableclk() \
+ do { \
+ sam_hsb_enableperipheral(PM_HSBMASK_PDCA); \
+ sam_pbb_enableperipheral(PM_PBBMASK_PDCA); \
+ } while (0)
+
+#define sam_crccu_enableclk() \
+ do { \
+ sam_hsb_enableperipheral(PM_HSBMASK_CRCCU); \
+ sam_pbb_enableperipheral(PM_PBBMASK_CRCCU); \
+ } while (0)
+
+#define sam_usbc_enableclk() \
+ do { \
+ sam_hsb_enableperipheral(PM_HSBMASK_USBC); \
+ sam_pbb_enableperipheral(PM_PBBMASK_USBC); \
+ } while (0)
+
+#define sam_pevc_enableclk() sam_pbb_enableperipheral(PM_PBBMASK_PEVC)
+#define sam_pm_enableclk() sam_pbc_enableperipheral(PM_PBCMASK_PM)
+#define sam_chipid_enableclk() sam_pbc_enableperipheral(PM_PBCMASK_CHIPID)
+#define sam_scif_enableclk() sam_pbc_enableperipheral(PM_PBCMASK_SCIF)
+#define sam_freqm_enableclk() sam_pbc_enableperipheral(PM_PBCMASK_FREQM)
+#define sam_gpio_enableclk() sam_pbc_enableperipheral(PM_PBCMASK_GPIO)
+#define sam_bpm_enableclk() sam_pbd_enableperipheral(PM_PBDMASK_BPM)
+#define sam_bscif_enableclk() sam_pbd_enableperipheral(PM_PBDMASK_BSCIF)
+#define sam_ast_enableclk() sam_pbd_enableperipheral(PM_PBDMASK_AST)
+#define sam_wdt_enableclk() sam_pbd_enableperipheral(PM_PBDMASK_WDT)
+#define sam_eic_enableclk() sam_pbd_enableperipheral(PM_PBDMASK_EIC)
+#define sam_picouart_enableclk() sam_pbd_enableperipheral(PM_PBDMASK_PICOUART)
+
+/* Macros to disable clocking to individual peripherals */
+
+#define sam_aesa_disableclk() sam_hsb_disableperipheral(PM_HSBMASK_AESA)
+#define sam_iisc_disableclk() sam_pba_disableperipheral(PM_PBAMASK_IISC)
+#define sam_spi_disableclk() sam_pba_disableperipheral(PM_PBAMASK_SPI)
+#define sam_tc0_disableclk() sam_pba_disableperipheral(PM_PBAMASK_TC0)
+#define sam_tc1_disableclk() sam_pba_disableperipheral(PM_PBAMASK_TC1)
+#define sam_twim0_disableclk() sam_pba_disableperipheral(PM_PBAMASK_TWIM0)
+#define sam_twis0_disableclk() sam_pba_disableperipheral(PM_PBAMASK_TWIS0)
+#define sam_twim1_disableclk() sam_pba_disableperipheral(PM_PBAMASK_TWIM1)
+#define sam_twis1_disableclk() sam_pba_disableperipheral(PM_PBAMASK_TWIS1)
+#define sam_usart0_disableclk() sam_pba_disableperipheral(PM_PBAMASK_USART0)
+#define sam_usart1_disableclk() sam_pba_disableperipheral(PM_PBAMASK_USART1)
+#define sam_usart2_disableclk() sam_pba_disableperipheral(PM_PBAMASK_USART2)
+#define sam_usart3_disableclk() sam_pba_disableperipheral(PM_PBAMASK_USART3)
+#define sam_adcife_disableclk() sam_pba_disableperipheral(PM_PBAMASK_ADCIFE)
+#define sam_dacc_disableclk() sam_pba_disableperipheral(PM_PBAMASK_DACC)
+#define sam_acifc_disableclk() sam_pba_disableperipheral(PM_PBAMASK_ACIFC)
+#define sam_gloc_disableclk() sam_pba_disableperipheral(PM_PBAMASK_GLOC)
+#define sam_abdacb_disableclk() sam_pba_disableperipheral(PM_PBAMASK_ABDACB)
+#define sam_trng_disableclk() sam_pba_disableperipheral(PM_PBAMASK_TRNG)
+#define sam_parc_disableclk() sam_pba_disableperipheral(PM_PBAMASK_PARC)
+#define sam_catb_disableclk() sam_pba_disableperipheral(PM_PBAMASK_CATB)
+#define sam_twim2_disableclk() sam_pba_disableperipheral(PM_PBAMASK_TWIM2)
+#define sam_twim3_disableclk() sam_pba_disableperipheral(PM_PBAMASK_TWIM3)
+#define sam_lcdca_disableclk() sam_pba_disableperipheral(PM_PBAMASK_LCDCA)
+#define sam_flashcalw_disableclk() sam_pba_disableperipheral(PM_HSBMASK_FLASHCALW)
+
+#define sam_picocache_disableclk() \
+ do { \
+ sam_hsb_disableperipheral(PM_HSBMASK_HRAMC1); \
+ sam_pbb_disableperipheral(PM_PBBMASK_HRAMC1); \
+ } while (0)
+
+#define sam_hmatrix_disableclk() sam_pbb_disableperipheral(PM_PBBMASK_HMATRIX)
+
+#define sam_pdca_disableclk() \
+ do { \
+ sam_hsb_disableperipheral(PM_HSBMASK_PDCA); \
+ sam_pbb_disableperipheral(PM_PBBMASK_PDCA); \
+ } while (0)
+
+#define sam_crccu_disableclk() \
+ do { \
+ sam_hsb_disableperipheral(PM_HSBMASK_CRCCU); \
+ sam_pbb_disableperipheral(PM_PBBMASK_CRCCU); \
+ } while (0)
+
+#define sam_usbc_disableclk() \
+ do { \
+ sam_hsb_disableperipheral(PM_HSBMASK_USBC); \
+ sam_pbb_disableperipheral(PM_PBBMASK_USBC); \
+ } while (0)
+
+#define sam_pevc_disableclk() sam_pbb_disableperipheral(PM_PBBMASK_PEVC)
+#define sam_pm_disableclk() sam_pbc_disableperipheral(PM_PBCMASK_PM)
+#define sam_chipid_disableclk() sam_pbc_disableperipheral(PM_PBCMASK_CHIPID)
+#define sam_scif_disableclk() sam_pbc_disableperipheral(PM_PBCMASK_SCIF)
+#define sam_freqm_disableclk() sam_pbc_disableperipheral(PM_PBCMASK_FREQM)
+#define sam_gpio_disableclk() sam_pbc_disableperipheral(PM_PBCMASK_GPIO)
+#define sam_bpm_disableclk() sam_pbd_disableperipheral(PM_PBDMASK_BPM)
+#define sam_bscif_disableclk() sam_pbd_disableperipheral(PM_PBDMASK_BSCIF)
+#define sam_ast_disableclk() sam_pbd_disableperipheral(PM_PBDMASK_AST)
+#define sam_wdt_disableclk() sam_pbd_disableperipheral(PM_PBDMASK_WDT)
+#define sam_eic_disableclk() sam_pbd_disableperipheral(PM_PBDMASK_EIC)
+#define sam_picouart_disableclk() sam_pbd_disableperipheral(PM_PBDMASK_PICOUART)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * 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: sam_modifyperipheral
+ *
+ * Description:
+ * This is a convenience function that is intended to be used to enable
+ * or disable module clocking.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_CHIP_SAM4L
+void sam_modifyperipheral(uintptr_t regaddr, uint32_t clrbits, uint32_t setbits);
+#endif
+
+/****************************************************************************
+ * Name: sam_pba_modifydivmask
+ *
+ * Description:
+ * This is a convenience function that is intended to be used to modify
+ * bits in the PBA divided clock (DIVMASK) register.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_CHIP_SAM4L
+void sam_pba_modifydivmask(uint32_t clrbits, uint32_t setbits);
+#endif
+
+/****************************************************************************
+ * Name: sam_pba_enableperipheral
+ *
+ * Description:
+ * This is a convenience function to enable a peripheral on the APBA
+ * bridge.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_CHIP_SAM4L
+void sam_pba_enableperipheral(uint32_t bitset);
+#endif
+
+/****************************************************************************
+ * Name: sam_pba_disableperipheral
+ *
+ * Description:
+ * This is a convenience function to disable a peripheral on the APBA
+ * bridge.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_CHIP_SAM4L
+void sam_pba_disableperipheral(uint32_t bitset);
+#endif
+
+/****************************************************************************
+ * Name: sam_pbb_enableperipheral
+ *
+ * Description:
+ * This is a convenience function to enable a peripheral on the APBB
+ * bridge.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_CHIP_SAM4L
+void sam_pbb_enableperipheral(uint32_t bitset);
+#endif
+
+/****************************************************************************
+ * Name: sam_pbb_disableperipheral
+ *
+ * Description:
+ * This is a convenience function to disable a peripheral on the APBA
+ * bridge.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_CHIP_SAM4L
+void sam_pbb_disableperipheral(uint32_t bitset);
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_SAM34_SAM4L_PERIPHCLKS_H */
diff --git a/nuttx/arch/arm/src/sam34/sam_clockconfig.h b/nuttx/arch/arm/src/sam34/sam_clockconfig.h
index 4ed9e6b87..fb3d3f6ee 100644
--- a/nuttx/arch/arm/src/sam34/sam_clockconfig.h
+++ b/nuttx/arch/arm/src/sam34/sam_clockconfig.h
@@ -43,7 +43,7 @@
#include <nuttx/config.h>
/************************************************************************************
- * Definitions
+ * Pre-processor Definitions
************************************************************************************/
/************************************************************************************
@@ -79,10 +79,7 @@ extern "C"
* Description:
* Called to initialize the SAM3/4. This does whatever setup is needed to put the
* SoC in a usable state. This includes the initialization of clocking using the
- * settings in board.h. (After power-on reset, the sam3u is initially running on
- * a 4MHz internal RC clock). This function also performs other low-level chip
- * initialization of the chip including EFC, master clock, IRQ and watchdog
- * configuration.
+ * settings in board.h.
*
************************************************************************************/
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_flashc.h b/nuttx/arch/avr/src/at32uc3/at32uc3_flashc.h
index e66663fee..c05f5ac18 100644
--- a/nuttx/arch/avr/src/at32uc3/at32uc3_flashc.h
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_flashc.h
@@ -89,12 +89,12 @@
#define FLASHC_FSR_QPRR (1 << 5) /* Bit 5: Quick Page Read Result */
#define FLASHC_FSR_FSZ_SHIFT (13) /* Bits 13-15: Flash Size */
#define FLASHC_FSR_FSZ_MASK (7 << FLASHC_FSR_FSZ_SHIFT)
-# define FLASHC_FSR_FSZ_23KB (0 << FLASHC_FSR_FSZ_SHIFT) /* 32 Kbytes */
+# define FLASHC_FSR_FSZ_32KB (0 << FLASHC_FSR_FSZ_SHIFT) /* 32 Kbytes */
# define FLASHC_FSR_FSZ_64KB (1 << FLASHC_FSR_FSZ_SHIFT) /* 64 Kbytes */
# define FLASHC_FSR_FSZ_128KB (2 << FLASHC_FSR_FSZ_SHIFT) /* 128 Kbytes */
# define FLASHC_FSR_FSZ_256KB (3 << FLASHC_FSR_FSZ_SHIFT) /* 256 Kbytes */
# define FLASHC_FSR_FSZ_384KB (4 << FLASHC_FSR_FSZ_SHIFT) /* 384 Kbytes */
-# define FLASHC_FSR_FSZ_512KGB (5 << FLASHC_FSR_FSZ_SHIFT) /* 512 Kbytes */
+# define FLASHC_FSR_FSZ_512KB (5 << FLASHC_FSR_FSZ_SHIFT) /* 512 Kbytes */
# define FLASHC_FSR_FSZ_768KB (6 << FLASHC_FSR_FSZ_SHIFT) /* 768 Kbytes */
# define FLASHC_FSR_FSZ_1MB (7 << FLASHC_FSR_FSZ_SHIFT) /* 1024 Kbytes */
#define FLASHC_FSR_LOCK(n) (1 << ((n)+16)