summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-04-11 10:01:44 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-04-11 10:01:44 -0600
commitb80e8be652dfa52e97daa65aa3e550cf31cb2409 (patch)
tree8abb9936ae969306603f76de23d58f46e20cda2a
parent45c91ff4bcae67cd45f1e61d6d35db73ff2ee4af (diff)
downloadpx4-nuttx-b80e8be652dfa52e97daa65aa3e550cf31cb2409.tar.gz
px4-nuttx-b80e8be652dfa52e97daa65aa3e550cf31cb2409.tar.bz2
px4-nuttx-b80e8be652dfa52e97daa65aa3e550cf31cb2409.zip
Remove all traces of CONFIG_ARMV7M_STACKCHECK
-rw-r--r--nuttx/arch/arm/src/armv7-m/Kconfig12
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_initialstate.c6
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_stackcheck.c112
-rw-r--r--nuttx/arch/arm/src/sam34/sam_start.c12
-rw-r--r--nuttx/arch/arm/src/samv7/sam_start.c12
-rw-r--r--nuttx/arch/arm/src/stm32/Make.defs4
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_start.c12
7 files changed, 0 insertions, 170 deletions
diff --git a/nuttx/arch/arm/src/armv7-m/Kconfig b/nuttx/arch/arm/src/armv7-m/Kconfig
index a9274b28d..5c853442a 100644
--- a/nuttx/arch/arm/src/armv7-m/Kconfig
+++ b/nuttx/arch/arm/src/armv7-m/Kconfig
@@ -106,18 +106,6 @@ config ARMV7M_OABI_TOOLCHAIN
Most of the older buildroot toolchains are OABI and are named
arm-nuttx-elf- vs. arm-nuttx-eabi-
-config ARMV7M_STACKCHECK
- bool "Check for stack overflow on each function call"
- default n
- depends on ARCH_CHIP_STM32
- ---help---
- This check uses R10 to check for a stack overflow within each function
- call. This has performances and code size impacts, but it will be able to
- catch hard to find stack overflows.
-
- Currently only available only for the STM32 architecture. The changes
- are not complex and patches for other architectures will be accepted.
-
config ARMV7M_ITMSYSLOG
bool "ITM SYSLOG support"
default n
diff --git a/nuttx/arch/arm/src/armv7-m/up_initialstate.c b/nuttx/arch/arm/src/armv7-m/up_initialstate.c
index c6ba22724..96a73829d 100644
--- a/nuttx/arch/arm/src/armv7-m/up_initialstate.c
+++ b/nuttx/arch/arm/src/armv7-m/up_initialstate.c
@@ -93,12 +93,6 @@ void up_initial_state(struct tcb_s *tcb)
xcp->regs[REG_SP] = (uint32_t)tcb->adj_stack_ptr;
-#ifdef CONFIG_ARMV7M_STACKCHECK
- /* Set the stack limit value */
-
- xcp->regs[REG_R10] = (uint32_t)tcb->stack_alloc_ptr + 64;
-#endif
-
/* Save the task entry point (stripping off the thumb bit) */
xcp->regs[REG_PC] = (uint32_t)tcb->start & ~1;
diff --git a/nuttx/arch/arm/src/armv7-m/up_stackcheck.c b/nuttx/arch/arm/src/armv7-m/up_stackcheck.c
deleted file mode 100644
index 3da70b449..000000000
--- a/nuttx/arch/arm/src/armv7-m/up_stackcheck.c
+++ /dev/null
@@ -1,112 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
- *
- * 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 PX4 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>
-
-#ifdef CONFIG_ARMV7M_STACKCHECK
-
-/* Support per function call stack checking.
- * This code uses R10 to check for a stack overflow within function calls.
- * This has a performance impact, but will be able to catch hard to find
- * stack overflows.
- */
-
-#include <stdint.h>
-
-#include "up_arch.h"
-#include "nvic.h"
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-void __cyg_profile_func_enter(void *func, void *caller) __attribute__((naked, no_instrument_function));
-void __cyg_profile_func_exit(void *func, void *caller) __attribute__((naked, no_instrument_function));
-void __stack_overflow_trap(void) __attribute__((naked, no_instrument_function));
-
-/****************************************************************************
- * Name: __stack_overflow_trap
- ****************************************************************************/
-
-void __stack_overflow_trap(void)
-{
- /* if we get here, the stack has overflowed */
-
- uint32_t regval;
-
- /* force hard fault */
- regval = getreg32(NVIC_INTCTRL);
- regval |= NVIC_INTCTRL_NMIPENDSET;
- putreg32(regval, NVIC_INTCTRL);
-
- /* XXX no need to trap it here, the fault handler gets to it */
-}
-
-/****************************************************************************
- * Name: __cyg_profile_func_enter
- ****************************************************************************/
-
-void __cyg_profile_func_enter(void *func, void *caller)
-{
- asm volatile (
- " mrs r2, ipsr \n" /* Check whether we are in interrupt mode */
- " cmp r2, #0 \n" /* since we don't switch r10 on interrupt entry, we */
- " bne 2f \n" /* can't detect overflow of the interrupt stack. */
- " \n"
- " sub r2, sp, #68 \n" /* compute stack pointer as though we just stacked a full frame */
- " mrs r1, control \n" /* Test CONTROL.FPCA to see whether we also need room for the FP */
- " tst r1, #4 \n" /* context. */
- " beq 1f \n"
- " sub r2, r2, #136 \n" /* subtract FP context frame size */
- "1: \n"
- " cmp r2, r10 \n" /* compare stack with limit */
- " bgt 2f \n" /* stack is above limit and thus OK */
- " b __stack_overflow_trap\n"
- "2: \n"
- " bx lr \n"
- );
-}
-
-/****************************************************************************
- * Name: __cyg_profile_func_exit
- ****************************************************************************/
-
-void __cyg_profile_func_exit(void *func, void *caller)
-{
- asm volatile("bx lr");
-}
-#endif
diff --git a/nuttx/arch/arm/src/sam34/sam_start.c b/nuttx/arch/arm/src/sam34/sam_start.c
index 0c2286b9a..3fe7cb556 100644
--- a/nuttx/arch/arm/src/sam34/sam_start.c
+++ b/nuttx/arch/arm/src/sam34/sam_start.c
@@ -70,12 +70,6 @@ static void go_os_start(void *pv, unsigned int nbytes)
__attribute__ ((naked,no_instrument_function,noreturn));
#endif
-#ifdef CONFIG_ARMV7M_STACKCHECK
-/* We need to get r10 set before we can allow instrumentation calls */
-
-void __start(void) __attribute__ ((no_instrument_function));
-#endif
-
/****************************************************************************
* Private Functions
****************************************************************************/
@@ -241,12 +235,6 @@ void __start(void)
const uint32_t *src;
uint32_t *dest;
-#ifdef CONFIG_ARMV7M_STACKCHECK
- /* Set the stack limit before we attempt to call any functions */
-
- __asm__ volatile ("sub r10, sp, %0" : : "r" (CONFIG_IDLETHREAD_STACKSIZE - 64) : );
-#endif
-
/* Clear .bss. We'll do this inline (vs. calling memset) just to be
* certain that there are no issues with the state of global variables.
*/
diff --git a/nuttx/arch/arm/src/samv7/sam_start.c b/nuttx/arch/arm/src/samv7/sam_start.c
index 82199b09d..b4a579a1f 100644
--- a/nuttx/arch/arm/src/samv7/sam_start.c
+++ b/nuttx/arch/arm/src/samv7/sam_start.c
@@ -111,12 +111,6 @@ static void go_os_start(void *pv, unsigned int nbytes)
* Private Functions
****************************************************************************/
-#ifdef CONFIG_ARMV7M_STACKCHECK
-/* we need to get r10 set before we can allow instrumentation calls */
-
-void __start(void) __attribute__ ((no_instrument_function));
-#endif
-
/****************************************************************************
* Name: sam_fpuconfig
*
@@ -313,12 +307,6 @@ void __start(void)
const uint32_t *src;
uint32_t *dest;
-#ifdef CONFIG_ARMV7M_STACKCHECK
- /* Set the stack limit before we attempt to call any functions */
-
- __asm__ volatile ("sub r10, sp, %0" : : "r" (CONFIG_IDLETHREAD_STACKSIZE - 64) : );
-#endif
-
/* Clear .bss. We'll do this inline (vs. calling memset) just to be
* certain that there are no issues with the state of global variables.
*/
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index 598c74b3a..cbac3350b 100644
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -54,10 +54,6 @@ CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c up_stackframe.c
CMN_CSRCS += up_systemreset.c up_unblocktask.c up_usestack.c up_doirq.c
CMN_CSRCS += up_hardfault.c up_svcall.c up_vfork.c
-ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
-CMN_CSRCS += up_stackcheck.c
-endif
-
ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
ifeq ($(CONFIG_ARMV7M_LAZYFPU),y)
CMN_ASRCS += up_lazyexception.S
diff --git a/nuttx/arch/arm/src/stm32/stm32_start.c b/nuttx/arch/arm/src/stm32/stm32_start.c
index e0613d26f..45ba66bf6 100644
--- a/nuttx/arch/arm/src/stm32/stm32_start.c
+++ b/nuttx/arch/arm/src/stm32/stm32_start.c
@@ -92,12 +92,6 @@ static void go_os_start(void *pv, unsigned int nbytes)
* Public Functions
****************************************************************************/
-#ifdef CONFIG_ARMV7M_STACKCHECK
-/* we need to get r10 set before we can allow instrumentation calls */
-
-void __start(void) __attribute__ ((no_instrument_function));
-#endif
-
/****************************************************************************
* Name: stm32_fpuconfig
*
@@ -245,12 +239,6 @@ void __start(void)
const uint32_t *src;
uint32_t *dest;
-#ifdef CONFIG_ARMV7M_STACKCHECK
- /* Set the stack limit before we attempt to call any functions */
-
- __asm__ volatile ("sub r10, sp, %0" : : "r" (CONFIG_IDLETHREAD_STACKSIZE - 64) : );
-#endif
-
/* Configure the UART so that we can get debug output as soon as possible */
stm32_clockconfig();