summaryrefslogtreecommitdiff
path: root/nuttx/arch/sh/src/m16c
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-02-15 01:43:01 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-02-15 01:43:01 +0000
commit538d6013a6d9f81576bbd6e87bf9932303ee36e8 (patch)
treea79d2dd7d3000d22097c57b8b493ced56e7b40aa /nuttx/arch/sh/src/m16c
parentc84258e30f468b86a586b8ac67c52a2959c49069 (diff)
downloadpx4-nuttx-538d6013a6d9f81576bbd6e87bf9932303ee36e8.tar.gz
px4-nuttx-538d6013a6d9f81576bbd6e87bf9932303ee36e8.tar.bz2
px4-nuttx-538d6013a6d9f81576bbd6e87bf9932303ee36e8.zip
Add M16C register dump logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1503 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/sh/src/m16c')
-rw-r--r--nuttx/arch/sh/src/m16c/Make.defs4
-rw-r--r--nuttx/arch/sh/src/m16c/chip.h24
-rwxr-xr-xnuttx/arch/sh/src/m16c/m16c_dumpstate.c241
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c28
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_sigdeliver.c6
5 files changed, 284 insertions, 19 deletions
diff --git a/nuttx/arch/sh/src/m16c/Make.defs b/nuttx/arch/sh/src/m16c/Make.defs
index ceba5fd76..60a91314f 100644
--- a/nuttx/arch/sh/src/m16c/Make.defs
+++ b/nuttx/arch/sh/src/m16c/Make.defs
@@ -44,8 +44,8 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c \
CHIP_ASRCS = m16c_vectors.S
#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 m16c_irq.c
+# m16c_timerisr.c m16c_serial.c m16c_dumpstate.c
+CHIP_CSRCS = m16c_initialstate.c m16c_copystate.c m16c_irq.c m16c_dumpstate.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 bd2655db3..aafe4e590 100644
--- a/nuttx/arch/sh/src/m16c/chip.h
+++ b/nuttx/arch/sh/src/m16c/chip.h
@@ -245,4 +245,28 @@
#define M16C_PUR2 0x003fe /* Pull-up control 2 */
#define M16C_PCR 0x003ff /* Port control */
+/************************************************************************************
+ * Global Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+extern uint16 g_snbss; /* Start of near .bss */
+extern uint16 g_enbss; /* End+1 of near .bss */
+extern uint16 g_sndata; /* Start of near .data */
+extern uint16 g_endata; /* End+1 of near .data */
+extern uint32 g_enronly; /* Start of relocated read-only data in FLASH */
+#ifdef CONFIG_M16C_HAVEFARRAM
+extern uint32 g_sfbss; /* Start of far .bss */
+extern uint32 g_efbss; /* End+1 of far .bss */
+extern uint32 g_sfdata; /* Start of far .data */
+extern uint32 g_efdata; /* End_1 of far .data */
+extern uint32 g_efronly; /* Start of relocated read-only data in FLASH */
+#endif
+extern uint32 g_svarvect; /* Start of variable vectors */
+extern uint32 g_heapbase; /* Start of the heap */
+
+#endif /* __ASSEMBLY__ */
+
+
#endif /* __ARCH_SH_SRC_M16C_CHIP_H */
diff --git a/nuttx/arch/sh/src/m16c/m16c_dumpstate.c b/nuttx/arch/sh/src/m16c/m16c_dumpstate.c
new file mode 100755
index 000000000..6d70d8cee
--- /dev/null
+++ b/nuttx/arch/sh/src/m16c/m16c_dumpstate.c
@@ -0,0 +1,241 @@
+/****************************************************************************
+ * arch/sh/src/m16c/m16c_assert.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 <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+#include "os_internal.h"
+#include "chip.h"
+
+#ifdef CONFIG_ARCH_STACKDUMP
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Output debug info if stack dump is selected -- even if debug is not
+ * selected.
+ */
+
+#ifdef CONFIG_ARCH_STACKDUMP
+# undef lldbg
+# define lldbg lib_lowprintf
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: m16c_getsp
+ ****************************************************************************/
+
+static inline uint16 m16c_getsp(void)
+{
+ uint16 sp;
+
+ __asm__ __volatile__
+ (
+ "\tstc sp, %0\n\t"
+ : "=r" (sp)
+ :
+ : "memory"
+ );
+ return sp;
+}
+
+/****************************************************************************
+ * Name: m16c_stackdump
+ ****************************************************************************/
+
+static void m16c_stackdump(uint16 sp, uint16 stack_base)
+{
+ uint16 stack;
+
+ for (stack = sp & ~7; stack < stack_base; stack += 8)
+ {
+ ubyte *ptr = (ubyte*)stack;
+ lldbg("%04x: %02x %02x %02x %02x %02x %02x %02x %02x\n",
+ stack, ptr[0], ptr[1], ptr[2], ptr[3], ptr[4], ptr[5], ptr[6], ptr[7]);
+ }
+}
+
+/****************************************************************************
+ * Name: m16c_registerdump
+ ****************************************************************************/
+
+static inline void m16c_registerdump(void)
+{
+ ubyte *ptr = (ubyte*) current_regs;
+
+ /* Are user registers available from interrupt processing? */
+
+ if (ptr)
+ {
+ /* Yes.. dump the interrupt registers */
+
+ lldbg("PC: %02x%02x%02x FLG: %02x00%02x FB: %02x%02x SB: %02x%02x SP: %02x%02x\n",
+ ptr[REG_FLGPCHI] & 0xff, ptr[REG_PC], ptr[REG_PC+1],
+ ptr[REG_FLGPCHI] >> 8, ptr[REG_FLG],
+ ptr[REG_FB], ptr[REG_FB+1],
+ ptr[REG_SB], ptr[REG_SB+1],
+ ptr[REG_SP], ptr[REG_SP+1]);
+
+ lldbg("R0: %02x%02x R1: %02x%02x R2: %02x%02x A0: %02x%02x A1: %02x%02x\n",
+ ptr[REG_R0], ptr[REG_R0+1], ptr[REG_R1], ptr[REG_R1+1],
+ ptr[REG_R2], ptr[REG_R2+1], ptr[REG_R3], ptr[REG_R3+1],
+ ptr[REG_A0], ptr[REG_A0+1], ptr[REG_A1], ptr[REG_A1+1]);
+
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_dumpstate
+ ****************************************************************************/
+
+void up_dumpstate(void)
+{
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+ uint16 sp = m16c_getsp();
+ uint16 ustackbase;
+ uint16 ustacksize;
+#if CONFIG_ARCH_INTERRUPTSTACK > 3
+ uint16 istackbase;
+ uint16 istacksize;
+#endif
+
+ /* Get the limits on the user stack memory */
+
+ if (rtcb->pid == 0)
+ {
+ ustackbase = g_heapbase - 1;
+ ustacksize = CONFIG_IDLETHREAD_STACKSIZE;
+ }
+ else
+ {
+ ustackbase = (uint16)rtcb->adj_stack_ptr;
+ ustacksize = (uint16)rtcb->adj_stack_size;
+ }
+
+ /* Get the limits on the interrupt stack memory. The near RAM memory map is as follows:
+ *
+ * 0x00400 - DATA Size: Determined by linker
+ * BSS Size: Determined by linker
+ * Interrupt stack Size: CONFIG_ARCH_INTERRUPTSTACK
+ * Idle stack Size: CONFIG_IDLETHREAD_STACKSIZE
+ * Heap Size: Everything remaining
+ * 0x00bff - (end+1)
+ */
+
+#if CONFIG_ARCH_INTERRUPTSTACK > 3
+ istackbase = g_enbss;
+ istacksize = CONFIG_ARCH_INTERRUPTSTACK;
+
+ /* Show interrupt stack info */
+
+ lldbg("sp: %04x\n", sp);
+ lldbg("IRQ stack:\n");
+ lldbg(" base: %04x\n", istackbase);
+ lldbg(" size: %04x\n", istacksize);
+
+ /* Does the current stack pointer lie within the interrupt
+ * stack?
+ */
+
+ if (sp <= istackbase && sp > istackbase - istacksize)
+ {
+ /* Yes.. dump the interrupt stack */
+
+ m16c_stackdump(sp, istackbase);
+
+ /* Extract the user stack pointer which should lie
+ * at the base of the interrupt stack.
+ */
+
+ sp = g_userstack;
+ lldbg("sp: %04x\n", sp);
+ }
+
+ /* Show user stack info */
+
+ lldbg("User stack:\n");
+ lldbg(" base: %04x\n", ustackbase);
+ lldbg(" size: %04x\n", ustacksize);
+#else
+ lldbg("sp: %04x\n", sp);
+ lldbg("stack base: %04x\n", ustackbase);
+ lldbg("stack size: %04x\n", ustacksize);
+#endif
+
+ /* Dump the user stack if the stack pointer lies within the allocated user
+ * stack memory.
+ */
+
+ if (sp > ustackbase || sp <= ustackbase - ustacksize)
+ {
+#if !defined(CONFIG_ARCH_INTERRUPTSTACK) || CONFIG_ARCH_INTERRUPTSTACK < 4
+ lldbg("ERROR: Stack pointer is not within allocated stack\n");
+#endif
+ }
+ else
+ {
+ m16c_stackdump(sp, ustackbase);
+ }
+
+ /* Then dump the registers (if available) */
+
+ m16c_registerdump();
+}
+
+#endif /* CONFIG_ARCH_STACKDUMP */
diff --git a/nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c b/nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c
index d33e63378..c62399b6f 100644
--- a/nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c
+++ b/nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c
@@ -146,18 +146,18 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
* the signals have been delivered.
*/
- 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];
+ tcb->xcp.sigdeliver = sigdeliver;
+ tcb->xcp.saved_pc[0] = current_regs[REG_PC];
+ tcb->xcp.saved_pc[1] = current_regs[REG_PC+1];
+ tcb->xcp.saved_flg = current_regs[REG_FLG];
/* Then set up to vector to the trampoline with interrupts
* disabled
*/
- current_regs[REG_PC16] = (uint32)up_sigdeliver >> 8;
- current_regs[REG_PC16+1] = (uint32)up_sigdeliver;
- current_regs[REG_FLG] &= ~M16C_FLG_I;
+ current_regs[REG_PC] = (uint32)up_sigdeliver >> 8;
+ current_regs[REG_PC+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.
@@ -180,18 +180,18 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
* the signals have been delivered.
*/
- 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];
+ tcb->xcp.sigdeliver = sigdeliver;
+ tcb->xcp.saved_pc[0] = tcb->xcp.regs[REG_PC];
+ tcb->xcp.saved_pc[1] = tcb->xcp.regs[REG_PC+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_PC16] = (uint32)up_sigdeliver >> 8;
- tcb->xcp.regs[REG_PC16+1] = (uint32)up_sigdeliver;
- tcb->xcp.regs[REG_FLG] &= ~M16C_FLG_I;
+ tcb->xcp.regs[REG_PC] = (uint32)up_sigdeliver >> 8;
+ tcb->xcp.regs[REG_PC+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 7cea935e4..2d4cf2069 100644
--- a/nuttx/arch/sh/src/m16c/m16c_sigdeliver.c
+++ b/nuttx/arch/sh/src/m16c/m16c_sigdeliver.c
@@ -102,9 +102,9 @@ void up_sigdeliver(void)
/* Save the real return state on the stack. */
up_copystate(regs, rtcb->xcp.regs);
- regs[REG_PC16] = rtcb->xcp.saved_pc[0];
- regs[REG_PC16+1] = rtcb->xcp.saved_pc[1];
- regs[REG_FLG] = rtcb->xcp.saved_flg;
+ regs[REG_PC] = rtcb->xcp.saved_pc[0];
+ regs[REG_PC+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