Changes to mindpx-v2 for upstream Nuttx and hardfault logging

This commit is contained in:
David Sidrane 2016-12-12 13:28:43 -10:00 committed by Lorenz Meier
parent f149adac54
commit 402251819d
12 changed files with 1147 additions and 409 deletions

View File

@ -1,5 +1,7 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)
set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake)
set(config_uavcan_num_ifaces 1)
@ -62,6 +64,7 @@ set(config_module_list
systemcmds/perf
systemcmds/pwm
systemcmds/esc_calib
systemcmds/hardfault_log
systemcmds/reboot
systemcmds/topic_listener
systemcmds/top

View File

@ -147,11 +147,23 @@
/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
* otherwise frequency is 2xAPBx.
* Note: TIM1,8 are on APB2, others on APB1
* Note: TIM1,8-11 are on APB2, others on APB1
*/
#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY)
#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY)
#define BOARD_TIM1_FREQUENCY STM32_APB2_TIM1_CLKIN
#define BOARD_TIM2_FREQUENCY STM32_APB1_TIM2_CLKIN
#define BOARD_TIM3_FREQUENCY STM32_APB1_TIM3_CLKIN
#define BOARD_TIM4_FREQUENCY STM32_APB1_TIM4_CLKIN
#define BOARD_TIM5_FREQUENCY STM32_APB1_TIM5_CLKIN
#define BOARD_TIM6_FREQUENCY STM32_APB1_TIM6_CLKIN
#define BOARD_TIM7_FREQUENCY STM32_APB1_TIM7_CLKIN
#define BOARD_TIM8_FREQUENCY STM32_APB2_TIM8_CLKIN
#define BOARD_TIM9_FREQUENCY STM32_APB2_TIM9_CLKIN
#define BOARD_TIM10_FREQUENCY STM32_APB2_TIM10_CLKIN
#define BOARD_TIM11_FREQUENCY STM32_APB2_TIM11_CLKIN
#define BOARD_TIM12_FREQUENCY STM32_APB1_TIM12_CLKIN
#define BOARD_TIM13_FREQUENCY STM32_APB1_TIM13_CLKIN
#define BOARD_TIM14_FREQUENCY STM32_APB1_TIM14_CLKIN
/* SDIO dividers. Note that slower clocking is required when DMA is disabled
* in order to avoid RX overrun/TX underrun errors due to delayed responses

View File

@ -1,5 +1,5 @@
############################################################################
# configs/mindpx-v2/nsh/Make.defs
# nuttx-configs/mindpx-v2/nsh/Make.defs
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
@ -35,14 +35,14 @@
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
include $(TOPDIR)/PX4_Warnings.mk
include $(TOPDIR)/PX4_Config.mk
#
# We only support building with the ARM bare-metal toolchain from
# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
#
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI${HOST_OS_FIRST_LETTER}
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
@ -62,17 +62,19 @@ ARCHCPUFLAGS = -mcpu=cortex-m4 \
-mfpu=fpv4-sp-d16 \
-mfloat-abi=hard
# Enable precise stack overflow tracking
# enable precise stack overflow tracking
ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10
endif
# pull in *just* libm from the toolchain ... this is grody
# Pull in *just* libm from the toolchain ... this is grody
LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}"
EXTRA_LIBS += $(LIBM)
# use our linker script
# Use our linker script
LDSCRIPT = ld.script
ifeq ($(WINTOOL),y)
@ -94,18 +96,20 @@ else
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps.sh
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
endif
# tool versions
# Tool versions
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
# optimisation flags
# Optimization flags
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
-fno-strict-aliasing \
-fno-strength-reduce \
@ -127,7 +131,8 @@ ARCHWARNINGSXX = $(ARCHWARNINGS) $(PX4_ARCHWARNINGSXX)
ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# this seems to be the only way to add linker flags
# This seems to be the only way to add linker flags
EXTRA_LIBS += --warn-common \
--gc-sections
@ -146,8 +151,8 @@ OBJEXT = .o
LIBEXT = .a
EXEEXT =
# Produce partially-linked $1 from files in $2
# produce partially-linked $1 from files in $2
define PRELINK
@echo "PRELINK: $1"
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1

View File

@ -1,52 +0,0 @@
############################################################################
# configs/px4fmu/nsh/appconfig
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# 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.
#
############################################################################
# Path to example in apps/examples containing the user_start entry point
CONFIGURED_APPS += examples/nsh
# The NSH application library
CONFIGURED_APPS += nshlib
CONFIGURED_APPS += system/readline
ifeq ($(CONFIG_CAN),y)
CONFIGURED_APPS += examples/can
endif
#ifeq ($(CONFIG_USBDEV),y)
#ifeq ($(CONFIG_CDCACM),y)
CONFIGURED_APPS += examples/cdcacm
#endif
#endif

File diff suppressed because it is too large Load Diff

View File

@ -80,5 +80,9 @@ distclean: clean
$(call DELFILE, Make.dep)
$(call DELFILE, .depend)
ifneq ($(BOARD_CONTEXT),y)
context:
endif
-include Make.dep

View File

@ -47,11 +47,6 @@
#include <nuttx/compiler.h>
#include <stdint.h>
#include <stm32.h>
#include <arch/board/board.h>
#define UDID_START 0x1FFF7A10
/****************************************************************************************************
* Definitions
****************************************************************************************************/
@ -300,9 +295,9 @@
#define BOARD_NAME "MINDPX_V2"
/* By Providing BOARD_ADC_USB_CONNECTED this board support the ADC
* system_power interface, and therefore provides the true logic
* GPIO BOARD_ADC_xxxx macros.
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
* this board support the ADC system_power interface, and therefore
* provides the true logic GPIO BOARD_ADC_xxxx macros.
*/
#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS))
#define BOARD_ADC_BRICK_VALID (1)
@ -359,24 +354,6 @@ extern void stm32_usbinitialize(void);
#define board_peripheral_reset(ms)
/****************************************************************************
* Name: nsh_archinitialize
*
* Description:
* Perform architecture specific initialization for NSH.
*
* CONFIG_NSH_ARCHINIT=y :
* Called from the NSH library
*
* CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, &&
* CONFIG_NSH_ARCHINIT=n :
* Called from board_initialize().
*
****************************************************************************/
#ifdef CONFIG_NSH_LIBRARY
int nsh_archinitialize(void);
#endif
#include "../common/board_common.h"

View File

@ -35,10 +35,10 @@
* @file mindpx2_init.c
*
* MINDPX-specific early startup code. This file implements the
* nsh_archinitialize() function that is called early by nsh during startup.
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialisation.
* subsystems and perform board-specific initialization.
*/
/****************************************************************************
@ -49,16 +49,18 @@
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/arch.h>
#include <nuttx/spi.h>
#include <nuttx/i2c.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
#include <nuttx/gran.h>
#include <nuttx/mm/gran.h>
#include <stm32.h>
#include "board_config.h"
@ -69,9 +71,14 @@
#include <drivers/drv_hrt.h>
#include <drivers/drv_led.h>
#include <systemlib/px4_macros.h>
#include <systemlib/cpuload.h>
#include <systemlib/perf_counter.h>
#include <systemlib/hardfault_log.h>
#include <systemlib/systemlib.h>
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
@ -82,13 +89,13 @@
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
# define message(...) lowsyslog(__VA_ARGS__)
# define message(...) syslog(__VA_ARGS__)
# else
# define message(...) printf(__VA_ARGS__)
# endif
#else
# ifdef CONFIG_DEBUG
# define message lowsyslog
# define message syslog
# else
# define message printf
# endif
@ -126,29 +133,12 @@ __END_DECLS
__EXPORT void
stm32_boardinitialize(void)
{
/* configure SPI interfaces */
stm32_spiinitialize();
/* configure LEDs */
up_ledinit();
}
/****************************************************************************
* Name: nsh_archinitialize
*
* Description:
* Perform architecture specific initialization
*
****************************************************************************/
board_autoled_initialize();
static struct spi_dev_s *spi1;
static struct spi_dev_s *spi2;
static struct spi_dev_s *spi4;
static struct sdio_dev_s *sdio;
__EXPORT int nsh_archinitialize(void)
{
/* configure ADC pins */
px4_arch_configgpio(GPIO_ADC1_IN4); /* VDD_5V_SENS */
px4_arch_configgpio(GPIO_ADC1_IN10); /* BATT_CURRENT_SENS */
px4_arch_configgpio(GPIO_ADC1_IN12); /* BATT_VOLTAGE_SENS */
@ -158,12 +148,7 @@ __EXPORT int nsh_archinitialize(void)
px4_arch_configgpio(GPIO_ADC1_IN15); /* PRESSURE_SENS */
/* configure power supply control/sense pins */
// px4_arch_configgpio(GPIO_VDD_5V_PERIPH_EN);
// px4_arch_configgpio(GPIO_VDD_3V3_SENSORS_EN);
// px4_arch_configgpio(GPIO_VDD_BRICK_VALID);
// px4_arch_configgpio(GPIO_VDD_SERVO_VALID);
// px4_arch_configgpio(GPIO_VDD_5V_HIPOWER_OC);
// px4_arch_configgpio(GPIO_VDD_5V_PERIPH_OC);
px4_arch_configgpio(GPIO_SBUS_INV);
px4_arch_configgpio(GPIO_RC_OUT); /* Serial RC output pin */
px4_arch_gpiowrite(GPIO_RC_OUT, 1); /* set it high to pull RC input up */
@ -179,7 +164,67 @@ __EXPORT int nsh_archinitialize(void)
px4_arch_configgpio(GPIO_GPIO6_OUTPUT);
px4_arch_configgpio(GPIO_GPIO7_OUTPUT);
/* configure SPI interfaces */
stm32_spiinitialize();
stm32_configgpio(GPIO_I2C2_SCL);
stm32_configgpio(GPIO_I2C2_SDA);
stm32_configgpio(GPIO_I2C1_SCL);
stm32_configgpio(GPIO_I2C1_SDA);
}
/****************************************************************************
* Name: board_app_initialize
*
* Description:
* Perform application specific initialization. This function is never
* called directly from application code, but only indirectly via the
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
*
* Input Parameters:
* arg - The boardctl() argument is passed to the board_app_initialize()
* implementation without modification. The argument has no
* meaning to NuttX; the meaning of the argument is a contract
* between the board-specific initalization logic and the the
* matching application logic. The value cold be such things as a
* mode enumeration value, a set of DIP switch switch settings, a
* pointer to configuration data read from a file or serial FLASH,
* or whatever you would like to do with it. Every implementation
* should accept zero/NULL as a default configuration.
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
static struct spi_dev_s *spi1;
static struct spi_dev_s *spi2;
static struct spi_dev_s *spi4;
static struct sdio_dev_s *sdio;
__EXPORT int board_app_initialize(uintptr_t arg)
{
#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
/* run C++ ctors before we go any further */
up_cxxinitialize();
# if defined(CONFIG_EXAMPLES_NSH_CXXINITIALIZE)
# error CONFIG_EXAMPLES_NSH_CXXINITIALIZE Must not be defined! Use CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE.
# endif
#else
# error platform is dependent on c++ both CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE must be defined.
#endif
/* configure the high-resolution time/callout interface */
hrt_init();
/* configure the DMA allocator */
@ -210,6 +255,138 @@ __EXPORT int nsh_archinitialize(void)
(hrt_callout)stm32_serial_dma_poll,
NULL);
#if defined(CONFIG_STM32_BBSRAM)
/* NB. the use of the console requires the hrt running
* to poll the DMA
*/
/* Using Battery Backed Up SRAM */
int filesizes[CONFIG_STM32_BBSRAM_FILES + 1] = BSRAM_FILE_SIZES;
stm32_bbsraminitialize(BBSRAM_PATH, filesizes);
#if defined(CONFIG_STM32_SAVE_CRASHDUMP)
/* Panic Logging in Battery Backed Up Files */
/*
* In an ideal world, if a fault happens in flight the
* system save it to BBSRAM will then reboot. Upon
* rebooting, the system will log the fault to disk, recover
* the flight state and continue to fly. But if there is
* a fault on the bench or in the air that prohibit the recovery
* or committing the log to disk, the things are too broken to
* fly. So the question is:
*
* Did we have a hard fault and not make it far enough
* through the boot sequence to commit the fault data to
* the SD card?
*/
/* Do we have an uncommitted hard fault in BBSRAM?
* - this will be reset after a successful commit to SD
*/
int hadCrash = hardfault_check_status("boot");
if (hadCrash == OK) {
message("[boot] There is a hard fault logged. Hold down the SPACE BAR," \
" while booting to halt the system!\n");
/* Yes. So add one to the boot count - this will be reset after a successful
* commit to SD
*/
int reboots = hardfault_increment_reboot("boot", false);
/* Also end the misery for a user that holds for a key down on the console */
int bytesWaiting;
ioctl(fileno(stdin), FIONREAD, (unsigned long)((uintptr_t) &bytesWaiting));
if (reboots > 2 || bytesWaiting != 0) {
/* Since we can not commit the fault dump to disk. Display it
* to the console.
*/
hardfault_write("boot", fileno(stdout), HARDFAULT_DISPLAY_FORMAT, false);
message("[boot] There were %d reboots with Hard fault that were not committed to disk - System halted %s\n",
reboots,
(bytesWaiting == 0 ? "" : " Due to Key Press\n"));
/* For those of you with a debugger set a break point on up_assert and
* then set dbgContinue = 1 and go.
*/
/* Clear any key press that got us here */
static volatile bool dbgContinue = false;
int c = '>';
while (!dbgContinue) {
switch (c) {
case EOF:
case '\n':
case '\r':
case ' ':
continue;
default:
putchar(c);
putchar('\n');
switch (c) {
case 'D':
case 'd':
hardfault_write("boot", fileno(stdout), HARDFAULT_DISPLAY_FORMAT, false);
break;
case 'C':
case 'c':
hardfault_rearm("boot");
hardfault_increment_reboot("boot", true);
break;
case 'B':
case 'b':
dbgContinue = true;
break;
default:
break;
} // Inner Switch
message("\nEnter B - Continue booting\n" \
"Enter C - Clear the fault log\n" \
"Enter D - Dump fault log\n\n?>");
fflush(stdout);
if (!dbgContinue) {
c = getchar();
}
break;
} // outer switch
} // for
} // inner if
} // outer if
#endif // CONFIG_STM32_SAVE_CRASHDUMP
#endif // CONFIG_STM32_BBSRAM
/* initial LED state */
drv_led_start();
led_off(LED_AMBER);
@ -220,7 +397,7 @@ __EXPORT int nsh_archinitialize(void)
if (!spi4) {
message("[boot] FAILED to initialize SPI port 4\n");
up_ledon(LED_AMBER);
board_autoled_on(LED_AMBER);
return -ENODEV;
}
@ -236,11 +413,11 @@ __EXPORT int nsh_archinitialize(void)
/* Get the SPI port for the FRAM */
spi1 = px4_spibus_initialize(1);
spi1 = stm32_spibus_initialize(1);
if (!spi1) {
message("[boot] FAILED to initialize SPI port 1\n");
up_ledon(LED_AMBER);
board_autoled_on(LED_AMBER);
return -ENODEV;
}
@ -289,3 +466,157 @@ __EXPORT int nsh_archinitialize(void)
return OK;
}
static void copy_reverse(stack_word_t *dest, stack_word_t *src, int size)
{
while (size--) {
*dest++ = *src--;
}
}
__EXPORT void board_crashdump(uintptr_t currentsp, FAR void *tcb, FAR const uint8_t *filename, int lineno)
{
/* We need a chunk of ram to save the complete context in.
* Since we are going to reboot we will use &_sdata
* which is the lowest memory and the amount we will save
* _should be_ below any resources we need herein.
* Unfortunately this is hard to test. See dead below
*/
fullcontext_s *pdump = (fullcontext_s *)&_sdata;
(void)enter_critical_section();
struct tcb_s *rtcb = (struct tcb_s *)tcb;
/* Zero out everything */
memset(pdump, 0, sizeof(fullcontext_s));
/* Save Info */
pdump->info.lineno = lineno;
if (filename) {
int offset = 0;
unsigned int len = strlen((char *)filename) + 1;
if (len > sizeof(pdump->info.filename)) {
offset = len - sizeof(pdump->info.filename) ;
}
strncpy(pdump->info.filename, (char *)&filename[offset], sizeof(pdump->info.filename));
}
/* Save the value of the pointer for current_regs as debugging info.
* It should be NULL in case of an ASSERT and will aid in cross
* checking the validity of system memory at the time of the
* fault.
*/
pdump->info.current_regs = (uintptr_t) CURRENT_REGS;
/* Save Context */
#if CONFIG_TASK_NAME_SIZE > 0
strncpy(pdump->info.name, rtcb->name, CONFIG_TASK_NAME_SIZE);
#endif
pdump->info.pid = rtcb->pid;
/* If current_regs is not NULL then we are in an interrupt context
* and the user context is in current_regs else we are running in
* the users context
*/
if (CURRENT_REGS) {
pdump->info.stacks.interrupt.sp = currentsp;
pdump->info.flags |= (eRegsPresent | eUserStackPresent | eIntStackPresent);
memcpy(pdump->info.regs, (void *)CURRENT_REGS, sizeof(pdump->info.regs));
pdump->info.stacks.user.sp = pdump->info.regs[REG_R13];
} else {
/* users context */
pdump->info.flags |= eUserStackPresent;
pdump->info.stacks.user.sp = currentsp;
}
if (pdump->info.pid == 0) {
pdump->info.stacks.user.top = g_idle_topstack - 4;
pdump->info.stacks.user.size = CONFIG_IDLETHREAD_STACKSIZE;
} else {
pdump->info.stacks.user.top = (uint32_t) rtcb->adj_stack_ptr;
pdump->info.stacks.user.size = (uint32_t) rtcb->adj_stack_size;;
}
#if CONFIG_ARCH_INTERRUPTSTACK > 3
/* Get the limits on the interrupt stack memory */
pdump->info.stacks.interrupt.top = (uint32_t)&g_intstackbase;
pdump->info.stacks.interrupt.size = (CONFIG_ARCH_INTERRUPTSTACK & ~3);
/* If In interrupt Context save the interrupt stack data centered
* about the interrupt stack pointer
*/
if ((pdump->info.flags & eIntStackPresent) != 0) {
stack_word_t *ps = (stack_word_t *) pdump->info.stacks.interrupt.sp;
copy_reverse(pdump->istack, &ps[arraySize(pdump->istack) / 2], arraySize(pdump->istack));
}
/* Is it Invalid? */
if (!(pdump->info.stacks.interrupt.sp <= pdump->info.stacks.interrupt.top &&
pdump->info.stacks.interrupt.sp > pdump->info.stacks.interrupt.top - pdump->info.stacks.interrupt.size)) {
pdump->info.flags |= eInvalidIntStackPrt;
}
#endif
/* If In interrupt context or User save the user stack data centered
* about the user stack pointer
*/
if ((pdump->info.flags & eUserStackPresent) != 0) {
stack_word_t *ps = (stack_word_t *) pdump->info.stacks.user.sp;
copy_reverse(pdump->ustack, &ps[arraySize(pdump->ustack) / 2], arraySize(pdump->ustack));
}
/* Is it Invalid? */
if (!(pdump->info.stacks.user.sp <= pdump->info.stacks.user.top &&
pdump->info.stacks.user.sp > pdump->info.stacks.user.top - pdump->info.stacks.user.size)) {
pdump->info.flags |= eInvalidUserStackPtr;
}
int rv = stm32_bbsram_savepanic(HARDFAULT_FILENO, (uint8_t *)pdump, sizeof(fullcontext_s));
/* Test if memory got wiped because of using _sdata */
if (rv == -ENXIO) {
char *dead = "Memory wiped - dump not saved!";
while (*dead) {
up_lowputc(*dead++);
}
} else if (rv == -ENOSPC) {
/* hard fault again */
up_lowputc('!');
}
#if defined(CONFIG_BOARD_RESET_ON_CRASH)
px4_systemreset(false);
#endif
}

View File

@ -64,14 +64,14 @@ __EXPORT void led_init()
{
/* Configure LED1 GPIO for output */
px4_arch_configgpio(GPIO_LED1);
stm32_configgpio(GPIO_LED1);
}
__EXPORT void led_on(int led)
{
if (led == 1) {
/* Pull down to switch on */
px4_arch_gpiowrite(GPIO_LED1, false);
stm32_gpiowrite(GPIO_LED1, false);
}
}
@ -79,18 +79,18 @@ __EXPORT void led_off(int led)
{
if (led == 1) {
/* Pull up to switch off */
px4_arch_gpiowrite(GPIO_LED1, true);
stm32_gpiowrite(GPIO_LED1, true);
}
}
__EXPORT void led_toggle(int led)
{
if (led == 1) {
if (px4_arch_gpioread(GPIO_LED1)) {
px4_arch_gpiowrite(GPIO_LED1, false);
if (stm32_gpioread(GPIO_LED1)) {
stm32_gpiowrite(GPIO_LED1, false);
} else {
px4_arch_gpiowrite(GPIO_LED1, true);
stm32_gpiowrite(GPIO_LED1, true);
}
}
}

View File

@ -46,7 +46,7 @@
#include <errno.h>
#include <debug.h>
#include <nuttx/can.h>
#include <nuttx/drivers/can.h>
#include <arch/board/board.h>
#include "chip.h"
@ -74,21 +74,6 @@
# define CAN_PORT 2
#endif
/* Debug ***************************************************************************/
/* Non-standard debug that may be enabled just for testing CAN */
#ifdef CONFIG_DEBUG_CAN
# define candbg dbg
# define canvdbg vdbg
# define canlldbg lldbg
# define canllvdbg llvdbg
#else
# define candbg(x...)
# define canvdbg(x...)
# define canlldbg(x...)
# define canllvdbg(x...)
#endif
/************************************************************************************
* Private Functions
************************************************************************************/
@ -120,7 +105,7 @@ int can_devinit(void)
can = stm32_caninitialize(CAN_PORT);
if (can == NULL) {
candbg("ERROR: Failed to get CAN interface\n");
canerr("ERROR: Failed to get CAN interface\n");
return -ENODEV;
}
@ -129,7 +114,7 @@ int can_devinit(void)
ret = can_register("/dev/can0", can);
if (ret < 0) {
candbg("ERROR: can_register failed: %d\n", ret);
canerr("ERROR: can_register failed: %d\n", ret);
return ret;
}

View File

@ -47,7 +47,7 @@
#include <stdbool.h>
#include <debug.h>
#include <nuttx/spi.h>
#include <nuttx/spi/spi.h>
#include <arch/board/board.h>
#include <up_arch.h>
@ -80,10 +80,6 @@ __EXPORT void weak_function stm32_spiinitialize(void)
* required for some peripheral
* state machines
*/
px4_arch_gpiowrite(GPIO_SPI_CS_GYRO, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_BARO, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_MPU, 1);
px4_arch_configgpio(GPIO_EXTI_GYRO_DRDY);
px4_arch_configgpio(GPIO_EXTI_MAG_DRDY);
@ -92,13 +88,12 @@ __EXPORT void weak_function stm32_spiinitialize(void)
#endif
#ifdef CONFIG_STM32_SPI1
px4_arch_configgpio(GPIO_SPI_CS_FRAM);
px4_arch_gpiowrite(GPIO_SPI_CS_FRAM, 1);
stm32_configgpio(GPIO_SPI_CS_FRAM);
stm32_gpiowrite(GPIO_SPI_CS_FRAM, 1);
#endif
#ifdef CONFIG_STM32_SPI2
px4_arch_configgpio(GPIO_SPI_CS_EXT0);
px4_arch_gpiowrite(GPIO_SPI_CS_EXT0, 1);
#endif
}
@ -109,22 +104,23 @@ __EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
switch (devid) {
case PX4_SPIDEV_GYRO:
/* Making sure the other peripherals are not selected */
px4_arch_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
px4_arch_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_BARO, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_MPU, 1);
stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
break;
case PX4_SPIDEV_ACCEL_MAG:
/* Making sure the other peripherals are not selected */
px4_arch_gpiowrite(GPIO_SPI_CS_GYRO, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
px4_arch_gpiowrite(GPIO_SPI_CS_BARO, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_MPU, 1);
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
break;
case PX4_SPIDEV_BARO:
/* Making sure the other peripherals are not selected */
px4_arch_gpiowrite(GPIO_SPI_CS_GYRO, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_BARO, !selected);
@ -133,10 +129,10 @@ __EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
case PX4_SPIDEV_MPU:
/* Making sure the other peripherals are not selected */
px4_arch_gpiowrite(GPIO_SPI_CS_GYRO, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_BARO, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_MPU, !selected);
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
stm32_gpiowrite(GPIO_SPI_CS_MPU, !selected);
break;
default:
@ -152,7 +148,7 @@ __EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devi
__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
/* there can only be one device on this bus, so always select it */
px4_arch_gpiowrite(GPIO_SPI_CS_FRAM, !selected);
stm32_gpiowrite(GPIO_SPI_CS_FRAM, !selected);
}
__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
@ -164,6 +160,7 @@ __EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devi
#ifdef CONFIG_STM32_SPI2
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
px4_arch_gpiowrite(GPIO_SPI_CS_EXT0, !selected);
}
@ -176,6 +173,7 @@ __EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devi
__EXPORT void board_spi_reset(int ms)
{
/* disable SPI bus */
px4_arch_configgpio(GPIO_SPI_CS_GYRO_OFF);
px4_arch_configgpio(GPIO_SPI_CS_ACCEL_MAG_OFF);
px4_arch_configgpio(GPIO_SPI_CS_BARO_OFF);
@ -205,8 +203,8 @@ __EXPORT void board_spi_reset(int ms)
px4_arch_gpiowrite(GPIO_EXTI_MPU_DRDY_OFF, 0);
// /* set the sensor rail off */
// px4_arch_configgpio(GPIO_VDD_3V3_SENSORS_EN);
// px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 0);
// stm32_configgpio(GPIO_VDD_3V3_SENSORS_EN);
// stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 0);
//
/* wait for the sensor rail to reach GND */
usleep(ms * 1000);
@ -215,7 +213,7 @@ __EXPORT void board_spi_reset(int ms)
// /* re-enable power */
//
// /* switch the sensor rail back on */
// px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 1);
// stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 1);
//
/* wait a bit before starting SPI, different times didn't influence results */
usleep(100);
@ -231,15 +229,16 @@ __EXPORT void board_spi_reset(int ms)
* required for some peripheral
* state machines
*/
px4_arch_gpiowrite(GPIO_SPI_CS_GYRO, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_BARO, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_FRAM, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_MPU, 1);
px4_arch_configgpio(GPIO_SPI4_SCK);
px4_arch_configgpio(GPIO_SPI4_MISO);
px4_arch_configgpio(GPIO_SPI4_MOSI);
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
stm32_gpiowrite(GPIO_SPI_CS_FRAM, 1);
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
stm32_configgpio(GPIO_SPI4_SCK);
stm32_configgpio(GPIO_SPI4_MISO);
stm32_configgpio(GPIO_SPI4_MOSI);
// XXX bring up the EXTI pins again
// px4_arch_configgpio(GPIO_GYRO_DRDY);

View File

@ -82,10 +82,10 @@ __EXPORT void stm32_usbinitialize(void)
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
#ifdef CONFIG_STM32_OTGFS
px4_arch_configgpio(GPIO_OTGFS_VBUS);
stm32_configgpio(GPIO_OTGFS_VBUS);
/* XXX We only support device mode
px4_arch_configgpio(GPIO_OTGFS_PWRON);
px4_arch_configgpio(GPIO_OTGFS_OVER);
stm32_configgpio(GPIO_OTGFS_PWRON);
stm32_configgpio(GPIO_OTGFS_OVER);
*/
#endif
}
@ -103,6 +103,6 @@ __EXPORT void stm32_usbinitialize(void)
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
ulldbg("resume: %d\n", resume);
uinfo("resume: %d\n", resume);
}