summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-12-07 13:06:34 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-12-07 13:06:34 -0600
commit16f1c02f2e6f5e7c69c11f5fe5f24ce2f1bac40a (patch)
treee13de5b7ff38c57cf684d7eb861d8c2ddd27446e /nuttx
parentad37e1f44299f3cdcc12750cb7e0e031fc8f9bcf (diff)
downloadpx4-nuttx-16f1c02f2e6f5e7c69c11f5fe5f24ce2f1bac40a.tar.gz
px4-nuttx-16f1c02f2e6f5e7c69c11f5fe5f24ce2f1bac40a.tar.bz2
px4-nuttx-16f1c02f2e6f5e7c69c11f5fe5f24ce2f1bac40a.zip
Add basic directory structure to support the Allwinner A10
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog5
-rw-r--r--nuttx/arch/arm/Kconfig11
-rw-r--r--nuttx/arch/arm/include/a1x/a10_irq.h89
-rw-r--r--nuttx/arch/arm/include/a1x/chip.h68
-rw-r--r--nuttx/arch/arm/include/a1x/irq.h90
-rw-r--r--nuttx/arch/arm/include/sama5/chip.h6
-rw-r--r--nuttx/arch/arm/include/sama5/sama5d3_irq.h7
-rw-r--r--nuttx/arch/arm/src/a1x/Kconfig19
-rw-r--r--nuttx/arch/arm/src/a1x/Make.defs96
9 files changed, 384 insertions, 7 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index aeef6562f..586d431d5 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -6169,3 +6169,8 @@
transfer with the out-of-range block before we test it (2013-12-05).
6.33 2014-xx-xx Gregory Nutt <gnutt@nuttx.org>
+
+ * arch/arm/include/a1x and src/a1x: Directory structure to support
+ the Allwinner A10. Not much there on the initial check-in
+ (2013-12-7).
+
diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig
index 1a5f494e3..22f54ba5d 100644
--- a/nuttx/arch/arm/Kconfig
+++ b/nuttx/arch/arm/Kconfig
@@ -10,6 +10,14 @@ choice
prompt "ARM chip selection"
default ARCH_CHIP_STM32
+config ARCH_CHIP_A1X
+ bool "Allwinner A1X"
+ select ARCH_CORTEXA8
+ select ARCH_HAVE_FPU
+ select ARCH_HAVE_LOWVECTORS
+ ---help---
+ Allwinner A1X family: A10, A10S (A12), A13 (ARM Cortex-A8)
+
config ARCH_CHIP_C5471
bool "TMS320 C5471"
select ARCH_ARM7TDMI
@@ -321,6 +329,9 @@ endif
if ARCH_ARM7TDMI || ARCH_ARM926EJS
source arch/arm/src/arm/Kconfig
endif
+if ARCH_CHIP_A1X
+source arch/arm/src/a1x/Kconfig
+endif
if ARCH_CHIP_C5471
source arch/arm/src/c5471/Kconfig
endif
diff --git a/nuttx/arch/arm/include/a1x/a10_irq.h b/nuttx/arch/arm/include/a1x/a10_irq.h
new file mode 100644
index 000000000..6ea6b5ba8
--- /dev/null
+++ b/nuttx/arch/arm/include/a1x/a10_irq.h
@@ -0,0 +1,89 @@
+/****************************************************************************************
+ * arch/arm/include/a1x/a10_irq.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly through
+ * nuttx/irq.h
+ */
+
+#ifndef __ARCH_ARM_INCLUDE_A1X_A10_IRQ_H
+#define __ARCH_ARM_INCLUDE_A1X_A10_IRQ_H
+
+/****************************************************************************************
+ * Included Files
+ ****************************************************************************************/
+
+/****************************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************************/
+
+/* External interrupts numbers */
+#warning Missing logic
+
+/* Total number of IRQ numbers */
+
+#define NR_IRQS 0
+
+/****************************************************************************************
+ * Public Types
+ ****************************************************************************************/
+
+/****************************************************************************************
+ * Inline functions
+ ****************************************************************************************/
+
+/****************************************************************************************
+ * Public Variables
+ ****************************************************************************************/
+
+/****************************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_ARM_INCLUDE_A1X_A10_IRQ_H */
+
diff --git a/nuttx/arch/arm/include/a1x/chip.h b/nuttx/arch/arm/include/a1x/chip.h
new file mode 100644
index 000000000..cca43bc03
--- /dev/null
+++ b/nuttx/arch/arm/include/a1x/chip.h
@@ -0,0 +1,68 @@
+/************************************************************************************
+ * arch/arm/include/a1x/chip.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_INCLUDE_A1X_CHIP_H
+#define __ARCH_ARM_INCLUDE_A1X_CHIP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* A1X Family */
+
+#if defined(CONFIG_ARCH_CHIP_A10)
+# define ALLWINNER_A1X 1 /* A1X family */
+#else
+# error Unrecognized A1X chip
+#endif
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_INCLUDE_A1X_CHIP_H */
diff --git a/nuttx/arch/arm/include/a1x/irq.h b/nuttx/arch/arm/include/a1x/irq.h
new file mode 100644
index 000000000..b799d7b40
--- /dev/null
+++ b/nuttx/arch/arm/include/a1x/irq.h
@@ -0,0 +1,90 @@
+/****************************************************************************************
+ * arch/arm/include/a1x/irq.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly through
+ * nuttx/irq.h
+ */
+
+#ifndef __ARCH_ARM_INCLUDE_A1X_IRQ_H
+#define __ARCH_ARM_INCLUDE_A1X_IRQ_H
+
+/****************************************************************************************
+ * Included Files
+ ****************************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/a1x/chip.h>
+
+/****************************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************************/
+
+/* Chip-Specific External interrupts */
+
+#if defined(CONFIG_ARCH_CHIP_A10)
+# include <arch/a1x/a10_irq.h>
+#else
+# error Unrecognized A1X chip
+#endif
+
+/****************************************************************************************
+ * Public Types
+ ****************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************************
+ * Public Data
+ ****************************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************************/
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_ARM_INCLUDE_A1X_IRQ_H */
+
diff --git a/nuttx/arch/arm/include/sama5/chip.h b/nuttx/arch/arm/include/sama5/chip.h
index 6048fb393..f4e98cdb9 100644
--- a/nuttx/arch/arm/include/sama5/chip.h
+++ b/nuttx/arch/arm/include/sama5/chip.h
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_INCLUDE_SAMAD5_CHIP_H
-#define __ARCH_ARM_INCLUDE_SAMAD5_CHIP_H
+#ifndef __ARCH_ARM_INCLUDE_SAMA5_CHIP_H
+#define __ARCH_ARM_INCLUDE_SAMA5_CHIP_H
/************************************************************************************
* Included Files
@@ -131,4 +131,4 @@
* Public Functions
************************************************************************************/
-#endif /* __ARCH_ARM_INCLUDE_SAMAD5_CHIP_H */
+#endif /* __ARCH_ARM_INCLUDE_SAMA5_CHIP_H */
diff --git a/nuttx/arch/arm/include/sama5/sama5d3_irq.h b/nuttx/arch/arm/include/sama5/sama5d3_irq.h
index 872a393e9..23038a7b3 100644
--- a/nuttx/arch/arm/include/sama5/sama5d3_irq.h
+++ b/nuttx/arch/arm/include/sama5/sama5d3_irq.h
@@ -37,8 +37,8 @@
* nuttx/irq.h
*/
-#ifndef __ARCH_ARM_INCLUDE_SAM34_SAMA5_SAMA5D3_IRQ_H
-#define __ARCH_ARM_INCLUDE_SAM34_SAMA5_SAMA5D3_IRQ_H
+#ifndef __ARCH_ARM_INCLUDE_SAMA5_SAMA5D3_IRQ_H
+#define __ARCH_ARM_INCLUDE_SAMA5_SAMA5D3_IRQ_H
/****************************************************************************************
* Included Files
@@ -392,5 +392,4 @@ extern "C" {
#endif
#endif
-#endif /* __ARCH_ARM_INCLUDE_SAM34_SAMA5_SAMA5D3_IRQ_H */
-
+#endif /* __ARCH_ARM_INCLUDE_SAMA5_SAMA5D3_IRQ_H */
diff --git a/nuttx/arch/arm/src/a1x/Kconfig b/nuttx/arch/arm/src/a1x/Kconfig
new file mode 100644
index 000000000..e83ac188a
--- /dev/null
+++ b/nuttx/arch/arm/src/a1x/Kconfig
@@ -0,0 +1,19 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+if ARCH_CHIP_A1X
+
+comment "A1x Configuration Options"
+
+choice
+ prompt "Allwinner A1X Chip Selection"
+ default ARCH_CHIP_A10
+
+config ARCH_CHIP_A10
+ bool "A10"
+
+endchoice
+
+endif # ARCH_CHIP_A1X
diff --git a/nuttx/arch/arm/src/a1x/Make.defs b/nuttx/arch/arm/src/a1x/Make.defs
new file mode 100644
index 000000000..29580a58d
--- /dev/null
+++ b/nuttx/arch/arm/src/a1x/Make.defs
@@ -0,0 +1,96 @@
+############################################################################
+# arch/arm/a1x/Make.defs
+#
+# Copyright (C) 2013 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name Gregory Nutt 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.
+#
+############################################################################
+
+# The vector table is the "head" object, i.e., the one that must forced into
+# the link in order to draw in all of the other components
+
+HEAD_ASRC = arm_vectortab.S
+
+# Force the start-up logic to be at the beginning of the .text to simplify
+# debug.
+
+ifeq ($(CONFIG_PAGING),y)
+CMN_ASRCS = arm_pghead.S
+else
+CMN_ASRCS = arm_head.S
+endif
+
+# Common assembly language files
+
+CMN_ASRCS += arm_vectors.S arm_fpuconfig.S arm_fullcontextrestore.S
+CMN_ASRCS += arm_saveusercontext.S arm_vectoraddrexcptn.S arm_vfork.S
+CMN_ASRCS += cp15_coherent_dcache.S cp15_invalidate_dcache.S
+CMN_ASRCS += cp15_clean_dcache.S cp15_flush_dcache.S cp15_invalidate_dcache_all.S
+
+# Common C source files
+
+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_puts.c up_mdelay.c up_udelay.c
+CMN_CSRCS += up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c
+
+CMN_CSRCS += arm_assert.c arm_blocktask.c arm_copyfullstate.c arm_dataabort.c
+CMN_CSRCS += arm_doirq.c arm_initialstate.c arm_mmu.c arm_prefetchabort.c
+CMN_CSRCS += arm_releasepending.c arm_reprioritizertr.c
+CMN_CSRCS += arm_schedulesigaction.c arm_sigdeliver.c arm_syscall.c
+CMN_CSRCS += arm_unblocktask.c arm_undefinedinsn.c
+
+# Configuration dependent C and assembly language files
+
+ifeq ($(CONFIG_PAGING),y)
+CMN_CSRCS += arm_allocpage.c arm_checkmapping.c arm_pginitialize.c
+CMN_CSRCS += arm_va2pte.c
+endif
+
+ifeq ($(CONFIG_ELF),y)
+CMN_CSRCS += arm_elf.c
+endif
+
+ifeq ($(CONFIG_ARCH_FPU),y)
+CMN_ASRCS += arm_savefpu.S arm_restorefpu.S
+CMN_CSRCS += arm_copyarmstate.c
+endif
+
+ifeq ($(CONFIG_DEBUG_STACK),y)
+CMN_CSRCS += up_checkstack.c
+endif
+
+# A1x-specific assembly language files
+
+CHIP_ASRCS =
+
+# A1x-specific C source files
+
+CHIP_CSRCS =