summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-02-14 01:08:39 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-02-14 01:08:39 +0000
commitc198c0206fa6d459d2c16713be7ef87f4eee627f (patch)
tree4e73e8a017a57b6c089f5e4ae1677f0452a1f2a1
parentab6cd2a0ec5b37f095ffe26ca2302ec8bbade103 (diff)
downloadpx4-nuttx-c198c0206fa6d459d2c16713be7ef87f4eee627f.tar.gz
px4-nuttx-c198c0206fa6d459d2c16713be7ef87f4eee627f.tar.bz2
px4-nuttx-c198c0206fa6d459d2c16713be7ef87f4eee627f.zip
Add task register intialization logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1492 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/sh/include/irq.h24
-rw-r--r--nuttx/arch/sh/include/m16c/irq.h55
-rw-r--r--nuttx/arch/sh/include/sh1/irq.h24
-rw-r--r--nuttx/arch/sh/src/m16c/Make.defs9
-rw-r--r--nuttx/arch/sh/src/m16c/chip.h13
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_copystate.c73
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_initialstate.c123
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c35
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_sigdeliver.c15
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_vectors.S14
-rw-r--r--nuttx/arch/sh/src/sh1/Make.defs4
-rw-r--r--nuttx/arch/sh/src/sh1/sh1_copystate.c (renamed from nuttx/arch/sh/src/common/up_copystate.c)6
12 files changed, 329 insertions, 66 deletions
diff --git a/nuttx/arch/sh/include/irq.h b/nuttx/arch/sh/include/irq.h
index 59b3c6c9c..87c80e349 100644
--- a/nuttx/arch/sh/include/irq.h
+++ b/nuttx/arch/sh/include/irq.h
@@ -55,30 +55,6 @@
* Public Types
****************************************************************************/
-/* This struct defines the way the registers are stored. We need to save: */
-
-#ifndef __ASSEMBLY__
-struct xcptcontext
-{
- /* The following function pointer is non-zero if there are pending signals
- * to be processed.
- */
-
-#ifndef CONFIG_DISABLE_SIGNALS
- void *sigdeliver; /* Actual type is sig_deliver_t */
-
- /* These are saved copies of LR and SR used during signal processing. */
-
- uint32 saved_pc;
- uint32 saved_sr;
-#endif
-
- /* Register save area */
-
- uint32 regs[XCPTCONTEXT_REGS];
-};
-#endif
-
/****************************************************************************
* Inline functions
****************************************************************************/
diff --git a/nuttx/arch/sh/include/m16c/irq.h b/nuttx/arch/sh/include/m16c/irq.h
index daec5d684..64ec0725f 100644
--- a/nuttx/arch/sh/include/m16c/irq.h
+++ b/nuttx/arch/sh/include/m16c/irq.h
@@ -196,18 +196,63 @@
#define M16C_SYSTIMER_IRQ M16C_TMRA0_IRQ
-/* IRQ Stack Frame Format. The SH-1 has a push down stack. The PC
- * and SR are pushed by hardware at the time an IRQ is taken.
+/* IRQ Stack Frame Format. The M16C has a push down stack. The CPU performs
+ * the following actions when an interrupt is taken:
+ *
+ * - Save FLG regsiter
+ * - Clear I, D, and U flags in FLG register
+ * - Builds stack frame like:
+ *
+ * sp -> PC bits 0-7
+ * sp+1 -> PC bits 8-15
+ * sp+2 -> FLG bits 0-7
+ * sp+3 -> FLG (Bits 12-14) + PC (bits 16-19)
+ *
+ * - Sets IPL
+ * - Vectors to interrupt handler
*/
-/* To be provided */
+#define REG_PC20 0 /* 20-bit PC [0]:bits 16-19 [1]:bits 8-15 [2]: bits 0-7 */
+#define REG_FLGPCHI 3 /* 8-bit FLG (bits 12-14) PC (bits 16-19) as would be
+ * presented by an interrupt */
+#define REG_FLG 4 /* 8-bit FLG register (bits 0-7) */
+#define REG_PC16 5 /* 16-bit PC [0]:bits8-15 [1]:bits 0-7 */
+#define REG_FB 7 /* 16-bit FB register */
+#define REG_SB 9 /* 16-bit SB register */
+#define REG_A1 11 /* 16-bit A1 register */
+#define REG_R3 13 /* 16-bit R3 register */
+#define REG_R2 15 /* 16-bit R2 register */
+#define REG_R1 17 /* 16-bit R1 register */
+#define REG_R0 19 /* 16-bit R0 register */
-#define XCPTCONTEXT_REGS (1)
-#define XCPTCONTEXT_SIZE (4 * XCPTCONTEXT_REGS)
+#define XCPTCONTEXT_SIZE 21
/************************************************************************************
* Public Types
************************************************************************************/
+/* This struct defines the way the registers are stored. We need to save: */
+
+#ifndef __ASSEMBLY__
+struct xcptcontext
+{
+ /* The following function pointer is non-zero if there are pending signals
+ * to be processed.
+ */
+
+#ifndef CONFIG_DISABLE_SIGNALS
+ FAR void *sigdeliver; /* Actual type is sig_deliver_t */
+
+ /* These are saved copies of LR and SR used during signal processing. */
+
+ ubyte saved_pc[2];
+ ubyte saved_flg;
+#endif
+
+ /* Register save area */
+
+ ubyte regs[XCPTCONTEXT_SIZE];
+};
+#endif
/************************************************************************************
* Public Data
diff --git a/nuttx/arch/sh/include/sh1/irq.h b/nuttx/arch/sh/include/sh1/irq.h
index 16a888d89..26155864a 100644
--- a/nuttx/arch/sh/include/sh1/irq.h
+++ b/nuttx/arch/sh/include/sh1/irq.h
@@ -454,6 +454,30 @@
* Public Types
************************************************************************************/
+/* This struct defines the way the registers are stored. We need to save: */
+
+#ifndef __ASSEMBLY__
+struct xcptcontext
+{
+ /* The following function pointer is non-zero if there are pending signals
+ * to be processed.
+ */
+
+#ifndef CONFIG_DISABLE_SIGNALS
+ void *sigdeliver; /* Actual type is sig_deliver_t */
+
+ /* These are saved copies of LR and SR used during signal processing. */
+
+ uint32 saved_pc;
+ uint32 saved_sr;
+#endif
+
+ /* Register save area */
+
+ uint32 regs[XCPTCONTEXT_REGS];
+};
+#endif
+
/************************************************************************************
* Public Data
************************************************************************************/
diff --git a/nuttx/arch/sh/src/m16c/Make.defs b/nuttx/arch/sh/src/m16c/Make.defs
index 3302536ab..39da7460b 100644
--- a/nuttx/arch/sh/src/m16c/Make.defs
+++ b/nuttx/arch/sh/src/m16c/Make.defs
@@ -36,16 +36,17 @@
HEAD_ASRC = m16c_head.S
CMN_ASRCS =
-CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
+CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c \
up_createstack.c up_doirq.c up_exit.c up_idle.c up_initialize.c \
up_interruptcontext.c up_lowputs.c up_mdelay.c up_puts.c \
up_releasepending.c up_releasestack.c up_reprioritizertr.c \
up_udelay.c up_unblocktask.c up_usestack.c
-#CHIP_ASRCS = m16c_vectors.S m16c_saveusercontext.S
+#CHIP_ASRCS = m16c_vectors.S m16c_saveusercontext.S m16c_restorecontext.S
CHIP_ASRCS = m16c_vectors.S
-#CHIP_CSRCS = m16c_lowputc.c m16c_irq.c m16c_timerisr.c m16c_serial.c
-CHIP_CSRCS =
+#CHIP_CSRCS = m16c_initialstate.c m16c_copystate.c m16c_lowputc.c m16c_irq.c \
+# m16c_timerisr.c m16c_serial.c
+CHIP_CSRCS = m16c_initialstate.c m16c_copystate.c
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
CHIP_CSRCS += m16c_schedulesigaction.c m16c_sigdeliver.c
diff --git a/nuttx/arch/sh/src/m16c/chip.h b/nuttx/arch/sh/src/m16c/chip.h
index 89f07c97a..bd2655db3 100644
--- a/nuttx/arch/sh/src/m16c/chip.h
+++ b/nuttx/arch/sh/src/m16c/chip.h
@@ -47,6 +47,19 @@
* Definitions
************************************************************************************/
+/* FLG register bits */
+
+#define M16C_FLG_C 0x0001 /* Bit 0: Carry flag */
+#define M16C_FLG_D 0x0002 /* Bit 1: Debug flag */
+#define M16C_FLG_Z 0x0004 /* Bit 2: Zero flag */
+#define M16C_FLG_S 0x0008 /* Bit 3: Sign flag */
+#define M16C_FLG_B 0x0010 /* Bit 4: Register bank flag */
+#define M16C_FLG_O 0x0020 /* Bit 5: Overflow flag */
+#define M16C_FLG_I 0x0040 /* Bit 6: Interrupt enable flag */
+#define M16C_FLG_U 0x0080 /* Bit 7: Stack pointer select flag */
+ /* Bits 8-11: Reserved */
+#define M16C_FLG_IPLMASK 0x7000 /* Bits 12:14: Processor interrupt priority level */
+ /* Bit 15: Reserved */
/* Memory Map */
/* Memory-mapped special function registers begin at address 0x00000 */
diff --git a/nuttx/arch/sh/src/m16c/m16c_copystate.c b/nuttx/arch/sh/src/m16c/m16c_copystate.c
new file mode 100644
index 000000000..e66637ab9
--- /dev/null
+++ b/nuttx/arch/sh/src/m16c/m16c_copystate.c
@@ -0,0 +1,73 @@
+/****************************************************************************
+ * arch/sh/src/m16c/up_copystate.c
+ *
+ * Copyright (C) 2009 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 "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_copystate
+ ****************************************************************************/
+
+/* A little faster than most memcpy's */
+
+void up_copystate(uint32 *dest, uint32 *src)
+{
+ memcpy(dest, src, XCPTCONTEXT_SIZE);
+}
+
diff --git a/nuttx/arch/sh/src/m16c/m16c_initialstate.c b/nuttx/arch/sh/src/m16c/m16c_initialstate.c
new file mode 100644
index 000000000..10dbd2d88
--- /dev/null
+++ b/nuttx/arch/sh/src/m16c/m16c_initialstate.c
@@ -0,0 +1,123 @@
+/****************************************************************************
+ * arch/sh/src/m16c/m16c_initialstate.c
+ *
+ * Copyright (C) 2009 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 <string.h>
+#include <nuttx/arch.h>
+#include "up_internal.h"
+#include "up_arch.h"
+
+/****************************************************************************
+ * Preprocessor Definitions
+ ****************************************************************************/
+
+#define M16C_DEFAULT_IPL 0 /* Global M16C Interrupt priority level */
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_getsr
+ ****************************************************************************/
+
+static inline irqstate_t up_getsr(void)
+{
+ irqstate_t flags;
+
+ __asm__ __volatile__
+ (
+ "stc sr, %0\n\t"
+ : "=&z" (flags)
+ :
+ : "memory"
+ );
+ return flags;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_initial_state
+ *
+ * Description:
+ * A new thread is being started and a new TCB has been created. This
+ * function is called to initialize the processor specific portions of the
+ * new TCB.
+ *
+ * This function must setup the intial architecture registers and/or stack
+ * so that execution will begin at tcb->start on the next context switch.
+ *
+ ****************************************************************************/
+
+void up_initial_state(FAR _TCB *tcb)
+{
+ FAR struct xcptcontext *xcp = &tcb->xcp;
+ FAR ubyte *regs = xcp->regs;
+
+ /* Initialize the initial exception register context structure */
+
+ memset(xcp, 0, sizeof(struct xcptcontext));
+
+ /* Offset 0-2: 20-bit PC [0]:bits 16-19 [1]:bits 8-15 [2]: bits 0-7 */
+
+ *regs++ = (uint32)tcb->start >> 16; /* Bits 16-19 of PC */
+ *regs++ = (uint32)tcb->start >> 8; /* Bits 8-15 of PC */
+ *regs++ = (uint32)tcb->start; /* Bits 0-7 of PC */
+
+ /* Offset 3: FLG (bits 12-14) PC (bits 16-19) as would be present by an interrupt */
+
+ *regs++ = ((M16C_DEFAULT_IPL << 4) | ((uint32)tcb->start >> 16));
+
+ /* Offset 4: FLG (bits 0-7) */
+
+ *regs++ = M16C_FLG_U | M16C_FLG_I;
+
+ /* Offset 5-6: 16-bit PC [0]:bits8-15 [1]:bits 0-7 */
+
+ *regs++ = (uint32)tcb->start >> 8; /* Bits 8-15 of PC */
+ *regs++ = (uint32)tcb->start; /* Bits 0-7 of PC */
+}
diff --git a/nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c b/nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c
index 074f189b5..d33e63378 100644
--- a/nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c
+++ b/nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c
@@ -141,25 +141,24 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
else
{
-#if 1
-# warning "Missing logic to schedule signals"
-#else
/* Save the return PC and SR and one scratch register
* These will be restored by the signal trampoline after
* the signals have been delivered.
*/
- tcb->xcp.sigdeliver = sigdeliver;
- tcb->xcp.saved_pc = current_regs[REG_PC];
- tcb->xcp.saved_sr = current_regs[REG_SR];
+ tcb->xcp.sigdeliver = sigdeliver;
+ tcb->xcp.saved_pc[0] = current_regs[REG_PC16];
+ tcb->xcp.saved_pc[1] = current_regs[REG_PC16+1];
+ tcb->xcp.saved_flg = current_regs[REG_FLG];
/* Then set up to vector to the trampoline with interrupts
* disabled
*/
- current_regs[REG_PC] = (uint32)up_sigdeliver;
- current_regs[REG_SR] |= 0x000000f0;
-#endif
+ current_regs[REG_PC16] = (uint32)up_sigdeliver >> 8;
+ current_regs[REG_PC16+1] = (uint32)up_sigdeliver;
+ current_regs[REG_FLG] &= ~M16C_FLG_I;
+
/* And make sure that the saved context in the TCB
* is the same as the interrupt return context.
*/
@@ -176,25 +175,23 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
else
{
- #if 1
-# warning "Missing logic to schedule signals"
-#else
- /* Save the return PC and SR and one scratch register
+ /* Save the return PC and SR and one scratch register
* These will be restored by the signal trampoline after
* the signals have been delivered.
*/
- tcb->xcp.sigdeliver = sigdeliver;
- tcb->xcp.saved_pc = tcb->xcp.regs[REG_PC];
- tcb->xcp.saved_sr = tcb->xcp.regs[REG_SR];
+ tcb->xcp.sigdeliver = sigdeliver;
+ tcb->xcp.saved_pc[0] = tcb->xcp.regs[REG_PC16];
+ tcb->xcp.saved_pc[1] = tcb->xcp.regs[REG_PC16+1];
+ tcb->xcp.saved_flg = tcb->xcp.regs[REG_FLG];
/* Then set up to vector to the trampoline with interrupts
* disabled
*/
- tcb->xcp.regs[REG_PC] = (uint32)up_sigdeliver;
- tcb->xcp.regs[REG_SR] |= 0x000000f0 ;
-#endif
+ tcb->xcp.regs[REG_PC16] = (uint32)up_sigdeliver >> 8;
+ tcb->xcp.regs[REG_PC16+1] = (uint32)up_sigdeliver;
+ tcb->xcp.regs[REG_FLG] &= ~M16C_FLG_I;
}
irqrestore(flags);
diff --git a/nuttx/arch/sh/src/m16c/m16c_sigdeliver.c b/nuttx/arch/sh/src/m16c/m16c_sigdeliver.c
index 9efa5f5ba..7cea935e4 100644
--- a/nuttx/arch/sh/src/m16c/m16c_sigdeliver.c
+++ b/nuttx/arch/sh/src/m16c/m16c_sigdeliver.c
@@ -81,12 +81,9 @@
void up_sigdeliver(void)
{
-#if 1
-# warning "Missing signal deliver logic"
-#else
#ifndef CONFIG_DISABLE_SIGNALS
_TCB *rtcb = (_TCB*)g_readytorun.head;
- uint32 regs[XCPTCONTEXT_REGS];
+ ubyte regs[XCPTCONTEXT_SIZE];
sig_deliver_t sigdeliver;
/* Save the errno. This must be preserved throughout the
@@ -105,8 +102,9 @@ void up_sigdeliver(void)
/* Save the real return state on the stack. */
up_copystate(regs, rtcb->xcp.regs);
- regs[REG_PC] = rtcb->xcp.saved_pc;
- regs[REG_SR] = rtcb->xcp.saved_sr;
+ regs[REG_PC16] = rtcb->xcp.saved_pc[0];
+ regs[REG_PC16+1] = rtcb->xcp.saved_pc[1];
+ regs[REG_FLG] = rtcb->xcp.saved_flg;
/* Get a local copy of the sigdeliver function pointer.
* we do this so that we can nullify the sigdeliver
@@ -118,9 +116,9 @@ void up_sigdeliver(void)
sigdeliver = rtcb->xcp.sigdeliver;
rtcb->xcp.sigdeliver = NULL;
- /* Then restore the task interrupt statat. */
+ /* Then restore the task interrupt state. */
- irqrestore(regs[REG_SR] & 0x000000f0);
+ irqrestore(rtcb->xcp.saved_flg);
/* Deliver the signals */
@@ -142,7 +140,6 @@ void up_sigdeliver(void)
up_ledoff(LED_SIGNAL);
up_fullcontextrestore(regs);
#endif
-#endif
}
#endif /* !CONFIG_DISABLE_SIGNALS */
diff --git a/nuttx/arch/sh/src/m16c/m16c_vectors.S b/nuttx/arch/sh/src/m16c/m16c_vectors.S
index ffbf07cb0..2aec1ab8d 100644
--- a/nuttx/arch/sh/src/m16c/m16c_vectors.S
+++ b/nuttx/arch/sh/src/m16c/m16c_vectors.S
@@ -283,6 +283,20 @@
* Name:
*
* Description:
+ * The M16C has a push down stack. The CPU performs the following actions when an
+ * interrupt is taken:
+ *
+ * - Save FLG regsiter
+ * - Clear I, D, and U flags in FLG register
+ * - Builds stack frame like:
+ *
+ * sp -> PC bits 0-7
+ * sp+1 -> PC bits 8-15
+ * sp+2 -> FLG bits 0-7
+ * sp+3 -> FLG (Bits 12-14) + PC (bits 16-19)
+ *
+ * - Sets IPL
+ * - Vectors to interrupt handler
*
************************************************************************************/
diff --git a/nuttx/arch/sh/src/sh1/Make.defs b/nuttx/arch/sh/src/sh1/Make.defs
index 591614cbf..aaa6bebe0 100644
--- a/nuttx/arch/sh/src/sh1/Make.defs
+++ b/nuttx/arch/sh/src/sh1/Make.defs
@@ -36,7 +36,7 @@
HEAD_ASRC = sh1_head.S
CMN_ASRCS =
-CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
+CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c \
up_createstack.c up_doirq.c up_exit.c up_idle.c up_initialize.c \
up_initialstate.c up_interruptcontext.c up_lowputs.c \
up_mdelay.c up_puts.c up_releasepending.c up_releasestack.c \
@@ -44,7 +44,7 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
CHIP_ASRCS = sh1_vector.S sh1_saveusercontext.S
CHIP_CSRCS = sh1_lowputc.c sh1_irq.c sh1_timerisr.c sh1_serial.c \
- sh1_initialstate.c sh1_dumpstate.c
+ sh1_initialstate.c sh1_copystate.c sh1_dumpstate.c
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
CMN_CSRCS += sh1_schedulesigaction.c sh1_sigdeliver.c
diff --git a/nuttx/arch/sh/src/common/up_copystate.c b/nuttx/arch/sh/src/sh1/sh1_copystate.c
index c74812438..4449c0425 100644
--- a/nuttx/arch/sh/src/common/up_copystate.c
+++ b/nuttx/arch/sh/src/sh1/sh1_copystate.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * arch/sh/src/common/up_copystate.c
+ * arch/sh/src/sh1/up_copystate.c
*
- * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -61,7 +61,7 @@
****************************************************************************/
/****************************************************************************
- * Name: up_undefinedinsn
+ * Name: up_copystate
****************************************************************************/
/* A little faster than most memcpy's */