Changes to px4fmu-v4 for upstream Nuttx and hardfault logging

This commit is contained in:
David Sidrane
2016-12-12 13:34:13 -10:00
committed by Lorenz Meier
parent c89c47e57e
commit 17633c0714
12 changed files with 1116 additions and 428 deletions
@@ -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)
@@ -61,6 +63,7 @@ set(config_module_list
systemcmds/perf
systemcmds/pwm
systemcmds/esc_calib
systemcmds/hardfault_log
systemcmds/reboot
systemcmds/topic_listener
systemcmds/top
+15 -3
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
+15 -10
View File
@@ -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
-52
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
+4
View File
@@ -80,5 +80,9 @@ distclean: clean
$(call DELFILE, Make.dep)
$(call DELFILE, .depend)
ifneq ($(BOARD_CONTEXT),y)
context:
endif
-include Make.dep
+4 -33
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
****************************************************************************************************/
@@ -168,7 +163,7 @@
#define ADC_BATTERY_VOLTAGE_CHANNEL 2
#define ADC_BATTERY_CURRENT_CHANNEL 3
#define ADC_5V_RAIL_SENSE 4
#define ADC_RC_RSSI_CHANNEL 11
#define ADC_RC_RSSI_CHANNEL 11
/* User GPIOs
*
@@ -251,9 +246,6 @@
#define GPIO_LED_SAFETY (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN3)
#define GPIO_BTN_SAFETY (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN4)
#define GPIO_PERIPH_3V3_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
/* for R07, this signal is active low */
//#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
//#define INVERT_RC_INPUT(_s) px4_arch_gpiowrite(GPIO_SBUS_INV, 1-_s);
/* for R12, this signal is active high */
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
#define INVERT_RC_INPUT(_s) px4_arch_gpiowrite(GPIO_SBUS_INV, _s)
@@ -266,7 +258,6 @@
/* Power switch controls ******************************************************/
#define POWER_SPEKTRUM(_s) px4_arch_gpiowrite(GPIO_SPEKTRUM_PWR_EN, (1-_s))
//#define GPIO_USART1_RX_SPEKTRUM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7)
#define SPEKTRUM_RX_AS_UART() px4_arch_configgpio(GPIO_USART1_RX)
// FMUv4 has a separate GPIO for serial RC output
@@ -277,9 +268,9 @@
#define BOARD_NAME "PX4FMU_V4"
/* By Providing BOARD_ADC_USB_CONNECTED this board support the ADC
* system_power interface, and herefore 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 (px4_arch_gpioread(GPIO_VDD_BRICK_VALID))
@@ -333,26 +324,6 @@ extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int 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"
#endif /* __ASSEMBLY__ */
+3 -18
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
************************************************************************************/
@@ -121,7 +106,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;
}
@@ -130,7 +115,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;
}
+371 -49
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
* Copyright (c) 2012-2016 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
@@ -35,10 +35,10 @@
* @file px4fmu_init.c
*
* PX4FMU-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,10 +71,15 @@
#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/err.h>
#include <systemlib/hardfault_log.h>
#include <systemlib/systemlib.h>
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
@@ -83,13 +90,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
@@ -123,13 +130,13 @@ __END_DECLS
__EXPORT void board_peripheral_reset(int ms)
{
/* set the peripheral rails off */
px4_arch_configgpio(GPIO_PERIPH_3V3_EN);
stm32_configgpio(GPIO_PERIPH_3V3_EN);
px4_arch_gpiowrite(GPIO_PERIPH_3V3_EN, 0);
stm32_gpiowrite(GPIO_PERIPH_3V3_EN, 0);
bool last = px4_arch_gpioread(GPIO_SPEKTRUM_PWR_EN);
bool last = stm32_gpioread(GPIO_SPEKTRUM_PWR_EN);
/* Keep Spektum on to discharge rail*/
px4_arch_gpiowrite(GPIO_SPEKTRUM_PWR_EN, 1);
stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, 1);
/* wait for the peripheral rail to reach GND */
usleep(ms * 1000);
@@ -138,8 +145,8 @@ __EXPORT void board_peripheral_reset(int ms)
/* re-enable power */
/* switch the peripheral rail back on */
px4_arch_gpiowrite(GPIO_SPEKTRUM_PWR_EN, last);
px4_arch_gpiowrite(GPIO_PERIPH_3V3_EN, 1);
stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, last);
stm32_gpiowrite(GPIO_PERIPH_3V3_EN, 1);
}
@@ -156,18 +163,65 @@ __EXPORT void board_peripheral_reset(int ms)
__EXPORT void
stm32_boardinitialize(void)
{
/* configure ADC pins */
stm32_configgpio(GPIO_ADC1_IN2); /* BATT_VOLTAGE_SENS */
stm32_configgpio(GPIO_ADC1_IN3); /* BATT_CURRENT_SENS */
stm32_configgpio(GPIO_ADC1_IN4); /* VDD_5V_SENS */
stm32_configgpio(GPIO_ADC1_IN11); /* RSSI analog in */
/* configure power supply control/sense pins */
stm32_configgpio(GPIO_PERIPH_3V3_EN);
stm32_configgpio(GPIO_VDD_BRICK_VALID);
stm32_configgpio(GPIO_SBUS_INV);
stm32_configgpio(GPIO_8266_GPIO0);
stm32_configgpio(GPIO_SPEKTRUM_PWR_EN);
stm32_configgpio(GPIO_8266_PD);
stm32_configgpio(GPIO_8266_RST);
stm32_configgpio(GPIO_BTN_SAFETY);
#ifdef GPIO_RC_OUT
stm32_configgpio(GPIO_RC_OUT); /* Serial RC output pin */
stm32_gpiowrite(GPIO_RC_OUT, 1); /* set it high to pull RC input up */
#endif
/* configure the GPIO pins to outputs and keep them low */
stm32_configgpio(GPIO_GPIO0_OUTPUT);
stm32_configgpio(GPIO_GPIO1_OUTPUT);
stm32_configgpio(GPIO_GPIO2_OUTPUT);
stm32_configgpio(GPIO_GPIO3_OUTPUT);
stm32_configgpio(GPIO_GPIO4_OUTPUT);
stm32_configgpio(GPIO_GPIO5_OUTPUT);
/* configure SPI interfaces */
stm32_spiinitialize();
/* configure LEDs */
up_ledinit();
board_autoled_initialize();
}
/****************************************************************************
* Name: nsh_archinitialize
* Name: board_app_initialize
*
* Description:
* Perform architecture specific initialization
* 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.
*
****************************************************************************/
@@ -175,41 +229,23 @@ static struct spi_dev_s *spi1;
static struct spi_dev_s *spi2;
static struct sdio_dev_s *sdio;
#include <math.h>
__EXPORT int nsh_archinitialize(void)
__EXPORT int board_app_initialize(uintptr_t arg)
{
/* configure ADC pins */
px4_arch_configgpio(GPIO_ADC1_IN2); /* BATT_VOLTAGE_SENS */
px4_arch_configgpio(GPIO_ADC1_IN3); /* BATT_CURRENT_SENS */
px4_arch_configgpio(GPIO_ADC1_IN4); /* VDD_5V_SENS */
px4_arch_configgpio(GPIO_ADC1_IN11); /* RSSI analog in */
#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
/* configure power supply control/sense pins */
px4_arch_configgpio(GPIO_PERIPH_3V3_EN);
px4_arch_configgpio(GPIO_VDD_BRICK_VALID);
/* run C++ ctors before we go any further */
px4_arch_configgpio(GPIO_SBUS_INV);
px4_arch_configgpio(GPIO_8266_GPIO0);
px4_arch_configgpio(GPIO_SPEKTRUM_PWR_EN);
px4_arch_configgpio(GPIO_8266_PD);
px4_arch_configgpio(GPIO_8266_RST);
px4_arch_configgpio(GPIO_BTN_SAFETY);
up_cxxinitialize();
#ifdef GPIO_RC_OUT
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 */
# 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 GPIO pins to outputs and keep them low */
px4_arch_configgpio(GPIO_GPIO0_OUTPUT);
px4_arch_configgpio(GPIO_GPIO1_OUTPUT);
px4_arch_configgpio(GPIO_GPIO2_OUTPUT);
px4_arch_configgpio(GPIO_GPIO3_OUTPUT);
px4_arch_configgpio(GPIO_GPIO4_OUTPUT);
px4_arch_configgpio(GPIO_GPIO5_OUTPUT);
/* configure the high-resolution time/callout interface */
hrt_init();
@@ -241,6 +277,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_RED);
@@ -249,11 +417,11 @@ __EXPORT int nsh_archinitialize(void)
/* Configure SPI-based devices */
spi1 = px4_spibus_initialize(1);
spi1 = stm32_spibus_initialize(1);
if (!spi1) {
message("[boot] FAILED to initialize SPI port 1\n");
up_ledon(LED_RED);
board_autoled_on(LED_RED);
return -ENODEV;
}
@@ -268,11 +436,11 @@ __EXPORT int nsh_archinitialize(void)
/* Get the SPI port for the FRAM */
spi2 = px4_spibus_initialize(2);
spi2 = stm32_spibus_initialize(2);
if (!spi2) {
message("[boot] FAILED to initialize SPI port 2\n");
up_ledon(LED_RED);
board_autoled_on(LED_RED);
return -ENODEV;
}
@@ -313,3 +481,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
}
+3 -3
View File
@@ -73,20 +73,20 @@ __EXPORT void led_init(void)
{
/* Configure LED GPIOs for output */
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
px4_arch_configgpio(g_ledmap[l]);
stm32_configgpio(g_ledmap[l]);
}
}
static void phy_set_led(int led, bool state)
{
/* Pull Down to switch on */
px4_arch_gpiowrite(g_ledmap[led], !state);
stm32_gpiowrite(g_ledmap[led], !state);
}
static bool phy_get_led(int led)
{
return !px4_arch_gpioread(g_ledmap[led]);
return !stm32_gpioread(g_ledmap[led]);
}
__EXPORT void led_on(int led)
+28 -49
View File
@@ -48,7 +48,7 @@
#include <debug.h>
#include <unistd.h>
#include <nuttx/spi.h>
#include <nuttx/spi/spi.h>
#include <arch/board/board.h>
#include <up_arch.h>
@@ -78,24 +78,13 @@ __EXPORT void stm32_spiinitialize(void)
px4_arch_configgpio(GPIO_SPI_CS_ICM_20608_G);
px4_arch_configgpio(GPIO_SPI_CS_BMI160);
/* De-activate all peripherals,
* required for some peripheral
* state machines
*/
px4_arch_gpiowrite(GPIO_SPI_CS_MPU9250, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_HMC5983, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_MS5611, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_ICM_20608_G, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_BMI160, 1);
px4_arch_configgpio(GPIO_DRDY_MPU9250);
px4_arch_configgpio(GPIO_DRDY_HMC5983);
px4_arch_configgpio(GPIO_DRDY_ICM_20608_G);
#endif
#ifdef CONFIG_STM32_SPI2
px4_arch_configgpio(GPIO_SPI_CS_FRAM);
px4_arch_gpiowrite(GPIO_SPI_CS_FRAM, 1);
stm32_configgpio(GPIO_SPI_CS_FRAM);
#endif
}
@@ -173,14 +162,14 @@ __EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
switch (devid) {
case SPIDEV_FLASH:
/* Making sure the other peripherals are not selected */
px4_arch_gpiowrite(GPIO_SPI_CS_MS5611, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_FRAM, !selected);
stm32_gpiowrite(GPIO_SPI_CS_MS5611, 1);
stm32_gpiowrite(GPIO_SPI_CS_FRAM, !selected);
break;
case PX4_SPIDEV_BARO:
/* Making sure the other peripherals are not selected */
px4_arch_gpiowrite(GPIO_SPI_CS_FRAM, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_MS5611, !selected);
stm32_gpiowrite(GPIO_SPI_CS_FRAM, 1);
stm32_gpiowrite(GPIO_SPI_CS_MS5611, !selected);
break;
default:
@@ -210,25 +199,25 @@ __EXPORT void board_spi_reset(int ms)
px4_arch_gpiowrite(GPIO_SPI_CS_OFF_ICM_20608_G, 0);
px4_arch_gpiowrite(GPIO_SPI_CS_OFF_BMI160, 0);
px4_arch_configgpio(GPIO_SPI1_SCK_OFF);
px4_arch_configgpio(GPIO_SPI1_MISO_OFF);
px4_arch_configgpio(GPIO_SPI1_MOSI_OFF);
stm32_configgpio(GPIO_SPI1_SCK_OFF);
stm32_configgpio(GPIO_SPI1_MISO_OFF);
stm32_configgpio(GPIO_SPI1_MOSI_OFF);
px4_arch_gpiowrite(GPIO_SPI1_SCK_OFF, 0);
px4_arch_gpiowrite(GPIO_SPI1_MISO_OFF, 0);
px4_arch_gpiowrite(GPIO_SPI1_MOSI_OFF, 0);
stm32_gpiowrite(GPIO_SPI1_SCK_OFF, 0);
stm32_gpiowrite(GPIO_SPI1_MISO_OFF, 0);
stm32_gpiowrite(GPIO_SPI1_MOSI_OFF, 0);
px4_arch_configgpio(GPIO_DRDY_OFF_MPU9250);
px4_arch_configgpio(GPIO_DRDY_OFF_HMC5983);
px4_arch_configgpio(GPIO_DRDY_OFF_ICM_20608_G);
stm32_configgpio(GPIO_DRDY_OFF_MPU9250);
stm32_configgpio(GPIO_DRDY_OFF_HMC5983);
stm32_configgpio(GPIO_DRDY_OFF_ICM_20608_G);
px4_arch_gpiowrite(GPIO_DRDY_OFF_MPU9250, 0);
px4_arch_gpiowrite(GPIO_DRDY_OFF_HMC5983, 0);
px4_arch_gpiowrite(GPIO_DRDY_OFF_ICM_20608_G, 0);
stm32_gpiowrite(GPIO_DRDY_OFF_MPU9250, 0);
stm32_gpiowrite(GPIO_DRDY_OFF_HMC5983, 0);
stm32_gpiowrite(GPIO_DRDY_OFF_ICM_20608_G, 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);
@@ -237,7 +226,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);
@@ -250,25 +239,15 @@ __EXPORT void board_spi_reset(int ms)
px4_arch_configgpio(GPIO_SPI_CS_ICM_20608_G);
px4_arch_configgpio(GPIO_SPI_CS_BMI160);
/* De-activate all peripherals,
* required for some peripheral
* state machines
*/
px4_arch_gpiowrite(GPIO_SPI_CS_MPU9250, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_HMC5983, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_MS5611, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_ICM_20608_G, 1);
px4_arch_gpiowrite(GPIO_SPI_CS_BMI160, 1);
px4_arch_configgpio(GPIO_SPI1_SCK);
px4_arch_configgpio(GPIO_SPI1_MISO);
px4_arch_configgpio(GPIO_SPI1_MOSI);
stm32_configgpio(GPIO_SPI1_SCK);
stm32_configgpio(GPIO_SPI1_MISO);
stm32_configgpio(GPIO_SPI1_MOSI);
// // XXX bring up the EXTI pins again
// px4_arch_configgpio(GPIO_GYRO_DRDY);
// px4_arch_configgpio(GPIO_MAG_DRDY);
// px4_arch_configgpio(GPIO_ACCEL_DRDY);
// px4_arch_configgpio(GPIO_EXTI_MPU_DRDY);
// stm32_configgpio(GPIO_GYRO_DRDY);
// stm32_configgpio(GPIO_MAG_DRDY);
// stm32_configgpio(GPIO_ACCEL_DRDY);
// stm32_configgpio(GPIO_EXTI_MPU_DRDY);
#endif
+4 -4
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);
}