summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-12-08 09:11:52 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-12-08 09:11:52 -0600
commitb2f157fd430fb34ebcc69e2dc6955bd5e0836fa0 (patch)
tree35f453710ec3155dec8ba5644421e774e5d772ef
parent8431b9d22ed4e6cb71dba92dd2e84fe1ab0e94f8 (diff)
downloadpx4-nuttx-b2f157fd430fb34ebcc69e2dc6955bd5e0836fa0.tar.gz
px4-nuttx-b2f157fd430fb34ebcc69e2dc6955bd5e0836fa0.tar.bz2
px4-nuttx-b2f157fd430fb34ebcc69e2dc6955bd5e0836fa0.zip
A10 mmu configuration and INTC register definitions
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/arch/arm/src/a1x/Make.defs2
-rw-r--r--nuttx/arch/arm/src/a1x/a1x_boot.c377
-rw-r--r--nuttx/arch/arm/src/a1x/chip/a10_memorymap.h78
-rw-r--r--nuttx/arch/arm/src/a1x/chip/a1x_intc.h212
5 files changed, 636 insertions, 36 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 3937c4f7e..0db5b3ebe 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -6175,3 +6175,6 @@
(2013-12-7).
* configs/pcduino-a10: Directory structure for the pcDuino board. This
board is based on the Allwinner A10 (2013-12-7).
+ * arch/arm/src/a1x/a1x_boot.c and chip/a1x_intc.h: More A10 logic
+ (2013-12-8).
+
diff --git a/nuttx/arch/arm/src/a1x/Make.defs b/nuttx/arch/arm/src/a1x/Make.defs
index 29580a58d..1ea07a8d8 100644
--- a/nuttx/arch/arm/src/a1x/Make.defs
+++ b/nuttx/arch/arm/src/a1x/Make.defs
@@ -93,4 +93,4 @@ CHIP_ASRCS =
# A1x-specific C source files
-CHIP_CSRCS =
+CHIP_CSRCS = a1x_boot.c
diff --git a/nuttx/arch/arm/src/a1x/a1x_boot.c b/nuttx/arch/arm/src/a1x/a1x_boot.c
new file mode 100644
index 000000000..1dba20beb
--- /dev/null
+++ b/nuttx/arch/arm/src/a1x/a1x_boot.c
@@ -0,0 +1,377 @@
+/****************************************************************************
+ * arch/arm/src/a1x/a1x_boot.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <assert.h>
+
+#ifdef CONFIG_PAGING
+# include <nuttx/page.h>
+#endif
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "arm.h"
+#include "mmu.h"
+#include "fpu.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* The vectors are, by default, positioned at the beginning of the text
+ * section. They will always have to be copied to the correct location.
+ *
+ * If we are using high vectors (CONFIG_ARCH_LOWVECTORS=n). In this case,
+ * the vectors will lie at virtual address 0xffff:000 and we will need
+ * to a) copy the vectors to another location, and b) map the vectors
+ * to that address, and
+ *
+ * For the case of CONFIG_ARCH_LOWVECTORS=y, defined. Vectors will be
+ * copied to SRAM A1 at address 0x0000:0000
+ */
+
+#if !defined(CONFIG_ARCH_LOWVECTORS) && defined(CONFIG_ARCH_ROMPGTABLE)
+# error High vector remap cannot be performed if we are using a ROM page table
+#endif
+
+/* if SDRAM is used, then it will be configured twice: It will first be
+ * configured to a temporary state to support low-level ininitialization.
+ * After the SDRAM has been fully initialized, SRAM be used to
+ * set the SDRM in its final, fully cache-able state.
+ */
+
+#undef NEED_SDRAM_REMAPPING
+#if defined(CONFIG_SAMA5_DDRCS) && !defined(CONFIG_SAMA5_BOOT_SDRAM) && \
+ !defined(CONFIG_ARCH_ROMPGTABLE)
+# define NEED_SDRAM_REMAPPING 1
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+extern uint32_t _vector_start; /* Beginning of vector block */
+extern uint32_t _vector_end; /* End+1 of vector block */
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/* This table describes how to map a set of 1Mb pages to space the physical
+ * address space of the A1X.
+ */
+
+#ifndef CONFIG_ARCH_ROMPGTABLE
+static const struct section_mapping_s section_mapping[] =
+{
+ { A1X_INTMEM_PSECTION, A1X_INTMEM_VSECTION,
+ A1X_INTMEM_MMUFLAGS, A1X_INTMEM_NSECTIONS
+ },
+ { A1X_PERIPH_PSECTION, A1X_PERIPH_VSECTION,
+ A1X_PERIPH_MMUFLAGS, A1X_PERIPH_NSECTIONS
+ },
+ { A1X_SRAMC_PSECTION, A1X_SRAMC_VSECTION,
+ A1X_SRAMC_MMUFLAGS, A1X_SRAMC_NSECTIONS
+ },
+ { A1X_DE_PSECTION, A1X_DE_VSECTION,
+ A1X_DE_MMUFLAGS, A1X_DE_NSECTIONS
+ },
+ { A1X_DDR_PSECTION, A1X_DDR_VSECTION,
+ A1X_DDR_MMUFLAGS, A1X_DDR_NSECTIONS
+ },
+ { A1X_BROM_PSECTION, A1X_BROM_VSECTION,
+ A1X_BROM_MMUFLAGS, A1X_BROM_NSECTIONS
+ }
+};
+
+#define NMAPPINGS \
+ (sizeof(section_mapping) / sizeof(struct section_mapping_s))
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: a1x_setupmappings
+ *
+ * Description
+ * Map all of the initial memory regions defined in section_mapping[]
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_ARCH_ROMPGTABLE
+static inline void a1x_setupmappings(void)
+{
+ int i;
+
+ for (i = 0; i < NMAPPINGS; i++)
+ {
+ mmu_l1_map_region(&section_mapping[i]);
+ }
+}
+#endif
+
+/****************************************************************************
+ * Name: a1x_vectorpermissions
+ *
+ * Description:
+ * Set permissions on the vector mapping.
+ *
+ ****************************************************************************/
+
+#if !defined(CONFIG_ARCH_ROMPGTABLE) && defined(CONFIG_ARCH_LOWVECTORS) && \
+ defined(CONFIG_PAGING)
+static void a1x_vectorpermissions(uint32_t mmuflags)
+{
+ /* The PTE for the beginning of ISRAM is at the base of the L2 page table */
+
+ uint32_t pte = mmu_l2_getentry(PG_L2_VECT_VADDR, 0);
+
+ /* String the MMU flags from the page table entry.
+ *
+ * The pte might be zero the first time this function is called.
+ */
+
+ if (pte == 0)
+ {
+ pte = PG_VECT_PBASE;
+ }
+ else
+ {
+ pte &= PG_L1_PADDRMASK;
+ }
+
+ /* Update the page table entry with the MMU flags and save */
+
+ mmu_l2_setentry(PG_L2_VECT_VADDR, pte, 0, mmuflags);
+}
+#endif
+
+/****************************************************************************
+ * Name: a1x_vectormapping
+ *
+ * Description:
+ * Setup a special mapping for the interrupt vectors when (1) the
+ * interrupt vectors are not positioned in ROM, and when (2) the interrupt
+ * vectors are located at the high address, 0xffff0000. When the
+ * interrupt vectors are located in ROM, we just have to assume that they
+ * were set up correctly; When vectors are located in low memory,
+ * 0x00000000, the mapping for the ROM memory region will be suppressed.
+ *
+ ****************************************************************************/
+
+#if !defined(CONFIG_ARCH_ROMPGTABLE) && !defined(CONFIG_ARCH_LOWVECTORS)
+static void a1x_vectormapping(void)
+{
+ uint32_t vector_paddr = A1X_VECTOR_PADDR & PTE_SMALL_PADDR_MASK;
+ uint32_t vector_vaddr = A1X_VECTOR_VADDR & PTE_SMALL_PADDR_MASK;
+ uint32_t vector_size = (uint32_t)&_vector_end - (uint32_t)&_vector_start;
+ uint32_t end_paddr = A1X_VECTOR_PADDR + vector_size;
+
+ /* REVISIT: Cannot really assert in this context */
+
+ DEBUGASSERT (vector_size <= VECTOR_TABLE_SIZE);
+
+ /* We want to keep our interrupt vectors and interrupt-related logic in
+ * zero-wait state internal SRAM (ISRAM). The A1X has 128Kb of ISRAM
+ * positioned at physical address 0x0300:0000; we need to map this to
+ * 0xffff:0000.
+ */
+
+ while (vector_paddr < end_paddr)
+ {
+ mmu_l2_setentry(VECTOR_L2_VBASE, vector_paddr, vector_vaddr,
+ MMU_L2_VECTORFLAGS);
+ vector_paddr += 4096;
+ vector_vaddr += 4096;
+ }
+
+ /* Now set the level 1 descriptor to refer to the level 2 page table. */
+
+ mmu_l1_setentry(VECTOR_L2_PBASE & PMD_PTE_PADDR_MASK,
+ A1X_VECTOR_VADDR & PMD_PTE_PADDR_MASK,
+ MMU_L1_VECTORFLAGS);
+}
+#else
+ /* No vector remap */
+
+# define a1x_vectormapping()
+#endif
+
+/****************************************************************************
+ * Name: a1x_copyvectorblock
+ *
+ * Description:
+ * Copy the interrupt block to its final destination. Vectors are already
+ * positioned at the beginning of the text region and only need to be
+ * copied in the case where we are using high vectors.
+ *
+ * NOTE: We don't actually have to copy the vector block. We could simply
+ * set the the INTC vector address.
+ *
+ ****************************************************************************/
+
+static void a1x_copyvectorblock(void)
+{
+ uint32_t *src;
+ uint32_t *end;
+ uint32_t *dest;
+
+ /* If we are using re-mapped vectors in an area that has been marked
+ * read only, then temparily mark the mapping write-able (non-buffered).
+ */
+
+#ifdef CONFIG_PAGING
+ a1x_vectorpermissions(MMU_L2_VECTRWFLAGS);
+#endif
+
+ /* Copy the vectors into ISRAM at the address that will be mapped to the vector
+ * address:
+ *
+ * A1X_VECTOR_PADDR - Unmapped, physical address of vector table in SRAM
+ * A1X_VECTOR_VSRAM - Virtual address of vector table in SRAM
+ * A1X_VECTOR_VADDR - Virtual address of vector table (0x00000000 or
+ * 0xffff0000)
+ */
+
+ src = (uint32_t*)&_vector_start;
+ end = (uint32_t*)&_vector_end;
+ dest = (uint32_t*)A1X_VECTOR_VSRAM;
+
+ while (src < end)
+ {
+ *dest++ = *src++;
+ }
+
+ /* Make the vectors read-only, cacheable again */
+
+#if !defined(CONFIG_ARCH_LOWVECTORS) && defined(CONFIG_PAGING)
+ a1x_vectorpermissions(MMU_L2_VECTORFLAGS);
+#endif
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_boot
+ *
+ * Description:
+ * Complete boot operations started in arm_head.S
+ *
+ * This logic will be executing in SDRAM. This boot logic was started by
+ * the A10 boot logic. At this point in time, clocking and SDRAM have
+ * already be initialized (they must be because we are executing out of
+ * SDRAM). So all that must be done here is to:
+ *
+ * 1) Refine the memory mapping,
+ * 2) Configure the serial console, and
+ * 3) Perform board-specific initializations.
+ *
+ ****************************************************************************/
+
+void up_boot(void)
+{
+#ifndef CONFIG_ARCH_ROMPGTABLE
+ /* __start provided the basic MMU mappings for SRAM. Now provide mappings
+ * for all IO regions (Including the vector region).
+ */
+
+ a1x_setupmappings();
+
+ /* Provide a special mapping for the IRAM interrupt vector positioned in
+ * high memory.
+ */
+
+ a1x_vectormapping();
+
+#endif /* CONFIG_ARCH_ROMPGTABLE */
+
+ /* Setup up vector block. _vector_start and _vector_end are exported from
+ * arm_vector.S
+ */
+
+ a1x_copyvectorblock();
+
+ /* Initialize the FPU */
+
+#ifdef CONFIG_ARCH_FPU
+ arm_fpuconfig();
+#endif
+
+ /* Perform common, low-level chip initialization (might do nothing) */
+
+ a1x_lowsetup();
+
+ /* Perform early serial initialization if we are going to use the serial
+ * driver.
+ */
+
+#ifdef USE_EARLYSERIALINIT
+ a1x_earlyserialinit();
+#endif
+
+ /* For the case of the separate user-/kernel-space build, perform whatever
+ * platform specific initialization of the user memory is required.
+ * Normally this just means initializing the user space .data and .bss
+ * segments.
+ */
+
+#ifdef CONFIG_NUTTX_KERNEL
+ a1x_userspace();
+#endif
+
+ /* Perform board-specific initialization, This must include:
+ *
+ * - Initialization of board-specific memory resources (e.g., SDRAM)
+ * - Configuration of board specific resources (PIOs, LEDs, etc).
+ */
+
+ a1x_boardinitialize();
+}
diff --git a/nuttx/arch/arm/src/a1x/chip/a10_memorymap.h b/nuttx/arch/arm/src/a1x/chip/a10_memorymap.h
index 7ee0209f8..7e90f8a36 100644
--- a/nuttx/arch/arm/src/a1x/chip/a10_memorymap.h
+++ b/nuttx/arch/arm/src/a1x/chip/a10_memorymap.h
@@ -103,7 +103,7 @@
#define A1X_ACE_OFFSET 0x0001a000 /* ACE 0x01c1:A000-0x01c1:afff 4K */
#define A1X_TVE1_OFFSET 0x0001b000 /* TVE 1 0x01c1:B000-0x01c1:bfff 4K */
#define A1X_USB2_OFFSET 0x0001c000 /* USB 2 0x01c1:C000-0x01c1:cfff 4K */
-#define A1X_CSI1_OFFSET 0x0001d000 /* CSI 1 0x01c1:D000-0x01c1:dfff 4K */
+#define A1X_CSI1_OFFSET 0x0001d000 /* CSI 1 0x01c1:D000-0x01c1:dfff 4K */
#define A1X_TZASC_OFFSET 0x0001e000 /* TZASC 0x01c1:E000-0x01c1:efff 4K */
#define A1X_SPI3_OFFSET 0x0001f000 /* SPI3 0x01c1:F000-0x01c1:ffff 4K */
#define A1X_CCM_OFFSET 0x00020000 /* CCM 0x01c2:0000-0x01c2:03ff 1K */
@@ -159,7 +159,7 @@
#define A1X_SRAMA2_PADDR (A1X_INTMEM_PSECTION+A1X_SRAMA2_OFFSET)
#define A1X_SRAMA3_PADDR (A1X_INTMEM_PSECTION+A1X_SRAMA3_OFFSET)
#define A1X_SRAMA4_PADDR (A1X_INTMEM_PSECTION+A1X_SRAMA4_OFFSET)
-#define A1X_SRAMNAND_PADDR
+#define A1X_SRAMNAND_PADDR
#define A1X_SRAMD_PADDR (A1X_INTMEM_PSECTION+A1X_SRAMD_OFFSET)
#define A1X_SRAMDSEC_PADDR (A1X_INTMEM_PSECTION+A1X_SRAMDSEC_OFFSET)
@@ -273,13 +273,16 @@
* span the entire physical address space. The definitions below specify
* the number of 1Mb entries that are required to span a particular address
* region.
+ *
+ * NOTE: the size of the mapped SDRAM region depends on the configured size
+ * of DRAM, not on the size of the address space assigned to DRAM.
*/
#define A1X_INTMEM_NSECTIONS _NSECTIONS(A1X_INTMEM_SIZE)
#define A1X_PERIPH_NSECTIONS _NSECTIONS(A1X_PERIPH_SIZE)
#define A1X_SRAMC_NSECTIONS _NSECTIONS(A1X_SRAMC_SIZE)
#define A1X_DE_NSECTIONS _NSECTIONS(A1X_DE_SIZE)
-#define A1X_DDR_NSECTIONS _NSECTIONS(A1X_DDR_SIZE)
+#define A1X_DDR_NSECTIONS _NSECTIONS(CONFIG_RAM_SIZE)
#define A1X_BROM_NSECTIONS _NSECTIONS(A1X_BROM_SIZE)
/* Section MMU Flags */
@@ -325,7 +328,7 @@
#define A1X_SRAMA2_VADDR (A1X_INTMEM_VSECTION+A1X_SRAMA2_OFFSET)
#define A1X_SRAMA3_VADDR (A1X_INTMEM_VSECTION+A1X_SRAMA3_OFFSET)
#define A1X_SRAMA4_VADDR (A1X_INTMEM_VSECTION+A1X_SRAMA4_OFFSET)
-#define A1X_SRAMNAND_VADDR
+#define A1X_SRAMNAND_VADDR
#define A1X_SRAMD_VADDR (A1X_INTMEM_VSECTION+A1X_SRAMD_OFFSET)
#define A1X_SRAMDSEC_VADDR (A1X_INTMEM_VSECTION+A1X_SRAMDSEC_OFFSET)
@@ -410,7 +413,7 @@
#define A1X_BROM_VADDR (A1X_BROM_VSECTION+A1X_BROM_OFFSET)
-/* NuttX vitual base address
+/* NuttX virtual base address
*
* The boot logic will create a temporarily mapping based on where NuttX is
* executing in memory. In this case, NuttX will be running from either
@@ -478,37 +481,45 @@
*
* 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
- * normal operation). There is this large whole in the physcal address space
- * for which there will never be level 1 mappings:
+ * normal operation). There are several large holes in the physical address
+ * space for which there will never be level 1 mappings:
+ *
+ * LI PAGE TABLE
+ * ADDRESS RANGE SIZE ENTRIES SECTIONS
+ * ----------------------- ------- -------------- ---------
+ * 0x0003:0000-0x01eb:ffff 275MB 0x0004-0x006c 26
+ * *(none usable) 0
+ * 0x01ec:0000-0x3fff:ffff 993MB 0x0078-0x0ffc 993
+ * *0x0400-0x0ffc 767
*
- * 0x80000000-0xefffffff: Undefined (1.75 GB)
+ * And the largest is probably from the end of SDRAM through 0xfff0:0000.
+ * But the size of that region varies with the size of the installed SDRAM.
+ * It is at least:
*
- * That is the offset where the main L2 page tables will be positioned. This
- * corresponds to page table offsets 0x000002000 up to 0x000003c00. That
- * is 1792 entries, each mapping 4KB of address for a total of 7MB of virtual
- * address space)
+ * LI PAGE TABLE
+ * ADDRESS RANGE SIZE ENTRIES SECTIONS
+ * ----------------------- ------- -------------- ---------
+ * 0xc000:0000-0xffef:ffff 1022MB *0x3000-0x3ff8 1022
*
- * Up to two L2 page tables may be used:
+ * And probably much larger.
*
- * 1) One mapping the vector table. However, L2 page tables must be aligned
- * to 1KB address boundaries, so the minimum L2 page table size is then
- * 1KB, mapping up a full megabyte of virtual address space.
+ * * NOTE that the L2 page table entries must be aligned 1KB address
+ * boundaries.
*
- * This L2 page table is only allocated if CONFIG_ARCH_LOWVECTORS is *not*
- * defined. The A1X boot-up logic will map the beginning of the boot
- * memory to address 0x0000:0000 using both the MMU and the AXI matrix
- * REMAP register. So no L2 page table is required.
+ * These two larger regions is where L2 page tables will positioned. Up to
+ * two L2 page tables may be used:
*
+ * 1) One mapping the vector table (only when CONFIG_ARCH_LOWVECTORS is not
+ * defined).
* 2) If on-demand paging is supported (CONFIG_PAGING=y), than an additional
- * L2 page table is needed. This page table will use the remainder of
- * the address space.
+ * L2 page table is needed.
*/
#ifndef CONFIG_ARCH_LOWVECTORS
/* Vector L2 page table offset/size */
-# define VECTOR_L2_OFFSET 0x000002000
-# define VECTOR_L2_SIZE 0x000000400
+# define VECTOR_L2_OFFSET 0x000000400
+# define VECTOR_L2_SIZE 0x000000bfc
/* Vector L2 page table base addresses */
@@ -519,18 +530,15 @@
# define VECTOR_L2_END_PADDR (VECTOR_L2_PBASE+VECTOR_L2_SIZE)
# define VECTOR_L2_END_VADDR (VECTOR_L2_VBASE+VECTOR_L2_SIZE)
+#endif
/* Paging L2 page table offset/size */
-# define PGTABLE_L2_OFFSET 0x000002400
-# define PGTABLE_L2_SIZE 0x000001800
+#define PGTABLE_START_PADDR (A1X_DDR_PSECTION+CONFIG_RAM_SIZE)
+#define PGTABLE_BROM_OFFSET 0x3ffc
-#else
-/* Paging L2 page table offset/size */
-
-# define PGTABLE_L2_OFFSET 0x000002000
-# define PGTABLE_L2_SIZE 0x000001c00
-#endif
+#define PGTABLE_L2_OFFSET ((PGTABLE_START_PADDR >> 18) & ~3)
+#define PGTABLE_L2_SIZE (PGTABLE_BROM_OFFSET - PGTABLE_L2_OFFSET)
/* Paging L2 page table base addresses
*
@@ -556,15 +564,15 @@
#define VECTOR_TABLE_SIZE 0x00010000
#ifdef CONFIG_ARCH_LOWVECTORS /* Vectors located at 0x0000:0000 */
# define A1X_VECTOR_PADDR A1X_SRAMA1_PADDR
-# define A1X_VECTOR_VSRAM A1X_ISRAM0_VADDR
+# define A1X_VECTOR_VSRAM A1X_SRAMA1_VADDR
# define A1X_VECTOR_VADDR 0x00000000
#else /* Vectors located at 0xffff:0000 -- this probably does not work */
# ifdef A1X_ISRAM1_SIZE >= VECTOR_TABLE_SIZE
# define A1X_VECTOR_PADDR (A1X_SRAMA1_PADDR+A1X_ISRAM1_SIZE-VECTOR_TABLE_SIZE)
-# define A1X_VECTOR_VSRAM (A1X_ISRAM1_VADDR+A1X_ISRAM1_SIZE-VECTOR_TABLE_SIZE)
+# define A1X_VECTOR_VSRAM (A1X_SRAMA1_VADDR+A1X_ISRAM1_SIZE-VECTOR_TABLE_SIZE)
# else
# define A1X_VECTOR_PADDR (A1X_SRAMA1_PADDR+A1X_ISRAM0_SIZE-VECTOR_TABLE_SIZE)
-# define A1X_VECTOR_VSRAM (A1X_ISRAM0_VADDR+A1X_ISRAM0_SIZE-VECTOR_TABLE_SIZE)
+# define A1X_VECTOR_VSRAM (A1X_SRAMA1_VADDR+A1X_ISRAM0_SIZE-VECTOR_TABLE_SIZE)
# endif
# define A1X_VECTOR_VADDR 0xffff0000
#endif
diff --git a/nuttx/arch/arm/src/a1x/chip/a1x_intc.h b/nuttx/arch/arm/src/a1x/chip/a1x_intc.h
new file mode 100644
index 000000000..186a80a2d
--- /dev/null
+++ b/nuttx/arch/arm/src/a1x/chip/a1x_intc.h
@@ -0,0 +1,212 @@
+/************************************************************************************
+ * arch/arm/src/a1x/chip/a1x_intc.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_A1X_CHIP_A1X_INTC_H
+#define __ARCH_ARM_SRC_A1X_CHIP_A1X_INTC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/a1x/chip.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define A1X_INTC_VECTOR_OFFSET 0x0000 /* Interrupt Vector */
+#define A1X_INTC_BASEADDR_OFFSET 0x0004 /* Interrupt Base Address */
+#define A1X_INTC_PROTECT_OFFSET 0x0008 /* Interrupt Protection Register */
+#define A1X_INTC_NMICTRL_OFFSET 0x000c /* Interrupt Control */
+#define A1X_INTC_IRQ_PEND0_OFFSET 0x0010 /* Interrupt IRQ Pending 0 Status */
+#define A1X_INTC_IRQ_PEND1_OFFSET 0x0014 /* Interrupt IRQ Pending 1 Status */
+#define A1X_INTC_IRQ_PEND2_OFFSET 0x0018 /* Interrupt IRQ Pending 2 Status */
+#define A1X_INTC_FIQ_PEND0_OFFSET 0x0020 /* Interrupt FIQ Pending 0 Status */
+#define A1X_INTC_FIQ_PEND1_OFFSET 0x0024 /* Interrupt FIQ Pending 1 Status */
+#define A1X_INTC_FIQ_PEND2_OFFSET 0x0028 /* Interrupt FIQ Pending 2 Status */
+#define A1X_INTC_IRQ_SEL0_OFFSET 0x0030 /* Interrupt Select 0 */
+#define A1X_INTC_IRQ_SEL1_OFFSET 0x0034 /* Interrupt Select 1 */
+#define A1X_INTC_IRQ_SEL2_OFFSET 0x0038 /* Interrupt Select 2 */
+#define A1X_INTC_EN0_OFFSET 0x0040 /* Interrupt Enable 0 */
+#define A1X_INTC_EN1_OFFSET 0x0044 /* Interrupt Enable 1 */
+#define A1X_INTC_EN2_OFFSET 0x0048 /* Interrupt Enable 2 */
+#define A1X_INTC_MASK0_OFFSET 0x0050 /* Interrupt Mask 0 */
+#define A1X_INTC_MASK1_OFFSET 0x0054 /* Interrupt Mask 1 */
+#define A1X_INTC_MASK2_OFFSET 0x0058 /* Interrupt Mask 2 */
+#define A1X_INTC_RESP0_OFFSET 0x0060 /* Interrupt Response 0 */
+#define A1X_INTC_RESP1_OFFSET 0x0064 /* Interrupt Response 1 */
+#define A1X_INTC_RESP2_OFFSET 0x0068 /* Interrupt Response 2 */
+#define A1X_INTC_FF0_OFFSET 0x0070 /* Interrupt Fast Forcing 0 */
+#define A1X_INTC_FF1_OFFSET 0x0074 /* Interrupt Fast Forcing 1 */
+#define A1X_INTC_FF2_OFFSET 0x0078 /* Interrupt Fast Forcing 2 */
+#define A1X_INTC_PRIO0_OFFSET 0x0080 /* Interrupt Source Priority 0 */
+#define A1X_INTC_PRIO1_OFFSET 0x0084 /* Interrupt Source Priority 1 */
+#define A1X_INTC_PRIO2_OFFSET 0x0088 /* Interrupt Source Priority 2 */
+#define A1X_INTC_PRIO3_OFFSET 0x008c /* Interrupt Source Priority 3 */
+#define A1X_INTC_PRIO4_OFFSET 0x0090 /* Interrupt Source Priority 4 */
+
+/* Register virtual addresses *******************************************************/
+
+#define A1X_INTC_VECTOR (A1X_INTC_VADDR+A1X_INTC_VECTOR_OFFSET)
+#define A1X_INTC_BASEADDR (A1X_INTC_VADDR+A1X_INTC_BASEADDR_OFFSET)
+#define A1X_INTC_PROTECT (A1X_INTC_VADDR+A1X_INTC_PROTECT_OFFSET)
+#define A1X_INTC_NMICTRL (A1X_INTC_VADDR+A1X_INTC_NMICTRL_OFFSET)
+#define A1X_INTC_IRQ_PEND0 (A1X_INTC_VADDR+A1X_INTC_IRQ_PEND0_OFFSET)
+#define A1X_INTC_IRQ_PEND1 (A1X_INTC_VADDR+A1X_INTC_IRQ_PEND1_OFFSET)
+#define A1X_INTC_IRQ_PEND2 (A1X_INTC_VADDR+A1X_INTC_IRQ_PEND2_OFFSET)
+#define A1X_INTC_FIQ_PEND0 (A1X_INTC_VADDR+A1X_INTC_FIQ_PEND0_OFFSET)
+#define A1X_INTC_FIQ_PEND1 (A1X_INTC_VADDR+A1X_INTC_FIQ_PEND1_OFFSET)
+#define A1X_INTC_FIQ_PEND2 (A1X_INTC_VADDR+A1X_INTC_FIQ_PEND2_OFFSET)
+#define A1X_INTC_IRQ_SEL0 (A1X_INTC_VADDR+A1X_INTC_IRQ_SEL0_OFFSET)
+#define A1X_INTC_IRQ_SEL1 (A1X_INTC_VADDR+A1X_INTC_IRQ_SEL1_OFFSET)
+#define A1X_INTC_IRQ_SEL2 (A1X_INTC_VADDR+A1X_INTC_IRQ_SEL2_OFFSET)
+#define A1X_INTC_EN0 (A1X_INTC_VADDR+A1X_INTC_EN0_OFFSET)
+#define A1X_INTC_EN1 (A1X_INTC_VADDR+A1X_INTC_EN1_OFFSET)
+#define A1X_INTC_EN2 (A1X_INTC_VADDR+A1X_INTC_EN2_OFFSET)
+#define A1X_INTC_MASK0 (A1X_INTC_VADDR+A1X_INTC_MASK0_OFFSET)
+#define A1X_INTC_MASK1 (A1X_INTC_VADDR+A1X_INTC_MASK1_OFFSET)
+#define A1X_INTC_MASK2 (A1X_INTC_VADDR+A1X_INTC_MASK2_OFFSET)
+#define A1X_INTC_RESP0 (A1X_INTC_VADDR+A1X_INTC_RESP0_OFFSET)
+#define A1X_INTC_RESP1 (A1X_INTC_VADDR+A1X_INTC_RESP1_OFFSET)
+#define A1X_INTC_RESP2 (A1X_INTC_VADDR+A1X_INTC_RESP2_OFFSET)
+#define A1X_INTC_FF0 (A1X_INTC_VADDR+A1X_INTC_FF0_OFFSET)
+#define A1X_INTC_FF1 (A1X_INTC_VADDR+A1X_INTC_FF1_OFFSET)
+#define A1X_INTC_FF2 (A1X_INTC_VADDR+A1X_INTC_FF2_OFFSET)
+#define A1X_INTC_PRIO0 (A1X_INTC_VADDR+A1X_INTC_PRIO0_OFFSET)
+#define A1X_INTC_PRIO1 (A1X_INTC_VADDR+A1X_INTC_PRIO1_OFFSET)
+#define A1X_INTC_PRIO2 (A1X_INTC_VADDR+A1X_INTC_PRIO2_OFFSET)
+#define A1X_INTC_PRIO3 (A1X_INTC_VADDR+A1X_INTC_PRIO3_OFFSET)
+#define A1X_INTC_PRIO4 (A1X_INTC_VADDR+A1X_INTC_PRIO4_OFFSET)
+
+/* Register bit field definitions ***************************************************/
+
+/* Interrupt Vector */
+
+#define INTC_VECTOR_MASK 0xfffffffc /* Bits 2-31: Vector address */
+
+/* Interrupt Base Address */
+
+#define INTC_BASEADDR_MASK 0xfffffffc /* Bits 2-31: Base address */
+
+/* Interrupt Control */
+
+#define INTC_PROTECT_PROTEN (1 << 0) /* Bit 0: Enabled protected register access */
+
+/* Interrupt Control */
+
+#define INTC_NMICTRL_SRCTYPE_SHIFT (0) /* Bits 0-1: External NMI Interrupt Source Type */
+#define INTC_NMICTRL_SRCTYPE_MASK (3 << INTC_NMICTRL_SRCTYPE_SHIFT)
+# define INTC_NMICTRL_SRCTYPE_LOW (0 << INTC_NMICTRL_SRCTYPE_SHIFT) /* Low level sensitive */
+# define INTC_NMICTRL_SRCTYPE_NEDGE (1 << INTC_NMICTRL_SRCTYPE_SHIFT) /* Negative edge trigged */
+
+/* Interrupt IRQ Pending 0-2 Status */
+
+#define INTC_IRQ_PEND(n) (1 << (n)) /* n=0-31: Interrupt pending */
+# define INTC_IRQ_PEND0(n) (1 << (n)) /* n=0-31: Interrupt pending */
+# define INTC_IRQ_PEND1(n) (1 << ((n) - 32)) /* n=32-63: Interrupt pending */
+# define INTC_IRQ_PEND2(n) (1 << ((n) - 64)) /* n=64-95: Interrupt pending */
+
+/* Interrupt FIQ Pending 0-2 Status */
+
+#define INTC_FIQ_PEND(n) (1 << (n)) /* n=0-31: Interrupt pending */
+# define INTC_FIQ_PEND0(n) (1 << (n)) /* n=0-31: Interrupt pending */
+# define INTC_FIQ_PEND1(n) (1 << ((n) - 32)) /* n=32-63: Interrupt pending */
+# define INTC_FIQ_PEND2(n) (1 << ((n) - 64)) /* n=64-95: Interrupt pending */
+
+/* Interrupt Select 0-2 */
+
+#define INTC_IRQ_SEL(n) (1 << (n)) /* n=0-31: FIQ (vs IRQ) */
+# define INTC_IRQ_SEL0(n) (1 << (n)) /* n=0-31: FIQ (vs IRQ) */
+# define INTC_IRQ_SEL1(n) (1 << ((n) - 32)) /* n=32-63: FIQ (vs IRQ) */
+# define INTC_IRQ_SEL2(n) (1 << ((n) - 64)) /* n=64-95: FIQ (vs IRQ) */
+
+/* Interrupt Enable 0-2 */
+
+#define INTC_EN(n) (1 << (n)) /* n=0-31: Interrupt enable */
+# define INTC_EN0(n) (1 << (n)) /* n=0-31: Interrupt enable */
+# define INTC_EN1(n) (1 << ((n) - 32)) /* n=32-63: Interrupt enable */
+# define INTC_EN2(n) (1 << ((n) - 64)) /* n=64-95: Interrupt enable */
+
+/* Interrupt Mask 0-2 */
+
+#define INTC_MASK(n) (1 << (n)) /* n=0-31: Interrupt mask */
+# define INTC_MASK0(n) (1 << (n)) /* n=0-31: Interrupt mask */
+# define INTC_MASK1(n) (1 << ((n) - 32)) /* n=32-63: Interrupt mask */
+# define INTC_MASK2(n) (1 << ((n) - 64)) /* n=64-95: Interrupt mask */
+
+/* Interrupt Response 0-2 */
+
+#define INTC_RESP(n) (1 << (n)) /* n=0-31: Interrupt level mask */
+# define INTC_RESP0(n) (1 << (n)) /* n=0-31: Interrupt level mask */
+# define INTC_RESP1(n) (1 << ((n) - 32)) /* n=32-63: Interrupt level mask */
+# define INTC_RESP2(n) (1 << ((n) - 64)) /* n=64-95: Interrupt level mask */
+
+/* Interrupt Fast Forcing 0-2 */
+
+#define INTC_FF(n) (1 << (n)) /* n=0-31: Enable fast forcing feature */
+# define INTC_FF0(n) (1 << (n)) /* n=0-31: Enable fast forcing feature */
+# define INTC_FF1(n) (1 << ((n) - 32)) /* n=32-63: Enable fast forcing feature */
+# define INTC_FF2(n) (1 << ((n) - 64)) /* n=64-95: Enable fast forcing feature */
+
+/* Interrupt Source Priority 0-4 */
+
+#define INTC_PRIO_SHIFT(n) ((n) << 1) /* n=0-15: Priority level */
+#define INTC_PRIO_MASK(n) (3 << INTC_PRIO_SHIFT(n))
+# define INTC_PRIO(n,p) ((uint32_t)(p) << INTC_PRIO_SHIFT(n))
+
+#define INTC_PRIO0_SHIFT(n) ((n) << 1) /* n=0-15: Priority level */
+#define INTC_PRIO0_MASK(n) (3 << INTC_PRIO0_SHIFT(n))
+# define INTC_PRIO0(n,p) ((uint32_t)(p) << INTC_PRIO0_SHIFT(n))
+
+#define INTC_PRIO1_SHIFT(n) (((n) - 16) << 1) /* n=16-31: Priority level */
+#define INTC_PRIO1_MASK(n) (3 << INTC_PRIO1_SHIFT(n))
+# define INTC_PRIO1(n,p) ((uint32_t)(p) << INTC_PRIO1_SHIFT(n))
+
+#define INTC_PRIO2_SHIFT(n) (((n) - 32) << 1) /* n=32-47: Priority level */
+#define INTC_PRIO2_MASK(n) (3 << INTC_PRIO2_SHIFT(n))
+# define INTC_PRIO2(n,p) ((uint32_t)(p) << INTC_PRIO2_SHIFT(n))
+
+#define INTC_PRIO3_SHIFT(n) (((n) - 48) << 1) /* n=48-63: Priority level */
+#define INTC_PRIO3_MASK(n) (3 << INTC_PRIO3_SHIFT(n))
+# define INTC_PRIO3(n,p) ((uint32_t)(p) << INTC_PRIO3_SHIFT(n))
+
+#define INTC_PRIO4_SHIFT(n) (((n) - 64) << 1) /* n=64-79: Priority level */
+#define INTC_PRIO4_MASK(n) (3 << INTC_PRIO4_SHIFT(n))
+# define INTC_PRIO4(n,p) ((uint32_t)(p) << INTC_PRIO4_SHIFT(n))
+
+#endif /* __ARCH_ARM_SRC_A1X_CHIP_A1X_INTC_H */