aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorDavid Sidrane <david_s5@nscdg.com>2015-03-03 16:30:51 -1000
committerDavid Sidrane <david_s5@nscdg.com>2015-03-05 08:33:56 -1000
commita702c6cf025036c906313f496c2b2495d6a8845b (patch)
treed6a9f264494385ebb4447573cede06b49b796b98 /src/modules
parent5549ee2097d1dc2f9377a0569a38a1f0fecef20b (diff)
downloadpx4-firmware-a702c6cf025036c906313f496c2b2495d6a8845b.tar.gz
px4-firmware-a702c6cf025036c906313f496c2b2495d6a8845b.tar.bz2
px4-firmware-a702c6cf025036c906313f496c2b2495d6a8845b.zip
Hard Fault Logging - one issue remians reduse memory foot print
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/systemlib/hardfault_log.h383
1 files changed, 383 insertions, 0 deletions
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 <david_s5@nscdg.com>
+ *
+ * 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 <systemlib/px4_macros.h>
+#include <stm32_bbsram.h>
+
+/****************************************************************************
+ * 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
+