summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-07-22 11:54:39 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-07-22 11:54:39 -0600
commitbd010e1e39749c4132ed12d50040c3958b84c6fe (patch)
treec2b79edf92162a61d25d0e69a5b17bde2011c9a5
parent769c5545a2372857df181152dde942e98765e2a6 (diff)
downloadpx4-nuttx-bd010e1e39749c4132ed12d50040c3958b84c6fe.tar.gz
px4-nuttx-bd010e1e39749c4132ed12d50040c3958b84c6fe.tar.bz2
px4-nuttx-bd010e1e39749c4132ed12d50040c3958b84c6fe.zip
SAMA5 interrupt handling logic
-rw-r--r--nuttx/ChangeLog5
-rw-r--r--nuttx/arch/arm/src/armv7-a/Toolchain.defs1
-rw-r--r--nuttx/arch/arm/src/sama5/Make.defs1
-rw-r--r--nuttx/arch/arm/src/sama5/chip/sam_aic.h197
-rw-r--r--nuttx/arch/arm/src/sama5/chip/sam_pit.h12
-rw-r--r--nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h152
-rw-r--r--nuttx/arch/arm/src/sama5/sam_clockconfig.h38
-rw-r--r--nuttx/arch/arm/src/sama5/sam_irq.c372
-rw-r--r--nuttx/arch/arm/src/sama5/sam_irq.h107
-rw-r--r--nuttx/arch/arm/src/sama5/sam_lowputc.h41
10 files changed, 821 insertions, 105 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 4938117e3..2497cd581 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -5145,7 +5145,10 @@
(2013-7-20).
* /arch/arm/src/armv7-a/arm_fpuconfig.S and fpu.h: A few more files for
the ARMv7-A/Cortex-A5 port (2013-7-21).
- * arm/src/sama5/sam_boot.c, sam_clockconfig.h, sam_lowputc.h, and
+ * arch/arm/src/sama5/sam_boot.c, sam_clockconfig.h, sam_lowputc.h, and
sam_timerisr.c: A few more files for the SAMA5D3 port (2013-7-21).
* configs/sama5d3x-ek/src/sam_autoleds.c: A few more files for the port
to the SAMA5D3x-EK board (2013-7-21).
+ * arch/arm/src/sama5/sam_irq.c: SAMA5 interrupt handling logic
+ (2013-7-22).
+
diff --git a/nuttx/arch/arm/src/armv7-a/Toolchain.defs b/nuttx/arch/arm/src/armv7-a/Toolchain.defs
index 201014107..f90307b25 100644
--- a/nuttx/arch/arm/src/armv7-a/Toolchain.defs
+++ b/nuttx/arch/arm/src/armv7-a/Toolchain.defs
@@ -150,4 +150,3 @@ ifeq ($(CONFIG_ARMV7A_TOOLCHAIN),GNU_EABIW)
WINTOOL = y
endif
endif
-
diff --git a/nuttx/arch/arm/src/sama5/Make.defs b/nuttx/arch/arm/src/sama5/Make.defs
index 64b8076c9..1abd1c686 100644
--- a/nuttx/arch/arm/src/sama5/Make.defs
+++ b/nuttx/arch/arm/src/sama5/Make.defs
@@ -43,6 +43,7 @@ CMN_CSRCS = up_initialize.c up_idle.c up_interruptcontext.c up_exit.c
CMN_CSRCS += up_createstack.c up_releasestack.c up_usestack.c up_vfork.c
CMN_CSRCS += up_mdelay.c up_udelay.c
CMN_CSRCS += up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c
+CMN_CSRCS += up_allocateheap.c
CMN_CSRCS += arm_assert.c arm_blocktask.c arm_copystate.c arm_dataabort.c
CMN_CSRCS += arm_doirq.c arm_initialstate.c arm_prefetchabort.c
diff --git a/nuttx/arch/arm/src/sama5/chip/sam_aic.h b/nuttx/arch/arm/src/sama5/chip/sam_aic.h
new file mode 100644
index 000000000..f9b07e58b
--- /dev/null
+++ b/nuttx/arch/arm/src/sama5/chip/sam_aic.h
@@ -0,0 +1,197 @@
+/************************************************************************************
+ * arch/arm/src/sama5/chip/sam_aic.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_SAMA5_CHIP_SAM_AIC_H
+#define __ARCH_ARM_SRC_SAMA5_CHIP_SAM_AIC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip/sam_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* AIC Register Offsets *************************************************************/
+
+#define SAM_AIC_SSR_OFFSET 0x0000 /* Source Select Register */
+#define SAM_AIC_SMR_OFFSET 0x0004 /* Source Mode Register */
+#define SAM_AIC_SVR_OFFSET 0x0008 /* Source Vector Register */
+#define SAM_AIC_IVR_OFFSET 0x0010 /* Interrupt Vector Register */
+#define SAM_AIC_FVR_OFFSET 0x0014 /* FIQ Interrupt Vector Register */
+#define SAM_AIC_ISR_OFFSET 0x0018 /* Interrupt Status Register */
+#define SAM_AIC_IPR0_OFFSET 0x0020 /* Interrupt Pending Register 0 */
+#define SAM_AIC_IPR1_OFFSET 0x0024 /* Interrupt Pending Register 1 */
+#define SAM_AIC_IPR2_OFFSET 0x0028 /* Interrupt Pending Register 2 */
+#define SAM_AIC_IPR3_OFFSET 0x002c /* Interrupt Pending Register 3 */
+#define SAM_AIC_IMR_OFFSET 0x0030 /* Interrupt Mask Register */
+#define SAM_AIC_CISR_OFFSET 0x0034 /* Core Interrupt Status Register */
+#define SAM_AIC_EOICR_OFFSET 0x0038 /* End of Interrupt Command Register */
+#define SAM_AIC_SPU_OFFSET 0x003c /* Spurious Interrupt Vector Register */
+#define SAM_AIC_IECR_OFFSET 0x0040 /* Interrupt Enable Command Register */
+#define SAM_AIC_IDCR_OFFSET 0x0044 /* Interrupt Disable Command Register */
+#define SAM_AIC_ICCR_OFFSET 0x0048 /* Interrupt Clear Command Register */
+#define SAM_AIC_ISCR_OFFSET 0x004c /* Interrupt Set Command Register */
+#define SAM_AIC_FFER_OFFSET 0x0050 /* Fast Forcing Enable Register */
+#define SAM_AIC_FFDR_OFFSET 0x0054 /* Fast Forcing Disable Register */
+#define SAM_AIC_FFSR_OFFSET 0x0058 /* Fast Forcing Status Register */
+#define SAM_AIC_DCR_OFFSET 0x006c /* Debug Control Register */
+#define SAM_AIC_WPMR_OFFSET 0x00e4 /* Write Protect Mode Register */
+#define SAM_AIC_WPSR_OFFSET 0x00e8 /* Write Protect Status Register */
+
+/* AIC Register Addresses ***********************************************************/
+
+#define SAM_AIC_SSR (SAM_AIC_VBASE+SAM_AIC_SSR_OFFSET)
+#define SAM_AIC_SMR (SAM_AIC_VBASE+SAM_AIC_SMR_OFFSET)
+#define SAM_AIC_SVR (SAM_AIC_VBASE+SAM_AIC_SVR_OFFSET)
+#define SAM_AIC_IVR (SAM_AIC_VBASE+SAM_AIC_IVR_OFFSET)
+#define SAM_AIC_FVR (SAM_AIC_VBASE+SAM_AIC_FVR_OFFSET)
+#define SAM_AIC_ISR (SAM_AIC_VBASE+SAM_AIC_ISR_OFFSET)
+#define SAM_AIC_IPR0 (SAM_AIC_VBASE+SAM_AIC_IPR0_OFFSET)
+#define SAM_AIC_IPR1 (SAM_AIC_VBASE+SAM_AIC_IPR1_OFFSET)
+#define SAM_AIC_IPR2 (SAM_AIC_VBASE+SAM_AIC_IPR2_OFFSET)
+#define SAM_AIC_IPR3 (SAM_AIC_VBASE+SAM_AIC_IPR3_OFFSET)
+#define SAM_AIC_IMR (SAM_AIC_VBASE+SAM_AIC_IMR_OFFSET)
+#define SAM_AIC_CISR (SAM_AIC_VBASE+SAM_AIC_CISR_OFFSET)
+#define SAM_AIC_EOICR (SAM_AIC_VBASE+SAM_AIC_EOICR_OFFSET)
+#define SAM_AIC_SPU (SAM_AIC_VBASE+SAM_AIC_SPU_OFFSET)
+#define SAM_AIC_IECR (SAM_AIC_VBASE+SAM_AIC_IECR_OFFSET)
+#define SAM_AIC_IDCR (SAM_AIC_VBASE+SAM_AIC_IDCR_OFFSET)
+#define SAM_AIC_ICCR (SAM_AIC_VBASE+SAM_AIC_ICCR_OFFSET)
+#define SAM_AIC_ISCR (SAM_AIC_VBASE+SAM_AIC_ISCR_OFFSET)
+#define SAM_AIC_FFER (SAM_AIC_VBASE+SAM_AIC_FFER_OFFSET)
+#define SAM_AIC_FFDR (SAM_AIC_VBASE+SAM_AIC_FFDR_OFFSET)
+#define SAM_AIC_FFSR (SAM_AIC_VBASE+SAM_AIC_FFSR_OFFSET)
+#define SAM_AIC_DCR (SAM_AIC_VBASE+SAM_AIC_DCR_OFFSET)
+#define SAM_AIC_WPMR (SAM_AIC_VBASE+SAM_AIC_WPMR_OFFSET)
+#define SAM_AIC_WPSR (SAM_AIC_VBASE+SAM_AIC_WPSR_OFFSET)
+
+/* AIC Register Bit Definitions *****************************************************/
+
+/* Source Select Register */
+
+#define AIC_SSR_MASK (0x7f) /* Bits 0-6: Interrupt line Selection */
+
+/* Source Mode Register */
+
+#define AIC_SMR_PRIOR_SHIFT (0) /* Bits 0-2: Priority level */
+#define AIC_SMR_PRIOR_MASK (7 << AIC_SMR_PRIOR_SHIFT)
+# define AIC_SMR_PRIOR_MIN (0)
+# define AIC_SMR_PRIOR_MAX (7)
+#define AIC_SMR_SRCTYPE_SHIFT (5) /* Bits 5-6: Interrupt source type */
+#define AIC_SMR_SRCTYPE_MASK (3 << AIC_SMR_SRCTYPE_SHIFT)
+# define AIC_SMR_SRCTYPE_IHIGH (0 << AIC_SMR_SRCTYPE_SHIFT) /* Internal high level */
+# define AIC_SMR_SRCTYPE_XLOW (0 << AIC_SMR_SRCTYPE_SHIFT) /* External low level */
+# define AIC_SMR_SRCTYPE_IRISING (1 << AIC_SMR_SRCTYPE_SHIFT) /* Internal positive edge */
+# define AIC_SMR_SRCTYPE_XFALLING (1 << AIC_SMR_SRCTYPE_SHIFT) /* External negative edge */
+# define AIC_SMR_SRCTYPE_XHIGH (2 << AIC_SMR_SRCTYPE_SHIFT) /* External high level */
+# define AIC_SMR_SRCTYPE_XRISING (3 << AIC_SMR_SRCTYPE_SHIFT) /* External rising edge */
+
+/* Source Vector Register (32-bit address) */
+/* Interrupt Vector Register (32-bit address) */
+/* FIQ Interrupt Vector Register (32-bit address) */
+
+/* Interrupt Status Register */
+
+#define AIC_ISR_MASK (0x7f) /* Bits 0-6: Current Interrupt Identifier */
+
+/* Interrupt Pending Register 0-3 */
+
+#define AIC_IPR(pid) (1 << (pid))
+
+/* Interrupt Mask Register */
+
+#define AIC_IMR_INTM (1 << 0) /* Bit 0: Interrupt Mask */
+
+/* Core Interrupt Status Register */
+
+#define AIC_CISR_NFIQ (1 << 0) /* Bit 0: NFIQ Status */
+#define AIC_CISR_NIRQ (1 << 1) /* Bit 1: NIRQ Status */
+
+/* End of Interrupt Command Register */
+
+#define AIC_EOICR_ENDIT (1 << 0) /* Bit 0: Interrupt Processing Complete Command */
+
+/* Spurious Interrupt Vector Register (32-bit address) */
+
+/* Interrupt Enable Command Register */
+
+#define AIC_IECR_INTEN (1 << 0) /* Bit 0: Interrupt Enable */
+
+/* Interrupt Disable Command Register */
+
+#define AIC_IDCR_INTD (1 << 0) /* Bit 0: Interrupt Disable */
+
+/* Interrupt Clear Command Register */
+
+#define AIC_ICCR_INTCLR (1 << 0) /* Bit 0: Interrupt Clear */
+
+/* Interrupt Set Command Register */
+
+#define AIC_ISCR_INTSET (1 << 0) /* Bit 0: Interrupt Set */
+
+/* Fast Forcing Enable Register */
+
+#define AIC_FFER_FFEN (1 << 0) /* Bit 0: Fast Forcing Enable */
+
+/* Fast Forcing Disable Register */
+
+#define AIC_FFDR_FFDIS (1 << 0) /* Bit 0: Fast Forcing Disable */
+
+/* Fast Forcing Status Register */
+
+#define AIC_FFSR_FFS (1 << 0) /* Bit 0: Fast Forcing Status */
+
+/* Debug Control Register */
+
+#define AIC_DCR_PROT (1 << 0) /* Bit 0: Protection Mode */
+#define AIC_DCR_GMSK (1 << 1) /* Bit 1: General Mask */
+
+/* Write Protect Mode Register */
+
+#define AIC_WPMR_WPEN (1 << 0) /* Bit 0: Write Protect Enable */
+#define AIC_WPMR_WPKEY_SHIFT (8) /* Bits 8-31: Write Protect KEY */
+#define AIC_WPMR_WPKEY_MASK (0x00ffffff << AIC_WPMR_WPKEY_SHIFT)
+# define AIC_WPMR_WPKEY (0x00414943 << AIC_WPMR_WPKEY_SHIFT)
+
+/* Write Protect Status Register */
+
+#define AIC_WPSR_WPVS (1 << 0) /* Bit 0: Write Protect Violation Status */
+#define AIC_WPSR_WPVSRC_SHIFT (8) /* Bits 8-23: Write Protect Violation Source */
+#define AIC_WPSR_WPVSRC_MASK (0x0000ffff << AIC_WPSR_WPVSRC_SHIFT)
+
+#endif /* __ARCH_ARM_SRC_SAMA5_CHIP_SAM_AIC_H */
diff --git a/nuttx/arch/arm/src/sama5/chip/sam_pit.h b/nuttx/arch/arm/src/sama5/chip/sam_pit.h
index 1eb93f787..1f93f4b75 100644
--- a/nuttx/arch/arm/src/sama5/chip/sam_pit.h
+++ b/nuttx/arch/arm/src/sama5/chip/sam_pit.h
@@ -53,16 +53,12 @@
#define SAM_PIT_PIVR_OFFSET 0x0008 /* Periodic Interval Value Register */
#define SAM_PIT_PIIR_OFFSET 0x000c /* Periodic Interval Image Register */
-/* PIT Virtual Base Address *********************************************************/
-
-#define SAM_PIT_VBASE (SAM_SYSC_VADDR+SAM_PITC_OFFSET)
-
/* PIT Register Addresses ***********************************************************/
-#define SAM_PIT_MR (SAM_PIT_VBASE+SAM_PIT_MR_OFFSET)
-#define SAM_PIT_SR (SAM_PIT_VBASE+SAM_PIT_SR_OFFSET)
-#define SAM_PIT_PIVR (SAM_PIT_VBASE+SAM_PIT_PIVR_OFFSET)
-#define SAM_PIT_PIIR (SAM_PIT_VBASE+SAM_PIT_PIIR_OFFSET)
+#define SAM_PIT_MR (SAM_PITC_VBASE+SAM_PIT_MR_OFFSET)
+#define SAM_PIT_SR (SAM_PITC_VBASE+SAM_PIT_SR_OFFSET)
+#define SAM_PIT_PIVR (SAM_PITC_VBASE+SAM_PIT_PIVR_OFFSET)
+#define SAM_PIT_PIIR (SAM_PITC_VBASE+SAM_PIT_PIIR_OFFSET)
/* PIT Register Bit Definitions *****************************************************/
diff --git a/nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h b/nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h
index e878e9e10..41824eb09 100644
--- a/nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h
+++ b/nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h
@@ -46,6 +46,22 @@
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
+/* Overview:
+ *
+ * SAMA5 Physical (unmapped) Memory Map
+ * - SAMA5 Internal Memories
+ * - SAMA5 Internal Peripheral Offsets
+ * - System Controller Peripheral Offsets
+ * Sizes of memory regions in bytes
+ * Sizes of memory regions in sections
+ * Section MMU Flags
+ * SAMA5 Virtual (mapped) Memory Map
+ * - Peripheral virtual base addresses
+ * - NuttX vitual base address
+ * MMU Page Table Location
+ * Page table start addresses
+ * Base address of the interrupt vector table
+ */
/* SAMA5 Physical (unmapped) Memory Map */
@@ -119,38 +135,39 @@
/* System Controller Peripheral Offsets */
-#define SAM_HSMC_OFFSET 0x0fffc000 /* 0x0fffc000-0x0fffcfff: HSMC */
+#define SAM_HSMC_OFFSET 0x00ffc000 /* 0x0fffc000-0x0fffcfff: HSMC */
/* 0x0fffd000-0x0fffe3ff: Reserved */
-#define SAM_FUSE_OFFSET 0x0fffe400 /* 0x0fffe400-0x0fffe5ff: FUSE */
-#define SAM_DMAC0_OFFSET 0x0fffe600 /* 0x0fffe600-0x0fffe7ff: DMAC0 */
-#define SAM_DMAC1_OFFSET 0x0fffe800 /* 0x0fffe800-0x0fffe9ff: DMAC1 */
-#define SAM_MPDDRC_OFFSET 0x0fffea00 /* 0x0fffea00-0x0fffebff: MPDDRC */
-#define SAM_MATRIX_OFFSET 0x0fffec00 /* 0x0fffec00-0x0fffedff: MATRIX */
-#define SAM_DBGU_OFFSET 0x0fffee00 /* 0x0fffee00-0x0fffefff: DBGU */
-#define SAM_AIC_OFFSET 0x0ffff000 /* 0x0ffff000-0x0ffff1ff: AIC */
-#define SAM_PIOA_OFFSET 0x0ffff200 /* 0x0ffff200-0x0ffff3ff: PIOA */
-#define SAM_PIOB_OFFSET 0x0ffff400 /* 0x0ffff400-0x0ffff5ff: PIOB */
-#define SAM_PIOC_OFFSET 0x0ffff600 /* 0x0ffff600-0x0ffff7ff: PIOC */
-#define SAM_PIOD_OFFSET 0x0ffff800 /* 0x0ffff800-0x0ffff9ff: PIOD */
-#define SAM_PIOE_OFFSET 0x0ffffa00 /* 0x0ffffa00-0x0ffffbff: PIOE */
-#define SAM_PMC_OFFSET 0x0ffffc00 /* 0x0ffffc00-0x0ffffdff: PMC */
-#define SAM_RSTC_OFFSET 0x0ffffe00 /* 0x0ffffe00-0x0ffffe0f: RSTC */
-#define SAM_SHDC_OFFSET 0x0ffffe10 /* 0x0ffffe10-0x0ffffe1f: SHDC */
+#define SAM_FUSE_OFFSET 0x00ffe400 /* 0x0fffe400-0x0fffe5ff: FUSE */
+#define SAM_DMAC0_OFFSET 0x00ffe600 /* 0x0fffe600-0x0fffe7ff: DMAC0 */
+#define SAM_DMAC1_OFFSET 0x00ffe800 /* 0x0fffe800-0x0fffe9ff: DMAC1 */
+#define SAM_MPDDRC_OFFSET 0x00ffea00 /* 0x0fffea00-0x0fffebff: MPDDRC */
+#define SAM_MATRIX_OFFSET 0x00ffec00 /* 0x0fffec00-0x0fffedff: MATRIX */
+#define SAM_DBGU_OFFSET 0x00ffee00 /* 0x0fffee00-0x0fffefff: DBGU */
+#define SAM_AIC_OFFSET 0x00fff000 /* 0x0ffff000-0x0ffff1ff: AIC */
+#define SAM_PIOA_OFFSET 0x00fff200 /* 0x0ffff200-0x0ffff3ff: PIOA */
+#define SAM_PIOB_OFFSET 0x00fff400 /* 0x0ffff400-0x0ffff5ff: PIOB */
+#define SAM_PIOC_OFFSET 0x00fff600 /* 0x0ffff600-0x0ffff7ff: PIOC */
+#define SAM_PIOD_OFFSET 0x00fff800 /* 0x0ffff800-0x0ffff9ff: PIOD */
+#define SAM_PIOE_OFFSET 0x00fffa00 /* 0x0ffffa00-0x0ffffbff: PIOE */
+#define SAM_PMC_OFFSET 0x00fffc00 /* 0x0ffffc00-0x0ffffdff: PMC */
+#define SAM_RSTC_OFFSET 0x00fffe00 /* 0x0ffffe00-0x0ffffe0f: RSTC */
+#define SAM_SHDC_OFFSET 0x00fffe10 /* 0x0ffffe10-0x0ffffe1f: SHDC */
/* 0x0ffffe20-0x0ffffe2f: Reserved */
-#define SAM_PITC_OFFSET 0x0ffffe30 /* 0x0ffffe30-0x0ffffe3f: PITC */
-#define SAM_WDT_OFFSET 0x0ffffe40 /* 0x0ffffe40-0x0ffffe4f: WDT */
-#define SAM_SCKCR_OFFSET 0x0ffffe50 /* 0x0ffffe50-0x0ffffe53: SCKCR */
-#define SAM_BSC_OFFSET 0x0ffffe54 /* 0x0ffffe54-0x0ffffe5f: BSC */
-#define SAM_GPBR_OFFSET 0x0ffffe60 /* 0x0ffffe60-0x0ffffe6f: GPBR */
+#define SAM_PITC_OFFSET 0x00fffe30 /* 0x0ffffe30-0x0ffffe3f: PITC */
+#define SAM_WDT_OFFSET 0x00fffe40 /* 0x0ffffe40-0x0ffffe4f: WDT */
+#define SAM_SCKCR_OFFSET 0x00fffe50 /* 0x0ffffe50-0x0ffffe53: SCKCR */
+#define SAM_BSC_OFFSET 0x00fffe54 /* 0x0ffffe54-0x0ffffe5f: BSC */
+#define SAM_GPBR_OFFSET 0x00fffe60 /* 0x0ffffe60-0x0ffffe6f: GPBR */
/* 0x0ffffe70-0x0ffffeaf: Reserved */
-#define SAM_RTCC_OFFSET 0x0ffffeb0 /* 0x0ffffeb0-0x0ffffedf: RTCC */
+#define SAM_RTCC_OFFSET 0x00fffeb0 /* 0x0ffffeb0-0x0ffffedf: RTCC */
/* 0x0ffffee0-0x0fffffff: Reserved */
-/* Sizes of memory regions in bytes (Excluding undefined addresses at the end of
- * the memory region). The implemented sizes of the EBI CS0-3 and DDRCS regions
+/* Sizes of memory regions in bytes.
+ *
+ * These sizes exclude the undefined addresses at the end of the memory
+ * region. The implemented sizes of the EBI CS0-3 and DDRCS regions
* are not known apriori and must be specified with configuration settings.
*/
-
/* 0x00000000-0x0fffffff: Internal Memories */
#define SAM_BOOTMEM_SIZE (1*1024*1024) /* 0x00000000-0x000fffff: Boot memory */
#define SAM_ROM_SIZE (1*1024*1024) /* 0x00100000-0x001fffff: ROM */
@@ -173,10 +190,12 @@
#define _NSECTIONS(b) (((b)+0x000fffff) >> 20)
-/* Sizes of sections/regions. The boot logic in sam_boot.c, will select
- * 1Mb level 1 MMU mappings to span the entire physical address space.
- * The definitions below specify the number of 1Mb entries that are
- * required to span a particular address region.
+/* Sizes of memory regions in sections.
+ *
+ * The boot logic in sam_boot.c, will select 1Mb level 1 MMU mappings to
+ * span the entire physical address space. The definitions below specify
+ * the number of 1Mb entries that are required to span a particular address
+ * region.
*/
#define SAM_BOOTMEM_NSECTIONS _NSECTIONS(SAM_BOOTMEM_SIZE)
@@ -225,7 +244,9 @@
#define SAM_PERIPHB_MMUFLAGS MMU_IOFLAGS
#define SAM_SYSC_MMUFLAGS MMU_IOFLAGS
-/* board_memorymap.h contains special mappings that are needed when a ROM
+/* SAMA5 Virtual (mapped) Memory Map
+ *
+ * board_memorymap.h contains special mappings that are needed when a ROM
* memory map is used. It is included in this odd location becaue it depends
* on some the virtual address definitions provided above.
*/
@@ -268,7 +289,68 @@
#endif
-/* The boot logic will create a temporarily mapping based on where NuttX is
+/* Peripheral virtual base addresses */
+
+#define SAM_HSMCI0_VBASE (SAM_PERIPHA_VSECTION+SAM_HSMCI0_OFFSET)
+#define SAM_SPI0_VBASE (SAM_PERIPHA_VSECTION+SAM_SPI0_OFFSET)
+#define SAM_SSC0_VBASE (SAM_PERIPHA_VSECTION+SAM_SSC0_OFFSET)
+#define SAM_CAN0_VBASE (SAM_PERIPHA_VSECTION+SAM_CAN0_OFFSET)
+#define SAM_TC012_VBASE (SAM_PERIPHA_VSECTION+SAM_TC012_OFFSET)
+#define SAM_TWI0_VBASE (SAM_PERIPHA_VSECTION+SAM_TWI0_OFFSET)
+#define SAM_TWI1_VBASE (SAM_PERIPHA_VSECTION+SAM_TWI1_OFFSET)
+#define SAM_USART0_VBASE (SAM_PERIPHA_VSECTION+SAM_USART0_OFFSET)
+#define SAM_USART1_VBASE (SAM_PERIPHA_VSECTION+SAM_USART1_OFFSET)
+#define SAM_UART0_VBASE (SAM_PERIPHA_VSECTION+SAM_UART0_OFFSET)
+#define SAM_GMAC_VBASE (SAM_PERIPHA_VSECTION+SAM_GMAC_OFFSET)
+#define SAM_PWMC_VBASE (SAM_PERIPHA_VSECTION+SAM_PWMC_OFFSET)
+#define SAM_LCDC_VBASE (SAM_PERIPHA_VSECTION+SAM_LCDC_OFFSET)
+#define SAM_ISI_VBASE (SAM_PERIPHA_VSECTION+SAM_ISI_OFFSET)
+#define SAM_SFR_VBASE (SAM_PERIPHA_VSECTION+SAM_SFR_OFFSET)
+
+#define SAM_HSMCI1_VBASE (SAM_PERIPHB_VSECTION+SAM_HSMCI1_OFFSET)
+#define SAM_HSMCI2_VBASE (SAM_PERIPHB_VSECTION+SAM_HSMCI2_OFFSET)
+#define SAM_SPI1_VBASE (SAM_PERIPHB_VSECTION+SAM_SPI1_OFFSET)
+#define SAM_SSC1_VBASE (SAM_PERIPHB_VSECTION+SAM_SSC1_OFFSET)
+#define SAM_CAN1_VBASE (SAM_PERIPHB_VSECTION+SAM_CAN1_OFFSET)
+#define SAM_TC345_VBASE (SAM_PERIPHB_VSECTION+SAM_TC345_OFFSET)
+#define SAM_TSADC_VBASE (SAM_PERIPHB_VSECTION+SAM_TSADC_OFFSET)
+#define SAM_TWI2_VBASE (SAM_PERIPHB_VSECTION+SAM_TWI2_OFFSET)
+#define SAM_USART2_VBASE (SAM_PERIPHB_VSECTION+SAM_USART2_OFFSET)
+#define SAM_USART3_VBASE (SAM_PERIPHB_VSECTION+SAM_USART3_OFFSET)
+#define SAM_UART1_VBASE (SAM_PERIPHB_VSECTION+SAM_UART1_OFFSET)
+#define SAM_EMAC_VBASE (SAM_PERIPHB_VSECTION+SAM_EMAC_OFFSET)
+#define SAM_UDPHS_VBASE (SAM_PERIPHB_VSECTION+SAM_UDPHS_OFFSET)
+#define SAM_SHA_VBASE (SAM_PERIPHB_VSECTION+SAM_SHA_OFFSET)
+#define SAM_AES_VBASE (SAM_PERIPHB_VSECTION+SAM_AES_OFFSET)
+#define SAM_TDES_VBASE (SAM_PERIPHB_VSECTION+SAM_TDES_OFFSET)
+#define SAM_TRNG_VBASE (SAM_PERIPHB_VSECTION+SAM_TRNG_OFFSET)
+
+#define SAM_HSMC_VBASE (SAM_SYSC_VSECTION+SAM_HSMC_OFFSET)
+#define SAM_FUSE_VBASE (SAM_SYSC_VSECTION+SAM_FUSE_OFFSET)
+#define SAM_DMAC0_VBASE (SAM_SYSC_VSECTION+SAM_DMAC0_OFFSET)
+#define SAM_DMAC1_VBASE (SAM_SYSC_VSECTION+SAM_DMAC1_OFFSET)
+#define SAM_MPDDRC_VBASE (SAM_SYSC_VSECTION+SAM_MPDDRC_OFFSET)
+#define SAM_MATRIX_VBASE (SAM_SYSC_VSECTION+SAM_MATRIX_OFFSET)
+#define SAM_DBGU_VBASE (SAM_SYSC_VSECTION+SAM_DBGU_OFFSET)
+#define SAM_AIC_VBASE (SAM_SYSC_VSECTION+SAM_AIC_OFFSET)
+#define SAM_PIOA_VBASE (SAM_SYSC_VSECTION+SAM_PIOA_OFFSET)
+#define SAM_PIOB_VBASE (SAM_SYSC_VSECTION+SAM_PIOB_OFFSET)
+#define SAM_PIOC_VBASE (SAM_SYSC_VSECTION+SAM_PIOC_OFFSET)
+#define SAM_PIOD_VBASE (SAM_SYSC_VSECTION+SAM_PIOD_OFFSET)
+#define SAM_PIOE_VBASE (SAM_SYSC_VSECTION+SAM_PIOE_OFFSET)
+#define SAM_PMC_VBASE (SAM_SYSC_VSECTION+SAM_PMC_OFFSET)
+#define SAM_RSTC_VBASE (SAM_SYSC_VSECTION+SAM_RSTC_OFFSET)
+#define SAM_SHDC_VBASE (SAM_SYSC_VSECTION+SAM_SHDC_OFFSET)
+#define SAM_PITC_VBASE (SAM_SYSC_VSECTION+SAM_PITC_OFFSET)
+#define SAM_WDT_VBASE (SAM_SYSC_VSECTION+SAM_WDT_OFFSET)
+#define SAM_SCKCR_VBASE (SAM_SYSC_VSECTION+SAM_SCKCR_OFFSET)
+#define SAM_BSC_VBASE (SAM_SYSC_VSECTION+SAM_BSC_OFFSET)
+#define SAM_GPBR_VBASE (SAM_SYSC_VSECTION+SAM_GPBR_OFFSET)
+#define SAM_RTCC_VBASE (SAM_SYSC_VSECTION+SAM_RTCC_OFFSET)
+
+/* NuttX vitual base address
+ *
+ * The boot logic will create a temporarily mapping based on where NuttX is
* executing in memory. In this case, NuttX could be running from NOR FLASH,
* SDRAM, external SRAM, or internal SRAM.
*/
@@ -283,7 +365,9 @@
# define NUTTX_START_VADDR SAM_ISRAM_VSECTION
#endif
-/* Determine the address of the MMU page table. We will try to place that page
+/* MMU Page Table Location
+ *
+ * Determine the address of the MMU page table. We will try to place that page
* table at the beginng of ISRAM0 if the vectors are at the high address, 0xffff:0000
* or at the end of ISRAM1 (or ISRAM0 if ISRAM1 is not available in this architecture)
* if the vectors are at 0x0000:0000
@@ -360,7 +444,7 @@
# endif
#endif
-/* Page table start addresses:
+/* Page table start addresses.
*
* 16Kb of memory is reserved hold the page table for the virtual mappings. A
* portion of this table is not accessible in the virtual address space (for
@@ -384,7 +468,7 @@
#define PGTABLE_L2_SIZE (4*256)
#define PGTABLE_L2_NENTRIES (PGTABLE_L2_ALLOC / PGTABLE_L2_SIZE)
-/* Determine the base address of the vector table:
+/* Base address of the interrupt vector table.
*
* SAM_VECTOR_PADDR - Unmapped, physical address of vector table in SRAM
* SAM_VECTOR_VSRAM - Virtual address of vector table in SRAM
diff --git a/nuttx/arch/arm/src/sama5/sam_clockconfig.h b/nuttx/arch/arm/src/sama5/sam_clockconfig.h
index 044890ba6..dd91b64a8 100644
--- a/nuttx/arch/arm/src/sama5/sam_clockconfig.h
+++ b/nuttx/arch/arm/src/sama5/sam_clockconfig.h
@@ -1,4 +1,4 @@
-/************************************************************************************
+/****************************************************************************
* arch/arm/src/sama5/sam_clockconfig.h
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
@@ -31,34 +31,34 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************************************/
+ ****************************************************************************/
#ifndef __ARCH_ARM_SRC_SAMA5_SAM_CLOCKCONFIG_H
#define __ARCH_ARM_SRC_SAMA5_SAM_CLOCKCONFIG_H
-/************************************************************************************
+/****************************************************************************
* Included Files
- ************************************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
-/************************************************************************************
+/****************************************************************************
* Pre-processor Definitions
- ************************************************************************************/
+ ****************************************************************************/
-/************************************************************************************
+/****************************************************************************
* Public Types
- ************************************************************************************/
+ ****************************************************************************/
-/************************************************************************************
+/****************************************************************************
* Inline Functions
- ************************************************************************************/
+ ****************************************************************************/
#ifndef __ASSEMBLY__
-/************************************************************************************
+/****************************************************************************
* Public Data
- ************************************************************************************/
+ ****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
@@ -69,19 +69,19 @@ extern "C"
#define EXTERN extern
#endif
-/************************************************************************************
+/****************************************************************************
* Public Function Prototypes
- ************************************************************************************/
+ ****************************************************************************/
-/************************************************************************************
+/****************************************************************************
* 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.
+ * 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);
diff --git a/nuttx/arch/arm/src/sama5/sam_irq.c b/nuttx/arch/arm/src/sama5/sam_irq.c
index 2c8cb1f3a..a14639ed6 100644
--- a/nuttx/arch/arm/src/sama5/sam_irq.c
+++ b/nuttx/arch/arm/src/sama5/sam_irq.c
@@ -50,10 +50,13 @@
#include "os_internal.h"
#include "up_internal.h"
-#ifdef CONFIG_GPIO_IRQ
-# include "sam_gpio.h"
+#ifdef CONFIG_PIO_IRQ
+# include "sam_pio.h"
#endif
+#include "chip/sam_aic.h"
+#include "sam_irq.h"
+
/****************************************************************************
* Definitions
****************************************************************************/
@@ -74,6 +77,11 @@ volatile uint32_t *current_regs;
* Private Data
****************************************************************************/
+static const uint8_t g_srctype[SCRTYPE_NTYPES] =
+{
+ 0, 0, 1, 1, 2, 3
+};
+
/****************************************************************************
* Private Functions
****************************************************************************/
@@ -92,9 +100,28 @@ static void sam_dumpaic(const char *msg, int irq)
irqstate_t flags;
flags = irqsave();
-#warning Missing logic
slldbg("AIC (%s, irq=%d):\n", msg, irq);
-#warning Missing logic
+
+ /* Select the register set associated with this irq */
+
+ putreg32(irq, SAM_AIC_SSR)
+
+ /* Then dump all of the (readable) register contents */
+
+ slldbg(" SSR: %08x SMR: %08x SVR: %08x IVR: %08x\n",
+ getreg32(SAM_AIC_SSR), getreg32(SAM_AIC_SMR),
+ getreg32(SAM_AIC_SVR), getreg32(SAM_AIC_IVR));
+ slldbg(" FVR: %08x ISR: %08x\n",
+ getreg32(SAM_AIC_FVR), getreg32(SAM_AIC_ISR));
+ slldbg(" IPR: %08x %08x %08x %08x\n",
+ getreg32(SAM_AIC_IPR0), getreg32(SAM_AIC_IPR1),
+ getreg32(SAM_AIC_IPR2), getreg32(SAM_AIC_IPR3));
+ slldbg(" IMR: %08x CISR: %08x SPU: %08x FFSR: %08x\n",
+ getreg32(SAM_AIC_IMR), getreg32(SAM_AIC_CISR),
+ getreg32(SAM_AIC_SPU), getreg32(SAM_AIC_FFSR));
+ slldbg(" DCR: %08x WPMR: %08x WPMR: %08x\n",
+ getreg32(SAM_AIC_DCR), getreg32(SAM_AIC_WPMR),
+ getreg32(SAM_AIC_WPMR));
irqrestore(flags);
}
#else
@@ -102,20 +129,156 @@ static void sam_dumpaic(const char *msg, int irq)
#endif
/****************************************************************************
+ * Name: sam_spurious
+ *
+ * Description:
+ * Spurious interrupt handler.
+ *
+ * Paragraph 17.8.6, Spurious Interrupt: "The Advanced Interrupt Controller
+ * features protection against spurious interrupts. A spurious interrupt is
+ * defined as being the assertion of an interrupt source long enough for the
+ * AIC to assert the nIRQ, but no longer present when AIC_IVR is read. This
+ * is most prone to occur when:
+ *
+ * o An external interrupt source is programmed in level-sensitive mode
+ * and an active level occurs for only a short time.
+ * o An internal interrupt source is programmed in level sensitive and
+ * the output signal of the corresponding embedded peripheral is
+ * activated for a short time. (As in the case for the Watchdog.)
+ * o An interrupt occurs just a few cycles before the software begins to
+ * mask it, thus resulting in a pulse on the interrupt source.
+ *
+ * "The AIC detects a spurious interrupt at the time the AIC_IVR is read
+ * while no enabled interrupt source is pending. When this happens, the AIC
+ * returns the value stored by the programmer in AIC_SPU (Spurious Vector
+ * Register). The programmer must store the address of a spurious interrupt
+ * handler in AIC_SPU as part of the application, to enable an as fast as
+ * possible return to the normal execution flow. This handler writes in
+ * AIC_EOICR and performs a return from interrupt."
+ *
+ ****************************************************************************/
+
+static void sam_spurious(void)
+{
+ /* This is probably irrevelant since true vectored interrupts are not used
+ * in this implementation. The value of AIC_IVR is ignored.
+ */
+
+ lldbg("Spurious interrupt\n");
+ PANIC();
+}
+
+/****************************************************************************
+ * Name: sam_fiqhandler
+ *
+ * Description:
+ * Default FIQ interrupt handler.
+ *
+ ****************************************************************************/
+
+static void sam_fiqhandler(void)
+{
+ /* This is probably irrevelant since true vectored interrupts are not used
+ * in this implementation. The value of AIC_IVR is ignored.
+ */
+
+ lldbg("FIQ\n");
+ PANIC();
+}
+
+/****************************************************************************
+ * Name: sam_irqhandler
+ *
+ * Description:
+ * Default IRQ interrupt handler.
+ *
+ ****************************************************************************/
+
+static void sam_irqhandler( void )
+{
+ /* This is probably irrevelant since true vectored interrupts are not used
+ * in this implementation. The value of AIC_IVR is ignored.
+ */
+
+ lldbg("IRQ\n");
+ PANIC();
+}
+
+/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_irqinitialize
+ *
+ * Description:
+ * This function is called by up_initialize() during the bring-up of the
+ * system. It is the responsibility of this function to but the interrupt
+ * subsystem into the working and ready state.
+ *
****************************************************************************/
void up_irqinitialize(void)
{
- /* Disable all interrupts */
-#warning Missing logic
+ int i;
+
+ /* The following operations need to be atomic, but since this function is
+ * called early in the intialization sequence, we expect to have exclusive
+ * access to the AIC.
+ */
+
+ /* Unprotect SMR, SVR, SPU and DCR register */
+
+ putreg32(AIC_WPMR_WPKEY, SAM_AIC_WPMR);
+
+ /* Configure the FIQ and the IRQs. */
+
+ for (i = 0; i < SAM_IRQ_NINT; i++)
+ {
+ /* Select the interrupt registers */
+
+ putreg32(i, SAM_AIC_SSR);
+
+ /* Disable the interrupt */
+
+ putreg32(AIC_IDCR_INTD, SAM_AIC_IDCR);
+
+ /* Set the (unused) FIQ/IRQ handler */
+
+ if (i == SAM_PID_FIQ)
+ {
+ putreg32((uint32_t)sam_fiqhandler, SAM_AIC_SVR);
+ }
+ else
+ {
+ putreg32((uint32_t)sam_irqhandler, SAM_AIC_SVR);
+ }
+
+ /* Set the default interrupt priority */
+
+ putreg32(SAM_DEFAULT_PRIOR, SAM_AIC_SMR);
+
+ /* Clear any pending interrupt */
+
+ putreg32(AIC_ICCR_INTCLR, SAM_AIC_ICCR);
+ }
+
+ /* Set the (unused) spurious interrupt handler */
+
+ putreg32((uint32_t)sam_spurious, SAM_AIC_SPU);
+
+ /* Perform 8 interrupt acknowledgements by writing any value to the
+ * EOICR register.
+ */
+
+ for (i = 0; i < 8 ; i++)
+ {
+ putreg32(AIC_EOICR_ENDIT, SAM_AIC_EOICR);
+ }
- /* Set all interrupts to the default priority */
-#warning Missing logic
+ /* Restore protection and the interrupt state */
+
+ putreg32(AIC_WPMR_WPKEY | AIC_WPMR_WPEN, SAM_AIC_WPMR);
/* currents_regs is non-NULL only while processing an interrupt */
@@ -123,11 +286,11 @@ void up_irqinitialize(void)
#ifndef CONFIG_SUPPRESS_INTERRUPTS
/* Initialize logic to support a second level of interrupt decoding for
- * GPIO pins.
+ * PIO pins.
*/
-#ifdef CONFIG_GPIO_IRQ
- sam_gpioirqinitialize();
+#ifdef CONFIG_PIO_IRQ
+ sam_pioirqinitialize();
#endif
/* And finally, enable interrupts */
@@ -137,6 +300,75 @@ void up_irqinitialize(void)
}
/****************************************************************************
+ * Name: up_decodeirq
+ *
+ * Description:
+ * This function is called from the IRQ vector handler in arm_vectors.S.
+ * At this point, the interrupt has been taken and the registers have
+ * been saved on the stack. This function simply needs to determine the
+ * the irq number of the interrupt and then to call up_doirq to dispatch
+ * the interrupt.
+ *
+ * Input paramters:
+ * regs - A pointer to the register save area on the stack.
+ *
+ ****************************************************************************/
+
+void up_decodeirq(uint32_t *regs)
+{
+ uint32_t regval;
+
+ /* Paragraph 17.8.5 Protect Mode: "The Protect Mode permits reading the
+ * Interrupt Vector Register without performing the associated automatic
+ * operations. ... Writing PROT in AIC_DCR (Debug Control Register) at 0x1
+ * enables the Protect Mode.
+ *
+ * "When the Protect Mode is enabled, the AIC performs interrupt stacking
+ * only when a write access is performed on the AIC_IVR. Therefore, the
+ * Interrupt Service Routines must write (arbitrary data) to the AIC_IVR
+ * just after reading it. The new context of the AIC, including the value
+ * of the Interrupt Status Register (AIC_ISR), is updated with the current
+ * interrupt only when AIC_IVR is written. ..."
+ *
+ * "To summarize, in normal operating mode, the read of AIC_IVR performs the
+ * following operations within the AIC:
+ *
+ * 1. Calculates active interrupt (higher than current or spurious).
+ * 2. Determines and returns the vector of the active interrupt.
+ * 3. Memorizes the interrupt.
+ * 4. Pushes the current priority level onto the internal stack.
+ * 5. Acknowledges the interrupt.
+ *
+ * "However, while the Protect Mode is activated, only operations 1 to 3 are
+ * performed when AIC_IVR is read. Operations 4 and 5 are only performed by
+ * the AIC when AIC_IVR is written.
+ *
+ * "Software that has been written and debugged using the Protect Mode runs
+ * correctly in Normal Mode without modification. However, in Normal Mode the
+ * AIC_IVR write has no effect and can be removed to optimize the code.
+ */
+
+ /* Write in the IVR to support Protect Mode */
+
+ regval = getreg32(SAM_AIC_IVR);
+ putreg32(regval, SAM_AIC_IVR);
+
+ /* Get the IRQ number from the interrrupt status register. NOTE that the
+ * IRQ number is the same is the peripheral ID (PID).
+ */
+
+ regval = getreg32(SAM_AIC_ISR) & AIC_ISR_MASK;
+
+ /* Dispatch the interrupt */
+
+ up_doirq((int)regval, regs);
+
+ /* Acknowledge interrupt */
+
+ putreg32(AIC_EOICR_ENDIT, SAM_AIC_EOICR);
+}
+
+/****************************************************************************
* Name: up_disable_irq
*
* Description:
@@ -146,16 +378,30 @@ void up_irqinitialize(void)
void up_disable_irq(int irq)
{
+ irqstate_t flags;
+
if (irq < SAM_IRQ_NINT)
{
-#warning Missing logic
+ /* These operations must be atomic */
+
+ flags = irqsave();
+
+ /* Select the register set associated with this irq */
+
+ putreg32(irq, SAM_AIC_SSR);
+
+ /* Disable the interrupt */
+
+ putreg32(AIC_IDCR_INTD, SAM_AIC_IDCR);
+ sam_dumpaic("disable", irq);
+ irqrestore(flags);
}
-#ifdef CONFIG_GPIO_IRQ
+#ifdef CONFIG_PIO_IRQ
else
{
- /* Maybe it is a (derived) GPIO IRQ */
+ /* Maybe it is a (derived) PIO IRQ */
- sam_gpioirqdisable(irq);
+ sam_pioirqdisable(irq);
}
#endif
sam_dumpaic("disable", irq);
@@ -171,19 +417,32 @@ void up_disable_irq(int irq)
void up_enable_irq(int irq)
{
+ irqstate_t flags;
+
if (irq < SAM_IRQ_NINT)
{
-#warning Missing logic
+ /* These operations must be atomic */
+
+ flags = irqsave();
+
+ /* Select the register set associated with this irq */
+
+ putreg32(irq, SAM_AIC_SSR);
+
+ /* Enable the interrupt */
+
+ putreg32(AIC_IECR_INTEN, SAM_AIC_IECR);
+ sam_dumpaic("enable", irq);
+ irqrestore(flags);
}
-#ifdef CONFIG_GPIO_IRQ
+#ifdef CONFIG_PIO_IRQ
else
{
- /* Maybe it is a (derived) GPIO IRQ */
+ /* Maybe it is a (derived) PIO IRQ */
- sam_gpioirqenable(irq);
+ sam_pioirqenable(irq);
}
#endif
- sam_dumpaic("enable", irq);
}
/****************************************************************************
@@ -213,12 +472,81 @@ void up_maskack_irq(int irq)
#ifdef CONFIG_ARCH_IRQPRIO
int up_prioritize_irq(int irq, int priority)
{
+ irqstate_t flags;
+ uint32_t regval;
+
+ DEBUGASSERT(irq < SAM_IRQ_NINT && (unsigned)priority <= AIC_SMR_PRIOR_MASK);
if (irq < SAM_IRQ_NINT)
{
-#warning Missing logic
+ /* These operations must be atomic */
+
+ flags = irqsave();
+
+ /* Select the register set associated with this irq */
+
+ putreg32(irq, SAM_AIC_SSR);
+
+ /* Unprotect and write the SMR register */
+
+ putreg32(AIC_WPMR_WPKEY, SAM_AIC_WPMR);
+
+ /* Set the new priority, preserving the current srctype */
+
+ regval = getreg32(SAM_AIC_SMR);
+ regval &= ~AIC_SMR_PRIOR_MASK;
+ regval |= (uint32_t)priority << AIC_SMR_PRIOR_SHIFT;
+ putreg32(regval, SAM_AIC_SMR);
+
+ /* Restore protection and the interrupt state */
+
+ putreg32(AIC_WPMR_WPKEY | AIC_WPMR_WPEN, SAM_AIC_WPMR);
+ sam_dumpaic("prioritize", irq);
+ irqrestore(flags);
}
- sam_dumpaic("prioritize", irq);
return OK;
}
#endif
+
+/****************************************************************************
+ * Name: sam_irq_srctype
+ *
+ * Description:
+ * irq - Identifies the IRQ source to be configured
+ * srctype - IRQ source configuration
+ *
+ ****************************************************************************/
+
+void sam_irq_srctype(int irq, enum sam_srctype_e srctype)
+{
+ irqstate_t flags;
+ uint32_t regval;
+
+ DEBUGASSERT(irq < SAM_IRQ_NINT && (unsigned)srctype < SCRTYPE_NTYPES);
+
+ /* These operations must be atomic */
+
+ flags = irqsave();
+
+ /* Select the register set associated with this irq */
+
+ putreg32(irq, SAM_AIC_SSR);
+
+ /* Unprotect and write the SMR register */
+
+ putreg32(AIC_WPMR_WPKEY, SAM_AIC_WPMR);
+
+ /* Set the new srctype, preserving the current priority */
+
+ regval = getreg32(SAM_AIC_SMR);
+ regval &= ~AIC_SMR_SRCTYPE_MASK;
+ regval |= (uint32_t)g_srctype[srctype] << AIC_SMR_SRCTYPE_SHIFT;
+ putreg32(regval, SAM_AIC_SMR);
+
+ /* Restore protection and the interrupt state */
+
+ putreg32(AIC_WPMR_WPKEY | AIC_WPMR_WPEN, SAM_AIC_WPMR);
+ sam_dumpaic("srctype", irq);
+ irqrestore(flags);
+}
+
diff --git a/nuttx/arch/arm/src/sama5/sam_irq.h b/nuttx/arch/arm/src/sama5/sam_irq.h
new file mode 100644
index 000000000..505aa6903
--- /dev/null
+++ b/nuttx/arch/arm/src/sama5/sam_irq.h
@@ -0,0 +1,107 @@
+/****************************************************************************
+ * arch/arm/src/sama5/sam_irq.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_SAMA5_SAM_IRQ_H
+#define __ARCH_ARM_SRC_SAMA5_SAM_IRQ_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip/sam_aic.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define SCRTYPE_NTYPES 6
+#define SAM_DEFAULT_PRIOR ((AIC_SMR_PRIOR_MAX+1) >> 1)
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+enum sam_srctype_e
+{
+ SRCTYPE_IHIGH = 0, /* Internal high level */
+ SRCTYPE_XLOW = 1, /* External low level */
+ SRCTYPE_IRISING = 2, /* Internal positive edge */
+ SRCTYPE_XFALLING = 3, /* External negative edge */
+ SRCTYPE_XHIGH = 4, /* External high level */
+ SRCTYPE_XRISING = 5 /* External rising edge */
+};
+
+/****************************************************************************
+ * 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_irq_srctype
+ *
+ * Description:
+ * irq - Identifies the IRQ source to be configured
+ * srctype - IRQ source configuration
+ *
+ ****************************************************************************/
+
+void sam_irq_srctype(int irq, enum sam_srctype_e srctype);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_SAMA5_SAM_IRQ_H */
diff --git a/nuttx/arch/arm/src/sama5/sam_lowputc.h b/nuttx/arch/arm/src/sama5/sam_lowputc.h
index 5a1c15875..a7e193062 100644
--- a/nuttx/arch/arm/src/sama5/sam_lowputc.h
+++ b/nuttx/arch/arm/src/sama5/sam_lowputc.h
@@ -1,4 +1,4 @@
-/************************************************************************************
+/****************************************************************************
* arch/arm/src/sama5/sam_lowputc.h
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
@@ -31,14 +31,14 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************************************/
+ ****************************************************************************/
#ifndef __ARCH_ARM_SRC_SAMA5_SAM_LOWPUTC_H
#define __ARCH_ARM_SRC_SAMA5_SAM_LOWPUTC_H
-/************************************************************************************
+/****************************************************************************
* Included Files
- ************************************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/compiler.h>
@@ -50,23 +50,23 @@
#include "up_internal.h"
#include "chip.h"
-/************************************************************************************
- * Definitions
- ************************************************************************************/
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
-/************************************************************************************
+/****************************************************************************
* Public Types
- ************************************************************************************/
+ ****************************************************************************/
-/************************************************************************************
+/****************************************************************************
* Inline Functions
- ************************************************************************************/
+ ****************************************************************************/
#ifndef __ASSEMBLY__
-/************************************************************************************
+/****************************************************************************
* Public Data
- ************************************************************************************/
+ ****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
@@ -77,19 +77,20 @@ extern "C"
#define EXTERN extern
#endif
-/************************************************************************************
+/****************************************************************************
* Public Function Prototypes
- ************************************************************************************/
+ ****************************************************************************/
-/************************************************************************************
+/****************************************************************************
* Name: sam_lowsetup
*
* Description:
- * Called at the very beginning of _start. Performs low level initialization
- * including setup of the console UART. This UART done early so that the serial
- * console is available for debugging very early in the boot sequence.
+ * Called at the very beginning of _start. Performs low level
+ * initialization including setup of the console UART. This UART done
+ * early so that the serial console is available for debugging very early
+ * in the boot sequence.
*
- ************************************************************************************/
+ ****************************************************************************/
void sam_lowsetup(void);