summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-09-18 22:12:52 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-09-18 22:12:52 +0000
commitcb28e069374a979bfafa651e4c8ddda8a95d3c79 (patch)
tree18f0805d7511a520729685c9ca81f1e7e70f3170 /nuttx/arch
parentb1bb829bbf07e59acb1aecf24c514901b32752e2 (diff)
downloadpx4-nuttx-cb28e069374a979bfafa651e4c8ddda8a95d3c79.tar.gz
px4-nuttx-cb28e069374a979bfafa651e4c8ddda8a95d3c79.tar.bz2
px4-nuttx-cb28e069374a979bfafa651e4c8ddda8a95d3c79.zip
LPC2148 timer irq fixes
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@931 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/include/lpc214x/irq.h2
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h1
-rw-r--r--nuttx/arch/arm/src/common/up_puts.c76
-rw-r--r--nuttx/arch/arm/src/common/up_undefinedinsn.c34
-rw-r--r--nuttx/arch/arm/src/lpc214x/Make.defs4
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c6
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_irq.c3
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_timerisr.c8
8 files changed, 108 insertions, 26 deletions
diff --git a/nuttx/arch/arm/include/lpc214x/irq.h b/nuttx/arch/arm/include/lpc214x/irq.h
index 01e27af0f..8e389218f 100644
--- a/nuttx/arch/arm/include/lpc214x/irq.h
+++ b/nuttx/arch/arm/include/lpc214x/irq.h
@@ -81,7 +81,7 @@
* following will be used by the system.
*/
-#define LPC214X_SYSTEMER_VEC 0 /* System timer */
+#define LPC214X_SYSTIMER_VEC 0 /* System timer */
/****************************************************************************
* Public Types
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index 836a2579f..e089e3ba1 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -120,6 +120,7 @@ extern void up_syscall(uint32 *regs);
extern int up_timerisr(int irq, uint32 *regs);
extern void up_undefinedinsn(uint32 *regs);
extern void up_lowputc(char ch);
+extern void up_puts(const char *str);
/* Defined in up_vectors.S */
diff --git a/nuttx/arch/arm/src/common/up_puts.c b/nuttx/arch/arm/src/common/up_puts.c
new file mode 100644
index 000000000..6a98153ec
--- /dev/null
+++ b/nuttx/arch/arm/src/common/up_puts.c
@@ -0,0 +1,76 @@
+/****************************************************************************
+ * arch/arm/src/common/up_puts.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <nuttx/arch.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_puts
+ *
+ * Description:
+ * This is a low-level helper function used to support debug.
+ *
+ ****************************************************************************/
+
+void up_puts(const char *str)
+{
+ while(*str)
+ {
+ up_putc(*str);
+ }
+}
diff --git a/nuttx/arch/arm/src/common/up_undefinedinsn.c b/nuttx/arch/arm/src/common/up_undefinedinsn.c
index 086f443e3..3a6bd39f6 100644
--- a/nuttx/arch/arm/src/common/up_undefinedinsn.c
+++ b/nuttx/arch/arm/src/common/up_undefinedinsn.c
@@ -1,7 +1,7 @@
-/************************************************************
- * common/up_undefinedinsn.c
+/****************************************************************************
+ * arch/arm/src/common/up_undefinedinsn.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* 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
+ * 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.
*
@@ -31,11 +31,11 @@
* 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>
@@ -44,9 +44,9 @@
#include "os_internal.h"
#include "up_internal.h"
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
/* Output debug info if stack dump is selected -- even if
* debug is not selected.
@@ -57,21 +57,21 @@
# define lldbg lib_lowprintf
#endif
-/************************************************************
+/****************************************************************************
* Private Data
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Public Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: up_undefinedinsn
- ************************************************************/
+ ****************************************************************************/
void up_undefinedinsn(uint32 *regs)
{
diff --git a/nuttx/arch/arm/src/lpc214x/Make.defs b/nuttx/arch/arm/src/lpc214x/Make.defs
index 6b10e4bad..d18788954 100644
--- a/nuttx/arch/arm/src/lpc214x/Make.defs
+++ b/nuttx/arch/arm/src/lpc214x/Make.defs
@@ -47,6 +47,10 @@ ifneq ($(CONFIG_DISABLE_SIGNALS),y)
CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c
endif
+ifeq ($(CONFIG_DEBUG),y)
+CMN_CSRCS += up_puts.c
+endif
+
CHIP_ASRCS = lpc214x_lowputc.S
CHIP_CSRCS = lpc214x_decodeirq.c lpc214x_irq.c lpc214x_timerisr.c \
lpc214x_serial.c
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c b/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c
index 12ae2354f..bf7b4940e 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c
@@ -127,9 +127,9 @@ static void lpc214x_decodeirq( uint32 *regs)
* times through the loop.
*/
- for (nibble = pending & 0xff, irq_base = 0;
- pending && irq < NR_IRQS;
- pending >>= 4, nibble = pending & 0xff, irq_base += 4)
+ for (nibble = pending & 0x0f, irq_base = 0;
+ pending && irq_base < NR_IRQS;
+ pending >>= 4, nibble = pending & 0x0f, irq_base += 4)
{
if (nibble)
{
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_irq.c b/nuttx/arch/arm/src/lpc214x/lpc214x_irq.c
index 96a40b0e2..1bfd6bba0 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_irq.c
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_irq.c
@@ -39,6 +39,7 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <debug.h>
#include <nuttx/irq.h>
#include "up_arch.h"
@@ -156,7 +157,7 @@ void up_enable_irq(int irq)
*/
uint32 val = vic_getreg(LPC214X_VIC_INTENABLE_OFFSET);
- vic_putreg(val | (1 << irq), LPC214X_VIC_INTENCLEAR_OFFSET);
+ vic_putreg(val | (1 << irq), LPC214X_VIC_INTENABLE_OFFSET);
irqrestore(flags);
}
}
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_timerisr.c b/nuttx/arch/arm/src/lpc214x/lpc214x_timerisr.c
index 618e9b15d..367b96ca3 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_timerisr.c
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_timerisr.c
@@ -60,9 +60,9 @@
#define tmr_getreg16(o) getreg16(LPC214X_TMR0_BASE+(o))
#define tmr_getreg32(o) getreg32(LPC214X_TMR0_BASE+(o))
-#define tmr_putreg8(o,v) putreg8((v), LPC214X_TMR0_BASE+(o))
-#define tmr_putreg16(o,v) putreg16((v), LPC214X_TMR0_BASE+(o))
-#define tmr_putreg32(o,v) putreg32((v), LPC214X_TMR0_BASE+(o))
+#define tmr_putreg8(v,o) putreg8((v), LPC214X_TMR0_BASE+(o))
+#define tmr_putreg16(v,o) putreg16((v), LPC214X_TMR0_BASE+(o))
+#define tmr_putreg32(v,o) putreg32((v), LPC214X_TMR0_BASE+(o))
/****************************************************************************
* Private Types
@@ -151,7 +151,7 @@ void up_timerinit(void)
/* Attach the timer interrupt vector */
#ifdef CONFIG_VECTORED_INTERRUPTS
- up_attach_vector(LPC214X_IRQ_SYSTIMER, LPC214X_SYSTEMER_VEC, (vic_vector_t)up_timerisr);
+ up_attach_vector(LPC214X_IRQ_SYSTIMER, LPC214X_SYSTIMER_VEC, (vic_vector_t)up_timerisr);
#else
(void)irq_attach(LPC214X_IRQ_SYSTIMER, (xcpt_t)up_timerisr);
#endif