summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-27 16:19:07 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-27 16:19:07 +0000
commit56bae3f8da4c6b9849323462f40a123c01df8608 (patch)
tree7e73899c2d53ab709415866302e120d572c1ff2b
parentb5a5ba0335a35555f062f7604377339552454886 (diff)
downloadpx4-nuttx-56bae3f8da4c6b9849323462f40a123c01df8608.tar.gz
px4-nuttx-56bae3f8da4c6b9849323462f40a123c01df8608.tar.bz2
px4-nuttx-56bae3f8da4c6b9849323462f40a123c01df8608.zip
Correct some ARMv6-M NVIC addresses
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5680 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/src/armv6-m/nvic.h55
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_dumpnvic.c111
-rw-r--r--nuttx/arch/arm/src/nuc1xx/Make.defs4
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_dumpgpio.c3
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_gpio.h2
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_irq.c1
-rw-r--r--nuttx/configs/nutiny-nuc120/README.txt16
7 files changed, 173 insertions, 19 deletions
diff --git a/nuttx/arch/arm/src/armv6-m/nvic.h b/nuttx/arch/arm/src/armv6-m/nvic.h
index c01d9421c..d088d7827 100644
--- a/nuttx/arch/arm/src/armv6-m/nvic.h
+++ b/nuttx/arch/arm/src/armv6-m/nvic.h
@@ -58,19 +58,19 @@
/* NVIC register offsets ****************************************************************************/
/* NVIC register offsets (all relative to ARMV6M_NVIC1_BASE) */
-#define ARMV6M_NVIC_ISER_OFFSET 0x0100 /* Interrupt set-enable register */
-#define ARMV6M_NVIC_ICER_OFFSET 0x0180 /* Interrupt clear-enable register */
-#define ARMV6M_NVIC_ISPR_OFFSET 0x0200 /* Interrupt set-pending register */
-#define ARMV6M_NVIC_ICPR_OFFSET 0x0280 /* Interrupt clear-pending register */
-#define ARMV6M_NVIC_IPR_OFFSET(n) (0x0400 + ((n) << 2))
-# define ARMV6M_NVIC_IPR0_OFFSET 0x0400 /* Interrupt priority register 0 */
-# define ARMV6M_NVIC_IPR1_OFFSET 0x0404 /* Interrupt priority register 1 */
-# define ARMV6M_NVIC_IPR2_OFFSET 0x0408 /* Interrupt priority register 2 */
-# define ARMV6M_NVIC_IPR3_OFFSET 0x040c /* Interrupt priority register 3 */
-# define ARMV6M_NVIC_IPR4_OFFSET 0x0410 /* Interrupt priority register 4 */
-# define ARMV6M_NVIC_IPR5_OFFSET 0x0414 /* Interrupt priority register 5 */
-# define ARMV6M_NVIC_IPR6_OFFSET 0x0418 /* Interrupt priority register 6 */
-# define ARMV6M_NVIC_IPR7_OFFSET 0x041c /* Interrupt priority register 7 */
+#define ARMV6M_NVIC_ISER_OFFSET 0x0000 /* Interrupt set-enable register */
+#define ARMV6M_NVIC_ICER_OFFSET 0x0080 /* Interrupt clear-enable register */
+#define ARMV6M_NVIC_ISPR_OFFSET 0x0100 /* Interrupt set-pending register */
+#define ARMV6M_NVIC_ICPR_OFFSET 0x0180 /* Interrupt clear-pending register */
+#define ARMV6M_NVIC_IPR_OFFSET(n) (0x0300 + ((n) << 2))
+# define ARMV6M_NVIC_IPR0_OFFSET 0x0300 /* Interrupt priority register 0 */
+# define ARMV6M_NVIC_IPR1_OFFSET 0x0304 /* Interrupt priority register 1 */
+# define ARMV6M_NVIC_IPR2_OFFSET 0x0308 /* Interrupt priority register 2 */
+# define ARMV6M_NVIC_IPR3_OFFSET 0x030c /* Interrupt priority register 3 */
+# define ARMV6M_NVIC_IPR4_OFFSET 0x0310 /* Interrupt priority register 4 */
+# define ARMV6M_NVIC_IPR5_OFFSET 0x0314 /* Interrupt priority register 5 */
+# define ARMV6M_NVIC_IPR6_OFFSET 0x0318 /* Interrupt priority register 6 */
+# define ARMV6M_NVIC_IPR7_OFFSET 0x031c /* Interrupt priority register 7 */
/* System control register offsets (all relative to ARMV6M_SYSCON2_BASE) */
@@ -364,8 +364,37 @@
* Public Data
****************************************************************************************************/
+#ifndef __ASSEMBLY__
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
/****************************************************************************************************
* Public Function Prototypes
****************************************************************************************************/
+/****************************************************************************************************
+ * Function: up_dumpnvic
+ *
+ * Description:
+ * Dump all NVIC and SYSCON registers along with a user message.
+ *
+ ****************************************************************************************************/
+
+#ifdef CONFIG_DEBUG
+void up_dumpnvic(FAR const char *msg);
+#else
+# define up_dumpnvic(m)
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_COMMON_ARMV6_M_NVIC_H */
diff --git a/nuttx/arch/arm/src/armv6-m/up_dumpnvic.c b/nuttx/arch/arm/src/armv6-m/up_dumpnvic.c
new file mode 100644
index 000000000..5d6be8cab
--- /dev/null
+++ b/nuttx/arch/arm/src/armv6-m/up_dumpnvic.c
@@ -0,0 +1,111 @@
+/****************************************************************************
+ * arch/arm/src/armv6-m/up_dumpnvic.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 <sys/types.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+
+#include "up_arch.h"
+
+#include "nvic.h"
+
+#ifdef CONFIG_DEBUG
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: up_dumpnvic
+ *
+ * Description:
+ * Dump all NVIC and SYSCON registers along with a user message.
+ *
+ ****************************************************************************/
+
+void up_dumpnvic(FAR const char *msg)
+{
+ irqstate_t flags;
+ int i;
+
+ /* The following requires exclusive access to the NVIC/SYSCON registers */
+
+ flags = irqsave();
+
+ lldbg("NVIC: %s\n", msg);
+ lldbg(" ISER: %08x ICER: %08x ISPR: %08x ICPR: %08x\n",
+ getreg32(ARMV6M_NVIC_ISER), getreg32(ARMV6M_NVIC_ICER),
+ getreg32(ARMV6M_NVIC_ISPR), getreg32(ARMV6M_NVIC_ICPR));
+
+ for (i = 0 ; i < 8; i += 4)
+ {
+ lldbg(" IPR%d: %08x IPR%d: %08x IPR%d: %08x IPR%d: %08x\n",
+ i, getreg32(ARMV6M_NVIC_IPR(i)),
+ i+1, getreg32(ARMV6M_NVIC_IPR(i+1)),
+ i+2, getreg32(ARMV6M_NVIC_IPR(i+2)),
+ i+3, getreg32(ARMV6M_NVIC_IPR(i+3)));
+ }
+
+ lldbg("SYSCON:\n");
+ lldbg(" CPUID: %08x ICSR: %08x AIRCR: %08x SCR: %08x\n",
+ getreg32(ARMV6M_SYSCON_CPUID), getreg32(ARMV6M_SYSCON_ICSR),
+ getreg32(ARMV6M_SYSCON_AIRCR), getreg32(ARMV6M_SYSCON_SCR));
+ lldbg(" CCR: %08x SHPR2: %08x SHPR3: %08x\n",
+ getreg32(ARMV6M_SYSCON_CCR), getreg32(ARMV6M_SYSCON_SHPR2),
+ getreg32(ARMV6M_SYSCON_SHPR3));
+
+ irqrestore(flags);
+}
+
+#endif /* CONFIG_DEBUG */
diff --git a/nuttx/arch/arm/src/nuc1xx/Make.defs b/nuttx/arch/arm/src/nuc1xx/Make.defs
index 0d20f8135..d491a15c9 100644
--- a/nuttx/arch/arm/src/nuc1xx/Make.defs
+++ b/nuttx/arch/arm/src/nuc1xx/Make.defs
@@ -55,6 +55,10 @@ ifeq ($(CONFIG_ELF),y)
CMN_CSRCS += up_elf.c
endif
+ifeq ($(CONFIG_DEBUG),y)
+CMN_CSRCS += up_dumpnvic.c
+endif
+
CHIP_ASRCS =
CHIP_CSRCS = nuc_clockconfig.c nuc_gpio.c nuc_idle.c nuc_irq.c nuc_lowputc.c
CHIP_CSRCS += nuc_serial.c nuc_start.c nuc_timerisr.c
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_dumpgpio.c b/nuttx/arch/arm/src/nuc1xx/nuc_dumpgpio.c
index aee9fa219..e9966ef3a 100644
--- a/nuttx/arch/arm/src/nuc1xx/nuc_dumpgpio.c
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_dumpgpio.c
@@ -104,7 +104,7 @@ static const char g_portchar[NUC_GPIO_NPORTS] =
*
****************************************************************************/
-int nuc_dumpgpio(gpio_cfgset_t pinset, const char *msg)
+void nuc_dumpgpio(gpio_cfgset_t pinset, const char *msg)
{
irqstate_t flags;
uintptr_t base;
@@ -138,7 +138,6 @@ int nuc_dumpgpio(gpio_cfgset_t pinset, const char *msg)
getreg32(base + NUC_GPIO_ISRC_OFFSET));
irqrestore(flags);
- return OK;
}
#endif /* CONFIG_DEBUG */
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h b/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h
index 807080475..58eaea570 100644
--- a/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h
@@ -245,7 +245,7 @@ bool nuc_gpioread(gpio_cfgset_t pinset);
****************************************************************************/
#ifdef CONFIG_DEBUG
-int nuc_dumpgpio(gpio_cfgset_t pinset, const char *msg);
+void nuc_dumpgpio(gpio_cfgset_t pinset, const char *msg);
#else
# define nuc_dumpgpio(p,m)
#endif
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_irq.c b/nuttx/arch/arm/src/nuc1xx/nuc_irq.c
index ed62e7f43..423e40031 100644
--- a/nuttx/arch/arm/src/nuc1xx/nuc_irq.c
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_irq.c
@@ -199,7 +199,6 @@ void up_irqinitialize(void)
putreg32(DEFPRIORITY32, ARMV6M_SYSCON_SHPR2);
putreg32(DEFPRIORITY32, ARMV6M_SYSCON_SHPR3);
- putreg32(DEFPRIORITY32, ARMV6M_SYSCON_SHPR3);
/* Now set all of the interrupt lines to the default priority */
diff --git a/nuttx/configs/nutiny-nuc120/README.txt b/nuttx/configs/nutiny-nuc120/README.txt
index f1e8aa0c6..c2359b0cd 100644
--- a/nuttx/configs/nutiny-nuc120/README.txt
+++ b/nuttx/configs/nutiny-nuc120/README.txt
@@ -95,6 +95,12 @@ LEDs
Serial Console
==============
+As with most NuttX configurations, the NuTiny-SKD-NUC120 configurations
+depend on having a serial console to interact with the software. The
+NuTiny-SDK-NUC120, however, has not on-board RS-232 drivers so will be
+necessary to connect the NuTiny-SDK-NUC120 UART pins to an external
+RS-232 driver board or TTL-to-Serial USB adaptor.
+
By default UART1 is used as the serial console on these boards. NUC120LE3AN
is provided as an LQFP48 package and, for this case, the UART1 RX signal
(RXD1) is on PB.4, pin 8, and the TX signal (TXD1) is on PB.5, pin 9.
@@ -300,7 +306,8 @@ Where <subdir> is one of the following:
CONFIG_WINDOWS_CYGWIN=y : Using Cygwin
CONFIG_ARMV6M_TOOLCHAIN_CODESOURCERYW=y : CodeSourcery for Windows
- 3. Serial Console. The serial console is on UART1 which is available
+ 3. Serial Console. A serial console is required to see the OS test
+ output. The serial console is configured on UART1 which is available
on JP5:
UART1 RX signal (RXD1) is on PB.4, pin 8, and
@@ -331,12 +338,17 @@ Where <subdir> is one of the following:
CONFIG_WINDOWS_CYGWIN=y : Using Cygwin
CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW=y : CodeSourcery for Windows
- 3. Serial Console. The serial console is on UART1 which is available
+ 3. Serial Console. A serial console is necessary to interrupt with
+ NSH. The serial console is configured on UART1 which is available
on JP5:
UART1 RX signal (RXD1) is on PB.4, pin 8, and
UART1 TX signal (TXD1) is on PB.5, pin 9.
+ It is possible to configure NSH to use a USB serial console instead
+ of an RS-232 serial console. However, that configuration has not
+ been impelmented as of this writing.
+
4. This configuration includes USB Support (CDC/ACM device)
CONFIG_STM32_USB=y : STM32 USB device support