summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-05-17 17:18:19 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-05-17 17:18:19 +0000
commit0fa834d4332608374852575437d2714f820868c4 (patch)
tree4e57188abe5ff32b2639ca69314fec94378bed8d
parent0368c4fac2539f3a8812f9471e9be74fb7aeb303 (diff)
downloadpx4-nuttx-0fa834d4332608374852575437d2714f820868c4.tar.gz
px4-nuttx-0fa834d4332608374852575437d2714f820868c4.tar.bz2
px4-nuttx-0fa834d4332608374852575437d2714f820868c4.zip
Debug Cortex-M3 interrupts
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1787 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/include/irq_cortexm3.h26
-rw-r--r--nuttx/arch/arm/src/common/up_blocktask.c9
-rw-r--r--nuttx/arch/arm/src/common/up_copystate.c19
-rw-r--r--nuttx/arch/arm/src/common/up_doirq.c11
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h18
-rw-r--r--nuttx/arch/arm/src/common/up_releasepending.c6
-rw-r--r--nuttx/arch/arm/src/common/up_reprioritizertr.c4
-rw-r--r--nuttx/arch/arm/src/common/up_schedulesigaction.c10
-rw-r--r--nuttx/arch/arm/src/common/up_sigdeliver.c3
-rw-r--r--nuttx/arch/arm/src/common/up_unblocktask.c6
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_context.S6
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_irq.c59
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_pendsv.c1
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_serial.c12
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_start.c1
-rw-r--r--nuttx/arch/arm/src/str71x/str71x_irq.c2
-rw-r--r--nuttx/arch/arm/src/str71x/str71x_serial.c12
-rw-r--r--nuttx/sched/task_activate.c2
18 files changed, 163 insertions, 44 deletions
diff --git a/nuttx/arch/arm/include/irq_cortexm3.h b/nuttx/arch/arm/include/irq_cortexm3.h
index a6c235811..8c149d1d6 100644
--- a/nuttx/arch/arm/include/irq_cortexm3.h
+++ b/nuttx/arch/arm/include/irq_cortexm3.h
@@ -178,13 +178,25 @@ static inline void irqrestore(irqstate_t primask)
__asm__ __volatile__
(
- "\ttst %0, #1\n"
- "\tbne 1f\n"
- "\tcpsie i\n"
- "1:\n"
- :
- : "r" (primask)
- : "memory");
+ "\ttst %0, #1\n"
+ "\tbne 1f\n"
+ "\tcpsie i\n"
+ "1:\n"
+ :
+ : "r" (primask)
+ : "memory");
+}
+
+/* Get the basepri register */
+
+static inline void setbasepri(uint32 basepri)
+{
+ __asm__ __volatile__
+ (
+ "\msr basepri, %0\n"
+ :
+ : "r" (basepri)
+ : "memory");
}
#endif /* __ASSEMBLY__ */
diff --git a/nuttx/arch/arm/src/common/up_blocktask.c b/nuttx/arch/arm/src/common/up_blocktask.c
index 819208a2c..2590597f8 100644
--- a/nuttx/arch/arm/src/common/up_blocktask.c
+++ b/nuttx/arch/arm/src/common/up_blocktask.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/common/up_blocktask.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,9 +39,12 @@
#include <nuttx/config.h>
#include <sys/types.h>
+
#include <sched.h>
#include <debug.h>
+
#include <nuttx/arch.h>
+
#include "os_internal.h"
#include "up_internal.h"
@@ -129,7 +132,7 @@ void up_block_task(_TCB *tcb, tstate_t task_state)
* Just copy the current_regs into the OLD rtcb.
*/
- up_copystate(rtcb->xcp.regs, current_regs);
+ up_savestate(rtcb->xcp.regs);
/* Restore the exception context of the rtcb at the (new) head
* of the g_readytorun task list.
@@ -139,7 +142,7 @@ void up_block_task(_TCB *tcb, tstate_t task_state)
/* Then switch contexts */
- up_copystate(current_regs, rtcb->xcp.regs);
+ up_restorestate(rtcb->xcp.regs);
}
/* Copy the user C context into the TCB at the (old) head of the
diff --git a/nuttx/arch/arm/src/common/up_copystate.c b/nuttx/arch/arm/src/common/up_copystate.c
index 1c4cb42ec..b73c6c95c 100644
--- a/nuttx/arch/arm/src/common/up_copystate.c
+++ b/nuttx/arch/arm/src/common/up_copystate.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/common/up_copystate.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -69,9 +69,22 @@
void up_copystate(uint32 *dest, uint32 *src)
{
int i;
- for (i = 0; i < XCPTCONTEXT_REGS; i++)
+
+ /* In the current ARM model, the state is always copied to and from the
+ * stack and TCB. In the Cortex-M3 model, the state is copied from the
+ * stack to the TCB, but only a referenced is passed to get the the state
+ * from the TCB. So the following check makes sense only for the Cortex-M3
+ * model:
+ */
+
+#ifdef __thumb2__
+ if (src != dest)
+#endif
{
- *dest++ = *src++;
+ for (i = 0; i < XCPTCONTEXT_REGS; i++)
+ {
+ *dest++ = *src++;
+ }
}
}
diff --git a/nuttx/arch/arm/src/common/up_doirq.c b/nuttx/arch/arm/src/common/up_doirq.c
index b863ec0c5..861f5f3d8 100644
--- a/nuttx/arch/arm/src/common/up_doirq.c
+++ b/nuttx/arch/arm/src/common/up_doirq.c
@@ -66,7 +66,11 @@
* Public Functions
****************************************************************************/
-uint32 *up_doirq(int irq, uint32* regs)
+#ifdef __thumb2__
+uint32 *up_doirq(int irq, uint32 *regs)
+#else
+void up_doirq(int irq, uint32 *regs)
+#endif
{
up_ledon(LED_INIRQ);
#ifdef CONFIG_SUPPRESS_INTERRUPTS
@@ -94,8 +98,9 @@ uint32 *up_doirq(int irq, uint32* regs)
* of context switching for te particular chip.
*/
+#ifdef __thumb2__
regs = current_regs;
-
+#endif
/* Indicate that we are no long in an interrupt handler */
current_regs = NULL;
@@ -108,5 +113,7 @@ uint32 *up_doirq(int irq, uint32* regs)
}
up_ledoff(LED_INIRQ);
#endif
+#ifdef __thumb2__
return regs;
+#endif
}
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index 430631853..34a7918e1 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -71,6 +71,20 @@
# define CONFIG_ARCH_INTERRUPTSTACK 0
#endif
+/* Macros to handle saving and restore interrupt state. In the current ARM
+ * model, the state is always copied to and from the stack and TCB. In the
+ * Cortex-M3 model, the state is copied from the stack to the TCB, but only
+ * a referenced is passed to get the the state from the TCB.
+ */
+
+#ifdef __thumb2__
+# define up_savestate(regs) up_copystate(regs, current_regs)
+# define up_restorestate(regs) (current_regs = regs)
+#else
+# define up_savestate(regs) up_copystate(regs, current_regs)
+# define up_restorestate(regs) up_copystate(current_regs, regs)
+#endif
+
/****************************************************************************
* Public Types
****************************************************************************/
@@ -122,7 +136,11 @@ extern void up_boot(void);
extern void up_copystate(uint32 *dest, uint32 *src);
extern void up_dataabort(uint32 *regs);
extern void up_decodeirq(uint32 *regs);
+#ifdef __thumb2__
extern uint32 *up_doirq(int irq, uint32 *regs);
+#else
+extern void up_doirq(int irq, uint32 *regs);
+#endif
extern void up_fullcontextrestore(uint32 *regs) __attribute__ ((noreturn));
extern void up_irqinitialize(void);
extern void up_prefetchabort(uint32 *regs);
diff --git a/nuttx/arch/arm/src/common/up_releasepending.c b/nuttx/arch/arm/src/common/up_releasepending.c
index d62fb25c2..d81479e87 100644
--- a/nuttx/arch/arm/src/common/up_releasepending.c
+++ b/nuttx/arch/arm/src/common/up_releasepending.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/common/up_releasepending.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -94,7 +94,7 @@ void up_release_pending(void)
* Just copy the current_regs into the OLD rtcb.
*/
- up_copystate(rtcb->xcp.regs, current_regs);
+ up_savestate(rtcb->xcp.regs);
/* Restore the exception context of the rtcb at the (new) head
* of the g_readytorun task list.
@@ -105,7 +105,7 @@ void up_release_pending(void)
/* Then switch contexts */
- up_copystate(current_regs, rtcb->xcp.regs);
+ up_restorestate(rtcb->xcp.regs);
}
/* Copy the exception context into the TCB of the task that
diff --git a/nuttx/arch/arm/src/common/up_reprioritizertr.c b/nuttx/arch/arm/src/common/up_reprioritizertr.c
index 41aa0d5e2..684ff7f43 100644
--- a/nuttx/arch/arm/src/common/up_reprioritizertr.c
+++ b/nuttx/arch/arm/src/common/up_reprioritizertr.c
@@ -142,7 +142,7 @@ void up_reprioritize_rtr(_TCB *tcb, ubyte priority)
* Just copy the current_regs into the OLD rtcb.
*/
- up_copystate(rtcb->xcp.regs, current_regs);
+ up_savestate(rtcb->xcp.regs);
/* Restore the exception context of the rtcb at the (new) head
* of the g_readytorun task list.
@@ -153,7 +153,7 @@ void up_reprioritize_rtr(_TCB *tcb, ubyte priority)
/* Then switch contexts */
- up_copystate(current_regs, rtcb->xcp.regs);
+ up_restorestate(rtcb->xcp.regs);
}
/* Copy the exception context into the TCB at the (old) head of the
diff --git a/nuttx/arch/arm/src/common/up_schedulesigaction.c b/nuttx/arch/arm/src/common/up_schedulesigaction.c
index fb6798468..a4ae20953 100644
--- a/nuttx/arch/arm/src/common/up_schedulesigaction.c
+++ b/nuttx/arch/arm/src/common/up_schedulesigaction.c
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_schedulesigaction.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -137,6 +137,12 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
* interrupted task is the same as the one that
* must receive the signal, then we will have to modify
* the return state as well as the state in the TCB.
+ *
+ * Hmmm... there looks like a latent bug here: The following
+ * logic would fail in the strange case where we are in an
+ * interrupt handler, the thread is signalling itself, but
+ * a context switch to another task has occurred so that
+ * current_regs does not refer to the thread at g_readytorun.head!
*/
else
@@ -171,7 +177,7 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
* is the same as the interrupt return context.
*/
- up_copystate(tcb->xcp.regs, current_regs);
+ up_savestate(tcb->xcp.regs);
}
}
diff --git a/nuttx/arch/arm/src/common/up_sigdeliver.c b/nuttx/arch/arm/src/common/up_sigdeliver.c
index bf5661696..aff743884 100644
--- a/nuttx/arch/arm/src/common/up_sigdeliver.c
+++ b/nuttx/arch/arm/src/common/up_sigdeliver.c
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_sigdeliver.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -109,6 +109,7 @@ void up_sigdeliver(void)
#else
regs[REG_CPSR] = rtcb->xcp.saved_cpsr;
#endif
+
/* Get a local copy of the sigdeliver function pointer.
* we do this so that we can nullify the sigdeliver
* function point in the TCB and accept more signal
diff --git a/nuttx/arch/arm/src/common/up_unblocktask.c b/nuttx/arch/arm/src/common/up_unblocktask.c
index a657a1b84..ea64ed1c6 100644
--- a/nuttx/arch/arm/src/common/up_unblocktask.c
+++ b/nuttx/arch/arm/src/common/up_unblocktask.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/common/up_unblocktask.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -121,7 +121,7 @@ void up_unblock_task(_TCB *tcb)
* Just copy the current_regs into the OLD rtcb.
*/
- up_copystate(rtcb->xcp.regs, current_regs);
+ up_savestate(rtcb->xcp.regs);
/* Restore the exception context of the rtcb at the (new) head
* of the g_readytorun task list.
@@ -131,7 +131,7 @@ void up_unblock_task(_TCB *tcb)
/* Then switch contexts */
- up_copystate(current_regs, rtcb->xcp.regs);
+ up_restorestate(rtcb->xcp.regs);
}
/* We are not in an interrupt handler. Copy the user C context
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_context.S b/nuttx/arch/arm/src/lm3s/lm3s_context.S
index a0a75fea4..9f74408d6 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_context.S
+++ b/nuttx/arch/arm/src/lm3s/lm3s_context.S
@@ -85,7 +85,7 @@ up_saveusercontext:
/* Perform the System call with R0=0 and R1=regs */
ldr r2, nvic_intctrl /* R2: Address NVIC INTCTRL registers */
- ldr r3, [r2, #0] /* R3: Contentx of NVIC INCTRL */
+ ldr r3, [r2, #0] /* R3: Content of NVIC INCTRL */
orr r3, r3, #NVIC_INTCTRL_PENDSVSET
mov r1, r0 /* R1: regs */
mov r0, #0 /* R0: 0 means save context (also return value) */
@@ -125,13 +125,13 @@ up_fullcontextrestore:
/* Perform the System call with R0=1 and R1=regs */
ldr r2, nvic_intctrl /* R2: Address NVIC INTCTRL registers */
- ldr r3, [r2, #0] /* R3: Contentx of NVIC INCTRL */
+ ldr r3, [r2, #0] /* R3: Content of NVIC INCTRL */
orr r3, r3, #NVIC_INTCTRL_PENDSVSET
mov r1, r0 /* R1: regs */
mov r0, #1 /* R0: 1 means restore context */
str r3, [r2, #0] /* Force Pend SV */
- /* These call should not return */
+ /* This call should not return */
bx lr /* Unnecessary ... will not return */
.size up_fullcontextrestore, .-up_fullcontextrestore
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_irq.c b/nuttx/arch/arm/src/lm3s/lm3s_irq.c
index c9f47c0df..c8307aac3 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_irq.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_irq.c
@@ -55,6 +55,12 @@
* Definitions
****************************************************************************/
+/* Enable debug features that are probably on desireable during bringup */
+
+#define LM2S_IRQ_DEBUG 1
+
+/* Get a 32-bit version of the default priority */
+
#define DEFPRIORITY32 \
(NVIC_SYSH_PRIORITY_DEFAULT << 24 |\
NVIC_SYSH_PRIORITY_DEFAULT << 16 |\
@@ -76,6 +82,39 @@ uint32 *current_regs;
****************************************************************************/
/****************************************************************************
+ * Name: lm3s_dumpnvic
+ *
+ * Description:
+ * Dump some interesting NVIC registers
+ *
+ ****************************************************************************/
+
+#if defined(LM2S_IRQ_DEBUG) && defined (CONFIG_DEBUG)
+static void lm3s_dumpnvic(const char *msg, int irq)
+{
+ slldbg("NVIC (%s, irq=%d):\n", msg, irq);
+ slldbg(" INTCTRL: %08x VECTAB: %08x\n",
+ getreg32(NVIC_INTCTRL), getreg32(NVIC_VECTAB));
+ slldbg(" IRQ ENABLE: %08x %08x\n",
+ getreg32(NVIC_IRQ0_31_ENABLE), getreg32(NVIC_IRQ32_63_ENABLE));
+ slldbg(" SYSH_PRIO: %08x %08x %08x\n",
+ getreg32(NVIC_SYSH4_7_PRIORITY), getreg32(NVIC_SYSH8_11_PRIORITY),
+ getreg32(NVIC_SYSH12_15_PRIORITY));
+ slldbg(" IRQ PRIO: %08x %08x %08x %08x\n",
+ getreg32(NVIC_IRQ0_3_PRIORITY), getreg32(NVIC_IRQ4_7_PRIORITY),
+ getreg32(NVIC_IRQ8_11_PRIORITY), getreg32(NVIC_IRQ12_15_PRIORITY));
+ slldbg(" %08x %08x %08x %08x\n",
+ getreg32(NVIC_IRQ16_19_PRIORITY), getreg32(NVIC_IRQ20_23_PRIORITY),
+ getreg32(NVIC_IRQ24_27_PRIORITY), getreg32(NVIC_IRQ28_31_PRIORITY));
+ slldbg(" %08x %08x %08x %08x\n",
+ getreg32(NVIC_IRQ32_35_PRIORITY), getreg32(NVIC_IRQ36_39_PRIORITY),
+ getreg32(NVIC_IRQ40_43_PRIORITY), getreg32(NVIC_IRQ44_47_PRIORITY));
+}
+#else
+# define lm3s_dumpnvic(msg, irq)
+#endif
+
+/****************************************************************************
* Name: lm3s_nmi, lm3s_hardfault, lm3s_mpu, lm3s_busfault, lm3s_usagefault,
* lm3s_svcall, lm3s_dbgmonitor, lm3s_pendsv, lm3s_reserved
*
@@ -217,7 +256,7 @@ static int lml3s_irqinfo(int irq, uint32 *regaddr, uint32 *bit)
}
/****************************************************************************
- * Public Funtions
+ * Public Functions
****************************************************************************/
/****************************************************************************
@@ -233,6 +272,10 @@ void up_irqinitialize(void)
/* Set all interrrupts (and exceptions) to the default priority */
+ putreg32(DEFPRIORITY32, NVIC_SYSH4_7_PRIORITY);
+ putreg32(DEFPRIORITY32, NVIC_SYSH8_11_PRIORITY);
+ putreg32(DEFPRIORITY32, NVIC_SYSH12_15_PRIORITY);
+
putreg32(DEFPRIORITY32, NVIC_IRQ0_3_PRIORITY);
putreg32(DEFPRIORITY32, NVIC_IRQ4_7_PRIORITY);
putreg32(DEFPRIORITY32, NVIC_IRQ8_11_PRIORITY);
@@ -245,10 +288,6 @@ void up_irqinitialize(void)
putreg32(DEFPRIORITY32, NVIC_IRQ36_39_PRIORITY);
putreg32(DEFPRIORITY32, NVIC_IRQ40_43_PRIORITY);
putreg32(DEFPRIORITY32, NVIC_IRQ44_47_PRIORITY);
- putreg32(DEFPRIORITY32, NVIC_IRQ48_51_PRIORITY);
- putreg32(DEFPRIORITY32, NVIC_IRQ52_55_PRIORITY);
- putreg32(DEFPRIORITY32, NVIC_IRQ56_59_PRIORITY);
- putreg32(DEFPRIORITY32, NVIC_IRQ60_63_PRIORITY);
/* currents_regs is non-NULL only while processing an interrupt */
@@ -272,7 +311,7 @@ void up_irqinitialize(void)
irq_attach(LMSB_IRQ_PENDSV, lm3s_pendsv);
#ifdef CONFIG_ARCH_IRQPRIO
- up_prioritize_irq(LMSB_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN);
+/* up_prioritize_irq(LMSB_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); */
#endif
/* Attach all other processor exceptions (except reset and sys tick) */
@@ -288,6 +327,8 @@ void up_irqinitialize(void)
irq_attach(LMSB_IRQ_RESERVED, lm3s_reserved);
#endif
+ lm3s_dumpnvic("inital", NR_IRQS);
+
#ifndef CONFIG_SUPPRESS_INTERRUPTS
/* Initialize FIQs */
@@ -298,6 +339,7 @@ void up_irqinitialize(void)
/* And finally, enable interrupts */
+ setbasepri(0);
irqrestore(0);
#endif
}
@@ -324,6 +366,7 @@ void up_disable_irq(int irq)
regval &= ~bit;
putreg32(regval, regaddr);
}
+ lm3s_dumpnvic("disable", irq);
}
/****************************************************************************
@@ -348,6 +391,7 @@ void up_enable_irq(int irq)
regval |= bit;
putreg32(regval, regaddr);
}
+ lm3s_dumpnvic("enable", irq);
}
/****************************************************************************
@@ -385,6 +429,7 @@ int up_prioritize_irq(int irq, int priority)
if (irq < LM3S_IRQ_INTERRUPTS)
{
+ irq -= 4;
regaddr = NVIC_SYSH_PRIORITY(irq);
}
else
@@ -398,6 +443,8 @@ int up_prioritize_irq(int irq, int priority)
regval &= ~(0xff << shift);
regval |= (priority << shift);
putreg32(regval, regaddr);
+
+ lm3s_dumpnvic("prioritize", irq);
return OK;
}
#endif
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_pendsv.c b/nuttx/arch/arm/src/lm3s/lm3s_pendsv.c
index 1db255fef..ef2b189c8 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_pendsv.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_pendsv.c
@@ -89,6 +89,7 @@ int lm3s_pendsv(int irq, FAR void *context)
* the TCB register save area.
*/
+ svdbg("Command: %d regs: %08x\n", svregs[REG_R0], tcbregs);
switch (svregs[REG_R0])
{
/* R0=0: This is a save context command. In this case, we simply need
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_serial.c b/nuttx/arch/arm/src/lm3s/lm3s_serial.c
index 71a877e3f..42cf0fe23 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_serial.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_serial.c
@@ -39,11 +39,13 @@
#include <nuttx/config.h>
#include <sys/types.h>
+
#include <unistd.h>
#include <semaphore.h>
#include <string.h>
#include <errno.h>
#include <debug.h>
+
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <nuttx/serial.h>
@@ -53,8 +55,6 @@
#include "up_arch.h"
#include "up_internal.h"
-#ifdef CONFIG_USE_SERIALDRIVER
-
/****************************************************************************
* Definitions
****************************************************************************/
@@ -82,6 +82,12 @@
# undef HAVE_CONSOLE
#endif
+/* If we are not using the serial driver for the console, then we
+ * still must provide some minimal implementation of up_putc.
+ */
+
+#ifdef CONFIG_USE_SERIALDRIVER
+
/* Which UART with be tty0/console and which tty1? */
#if defined(CONFIG_UART0_SERIAL_CONSOLE)
@@ -796,7 +802,7 @@ static boolean up_txempty(struct uart_dev_s *dev)
}
/****************************************************************************
- * Public Funtions
+ * Public Functions
****************************************************************************/
/****************************************************************************
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_start.c b/nuttx/arch/arm/src/lm3s/lm3s_start.c
index 8de6e48e1..df1a48c84 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_start.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_start.c
@@ -151,6 +151,7 @@ void __start(void)
/* Then start NuttX */
+ showprogress('\r');
showprogress('\n');
os_start();
diff --git a/nuttx/arch/arm/src/str71x/str71x_irq.c b/nuttx/arch/arm/src/str71x/str71x_irq.c
index 1c243f460..db2ea57aa 100644
--- a/nuttx/arch/arm/src/str71x/str71x_irq.c
+++ b/nuttx/arch/arm/src/str71x/str71x_irq.c
@@ -65,7 +65,7 @@ uint32 *current_regs;
****************************************************************************/
/****************************************************************************
- * Public Funtions
+ * Public Functions
****************************************************************************/
/****************************************************************************
diff --git a/nuttx/arch/arm/src/str71x/str71x_serial.c b/nuttx/arch/arm/src/str71x/str71x_serial.c
index 88203d37b..1d4a28f75 100644
--- a/nuttx/arch/arm/src/str71x/str71x_serial.c
+++ b/nuttx/arch/arm/src/str71x/str71x_serial.c
@@ -54,8 +54,6 @@
#include "up_internal.h"
#include "str71x_internal.h"
-#ifdef CONFIG_USE_SERIALDRIVER
-
/****************************************************************************
* Definitions
****************************************************************************/
@@ -73,11 +71,17 @@
#if defined(CONFIG_UART0_SERIAL_CONSOLE) || defined(CONFIG_UART1_SERIAL_CONSOLE) ||\
defined(CONFIG_UART2_SERIAL_CONSOLE) || defined(CONFIG_UART3_SERIAL_CONSOLE)
-# define HAVE_CONSOLE
+# define HAVE_CONSOLE 1
#else
# undef HAVE_CONSOLE
#endif
+/* If we are not using the serial driver for the console, then we
+ * still must provide some minimal implementation of up_putc().
+ */
+
+#ifdef CONFIG_USE_SERIALDRIVER
+
/* Which UART with be tty0/console and which tty1? tty2? tty3? */
#if defined(CONFIG_UART0_SERIAL_CONSOLE) || !defined(HAVE_CONSOLE)
@@ -855,7 +859,7 @@ static boolean up_txempty(struct uart_dev_s *dev)
}
/****************************************************************************
- * Public Funtions
+ * Public Functions
****************************************************************************/
/****************************************************************************
diff --git a/nuttx/sched/task_activate.c b/nuttx/sched/task_activate.c
index a9646cefe..d22593147 100644
--- a/nuttx/sched/task_activate.c
+++ b/nuttx/sched/task_activate.c
@@ -1,7 +1,7 @@
/****************************************************************************
* task_activate.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without