summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-02-17 08:14:19 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-02-17 08:14:19 -0600
commit2e03944fad977e7894526c943828a6a2b853b015 (patch)
treebe500574db6b11c1dcea3f016f589beaf20d7105
parent50f50139abe5ae04ea1545ba015ace5f7687aa78 (diff)
downloadpx4-nuttx-2e03944fad977e7894526c943828a6a2b853b015.tar.gz
px4-nuttx-2e03944fad977e7894526c943828a6a2b853b015.tar.bz2
px4-nuttx-2e03944fad977e7894526c943828a6a2b853b015.zip
SAMD20: Misc changes for a clean build with debug enabled
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_irq.c2
-rw-r--r--nuttx/arch/arm/src/samd/Make.defs4
-rw-r--r--nuttx/arch/arm/src/samd/sam_irq.c130
-rw-r--r--nuttx/arch/arm/src/samd/sam_irq.h14
-rw-r--r--nuttx/arch/arm/src/samd/sam_irqprio.c140
-rw-r--r--nuttx/configs/samd20-xplained/README.txt2
-rw-r--r--nuttx/configs/samd20-xplained/include/board.h2
-rw-r--r--nuttx/configs/samd20-xplained/nsh/defconfig2
8 files changed, 193 insertions, 103 deletions
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_irq.c b/nuttx/arch/arm/src/nuc1xx/nuc_irq.c
index 364bb7f0f..ee4ce2bd9 100644
--- a/nuttx/arch/arm/src/nuc1xx/nuc_irq.c
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_irq.c
@@ -352,7 +352,7 @@ int up_prioritize_irq(int irq, int priority)
irq == NUC_IRQ_PENDSV ||
irq == NUC_IRQ_SYSTICK ||
(irq >= NUC_IRQ_INTERRUPT && irq < NR_IRQS));
- DEBUGASSERT(priority >= NVIC_SYSH_DISABLE_PRIORITY &&
+ DEBUGASSERT(priority >= NVIC_SYSH_PRIORITY_MAX &&
priority <= NVIC_SYSH_PRIORITY_MIN);
/* Check for external interrupt */
diff --git a/nuttx/arch/arm/src/samd/Make.defs b/nuttx/arch/arm/src/samd/Make.defs
index ae7ed8964..d4ed5f200 100644
--- a/nuttx/arch/arm/src/samd/Make.defs
+++ b/nuttx/arch/arm/src/samd/Make.defs
@@ -74,3 +74,7 @@ CHIP_CSRCS += sam_port.c sam_serial.c sam_start.c sam_timerisr.c sam_usart.c
ifeq ($(CONFIG_NUTTX_KERNEL),y)
CHIP_CSRCS += sam_userspace.c
endif
+
+ifeq ($(CONFIG_NUTTX_KERNEL),y)
+CHIP_CSRCS += sam_irqprio.c
+endif
diff --git a/nuttx/arch/arm/src/samd/sam_irq.c b/nuttx/arch/arm/src/samd/sam_irq.c
index abbec2510..000f58b62 100644
--- a/nuttx/arch/arm/src/samd/sam_irq.c
+++ b/nuttx/arch/arm/src/samd/sam_irq.c
@@ -78,50 +78,6 @@ volatile uint32_t *current_regs;
****************************************************************************/
/****************************************************************************
- * Name: sam_dumpnvic
- *
- * Description:
- * Dump some interesting NVIC registers
- *
- ****************************************************************************/
-
-#if defined(CONFIG_DEBUG_IRQ)
-static void sam_dumpnvic(const char *msg, int irq)
-{
- irqstate_t flags;
-
- flags = irqsave();
-
- lldbg("NVIC (%s, irq=%d):\n", msg, irq);
- lldbg(" ISER: %08x ICER: %08x\n",
- getreg32(ARMV6M_NVIC_ISER), getreg32(ARMV6M_NVIC_ICER));
- lldbg(" ISPR: %08x ICPR: %08x\n",
- getreg32(ARMV6M_NVIC_ISPR), getreg32(ARMV6M_NVIC_ICPR));
- lldbg(" IRQ PRIO: %08x %08x %08x %08x\n",
- getreg32(ARMV6M_NVIC_IPR0), getreg32(ARMV6M_NVIC_IPR1),
- getreg32(ARMV6M_NVIC_IPR2), getreg32(ARMV6M_NVIC_IPR3));
- lldbg(" %08x %08x %08x %08x\n",
- getreg32(ARMV6M_NVIC_IPR4), getreg32(ARMV6M_NVIC_IPR5),
- getreg32(ARMV6M_NVIC_IPR6), getreg32(ARMV6M_NVIC_IPR7));
-
- lldbg("SYSCON:\n");
- lldbg(" CPUID: %08x\n",
- getreg32(ARMV6M_SYSCON_CPUID));
- lldbg(" ICSR: %08x AIRCR: %08x\n",
- getreg32(ARMV6M_SYSCON_ICSR), getreg32(ARMV6M_SYSCON_AIRCR));
- lldbg(" SCR: %08x CCR: %08x\n",
- getreg32(ARMV6M_SYSCON_SCR), getreg32(ARMV6M_SYSCON_CCR));
- lldbg(" SHPR2: %08x SHPR3: %08x\n",
- getreg32(ARMV6M_SYSCON_SHPR2), getreg32(ARMV6M_SYSCON_SHPR3));
-
- irqrestore(flags);
-}
-
-#else
-# define sam_dumpnvic(msg, irq)
-#endif
-
-/****************************************************************************
* Name: sam_nmi, sam_busfault, sam_usagefault, sam_pendsv,
* sam_dbgmonitor, sam_pendsv, sam_reserved
*
@@ -331,70 +287,46 @@ void up_ack_irq(int irq)
}
/****************************************************************************
- * Name: up_prioritize_irq
+ * Name: sam_dumpnvic
*
* Description:
- * Set the priority of an IRQ.
- *
- * Since this API is not supported on all architectures, it should be
- * avoided in common implementations where possible.
+ * Dump some interesting NVIC registers
*
****************************************************************************/
-#ifdef CONFIG_ARCH_IRQPRIO
-int up_prioritize_irq(int irq, int priority)
+#ifdef CONFIG_DEBUG_IRQ
+void sam_dumpnvic(const char *msg, int irq)
{
- uint32_t regaddr;
- uint32_t regval;
- int shift;
-
- DEBUGASSERT(irq == SAM_IRQ_SVCALL ||
- irq == SAM_IRQ_PENDSV ||
- irq == SAM_IRQ_SYSTICK ||
- (irq >= SAM_IRQ_INTERRUPT && irq < NR_IRQS));
- DEBUGASSERT(priority >= NVIC_SYSH_DISABLE_PRIORITY &&
- priority <= NVIC_SYSH_PRIORITY_MIN);
-
- /* Check for external interrupt */
-
- if (irq >= SAM_IRQ_INTERRUPT && irq < SAM_IRQ_INTERRUPT + SAM_IRQ_NINTS)
- {
- /* ARMV6M_NVIC_IPR() maps register IPR0-IPR7 with four settings per
- * register.
- */
-
- regaddr = ARMV6M_NVIC_IPR(irq >> 2);
- shift = (irq & 3) << 3;
- }
-
- /* Handle processor exceptions. Only SVCall, PendSV, and SysTick can be
- * reprioritized. And we will not permit modification of SVCall through
- * this function.
- */
+ irqstate_t flags;
- else if (irq == SAM_IRQ_PENDSV)
- {
- regaddr = ARMV6M_SYSCON_SHPR2;
- shift = SYSCON_SHPR3_PRI_14_SHIFT;
- }
- else if (irq == SAM_IRQ_SYSTICK)
- {
- regaddr = ARMV6M_SYSCON_SHPR2;
- shift = SYSCON_SHPR3_PRI_15_SHIFT;
- }
- else
- {
- return ERROR;
- }
+ flags = irqsave();
- /* Set the priority */
+ lldbg("NVIC (%s, irq=%d):\n", msg, irq);
+ lldbg(" ISER: %08x ICER: %08x\n",
+ getreg32(ARMV6M_NVIC_ISER), getreg32(ARMV6M_NVIC_ICER));
+ lldbg(" ISPR: %08x ICPR: %08x\n",
+ getreg32(ARMV6M_NVIC_ISPR), getreg32(ARMV6M_NVIC_ICPR));
+ lldbg(" IRQ PRIO: %08x %08x %08x %08x\n",
+ getreg32(ARMV6M_NVIC_IPR0), getreg32(ARMV6M_NVIC_IPR1),
+ getreg32(ARMV6M_NVIC_IPR2), getreg32(ARMV6M_NVIC_IPR3));
+ lldbg(" %08x %08x %08x %08x\n",
+ getreg32(ARMV6M_NVIC_IPR4), getreg32(ARMV6M_NVIC_IPR5),
+ getreg32(ARMV6M_NVIC_IPR6), getreg32(ARMV6M_NVIC_IPR7));
- regval = getreg32(regaddr);
- regval &= ~((uint32_t)0xff << shift);
- regval |= ((uint32_t)priority << shift);
- putreg32(regval, regaddr);
+ lldbg("SYSCON:\n");
+ lldbg(" CPUID: %08x\n",
+ getreg32(ARMV6M_SYSCON_CPUID));
+ lldbg(" ICSR: %08x AIRCR: %08x\n",
+ getreg32(ARMV6M_SYSCON_ICSR), getreg32(ARMV6M_SYSCON_AIRCR));
+ lldbg(" SCR: %08x CCR: %08x\n",
+ getreg32(ARMV6M_SYSCON_SCR), getreg32(ARMV6M_SYSCON_CCR));
+ lldbg(" SHPR2: %08x SHPR3: %08x\n",
+ getreg32(ARMV6M_SYSCON_SHPR2), getreg32(ARMV6M_SYSCON_SHPR3));
- sam_dumpnvic("prioritize", irq);
- return OK;
+ irqrestore(flags);
}
+
+#else
+# define sam_dumpnvic(msg, irq)
#endif
+
diff --git a/nuttx/arch/arm/src/samd/sam_irq.h b/nuttx/arch/arm/src/samd/sam_irq.h
index 4bcf2eeef..fa35993f5 100644
--- a/nuttx/arch/arm/src/samd/sam_irq.h
+++ b/nuttx/arch/arm/src/samd/sam_irq.h
@@ -62,4 +62,18 @@
* Public Functions
************************************************************************************/
+/****************************************************************************
+ * Name: sam_dumpnvic
+ *
+ * Description:
+ * Dump some interesting NVIC registers
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG_IRQ
+void sam_dumpnvic(const char *msg, int irq);
+#else
+# define sam_dumpnvic(msg, irq)
+#endif
+
#endif /* __ARCH_ARM_SRC_SAMD_SAM_IRQ_H */
diff --git a/nuttx/arch/arm/src/samd/sam_irqprio.c b/nuttx/arch/arm/src/samd/sam_irqprio.c
new file mode 100644
index 000000000..30046c1a2
--- /dev/null
+++ b/nuttx/arch/arm/src/samd/sam_irqprio.c
@@ -0,0 +1,140 @@
+/****************************************************************************
+ * arch/arm/src/stm32/kl_irqprio.c
+ * arch/arm/src/chip/kl_irqprio.c
+ *
+ * Copyright (C) 2014 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 <assert.h>
+#include <arch/irq.h>
+
+#include "nvic.h"
+#include "up_arch.h"
+
+#include "sam_irq.h"
+
+#ifdef CONFIG_ARCH_IRQPRIO
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_prioritize_irq
+ *
+ * Description:
+ * Set the priority of an IRQ.
+ *
+ * Since this API is not supported on all architectures, it should be
+ * avoided in common implementations where possible.
+ *
+ ****************************************************************************/
+
+int up_prioritize_irq(int irq, int priority)
+{
+ uint32_t regaddr;
+ uint32_t regval;
+ int shift;
+
+ DEBUGASSERT(irq == SAM_IRQ_SVCALL ||
+ irq == SAM_IRQ_PENDSV ||
+ irq == SAM_IRQ_SYSTICK ||
+ (irq >= SAM_IRQ_INTERRUPT && irq < NR_IRQS));
+ DEBUGASSERT(priority >= NVIC_SYSH_PRIORITY_MAX &&
+ priority <= NVIC_SYSH_PRIORITY_MIN);
+
+ /* Check for external interrupt */
+
+ if (irq >= SAM_IRQ_INTERRUPT && irq < SAM_IRQ_INTERRUPT + SAM_IRQ_NINTS)
+ {
+ /* ARMV6M_NVIC_IPR() maps register IPR0-IPR7 with four settings per
+ * register.
+ */
+
+ regaddr = ARMV6M_NVIC_IPR(irq >> 2);
+ shift = (irq & 3) << 3;
+ }
+
+ /* Handle processor exceptions. Only SVCall, PendSV, and SysTick can be
+ * reprioritized. And we will not permit modification of SVCall through
+ * this function.
+ */
+
+ else if (irq == SAM_IRQ_PENDSV)
+ {
+ regaddr = ARMV6M_SYSCON_SHPR2;
+ shift = SYSCON_SHPR3_PRI_14_SHIFT;
+ }
+ else if (irq == SAM_IRQ_SYSTICK)
+ {
+ regaddr = ARMV6M_SYSCON_SHPR2;
+ shift = SYSCON_SHPR3_PRI_15_SHIFT;
+ }
+ else
+ {
+ return ERROR;
+ }
+
+ /* Set the priority */
+
+ regval = getreg32(regaddr);
+ regval &= ~((uint32_t)0xff << shift);
+ regval |= ((uint32_t)priority << shift);
+ putreg32(regval, regaddr);
+
+ sam_dumpnvic("prioritize", irq);
+ return OK;
+}
+#endif
diff --git a/nuttx/configs/samd20-xplained/README.txt b/nuttx/configs/samd20-xplained/README.txt
index 782b82113..149a776de 100644
--- a/nuttx/configs/samd20-xplained/README.txt
+++ b/nuttx/configs/samd20-xplained/README.txt
@@ -420,7 +420,7 @@ Serial Consoles
The SAMD20 Xplained Pro contains an Embedded Debugger (EDBG) that can be
used to program and debug the ATSAMD20J18A using Serial Wire Debug (SWD).
- The Embedded debugger also include a Virtual Com port interface over
+ The Embedded debugger also include a Virtual COM port interface over
SERCOM3. Virtual COM port connections:
PA24 SERCOM3 / USART TXD
diff --git a/nuttx/configs/samd20-xplained/include/board.h b/nuttx/configs/samd20-xplained/include/board.h
index 7893b5bbe..d8334c824 100644
--- a/nuttx/configs/samd20-xplained/include/board.h
+++ b/nuttx/configs/samd20-xplained/include/board.h
@@ -373,7 +373,7 @@
/* The SAMD20 Xplained Pro contains an Embedded Debugger (EDBG) that can be
* used to program and debug the ATSAMD20J18A using Serial Wire Debug (SWD).
- * The Embedded debugger also include a Virtual Com port interface over
+ * The Embedded debugger also include a Virtual COM port interface over
* SERCOM3. Virtual COM port connections:
*
* PA24 SERCOM3 / USART TXD
diff --git a/nuttx/configs/samd20-xplained/nsh/defconfig b/nuttx/configs/samd20-xplained/nsh/defconfig
index f0a65c99f..61abc85a7 100644
--- a/nuttx/configs/samd20-xplained/nsh/defconfig
+++ b/nuttx/configs/samd20-xplained/nsh/defconfig
@@ -186,7 +186,7 @@ CONFIG_ARCH_HAVE_IRQPRIO=y
CONFIG_ARCH_HAVE_VFORK=y
# CONFIG_ARCH_HAVE_MMU is not set
# CONFIG_ARCH_NAND_HWECC is not set
-CONFIG_ARCH_IRQPRIO=y
+# CONFIG_ARCH_IRQPRIO is not set
CONFIG_ARCH_STACKDUMP=y
# CONFIG_ENDIAN_BIG is not set
# CONFIG_ARCH_HAVE_RAMFUNCS is not set