summaryrefslogtreecommitdiff
path: root/nuttx/arch/avr/src
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-06-18 13:22:36 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-06-18 13:22:36 +0000
commitfe368e772ce7195b9f751b78febc236527797fb5 (patch)
tree61aae4ce1f919d103611010ba615ec8952c85768 /nuttx/arch/avr/src
parent8c6ebe6f07cb81ab197850c2af4c75fb50e5f1cb (diff)
downloadpx4-nuttx-fe368e772ce7195b9f751b78febc236527797fb5.tar.gz
px4-nuttx-fe368e772ce7195b9f751b78febc236527797fb5.tar.bz2
px4-nuttx-fe368e772ce7195b9f751b78febc236527797fb5.zip
Add logic to measure AVR stack usage
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3722 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/avr/src')
-rw-r--r--nuttx/arch/avr/src/at90usb/Make.defs4
-rwxr-xr-xnuttx/arch/avr/src/at90usb/at90usb_exceptions.S2
-rw-r--r--nuttx/arch/avr/src/at90usb/at90usb_lowinit.c12
-rw-r--r--nuttx/arch/avr/src/atmega/Make.defs4
-rw-r--r--nuttx/arch/avr/src/atmega/atmega_lowinit.c12
-rw-r--r--nuttx/arch/avr/src/avr/avr_internal.h31
-rwxr-xr-xnuttx/arch/avr/src/avr/excptmacros.h8
-rw-r--r--nuttx/arch/avr/src/avr/up_checkstack.c141
-rw-r--r--nuttx/arch/avr/src/avr/up_createstack.c40
-rw-r--r--nuttx/arch/avr/src/avr/up_usestack.c20
-rw-r--r--nuttx/arch/avr/src/avr32/avr32_internal.h10
11 files changed, 233 insertions, 51 deletions
diff --git a/nuttx/arch/avr/src/at90usb/Make.defs b/nuttx/arch/avr/src/at90usb/Make.defs
index 706eca544..7a353dbf4 100644
--- a/nuttx/arch/avr/src/at90usb/Make.defs
+++ b/nuttx/arch/avr/src/at90usb/Make.defs
@@ -58,6 +58,10 @@ ifeq ($(CONFIG_AVR_SPI),y)
CMN_CSRCS += up_spi.c
endif
+ifeq ($(CONFIG_DEBUG_STACK),y)
+CMN_CSRCS += up_checkstack.c
+endif
+
# Required AT90USB files
CHIP_ASRCS = at90usb_exceptions.S
diff --git a/nuttx/arch/avr/src/at90usb/at90usb_exceptions.S b/nuttx/arch/avr/src/at90usb/at90usb_exceptions.S
index 44b607033..79eda5f18 100755
--- a/nuttx/arch/avr/src/at90usb/at90usb_exceptions.S
+++ b/nuttx/arch/avr/src/at90usb/at90usb_exceptions.S
@@ -148,7 +148,7 @@ excpt_common:
breq .Lnoswitch
/* A context switch has occurred, jump to up_fullcontextrestore with r24, r25
- * equal to the address of the new register save ared.
+ * equal to the address of the new register save area.
*/
jmp up_fullcontextrestore
diff --git a/nuttx/arch/avr/src/at90usb/at90usb_lowinit.c b/nuttx/arch/avr/src/at90usb/at90usb_lowinit.c
index e446fcf13..f7a1b921e 100644
--- a/nuttx/arch/avr/src/at90usb/at90usb_lowinit.c
+++ b/nuttx/arch/avr/src/at90usb/at90usb_lowinit.c
@@ -101,9 +101,7 @@
static inline void up_wdtinit(void)
{
-#ifndef CONFIG_AVR_WDT
- wdt_disable();
-#else
+#ifdef CONFIG_AVR_WDT
wdt_enable(WDTO_VALUE);
#endif
}
@@ -124,14 +122,18 @@ static inline void up_wdtinit(void)
void up_lowinit(void)
{
- /* Initialize the watchdog timer */
+ /* Disable the watchdog timer */
- up_wdtinit();
+ wdt_disable();
/* Set the system clock divider to 1 */
clock_prescale_set(clock_div_1);
+ /* Initialize the watchdog timer */
+
+ up_wdtinit();
+
/* Initialize a console (probably a serial console) */
up_consoleinit();
diff --git a/nuttx/arch/avr/src/atmega/Make.defs b/nuttx/arch/avr/src/atmega/Make.defs
index 16f0f5a62..47683fcd0 100644
--- a/nuttx/arch/avr/src/atmega/Make.defs
+++ b/nuttx/arch/avr/src/atmega/Make.defs
@@ -58,6 +58,10 @@ ifeq ($(CONFIG_AVR_SPI),y)
CMN_CSRCS += up_spi.c
endif
+ifeq ($(CONFIG_DEBUG_STACK),y)
+CMN_CSRCS += up_checkstack.c
+endif
+
# Required ATMEGA files
CHIP_ASRCS = atmega_exceptions.S
diff --git a/nuttx/arch/avr/src/atmega/atmega_lowinit.c b/nuttx/arch/avr/src/atmega/atmega_lowinit.c
index 5802a22f0..bb0a4d512 100644
--- a/nuttx/arch/avr/src/atmega/atmega_lowinit.c
+++ b/nuttx/arch/avr/src/atmega/atmega_lowinit.c
@@ -101,9 +101,7 @@
static inline void up_wdtinit(void)
{
-#ifndef CONFIG_AVR_WDT
- wdt_disable();
-#else
+#ifdef CONFIG_AVR_WDT
wdt_enable(WDTO_VALUE);
#endif
}
@@ -124,14 +122,18 @@ static inline void up_wdtinit(void)
void up_lowinit(void)
{
- /* Initialize the watchdog timer */
+ /* Disable the watchdog timer */
- up_wdtinit();
+ wdt_disable();
/* Set the system clock divider to 1 */
clock_prescale_set(clock_div_1);
+ /* Initialize the watchdog timer */
+
+ up_wdtinit();
+
/* Initialize a console (probably a serial console) */
up_consoleinit();
diff --git a/nuttx/arch/avr/src/avr/avr_internal.h b/nuttx/arch/avr/src/avr/avr_internal.h
index 841b8376a..288a8914a 100644
--- a/nuttx/arch/avr/src/avr/avr_internal.h
+++ b/nuttx/arch/avr/src/avr/avr_internal.h
@@ -41,6 +41,7 @@
****************************************************************************/
#ifndef __ASSEMBLY__
+# include <sys/types.h>
# include <stdint.h>
# include <stdbool.h>
#endif
@@ -103,16 +104,6 @@ extern uint16_t g_heapbase;
extern void up_copystate(uint8_t *dest, uint8_t *src);
/************************************************************************************
- * Name: up_saveusercontext
- *
- * Description:
- * Save the register context of the currently executing (user) thread.
- *
- ************************************************************************************/
-
-extern int up_saveusercontext(uint8_t *saveregs);
-
-/************************************************************************************
* Name: up_fullcontextrestore
*
* Description:
@@ -181,6 +172,26 @@ extern int avr_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool
#endif
#endif
+/****************************************************************************
+ * Name: up_check_stack
+ *
+ * Description:
+ * Determine (approximately) how much stack has been used be searching the
+ * stack memory for a high water mark. That is, the deepest level of the
+ * stack that clobbered some recognizable marker in the stack memory.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned value:
+ * The estimated amount of stack space used.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_STACK)
+extern size_t up_check_stack(void);
+#endif
+
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_AVR_SRC_AVR_AVR_INTERNAL_H */
diff --git a/nuttx/arch/avr/src/avr/excptmacros.h b/nuttx/arch/avr/src/avr/excptmacros.h
index 0cc8902d8..604ad5fae 100755
--- a/nuttx/arch/avr/src/avr/excptmacros.h
+++ b/nuttx/arch/avr/src/avr/excptmacros.h
@@ -209,12 +209,16 @@
push r27
/* Finally, save the stack pointer. BUT we want the value of the stack pointer as
- * it was on entry into this macro. We'll have to subtract to get that value.
+ * it was just BEFORE the exception. We'll have to add to get that value.
+ * The value to add is the size of the register save area including the bytes
+ * pushed by the interrupt handler (2), by the HANDLER macro (1), and the 32
+ * registers pushed above. That is, the entire size of the register save structure
+ * MINUS two bytes for the stack pointer which has not yet been saved.
*/
in r26, _SFR_IO_ADDR(SPL)
in r27, _SFR_IO_ADDR(SPH)
- adiw r26, XCPTCONTEXT_REGS
+ adiw r26, XCPTCONTEXT_REGS-2
push r26 /* SPL then SPH */
push r27
diff --git a/nuttx/arch/avr/src/avr/up_checkstack.c b/nuttx/arch/avr/src/avr/up_checkstack.c
new file mode 100644
index 000000000..bf646f7ec
--- /dev/null
+++ b/nuttx/arch/avr/src/avr/up_checkstack.c
@@ -0,0 +1,141 @@
+/****************************************************************************
+ * arch/avr/src/avr/up_checkstack.c
+ *
+ * Copyright (C) 2011 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 <stdint.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_STACK)
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_check_stack
+ *
+ * Description:
+ * Determine (approximately) how much stack has been used be searching the
+ * stack memory for a high water mark. That is, the deepest level of the
+ * stack that clobbered some recognizable marker in the stack memory.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned value:
+ * The estimated amount of stack space used.
+ *
+ ****************************************************************************/
+
+size_t up_check_tcbstack(FAR _TCB *tcb)
+{
+ FAR uint8_t *ptr;
+ size_t mark;
+ int i, j;
+
+ /* The AVR uses a push-down stack: the stack grows toward lower addresses
+ * in memory. We need to start at the lowest address in the stack memory
+ * allocation and search to higher addresses. The first byte we encounter
+ * that does not have the magic value is the high water mark.
+ */
+
+ for (ptr = (FAR uint8_t *)tcb->stack_alloc_ptr, mark = tcb->adj_stack_size;
+ *ptr == 0xaa && mark > 0;
+ ptr++, mark--);
+
+ /* If the stack is completely used, then this might mean that the stack
+ * overflowed from above (meaning that the stack is too small), or may
+ * have been overwritten from below meaning that some other stack or data
+ * structure overflowed.
+ *
+ * If you see returned values saying that the entire stack is being used
+ * then enable the following logic to see it there are unused areas in the
+ * middle of the stack.
+ */
+
+#if 0
+ if (mark + 16 > tcb->adj_stack_size)
+ {
+ ptr = (FAR uint8_t *)tcb->stack_alloc_ptr;
+ for (i = 0; i < tcb->adj_stack_size; i += 64)
+ {
+ for (j = 0; j < 64; j++)
+ {
+ int ch;
+ if (*ptr++ == 0xaa)
+ {
+ ch = '.';
+ }
+ else
+ {
+ ch = 'X';
+ }
+ up_putc(ch);
+ }
+ up_putc('\n');
+ }
+ }
+#endif
+
+ /* Return our guess about how much stack space was used */
+
+ return mark;
+}
+
+size_t up_check_stack(void)
+{
+ return up_check_tcbstack((FAR _TCB*)g_readytorun.head);
+}
+
+#endif /* CONFIG_DEBUG && CONFIG_DEBUG_STACK */
diff --git a/nuttx/arch/avr/src/avr/up_createstack.c b/nuttx/arch/avr/src/avr/up_createstack.c
index dcd8ecd76..2ef60e815 100644
--- a/nuttx/arch/avr/src/avr/up_createstack.c
+++ b/nuttx/arch/avr/src/avr/up_createstack.c
@@ -43,6 +43,7 @@
#include <sys/types.h>
#include <stdint.h>
#include <stdlib.h>
+#include <string.h>
#include <sched.h>
#include <debug.h>
@@ -88,43 +89,58 @@
int up_create_stack(_TCB *tcb, size_t stack_size)
{
- if (tcb->stack_alloc_ptr &&
- tcb->adj_stack_size != stack_size)
+ /* Is there already a stack allocated of a different size? */
+
+ if (tcb->stack_alloc_ptr && tcb->adj_stack_size != stack_size)
{
+ /* Yes.. free it */
+
sched_free(tcb->stack_alloc_ptr);
tcb->stack_alloc_ptr = NULL;
}
+ /* Do we need to allocate a stack? */
+
if (!tcb->stack_alloc_ptr)
{
-#ifdef CONFIG_DEBUG
+ /* Allocate the stack. If DEBUG is enabled (but not stack debug),
+ * then create a zeroed stack to make stack dumps easier to trace.
+ */
+
+#if defined(CONFIG_DEBUG) && !defined(CONFIG_DEBUG_STACK)
tcb->stack_alloc_ptr = (FAR void *)zalloc(stack_size);
#else
tcb->stack_alloc_ptr = (FAR void *)malloc(stack_size);
#endif
}
+ /* Did we successfully allocate a stack? */
+
if (tcb->stack_alloc_ptr)
{
size_t top_of_stack;
- size_t size_of_stack;
- /* The AVR uses a push-down stack: the stack grows toward lower
- * addresses in memory. The stack pointer register, points to the
- * lowest, valid work address (the "top" of the stack). Items on the
- * stack are referenced as positive word offsets from sp.
+ /* Yes.. If stack debug is enabled, then fill the stack with a
+ * recognizable value that we can use later to test for high
+ * water marks.
*/
- top_of_stack = (size_t)tcb->stack_alloc_ptr + stack_size - 1;
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_STACK)
+ memset(tcb->stack_alloc_ptr, 0xaa, stack_size);
+#endif
- /* The AVR stack does not have to be aligned */
+ /* The AVR uses a push-down stack: the stack grows toward lower
+ * addresses in memory. The stack pointer register, points to the
+ * lowest, valid work address (the "top" of the stack). Items on the
+ * stack are referenced as positive word offsets from sp.
+ */
- size_of_stack = top_of_stack - (size_t)tcb->stack_alloc_ptr + 1;
+ top_of_stack = (size_t)tcb->stack_alloc_ptr + stack_size - 1;
/* Save the adjusted stack values in the _TCB */
tcb->adj_stack_ptr = (FAR void *)top_of_stack;
- tcb->adj_stack_size = size_of_stack;
+ tcb->adj_stack_size = stack_size;
up_ledon(LED_STACKCREATED);
return OK;
diff --git a/nuttx/arch/avr/src/avr/up_usestack.c b/nuttx/arch/avr/src/avr/up_usestack.c
index 15e13a7a3..0c86b64ee 100644
--- a/nuttx/arch/avr/src/avr/up_usestack.c
+++ b/nuttx/arch/avr/src/avr/up_usestack.c
@@ -41,6 +41,7 @@
#include <sys/types.h>
#include <stdint.h>
+#include <string.h>
#include <sched.h>
#include <debug.h>
@@ -84,10 +85,13 @@
int up_use_stack(_TCB *tcb, void *stack, size_t stack_size)
{
size_t top_of_stack;
- size_t size_of_stack;
+
+ /* Is there already a stack allocated? */
if (tcb->stack_alloc_ptr)
{
+ /* Yes.. free it */
+
sched_free(tcb->stack_alloc_ptr);
}
@@ -95,6 +99,14 @@ int up_use_stack(_TCB *tcb, void *stack, size_t stack_size)
tcb->stack_alloc_ptr = stack;
+ /* If stack debug is enabled, then fill the stack with a recognizable value
+ * that we can use later to test for high water marks.
+ */
+
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_STACK)
+ memset(tcb->stack_alloc_ptr, 0xaa, stack_size);
+#endif
+
/* The AVR uses a push-down stack: the stack grows toward loweraddresses in
* memory. The stack pointer register, points to the lowest, valid work
* address (the "top" of the stack). Items on the stack are referenced as
@@ -103,14 +115,10 @@ int up_use_stack(_TCB *tcb, void *stack, size_t stack_size)
top_of_stack = (size_t)tcb->stack_alloc_ptr + stack_size - 1;
- /* The AVR stack does not need to be aligned */
-
- size_of_stack = top_of_stack - (size_t)tcb->stack_alloc_ptr + 4;
-
/* Save the adjusted stack values in the _TCB */
tcb->adj_stack_ptr = (FAR void *)top_of_stack;
- tcb->adj_stack_size = size_of_stack;
+ tcb->adj_stack_size = stack_size;
return OK;
}
diff --git a/nuttx/arch/avr/src/avr32/avr32_internal.h b/nuttx/arch/avr/src/avr32/avr32_internal.h
index 58aa555aa..56065edce 100644
--- a/nuttx/arch/avr/src/avr32/avr32_internal.h
+++ b/nuttx/arch/avr/src/avr32/avr32_internal.h
@@ -102,16 +102,6 @@ extern uint32_t g_heapbase;
extern void up_copystate(uint32_t *dest, uint32_t *src);
/************************************************************************************
- * Name: up_saveusercontext
- *
- * Description:
- * Save the register context of the currently executing (user) thread.
- *
- ************************************************************************************/
-
-extern int up_saveusercontext(uint32_t *saveregs);
-
-/************************************************************************************
* Name: up_fullcontextrestore
*
* Description: