mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 14:47:44 +08:00
Changes to aerofc-v1 for upstream Nuttx and hardfault logging
This commit is contained in:
committed by
Lorenz Meier
parent
2e235b9013
commit
a2adf94d13
@@ -1,7 +1,11 @@
|
||||
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 2)
|
||||
|
||||
set(config_module_list
|
||||
#
|
||||
# Board support modules
|
||||
@@ -30,6 +34,8 @@ set(config_module_list
|
||||
systemcmds/param
|
||||
systemcmds/perf
|
||||
systemcmds/pwm
|
||||
systemcmds/esc_calib
|
||||
systemcmds/hardfault_log
|
||||
systemcmds/motor_test
|
||||
systemcmds/reboot
|
||||
systemcmds/top
|
||||
|
||||
@@ -150,11 +150,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
|
||||
|
||||
/* LED definitions ******************************************************************/
|
||||
/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any
|
||||
|
||||
@@ -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
|
||||
@@ -157,4 +162,3 @@ HOSTCC = gcc
|
||||
HOSTINCLUDES = -I.
|
||||
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
|
||||
HOSTLDFLAGS =
|
||||
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -80,5 +80,8 @@ distclean: clean
|
||||
$(call DELFILE, Make.dep)
|
||||
$(call DELFILE, .depend)
|
||||
|
||||
-include Make.dep
|
||||
ifneq ($(BOARD_CONTEXT),y)
|
||||
context:
|
||||
endif
|
||||
|
||||
-include Make.dep
|
||||
|
||||
@@ -33,13 +33,13 @@
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file tap-v1_init.c
|
||||
* @file aerofc-v1_init.c
|
||||
*
|
||||
* tap-v1-specific early startup code. This file implements the
|
||||
* nsh_archinitialize() function that is called early by nsh during startup.
|
||||
* aerofc-specific early startup code. This file implements the
|
||||
* 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.
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
@@ -50,16 +50,14 @@
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/i2c.h>
|
||||
#include <nuttx/board.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
|
||||
|
||||
|
||||
#include "stm32.h"
|
||||
#include "board_config.h"
|
||||
#include "stm32_uart.h"
|
||||
|
||||
@@ -68,7 +66,11 @@
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_led.h>
|
||||
|
||||
#include <systemlib/px4_macros.h>
|
||||
#include <systemlib/cpuload.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/hardfault_log.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
# if defined(FLASH_BASED_PARAMS)
|
||||
# include <systemlib/flashparams/flashfs.h>
|
||||
@@ -84,13 +86,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
|
||||
@@ -129,31 +131,53 @@ __END_DECLS
|
||||
|
||||
__EXPORT void stm32_boardinitialize(void)
|
||||
{
|
||||
/* configure LEDs */
|
||||
|
||||
board_autoled_initialize();
|
||||
|
||||
/* turn sensors on */
|
||||
stm32_configgpio(GPIO_VDD_5V_SENSORS_EN);
|
||||
|
||||
/* configure SPI interfaces */
|
||||
stm32_spiinitialize();
|
||||
|
||||
/* configure LEDs (empty call to NuttX' ledinit) */
|
||||
up_ledinit();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nsh_archinitialize
|
||||
* Name: board_app_initialize
|
||||
*
|
||||
* Description:
|
||||
* Perform architecture specific initialization
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
__EXPORT int nsh_archinitialize(void)
|
||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
int result;
|
||||
|
||||
#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 */
|
||||
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
message("DMA alloc FAILED");
|
||||
}
|
||||
|
||||
/* configure CPU load estimation */
|
||||
#ifdef CONFIG_SCHED_INSTRUMENTATION
|
||||
cpuload_initialize_once();
|
||||
@@ -176,6 +200,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);
|
||||
@@ -206,7 +362,7 @@ __EXPORT int nsh_archinitialize(void)
|
||||
|
||||
if (result != OK) {
|
||||
message("[boot] FAILED to init params in FLASH %d\n", result);
|
||||
up_ledon(LED_AMBER);
|
||||
led_on(LED_AMBER);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
@@ -214,3 +370,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
|
||||
}
|
||||
|
||||
@@ -48,7 +48,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"
|
||||
@@ -73,11 +73,6 @@ __EXPORT void stm32_spiinitialize(void)
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
px4_arch_configgpio(GPIO_SPI_CS_MPU6500);
|
||||
|
||||
/* De-activate all peripherals,
|
||||
* required for some peripheral
|
||||
* state machines
|
||||
*/
|
||||
px4_arch_gpiowrite(GPIO_SPI_CS_MPU6500, 1);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@@ -102,4 +102,3 @@ __EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
|
||||
{
|
||||
//ulldbg("resume: %d\n", resume);
|
||||
}
|
||||
|
||||
|
||||
@@ -50,16 +50,11 @@
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <stm32.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
/* Configuration ************************************************************************************/
|
||||
|
||||
#define UDID_START 0x1FFF7A10
|
||||
|
||||
/* PX4FMU GPIOs ***********************************************************************************/
|
||||
/* LEDs */
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12)
|
||||
@@ -71,20 +66,25 @@
|
||||
* I2C busses
|
||||
*
|
||||
* Peripheral Port Signal Name CONN
|
||||
* I2C1_SDA PB9 I2C1_SDA J2-4,9,16,21 mpu6050, U4 MS6507
|
||||
* I2C1_SDL PB8 I2C1_SCL J2-3,10,15,22 mpu6050, U4 MS6507
|
||||
* I2C1_SDA PB9
|
||||
* I2C1_SDL PB8
|
||||
*
|
||||
* I2C2_SDA PB11 Sonar Echo/I2C_SDA JP2-31,32
|
||||
* I2C2_SDL PB10 Sonar Trig/I2C_SCL JP2-29,30
|
||||
* I2C2_SDA PB11
|
||||
* I2C2_SDL PB10
|
||||
*
|
||||
* I2C3_SDA PC9 COMPASS_I2C3_SDA JP1-27,28
|
||||
* I2C3_SDL PA8 COMPASS_I2C3_SCL JP1-25,26
|
||||
* I2C3_SDA PC9
|
||||
* I2C3_SDL PA8
|
||||
*
|
||||
*/
|
||||
|
||||
#define PX4_I2C_BUS_EXPANSION 1
|
||||
#define PX4_I2C_BUS_ONBOARD 3
|
||||
|
||||
#define PX4_I2C_OBDEV_HMC5883 0x1E
|
||||
#define PX4_I2C_OBDEV_HMC5883 0x1e
|
||||
|
||||
#define GPIO_SPI_CS_MPU6500 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
|
||||
#define PX4_SPI_BUS_SENSORS 1
|
||||
#define PX4_SPIDEV_MPU 1
|
||||
|
||||
/*
|
||||
* ADC channels
|
||||
@@ -127,10 +127,6 @@
|
||||
|
||||
#define BOARD_NAME "AEROFC_V1"
|
||||
|
||||
#define GPIO_SPI_CS_MPU6500 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
|
||||
#define PX4_SPI_BUS_SENSORS 1
|
||||
#define PX4_SPIDEV_MPU 1
|
||||
|
||||
#define FLASH_BASED_PARAMS
|
||||
|
||||
__BEGIN_DECLS
|
||||
@@ -174,26 +170,6 @@ extern void stm32_usbinitialize(void);
|
||||
|
||||
extern int board_sdio_initialize(void);
|
||||
|
||||
/****************************************************************************
|
||||
* 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
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_pwr_init()
|
||||
*
|
||||
@@ -226,6 +202,8 @@ bool board_pwr_button_down(void);
|
||||
|
||||
void board_pwr(bool on_not_off);
|
||||
|
||||
#include "../common/board_common.h"
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
__END_DECLS
|
||||
|
||||
Reference in New Issue
Block a user