From 1a0b8a627c73afcdf8d1571b4d22ce121bb570ce Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 3 Mar 2015 16:30:51 -1000 Subject: Hard Fault Logging - one issue remians reduse memory foot print --- ROMFS/px4fmu_common/init.d/rcS | 14 +- makefiles/config_px4fmu-v2_default.mk | 1 + makefiles/config_px4fmu-v2_multiplatform.mk | 1 + makefiles/config_px4fmu-v2_test.mk | 1 + src/drivers/boards/px4fmu-v2/px4fmu2_init.c | 261 ++++++++++ src/modules/systemlib/hardfault_log.h | 383 ++++++++++++++ src/systemcmds/hardfault_log/hardfault_log.c | 718 +++++++++++++++++++++++++++ src/systemcmds/hardfault_log/module.mk | 43 ++ 8 files changed, 1420 insertions(+), 2 deletions(-) create mode 100644 src/modules/systemlib/hardfault_log.h create mode 100644 src/systemcmds/hardfault_log/hardfault_log.c create mode 100644 src/systemcmds/hardfault_log/module.mk diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 266af42e6..706faa42b 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -29,8 +29,18 @@ if mount -t vfat /dev/mmcsd0 /fs/microsd then set LOG_FILE /fs/microsd/bootlog.txt echo "[i] microSD mounted: /fs/microsd" - # Start playing the startup tune - tone_alarm start + if hardfault_log check + then + tone_alarm error + if hardfault_log commit + then + hardfault_log reset + tone_alarm stop + fi + else + # Start playing the startup tune + tone_alarm start + fi else set LOG_FILE /dev/null fi diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk index 92346715c..e69aa8244 100644 --- a/makefiles/config_px4fmu-v2_default.mk +++ b/makefiles/config_px4fmu-v2_default.mk @@ -56,6 +56,7 @@ MODULES += systemcmds/perf MODULES += systemcmds/preflight_check MODULES += systemcmds/pwm MODULES += systemcmds/esc_calib +MODULES += systemcmds/hardfault_log MODULES += systemcmds/reboot MODULES += systemcmds/top MODULES += systemcmds/config diff --git a/makefiles/config_px4fmu-v2_multiplatform.mk b/makefiles/config_px4fmu-v2_multiplatform.mk index 568f940ee..2a92890aa 100644 --- a/makefiles/config_px4fmu-v2_multiplatform.mk +++ b/makefiles/config_px4fmu-v2_multiplatform.mk @@ -54,6 +54,7 @@ MODULES += systemcmds/perf MODULES += systemcmds/preflight_check MODULES += systemcmds/pwm MODULES += systemcmds/esc_calib +MODULES += systemcmds/hardfault_log MODULES += systemcmds/reboot MODULES += systemcmds/top MODULES += systemcmds/config diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk index ed8a50f6a..2100cd5d2 100644 --- a/makefiles/config_px4fmu-v2_test.mk +++ b/makefiles/config_px4fmu-v2_test.mk @@ -41,6 +41,7 @@ MODULES += systemcmds/perf MODULES += systemcmds/preflight_check MODULES += systemcmds/pwm MODULES += systemcmds/esc_calib +MODULES += systemcmds/hardfault_log MODULES += systemcmds/reboot MODULES += systemcmds/top MODULES += systemcmds/config diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c index 7c4a450ec..98babbf05 100644 --- a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c +++ b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c @@ -49,6 +49,7 @@ #include #include +#include #include #include @@ -70,9 +71,12 @@ #include #include +#include #include #include +#include + #if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE) #include #endif @@ -269,6 +273,131 @@ __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; + int nfc = stm32_bbsraminitialize(BBSRAM_PATH, filesizes); + + syslog(LOG_INFO, "[boot] %d Battery Backed Up File(s) \n",nfc); + +#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) { + + syslog(LOG_INFO, "[boot] There was a hard fault hit the SPACE BAR 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); + + syslog(LOG_INFO, "[boot] There were %d uncommitted Hard faults 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; + for (int c ='>'; !dbgContinue; c= getchar()) { + + 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 + + syslog(LOG_INFO, "\nEnter B - Continue booting\n" \ + "Enter C - Clear the fault log\n" \ + "Enter D - Dump fault log\n\n?>"); + fflush(stdout); + 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); @@ -354,3 +483,135 @@ __EXPORT int nsh_archinitialize(void) return OK; } + +__EXPORT void board_crashdump(uint32_t currentsp, void *tcb, uint8_t *filename, int lineno) +{ + /* We need a chunk of ram to save the complete contest in. + * Since we are going to reboot we will use &_sdata + * + */ + fullcontext_s *pdump = (fullcontext_s*)&_sdata; + + (void)irqsave(); + + 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 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 CONFIG_TASK_NAME_SIZE > 0 + strncpy(pdump->context.proc.name, rtcb->name, CONFIG_TASK_NAME_SIZE); +#endif + + pdump->context.proc.pid = rtcb->pid; + + pdump->context.stack.current_sp = currentsp; + + if (current_regs) + { + pdump->info.stuff |= eRegs; + memcpy(&pdump->context.proc.xcp.regs, (void*)current_regs, sizeof(pdump->context.proc.xcp.regs)); + currentsp = pdump->context.proc.xcp.regs[REG_R13]; + } + + + pdump->context.stack.itopofstack = (uint32_t) &g_intstackbase;; + pdump->context.stack.istacksize = (CONFIG_ARCH_INTERRUPTSTACK & ~3); + + if (pdump->context.proc.pid == 0) { + + pdump->context.stack.utopofstack = g_idle_topstack - 4; + pdump->context.stack.ustacksize = CONFIG_IDLETHREAD_STACKSIZE; + + } else { + pdump->context.stack.utopofstack = (uint32_t) rtcb->adj_stack_ptr; + pdump->context.stack.ustacksize = (uint32_t) rtcb->adj_stack_size;; + } + +#if CONFIG_ARCH_INTERRUPTSTACK > 3 + + /* Get the limits on the interrupt stack memory */ + + pdump->context.stack.itopofstack = (uint32_t)&g_intstackbase; + pdump->context.stack.istacksize = (CONFIG_ARCH_INTERRUPTSTACK & ~3); + + /* If the current stack pointer is within the interrupt stack then + * save the interrupt stack data centered about the interrupt stack pointer + */ + + if (pdump->context.stack.current_sp <= pdump->context.stack.itopofstack && + pdump->context.stack.current_sp > pdump->context.stack.itopofstack - pdump->context.stack.istacksize) + { + pdump->info.stuff |= eIntStack; + memcpy(&pdump->istack, (void *)(pdump->context.stack.current_sp-sizeof(pdump->istack)/2), + sizeof(pdump->istack)); + } + +#endif + + /* If the saved context of the interrupted process's stack pointer lies within the + * allocated user stack memory then save the user stack centered about the user sp + */ + if (currentsp <= pdump->context.stack.utopofstack && + currentsp > pdump->context.stack.utopofstack - pdump->context.stack.ustacksize) + { + pdump->info.stuff |= eUserStack; + memcpy(&pdump->ustack, (void *)(currentsp-sizeof(pdump->ustack)/2), sizeof(pdump->ustack)); + } + + /* Oh boy we have a real hot mess on our hands so save above and below the + * current sp + */ + + if ((pdump->info.stuff & eStackValid) == 0) + { + pdump->info.stuff |= eStackUnknown; +#if CONFIG_ARCH_INTERRUPTSTACK > 3 + /* sp and above in istack */ + memcpy(&pdump->istack, (void *)pdump->context.stack.current_sp, sizeof(pdump->istack)); + /* below in ustack */ + memcpy(&pdump->ustack, (void *)(pdump->context.stack.current_sp-sizeof(pdump->ustack)), + sizeof(pdump->ustack)); +#else + /* save above and below in ustack */ + memcpy(&pdump->ustack, (void *)(pdump->context.stack.current_sp-sizeof(pdump->ustack)/2), + sizeof(pdump->ustack)/2); +#endif + } + + stm32_bbsram_savepanic(HARDFAULT_FILENO, (uint8_t*)pdump, sizeof(fullcontext_s)); + + +#if defined(CONFIG_BOARD_RESET_ON_CRASH) + systemreset(false); +#endif +} diff --git a/src/modules/systemlib/hardfault_log.h b/src/modules/systemlib/hardfault_log.h new file mode 100644 index 000000000..2161103a1 --- /dev/null +++ b/src/modules/systemlib/hardfault_log.h @@ -0,0 +1,383 @@ +/**************************************************************************** + * + * Copyright (C) 2015 PX4 Development Team. All rights reserved. + * Author: @author David Sidrane + * + * 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. + * + ****************************************************************************/ +#pragma once +/**************************************************************************** + * Included Files + ****************************************************************************/ +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +#define FREEZE_STR(s) #s +#define STRINGIFY(s) FREEZE_STR(s) +#define HARDFAULT_FILENO 3 +#define HARDFAULT_PATH BBSRAM_PATH""STRINGIFY(HARDFAULT_FILENO) +#define HARDFAULT_REBOOT_FILENO 0 +#define HARDFAULT_REBOOT_PATH BBSRAM_PATH""STRINGIFY(HARDFAULT_REBOOT_FILENO) + + +#define BBSRAM_SIZE_FN0 (sizeof(int)) +#define BBSRAM_SIZE_FN1 384 /* greater then 2.5 times the size of vehicle_status_s */ +#define BBSRAM_SIZE_FN2 384 /* greater then 2.5 times the size of vehicle_status_s */ +#define BBSRAM_SIZE_FN3 -1 + +/* The following guides in the amount of the user and interrupt stack + * data we can save. The amount of storage left will dictate the actual + * number of entries of the user stack data saved. If it is too big + * It will be truncated by the call to stm32_bbsram_savepanic + */ +#define BBSRAM_HEADER_SIZE 20 /* This is an assumption */ +#define BBSRAM_USED ((4*BBSRAM_HEADER_SIZE)+(BBSRAM_SIZE_FN0+BBSRAM_SIZE_FN1+BBSRAM_SIZE_FN2)) +#define BBSRAM_REAMINING (STM32_BBSRAM_SIZE-BBSRAM_USED) +#if CONFIG_ARCH_INTERRUPTSTACK <= 3 +# define BBSRAM_NUMBER_STACKS 1 +#else +# define BBSRAM_NUMBER_STACKS 2 +#endif +#define BBSRAM_FIXED_ELEMENTS_SIZE (sizeof(context_s)+sizeof(info_s)) +#define BBSRAM_LEFTOVER (BBSRAM_REAMINING-BBSRAM_FIXED_ELEMENTS_SIZE) + +#define CONFIG_ISTACK_SIZE (BBSRAM_LEFTOVER/BBSRAM_NUMBER_STACKS/sizeof(stack_word_t)) +#define CONFIG_USTACK_SIZE (BBSRAM_LEFTOVER/BBSRAM_NUMBER_STACKS/sizeof(stack_word_t)) + +/* The path to the Battery Backed up SRAM */ +#define BBSRAM_PATH "/fs/bbr" +/* The sizes of the files to create (-1) use rest of BBSRAM memory */ +#define BSRAM_FILE_SIZES { \ + BBSRAM_SIZE_FN0, /* For Time stamp only */ \ + BBSRAM_SIZE_FN1, /* For Current Flight Parameters Copy A */ \ + BBSRAM_SIZE_FN2, /* For Current Flight Parameters Copy B*/ \ + BBSRAM_SIZE_FN3, /* For the Panic Log use rest of space */ \ + 0 /* End of table marker */ \ +} + +/* For Assert keep this much of the file name*/ +#define MAX_FILE_PATH_LENGTH 40 + + +/* Fixed size strings + * To change a format add the number of chars not represented by the format + * Specifier to the xxxx_NUM definei.e %Y is YYYY so add 2 and %s is -2 + * Also xxxxTIME_FMT need to match in size. See CCASERT in hardfault_log.c + */ +#define LOG_PATH_BASE "/fs/microsd/" +#define LOG_PATH_BASE_LEN ((arraySize(LOG_PATH_BASE))-1) + +#define LOG_NAME_FMT "fault_%s.log" +#define LOG_NAME_NUM ( -2 ) +#define LOG_NAME_LEN ((arraySize(LOG_NAME_FMT)-1) + LOG_NAME_NUM) + +#define TIME_FMT "%Y_%m_%d_%H_%M_%S" +#define TIME_FMT_NUM (2+ 0+ 0+ 0+ 0+ 0) +#define TIME_FMT_LEN (((arraySize(TIME_FMT)-1) + TIME_FMT_NUM)) + +#define LOG_PATH_LEN ((LOG_PATH_BASE_LEN + LOG_NAME_LEN + TIME_FMT_LEN)) + +#define HEADER_TIME_FMT "%Y-%m-%d-%H:%M:%S" +#define HEADER_TIME_FMT_NUM (2+ 0+ 0+ 0+ 0+ 0) +#define HEADER_TIME_FMT_LEN (((arraySize(HEADER_TIME_FMT)-1) + HEADER_TIME_FMT_NUM)) + +/* Select which format to use. On a terminal the details are at the bottom + * and in a file they are at the top + */ +#define HARDFAULT_DISPLAY_FORMAT 1 +#define HARDFAULT_FILE_FORMAT 0 + +/**************************************************************************** + * Public Types + ****************************************************************************/ +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/* Used for stack frame storage */ +typedef uint32_t stack_word_t; + +typedef struct { + int pid; /* Process ID */ + struct xcptcontext xcp; /* Interrupt register save area */ +#if CONFIG_TASK_NAME_SIZE > 0 + char name[CONFIG_TASK_NAME_SIZE+1]; /* Task name (with NULL terminator) */ +#endif +} process_t; + +/* Stack related data */ +typedef struct { + uint32_t current_sp; /* The stack the up_assert is running on + * it may be either the user stack for an assertion + * failure or the interrupt stack in the case of a + * hard fault + */ + uint32_t utopofstack; /* Top of the user stack at the time of the + * up_assert + */ + uint32_t ustacksize; /* Size of the user stack at the time of the + * up_assert + */ + +#if CONFIG_ARCH_INTERRUPTSTACK > 3 + + uint32_t itopofstack; /* Top of the interrupt stack at the time of the + * up_assert + */ + uint32_t istacksize; /* Size of the interrupt stack at the time of the + * up_assert + */ +#endif + +} stack_t; + +/* Not Used for reference only */ + +typedef struct +{ + uint32_t r0; + uint32_t r1; + uint32_t r2; + uint32_t r3; + uint32_t r4; + uint32_t r5; + uint32_t r6; + uint32_t r7; + uint32_t r8; + uint32_t r9; + uint32_t r10; + uint32_t r11; + uint32_t r12; + uint32_t sp; + uint32_t lr; + uint32_t pc; + uint32_t xpsr; + uint32_t d0; + uint32_t d1; + uint32_t d2; + uint32_t d3; + uint32_t d4; + uint32_t d5; + uint32_t d6; + uint32_t d7; + uint32_t d8; + uint32_t d9; + uint32_t d10; + uint32_t d11; + uint32_t d12; + uint32_t d13; + uint32_t d14; + uint32_t d15; + uint32_t fpscr; + uint32_t sp_main; + uint32_t sp_process; + uint32_t apsr; + uint32_t ipsr; + uint32_t epsr; + uint32_t primask; + uint32_t basepri; + uint32_t faultmask; + uint32_t control; + uint32_t s0; + uint32_t s1; + uint32_t s2; + uint32_t s3; + uint32_t s4; + uint32_t s5; + uint32_t s6; + uint32_t s7; + uint32_t s8; + uint32_t s9; + uint32_t s10; + uint32_t s11; + uint32_t s12; + uint32_t s13; + uint32_t s14; + uint32_t s15; + uint32_t s16; + uint32_t s17; + uint32_t s18; + uint32_t s19; + uint32_t s20; + uint32_t s21; + uint32_t s22; + uint32_t s23; + uint32_t s24; + uint32_t s25; + uint32_t s26; + uint32_t s27; + uint32_t s28; + uint32_t s29; + uint32_t s30; + uint32_t s31; +} proc_regs_s; + + +/* Flags to identify what is in the dump */ +typedef enum { + eRegs = 0x01, + eUserStack = 0x02, + eIntStack = 0x04, + eStackUnknown = 0x08, + eStackValid = eUserStack | eIntStack, +} stuff_t; + +typedef struct { + stuff_t stuff; /* What is in the dump */ + uintptr_t current_regs; /* Used to validate the dump */ + int lineno; /* __LINE__ to up_assert */ + char filename[MAX_FILE_PATH_LENGTH]; /* Last MAX_FILE_PATH_LENGTH of chars in + * __FILE__ to up_assert + */ +} info_s; + +typedef struct { /* The Context data */ + stack_t stack; + process_t proc; +} context_s; + +typedef struct { + info_s info; /* Then info */ + context_s context; /* The Context data */ +#if CONFIG_ARCH_INTERRUPTSTACK > 3 /* The amount of stack data is compile time + * sized backed on what is left after the + * other BBSRAM files are defined + * The order is such that only the + * ustack should be truncated + */ + stack_word_t istack[CONFIG_USTACK_SIZE]; +#endif + stack_word_t ustack[CONFIG_ISTACK_SIZE]; +} fullcontext_s; + +/**************************************************************************** + * Name: hardfault_check_status + * + * Description: + * Check the status of the BBSRAM hard fault file which can be in + * one of two states Armed, Valid or Broken. + * + * Armed - The file in the armed state is not accessible in the fs + * the act of unlinking it is what arms it. + * + * Valid - The file in the armed state is not accessible in the fs + * the act of unlinking it is what arms it. + * + * Inputs: + * - caller: A label to display in syslog output + * + * Returned Value: + * -ENOENT Armed - The file in the armed state + * OK Valid - The file contains data from a fault that has not + * been committed to disk (see write_hardfault). + * - Any < 0 Broken - Should not happen + * + ****************************************************************************/ +int hardfault_check_status(char *caller); + +/**************************************************************************** + * Name: hardfault_write + * + * Description: + * Will parse and write a human readable output of the data + * in the BBSRAM file. Once + * + * + * Inputs: + * - caller: A label to display in syslog output + * - fd: An FD to write the data to + * - format: Select which format to use. + * + * HARDFAULT_DISPLAY_FORMAT On the console the details are + * at the bottom + * HARDFAULT_FILE_FORMAT In a file details are at the top + * of the log file + * + * - rearm: If true will move the file to the Armed state, if + * false the file is not armed and can be read again + * + * Returned Value: + * + * OK or errno + * + * + ****************************************************************************/ +int hardfault_write(char *caller, int fd, int format, bool rearm); + +/**************************************************************************** + * Name: hardfault_rearm + * + * Description: + * Will move the file to the Armed state + * + * + * Inputs: + * - caller: A label to display in syslog output + * + * Returned Value: + * + * OK or errno + * + * + ****************************************************************************/ +int hardfault_rearm(char *caller); + +/**************************************************************************** + * Name: hardfault_increment_reboot + * + * Description: + * Will increment the reboot counter. The reboot counter will help + * detect reboot loops. + * + * + * Inputs: + * - caller: A label to display in syslog output + * - reset : when set will reset the reboot counter to 0. + * + * Returned Value: + * + * The current value of the reboot counter (post increment). + * + * + ****************************************************************************/ +int hardfault_increment_reboot(char *caller, bool reset); + +#if defined(__cplusplus) +extern "C" +} +#endif + diff --git a/src/systemcmds/hardfault_log/hardfault_log.c b/src/systemcmds/hardfault_log/hardfault_log.c new file mode 100644 index 000000000..e8f37335b --- /dev/null +++ b/src/systemcmds/hardfault_log/hardfault_log.c @@ -0,0 +1,718 @@ +/**************************************************************************** + * + * Copyright (C) 2015 PX4 Development Team. All rights reserved. + * Author: @author David Sidrane + * + * 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 +#include + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ +__EXPORT int hardfault_log_main(int argc, char *argv[]); + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ +static int genfault(int fault); +/**************************************************************************** + * Private Data + ****************************************************************************/ +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ +/**************************************************************************** + * genfault + ****************************************************************************/ + +static int genfault(int fault) +{ + + /* Pointer to System Control Block's System Control Register */ + + uint32_t *pCCR = (uint32_t *)0xE000ED14; + + static volatile int k = 0; + + switch(fault) + { + case 0: + + /* Enable divide by 0 fault generation */ + + *pCCR |= 0x10; + + k = 1 / fault; + + /* This is not going to happen + * Enable divide by 0 fault generation + */ + + *pCCR &= ~0x10; + break; + + case 1: + ASSERT( fault== 0); + /* This is not going to happen */ + break; + + case 2: + printf("null %s\n",NULL); + /* This is not going to happen */ + break; + + case 3: + { + char marker[20]; + strncpy(marker, "<-- ", sizeof(marker)); + printf("nill %s\n",""); + printf("nill fault==3 %s\n",(fault==3) ? "3" : ""); + printf("nill fault!=3 %s\n",(fault!=3) ? "3" : ""); + printf("0x%08x 0x%08x%s\n", fault, -fault, (fault==3) ? "" : marker); + printf("0x%08x 0x%08x%s\n", fault, -fault, (fault!=3) ? "" : marker); + printf("0x%08x 0x%08x%s\n", fault, -fault, fault==3 ? "" : marker); + printf("0x%08x 0x%08x%s\n", fault, -fault, fault!=3 ? "" : marker); + } + /* This is not going to happen */ + break; + + default: + break; + + } + UNUSED(k); + return OK; +} + + +/**************************************************************************** + * format_fault_time + ****************************************************************************/ +/* Ensure Size is the same foe formats or rewrite this */ +CCASSERT(TIME_FMT_LEN==HEADER_TIME_FMT_LEN); +static int format_fault_time(char *format, struct timespec *ts, char *buffer, unsigned int maxsz) +{ + int ret = -EINVAL; + if (buffer != NULL && format != NULL) { + ret = -ENOMEM; + if (maxsz >= TIME_FMT_LEN + 1 ) { + struct tm tt; + time_t time_sec = ts->tv_sec + (ts->tv_nsec / 1e9); + gmtime_r(&time_sec, &tt); + if (TIME_FMT_LEN == strftime(buffer, maxsz, format , &tt)) { + ret = OK; + } + } + } + return ret; +} + +/**************************************************************************** + * format_fault_file_name + ****************************************************************************/ + +static int format_fault_file_name(struct timespec *ts, char *buffer, unsigned int maxsz) +{ + char fmtbuff[ TIME_FMT_LEN + 1]; + int ret = -EINVAL; + + if (buffer) { + + ret = -ENOMEM; + unsigned int plen = LOG_PATH_BASE_LEN; + if (maxsz >= LOG_PATH_LEN) { + strncpy(buffer, LOG_PATH_BASE, plen); + maxsz -= plen; + int rv = format_fault_time(TIME_FMT,ts, fmtbuff, arraySize(fmtbuff)); + if (rv == OK) { + int n = snprintf(&buffer[plen], maxsz , LOG_NAME_FMT, fmtbuff); + if (n == (int) LOG_NAME_LEN + TIME_FMT_LEN) { + ret = OK; + } + } + } + } + return ret; +} + +/**************************************************************************** + * identify + ****************************************************************************/ +static void identify(char *caller) +{ + if (caller) { + syslog(LOG_INFO, "[%s] ", caller); + } +} + + +/**************************************************************************** + * hardfault_get_desc + ****************************************************************************/ +static int hardfault_get_desc(char *caller, struct bbsramd_s *desc, bool silent) +{ + int ret = -ENOENT; + int fd = open(HARDFAULT_PATH, O_RDONLY); + if (fd < 0 ) { + if (!silent) { + identify(caller); + syslog(LOG_INFO, "Failed to open Fault Log file [%s] (%d)\n", HARDFAULT_PATH, fd); + } + } else { + ret = -EIO; + int rv = ioctl(fd, STM32_BBSRAM_GETDESC_IOCTL, (unsigned long)((uintptr_t)desc)); + if (rv >= 0) { + ret = fd; + } else { + identify(caller); + syslog(LOG_INFO, "Failed to get Fault Log descriptor (%d)\n",rv); + } + } + return ret; +} + +/**************************************************************************** + * write_stack_detail + ****************************************************************************/ +static void write_stack_detail(int size, uint32_t topaddr, uint32_t spaddr, + uint32_t botaddr, char *sp_name, char *buffer, int max, int fd) +{ + + int n = 0; + n = snprintf(&buffer[n], max-n, " %s stack:\n",sp_name); + n += snprintf(&buffer[n], max-n, " top: 0x%08x\n", topaddr); + n += snprintf(&buffer[n], max-n, " sp: 0x%08x\n", spaddr); + write(fd, buffer,n); + n = 0; + n += snprintf(&buffer[n], max-n, " bottom: 0x%08x\n", botaddr); + n += snprintf(&buffer[n], max-n, " size: 0x%08x\n", size); + write(fd, buffer,n); +#ifndef CONFIG_STACK_COLORATION + FAR struct tcb_s tcb; + tcb.stack_alloc_ptr = (void*) botaddr; + tcb.adj_stack_size = size; + n = snprintf(buffer, max, " used: %08x\n", up_check_tcbstack(&tcb)); + write(fd, buffer,n); +#endif +} + +/**************************************************************************** + * write_stack + ****************************************************************************/ +static void write_stack(stack_word_t *swindow, int winsize, uint32_t wtopaddr, + uint32_t topaddr, uint32_t spaddr, uint32_t botaddr, + char *sp_name, char *buffer, int max, int fd) +{ + char marker[30]; + for (int i = winsize; i >= 0; i--) { + if (wtopaddr == topaddr) { + strncpy(marker, "<-- ", sizeof(marker)); + strncat(marker, sp_name, sizeof(marker)); + strncat(marker, " top", sizeof(marker)); + } else if (wtopaddr == spaddr) { + strncpy(marker, "<-- ", sizeof(marker)); + strncat(marker, sp_name, sizeof(marker)); + } else if (wtopaddr == botaddr) { + strncpy(marker, "<-- ", sizeof(marker)); + strncat(marker, sp_name, sizeof(marker)); + strncat(marker, " bottom", sizeof(marker)); + } else { + marker[0] = '\0'; + } + int n = snprintf(buffer, max,"0x%08x 0x%08x%s\n", wtopaddr, swindow[i], marker); + write(fd, buffer,n); + wtopaddr--; + } +} + +/**************************************************************************** + * write_registers + ****************************************************************************/ +static void write_registers(fullcontext_s* fc, char *buffer, int max, int fd) +{ + int n = snprintf(buffer, max, " r0:0x%08x r1:0x%08x r2:0x%08x r3:0x%08x r4:0x%08x r5:0x%08x r6:0x%08x r7:0x%08x\n", + fc->context.proc.xcp.regs[REG_R0], fc->context.proc.xcp.regs[REG_R1], + fc->context.proc.xcp.regs[REG_R2], fc->context.proc.xcp.regs[REG_R3], + fc->context.proc.xcp.regs[REG_R4], fc->context.proc.xcp.regs[REG_R5], + fc->context.proc.xcp.regs[REG_R6], fc->context.proc.xcp.regs[REG_R7]); + + write(fd, buffer,n); + n = snprintf(buffer, max, " r8:0x%08x r9:0x%08x r10:0x%08x r11:0x%08x r12:0x%08x sp:0x%08x lr:0x%08x pc:0x%08x\n", + fc->context.proc.xcp.regs[REG_R8], fc->context.proc.xcp.regs[REG_R9], + fc->context.proc.xcp.regs[REG_R10], fc->context.proc.xcp.regs[REG_R11], + fc->context.proc.xcp.regs[REG_R12], fc->context.proc.xcp.regs[REG_R13], + fc->context.proc.xcp.regs[REG_R14], fc->context.proc.xcp.regs[REG_R15]); + + write(fd, buffer,n); + +#ifdef CONFIG_ARMV7M_USEBASEPRI + n = snprintf(buffer, max, " xpsr:0x%08x basepri:0x%08x control:0x%08x\n", + fc->context.proc.xcp.regs[REG_XPSR], fc->context.proc.xcp.regs[REG_BASEPRI], + getcontrol()); +#else + n = snprintf(buffer, max, " xpsr:0x%08x primask:0x%08x control:0x%08x\n", + fc->context.proc.xcp.regs[REG_XPSR], fc->context.proc.xcp.regs[REG_PRIMASK], + getcontrol()); +#endif + write(fd, buffer,n); + +#ifdef REG_EXC_RETURN + n = snprintf(buffer, max, " exe return:0x%08x\n", fc->context.proc.xcp.regs[REG_EXC_RETURN]); + write(fd, buffer,n); +#endif +} + +/**************************************************************************** + * write_registers_info + ****************************************************************************/ +static int write_registers_info(int fdout, fullcontext_s *fc, char *buffer, + int sz) +{ + int ret = -ENOENT; + if (fc->info.stuff & eRegs) { + int n = snprintf(buffer, sz, " Processor registers: from 0x%08x\n", fc->info.current_regs); + write(fdout, buffer,n); + write_registers(fc, buffer, sz, fdout); + ret = OK; + } + return ret; +} + +/**************************************************************************** + * write_interrupt_stack_info + ****************************************************************************/ +static int write_interrupt_stack_info(int fdout, fullcontext_s *fc, char *buffer, + unsigned int sz) +{ + int ret = -ENOENT; + if (fc->info.stuff & eIntStack) { + write_stack_detail(fc->context.stack.istacksize, + fc->context.stack.itopofstack, + fc->context.stack.current_sp, + fc->context.stack.itopofstack - fc->context.stack.istacksize, + "IRQ", + buffer, sz, fdout); + ret = OK; + } + return ret; +} + +/**************************************************************************** + * write_user_stack_info + ****************************************************************************/ +static int write_user_stack_info(int fdout, fullcontext_s *fc, char *buffer, + unsigned int sz) +{ + int ret = -ENOENT; + if (fc->info.stuff & eUserStack) { + write_stack_detail(fc->context.stack.ustacksize, + fc->context.stack.utopofstack, + fc->context.proc.xcp.regs[REG_R13], + fc->context.stack.utopofstack - fc->context.stack.ustacksize, + "User", + buffer, sz, fdout); + ret = OK; + } + return ret; +} + +/**************************************************************************** + * write_dump_info + ****************************************************************************/ +static void write_dump_info(int fdout, fullcontext_s *fc, struct timespec *ts, + char *buffer, unsigned int sz) +{ + char fmtbuff[ TIME_FMT_LEN + 1]; + format_fault_time(HEADER_TIME_FMT, ts, fmtbuff, sizeof(fmtbuff)); + + bool isFault = (fc->info.current_regs != 0 || fc->context.proc.pid == 0); + int n; + n = snprintf(buffer, sz, "System fault Occurred on: %s\n", fmtbuff); + write(fdout, buffer, n); + if (isFault) { + n = snprintf(buffer, sz, " Type:Hard Fault"); + } else { + n = snprintf(buffer, sz, " Type:Assertion failed"); + } + write(fdout, buffer, n); + +#ifdef CONFIG_TASK_NAME_SIZE + n = snprintf(buffer, sz, " in file:%s at line: %d running task: %s\n", + fc->info.filename, fc->info.lineno, fc->context.proc.name); +#else + n = snprintf(buffer, sz, " in file:%s at line: %d \n", + fc->info.filename, fc->info.lineno); +#endif + write(fdout, buffer, n); + n = snprintf(buffer, sz, " FW git-hash: %s\n", FW_GIT); + write(fdout, buffer, n); + n = snprintf(buffer, sz, " Build datetime: %s %s\n", __DATE__, __TIME__); + write(fdout, buffer, n); + +} + +/**************************************************************************** + * write_dump_time + ****************************************************************************/ +static void write_dump_time(char *caller, char *tag, int fdout, + struct timespec *ts, char *buffer, unsigned int sz) +{ + char fmtbuff[ TIME_FMT_LEN + 1]; + format_fault_time(HEADER_TIME_FMT, ts, fmtbuff, sizeof(fmtbuff)); + int n = snprintf(buffer, sz, "[%s] -- %s %s Fault Log --\n",caller, fmtbuff, tag); + write(fdout, buffer, n); +} +/**************************************************************************** + * write_dump_footer + ****************************************************************************/ +static void write_dump_header(char * caller, int fdout, struct timespec *ts, + char *buffer, unsigned int sz) +{ + write_dump_time(caller, "Begin", fdout, ts, buffer, sz); +} +/**************************************************************************** + * write_dump_footer + ****************************************************************************/ +static void write_dump_footer(char * caller, int fdout, struct timespec *ts, + char *buffer, unsigned int sz) +{ + write_dump_time(caller, "END", fdout, ts, buffer, sz); +} +/**************************************************************************** + * write_intterupt_satck + ****************************************************************************/ +static int write_intterupt_stack(int fdout, fullcontext_s *fc, char *buffer, + unsigned int sz) +{ + int ret = -ENOENT; + if ((fc->info.stuff & eIntStack) != 0) { + int winsize = arraySize(fc->istack); + int wtopaddr = fc->context.stack.current_sp + winsize/2; + write_stack(fc->istack, winsize, wtopaddr, + fc->context.stack.itopofstack, + fc->context.stack.current_sp, + fc->context.stack.itopofstack - fc->context.stack.istacksize, + "Interrupt sp", buffer, sz, fdout); + ret = OK; + } + + return ret; +} + + +/**************************************************************************** + * write_user_stack + ****************************************************************************/ +static int write_user_stack(int fdout, fullcontext_s *fc, char *buffer, + unsigned int sz) +{ + int ret = -ENOENT; + if ((fc->info.stuff & eUserStack) != 0) { + int winsize = arraySize(fc->ustack); + int wtopaddr = fc->context.proc.xcp.regs[REG_R13] + winsize/2; + write_stack(fc->ustack, winsize, wtopaddr, + fc->context.stack.utopofstack, + fc->context.proc.xcp.regs[REG_R13], + fc->context.stack.utopofstack - fc->context.stack.ustacksize, + "User sp", buffer, sz, fdout); + ret = OK; + } + + return ret; +} + +/**************************************************************************** + * commit + ****************************************************************************/ +static int hardfault_commit(char *caller) +{ + int ret = -ENOENT; + int state = -1; + struct bbsramd_s desc; + char path[LOG_PATH_LEN+1]; + ret = hardfault_get_desc(caller, &desc, false); + if (ret >= 0) { + int fd = ret; + state = (desc.lastwrite.tv_sec || desc.lastwrite.tv_nsec) ? OK : 1; + int rv = close(fd); + if (rv < 0) { + identify(caller); + syslog(LOG_INFO, "Failed to Close Fault Log (%d)\n",rv); + } else { + if (state != OK) { + identify(caller); + syslog(LOG_INFO, "Nothing to save\n",path); + ret = -ENOENT; + } else { + ret = format_fault_file_name(&desc.lastwrite, path, arraySize(path)); + if (ret == OK) { + int fdout = open(path, O_RDWR | O_CREAT); + if (fdout > 0) { + identify(caller); + syslog(LOG_INFO, "Saving Fault Log file %s\n",path); + ret = hardfault_write(caller, fdout, HARDFAULT_FILE_FORMAT, true); + identify(caller); + syslog(LOG_INFO, "Done saving Fault Log file\n"); + close(fdout); + } + + } + } + } + } + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ +/**************************************************************************** + * hardfault_rearm + ****************************************************************************/ +__EXPORT int hardfault_rearm(char *caller) +{ + int ret = OK; + int rv = unlink(HARDFAULT_PATH); + if (rv < 0) { + identify(caller); + syslog(LOG_INFO, "Failed to re arming Fault Log (%d)\n",rv); + ret = -EIO; + } else { + identify(caller); + syslog(LOG_INFO, "Fault Log is Armed\n"); + } + return ret; +} + +/**************************************************************************** + * hardfault_check_status + ****************************************************************************/ +__EXPORT int hardfault_check_status(char *caller) +{ + int state = -1; + struct bbsramd_s desc; + int ret = hardfault_get_desc(caller, &desc, true); + if (ret < 0) { + identify(caller); + if (ret == -ENOENT) { + syslog(LOG_INFO, "Fault Log is Armed\n"); + } else { + syslog(LOG_INFO, "Failed to open Fault Log file [%s] (%d)\n", HARDFAULT_PATH, ret); + } + } else { + int fd = ret; + state = (desc.lastwrite.tv_sec || desc.lastwrite.tv_nsec) ? OK : 1; + int rv = close(fd); + if (rv < 0) { + identify(caller); + syslog(LOG_INFO, "Failed to Close Fault Log (%d)\n",rv); + } else { + ret = state; + identify(caller); + syslog(LOG_INFO, "Fault Log info File No %d Length %d flags:0x%02x state:%d\n", + (unsigned int)desc.fileno, (unsigned int) desc.len, (unsigned int)desc.flags, state); + if (state == OK) { + char buf[TIME_FMT_LEN + 1]; + format_fault_time(HEADER_TIME_FMT, &desc.lastwrite, buf, arraySize(buf)); + identify(caller); + syslog(LOG_INFO, "Fault Logged on %s - Valid\n",buf); + } else { + rv = hardfault_rearm(caller); + if (rv < 0) { + ret = rv; + } + } + } + } + return ret; +} + +/**************************************************************************** + * hardfault_increment_reboot + ****************************************************************************/ +__EXPORT int hardfault_increment_reboot(char *caller, bool reset) +{ + int ret = -EIO; + int count = 0; + int fd = open(HARDFAULT_REBOOT_PATH, O_RDWR | O_CREAT); + if (fd < 0) { + identify(caller); + syslog(LOG_INFO, "Failed to open Fault reboot count file [%s] (%d)\n", HARDFAULT_REBOOT_PATH, ret); + } else { + if (!reset) { + read(fd, &count, sizeof(count)); + lseek(fd, 0, SEEK_SET); + count++; + } + ret = write(fd, &count, sizeof(count)); + close(fd); + ret = count; + } + return ret; +} +/**************************************************************************** + * hardfault_write + ****************************************************************************/ +fullcontext_s dump; + +__EXPORT int hardfault_write(char *caller, int fd, int format, bool rearm) +{ + char line[200]; + memset(&dump,0,sizeof(dump)); + struct bbsramd_s desc; + int ret = hardfault_get_desc(caller, &desc, false); + if (ret >= 0) { + int hffd = ret; + ret = read(hffd, (char *)&dump, sizeof(dump)); + if (ret < 0) { + identify(caller); + syslog(LOG_INFO, "Failed to read Fault Log file [%s] (%d)\n", HARDFAULT_PATH, ret); + } else { + ret = close(hffd); + if (ret < 0) { + identify(caller); + syslog(LOG_INFO, "Failed to Close Fault Log (%d)\n", ret); + + } else { + + switch(format) { + case HARDFAULT_DISPLAY_FORMAT: + write_dump_header(caller, fd, &desc.lastwrite,line, arraySize(line)); + write_intterupt_stack(fd, &dump, line, arraySize(line)); + write_user_stack(fd, &dump, line, arraySize(line)); + write_dump_info(fd, &dump, &desc.lastwrite, line, arraySize(line)); + write_registers_info(fd, &dump, line, arraySize(line)); + write_interrupt_stack_info(fd, &dump, line, arraySize(line)); + write_user_stack_info(fd, &dump, line, arraySize(line)); + break; + + case HARDFAULT_FILE_FORMAT: + write_dump_header(caller, fd, &desc.lastwrite,line, arraySize(line)); + write_dump_info(fd, &dump, &desc.lastwrite, line, arraySize(line)); + write_registers_info(fd, &dump, line, arraySize(line)); + write_interrupt_stack_info(fd, &dump, line, arraySize(line)); + write_user_stack_info(fd, &dump,line, arraySize(line)); + write_intterupt_stack(fd, &dump,line, arraySize(line)); + write_user_stack(fd, &dump, line, arraySize(line)); + break; + + default: + return -EINVAL; + break; + } + + write_dump_footer(caller, fd, &desc.lastwrite,line, arraySize(line)); + + if (rearm) { + ret = hardfault_rearm(caller); + + } + } + } + } + return ret; +} + +/**************************************************************************** + * Name: hardfault_log_main + ****************************************************************************/ +__EXPORT int hardfault_log_main(int argc, char *argv[]) +{ + char *self = "hardfault_log"; + + if (!strcmp(argv[1], "check")) { + + return hardfault_check_status(self); + + } else if (!strcmp(argv[1], "rearm")) { + + return hardfault_rearm(self); + + } else if (!strcmp(argv[1], "fault")) { + + int fault = 0; + if (argc > 2) { + fault = atol(argv[2]); + } + return genfault(fault); + + } else if (!strcmp(argv[1], "commit")) { + + return hardfault_commit(self); + + } else if (!strcmp(argv[1], "count")) { + + return hardfault_increment_reboot(self,false); + + } else if (!strcmp(argv[1], "reset")) { + + return hardfault_increment_reboot(self,true); + + } + + fprintf(stderr, "unrecognised command, try 'check' ,'rearm' , 'fault', 'count', 'reset' or 'commit'\n"); + return -EINVAL; +} diff --git a/src/systemcmds/hardfault_log/module.mk b/src/systemcmds/hardfault_log/module.mk new file mode 100644 index 000000000..8a6016c33 --- /dev/null +++ b/src/systemcmds/hardfault_log/module.mk @@ -0,0 +1,43 @@ +############################################################################ +# +# Copyright (c) 2012, 2015 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. +# +############################################################################ + +# +# reboot command. +# + +MODULE_COMMAND = hardfault_log +SRCS = hardfault_log.c + +MAXOPTIMIZATION = -Os + +MODULE_STACKSIZE = 1024 -- cgit v1.2.3