diff --git a/CMakeLists.txt b/CMakeLists.txt index 7e981274b4..635a0ca10a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -161,6 +161,16 @@ set(target_name "${OS}-${BOARD}-${LABEL}") message(STATUS "${target_name}") +# The Url for the elf file for crash logging + +if (DEFINED ENV{BUILD_URI}) + set (BUILD_URI $ENV{BUILD_URI}) +else() + set (BUILD_URI "localhost") +endif() + +add_definitions(-DBUILD_URI=${BUILD_URI}) + # Define GNU standard installation directories include(GNUInstallDirs) @@ -243,7 +253,7 @@ if (CATKIN_DEVEL_PREFIX) message(FATAL_ERROR "catkin not found") endif() else() - message(STATUS "catkin DISABLED") + #message(STATUS "catkin DISABLED") endif() find_package(PythonInterp REQUIRED) @@ -337,6 +347,7 @@ add_definitions(${definitions}) #============================================================================= # source code generation # + add_subdirectory(msg) px4_generate_messages(TARGET msg_gen MSG_FILES ${msg_files} @@ -413,7 +424,7 @@ set(module_external_libraries "${module_external_libraries}" CACHE INTERNAL "mod add_subdirectory(src/firmware/${OS}) -#add_dependencies(df_driver_framework nuttx_export_${CONFIG}.stamp) +#add_dependencies(df_driver_framework nuttx_export_${CONFIG}) if (NOT "${OS}" STREQUAL "nuttx") endif() diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 0ce78312d7..a3fa9d5ba2 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -24,6 +24,11 @@ # UART7 /dev/ttyS5 ? # UART8 /dev/ttyS6 CONSOLE +# +# Mount the procfs. +# +mount -t procfs /proc + # # Start CDC/ACM serial driver # @@ -43,8 +48,19 @@ set LOG_FILE /fs/microsd/bootlog.txt # REBOOTWORK this needs to start after the flight control loop if mount -t vfat /dev/mmcsd0 /fs/microsd then - # Start playing the startup tune - tone_alarm start + echo "[i] microSD mounted: /fs/microsd" + 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 tone_alarm MBAGP if mkfatfs /dev/mmcsd0 @@ -294,7 +310,7 @@ then if px4io forceupdate 14662 ${IO_FILE} then - usleep 500000 + usleep 10000 if px4io checkcrc $IO_FILE then echo "PX4IO CRC OK after updating" >> $LOG_FILE diff --git a/src/lib/version/version.h b/src/lib/version/version.h index ae2acbd4eb..e4a0c839a8 100644 --- a/src/lib/version/version.h +++ b/src/lib/version/version.h @@ -53,6 +53,11 @@ __EXPORT const char *board_name(void); __END_DECLS +#define FREEZE_STR(s) #s +#define STRINGIFY(s) FREEZE_STR(s) +#define FW_GIT STRINGIFY(GIT_VERSION) +#define FW_BUILD_URI STRINGIFY(BUILD_URI) + #if defined(CONFIG_ARCH_BOARD_SITL) # define HW_ARCH "SITL" #elif defined(CONFIG_ARCH_BOARD_EAGLE) diff --git a/src/modules/systemlib/hardfault_log.h b/src/modules/systemlib/hardfault_log.h new file mode 100644 index 0000000000..334db78656 --- /dev/null +++ b/src/modules/systemlib/hardfault_log.h @@ -0,0 +1,355 @@ +/**************************************************************************** + * + * 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 (PX4_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(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 + ****************************************************************************/ + +/* Used for stack frame storage */ +typedef uint32_t stack_word_t; + +/* Stack related data */ + +typedef struct { + uint32_t sp; + uint32_t top; + uint32_t size; + +} _stack_s; + +typedef struct { + _stack_s user; +#if CONFIG_ARCH_INTERRUPTSTACK > 3 + _stack_s interrupt; +#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 { + eRegsPresent = 0x01, + eUserStackPresent = 0x02, + eIntStackPresent = 0x04, + eInvalidUserStackPtr = 0x20, + eInvalidIntStackPrt = 0x40, +} fault_flags_t; + +typedef struct { + fault_flags_t flags; /* What is in the dump */ + uintptr_t current_regs; /* Used to validate the dump */ + int lineno; /* __LINE__ to up_assert */ + int pid; /* Process ID */ + uint32_t regs[XCPTCONTEXT_REGS]; /* Interrupt register save + * area */ + stack_t stacks; /* Stack info */ +#if CONFIG_TASK_NAME_SIZE > 0 + char name[CONFIG_TASK_NAME_SIZE + 1]; /* Task name (with NULL + * terminator) */ +#endif + char filename[MAX_FILE_PATH_LENGTH]; /* the Last of chars in + * __FILE__ to up_assert */ +} info_s; + +typedef struct { + info_s info; /* The info */ +#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; + +__BEGIN_DECLS +/**************************************************************************** + * 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) weak_function; + +/**************************************************************************** + * 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) weak_function; + +/**************************************************************************** + * 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) weak_function; + +/**************************************************************************** + * 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) weak_function; + +__END_DECLS diff --git a/src/systemcmds/hardfault_log/CMakeLists.txt b/src/systemcmds/hardfault_log/CMakeLists.txt new file mode 100644 index 0000000000..b4b6ebf11c --- /dev/null +++ b/src/systemcmds/hardfault_log/CMakeLists.txt @@ -0,0 +1,43 @@ +############################################################################ +# +# Copyright (c) 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. +# +############################################################################ +px4_add_module( + MODULE systemcmds__hardfault_log + MAIN hardfault_log + STACK_MAIN 1024 + COMPILE_FLAGS + -Os + SRCS + hardfault_log.c + DEPENDS + platforms__common + ) diff --git a/src/systemcmds/hardfault_log/hardfault_log.c b/src/systemcmds/hardfault_log/hardfault_log.c new file mode 100644 index 0000000000..795166f552 --- /dev/null +++ b/src/systemcmds/hardfault_log/hardfault_log.c @@ -0,0 +1,955 @@ +/**************************************************************************** + * + * 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 +#include +#include + + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ +__EXPORT int hardfault_log_main(int argc, char *argv[]); + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +#define OUT_BUFFER_LEN 200 +/**************************************************************************** + * 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; + + 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, PX4_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 int write_stack_detail(bool inValid, _stack_s *si, char *sp_name, + char *buffer, int max, int fd) +{ + + int n = 0; + uint32_t sbot = si->top - si->size; + n = snprintf(&buffer[n], max - n, " %s stack: \n", sp_name); + n += snprintf(&buffer[n], max - n, " top: 0x%08x\n", si->top); + n += snprintf(&buffer[n], max - n, " sp: 0x%08x %s\n", si->sp, (inValid ? "Invalid" : "Valid")); + + if (n != write(fd, buffer, n)) { + return -EIO; + } + + n = 0; + n += snprintf(&buffer[n], max - n, " bottom: 0x%08x\n", sbot); + n += snprintf(&buffer[n], max - n, " size: 0x%08x\n", si->size); + + if (n != write(fd, buffer, n)) { + return -EIO; + } + +#ifdef CONFIG_STACK_COLORATION + FAR struct tcb_s tcb; + tcb.stack_alloc_ptr = (void *) sbot; + tcb.adj_stack_size = si->size; + n = snprintf(buffer, max, " used: %08x\n", up_check_tcbstack(&tcb)); + + if (n != write(fd, buffer, n)) { + return -EIO; + } + +#endif + return OK; +} + +/**************************************************************************** + * write_stack + ****************************************************************************/ +static int read_stack(int fd, stack_word_t *words, int num) +{ + int bytes = read(fd, (char *) words, sizeof(stack_word_t) * num); + + if (bytes > 0) { + bytes /= sizeof(stack_word_t); + } + + return bytes; +} +static int write_stack(bool inValid, int winsize, uint32_t wtopaddr, + uint32_t topaddr, uint32_t spaddr, uint32_t botaddr, + char *sp_name, char *buffer, int max, int infd, int outfd) +{ + char marker[30]; + stack_word_t stack[32]; + int ret = OK; + + int n = snprintf(buffer, max, "%s memory region, stack pointer lies %s stack\n", + sp_name, (inValid ? "outside of" : "within")); + + if (n != write(outfd, buffer, n)) { + + ret = -EIO; + + } else { + + while (winsize > 0 && ret == OK) { + int chunk = read_stack(infd, stack, arraySize(stack)); + + if (chunk <= 0) { + ret = -EIO; + + } else { + winsize -= chunk; + + for (int i = 0; i < chunk; 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'; + } + + n = snprintf(buffer, max, "0x%08x 0x%08x%s\n", wtopaddr, stack[i], marker); + + if (n != write(outfd, buffer, n)) { + ret = -EIO; + } + + wtopaddr--; + } + } + } + } + + return ret; +} + +/**************************************************************************** + * write_registers + ****************************************************************************/ +static int write_registers(uint32_t regs[], 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", + regs[REG_R0], regs[REG_R1], + regs[REG_R2], regs[REG_R3], + regs[REG_R4], regs[REG_R5], + regs[REG_R6], regs[REG_R7]); + + if (n != write(fd, buffer, n)) { + return -EIO; + } + + 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", + regs[REG_R8], regs[REG_R9], + regs[REG_R10], regs[REG_R11], + regs[REG_R12], regs[REG_R13], + regs[REG_R14], regs[REG_R15]); + + if (n != write(fd, buffer, n)) { + return -EIO; + } + +#ifdef CONFIG_ARMV7M_USEBASEPRI + n = snprintf(buffer, max, " xpsr:0x%08x basepri:0x%08x control:0x%08x\n", + regs[REG_XPSR], regs[REG_BASEPRI], + getcontrol()); +#else + n = snprintf(buffer, max, " xpsr:0x%08x primask:0x%08x control:0x%08x\n", + regs[REG_XPSR], regs[REG_PRIMASK], + getcontrol()); +#endif + + if (n != write(fd, buffer, n)) { + return -EIO; + } + +#ifdef REG_EXC_RETURN + n = snprintf(buffer, max, " exe return:0x%08x\n", regs[REG_EXC_RETURN]); + + if (n != write(fd, buffer, n)) { + return -EIO; + } + +#endif + return OK; +} + +/**************************************************************************** + * write_registers_info + ****************************************************************************/ +static int write_registers_info(int fdout, info_s *pi , char *buffer, int sz) +{ + int ret = ENOENT; + + if (pi->flags & eRegsPresent) { + ret = -EIO; + int n = snprintf(buffer, sz, " Processor registers: from 0x%08x\n", pi->current_regs); + + if (n == write(fdout, buffer, n)) { + ret = write_registers(pi->regs, buffer, sz, fdout); + } + } + + return ret; +} + +/**************************************************************************** + * write_interrupt_stack_info + ****************************************************************************/ +static int write_interrupt_stack_info(int fdout, info_s *pi, char *buffer, + unsigned int sz) +{ + int ret = ENOENT; + + if (pi->flags & eIntStackPresent) { + ret = write_stack_detail((pi->flags & eInvalidIntStackPrt) != 0, + &pi->stacks.interrupt, "IRQ", + buffer, sz, fdout); + } + + return ret; +} + +/**************************************************************************** + * write_user_stack_info + ****************************************************************************/ +static int write_user_stack_info(int fdout, info_s *pi, char *buffer, + unsigned int sz) +{ + int ret = ENOENT; + + if (pi->flags & eUserStackPresent) { + ret = write_stack_detail((pi->flags & eInvalidUserStackPtr) != 0, + &pi->stacks.user, "User", buffer, sz, fdout); + } + + return ret; +} + +/**************************************************************************** + * write_dump_info + ****************************************************************************/ +static int write_dump_info(int fdout, info_s *info, struct bbsramd_s *desc, + char *buffer, unsigned int sz) +{ + char fmtbuff[ TIME_FMT_LEN + 1]; + format_fault_time(HEADER_TIME_FMT, &desc->lastwrite, fmtbuff, sizeof(fmtbuff)); + + bool isFault = (info->current_regs != 0 || info->pid == 0); + int n; + n = snprintf(buffer, sz, "System fault Occurred on: %s\n", fmtbuff); + + if (n != write(fdout, buffer, n)) { + return -EIO; + } + + if (isFault) { + n = snprintf(buffer, sz, " Type:Hard Fault"); + + } else { + n = snprintf(buffer, sz, " Type:Assertion failed"); + } + + if (n != write(fdout, buffer, n)) { + return -EIO; + } + +#ifdef CONFIG_TASK_NAME_SIZE + n = snprintf(buffer, sz, " in file:%s at line: %d running task: %s\n", + info->filename, info->lineno, info->name); +#else + n = snprintf(buffer, sz, " in file:%s at line: %d \n", + info->filename, info->lineno); +#endif + + if (n != write(fdout, buffer, n)) { + return -EIO; + } + + n = snprintf(buffer, sz, " FW git-hash: %s\n", FW_GIT); + + if (n != write(fdout, buffer, n)) { + return -EIO; + } + + n = snprintf(buffer, sz, " Build datetime: %s %s\n", __DATE__, __TIME__); + + if (n != write(fdout, buffer, n)) { + return -EIO; + } + + n = snprintf(buffer, sz, " Build url: %s \n", FW_BUILD_URI); + + if (n != write(fdout, buffer, n)) { + return -EIO; + } + + return OK; +} + +/**************************************************************************** + * write_dump_time + ****************************************************************************/ +static int write_dump_time(char *caller, char *tag, int fdout, + struct timespec *ts, char *buffer, unsigned int sz) +{ + int ret = OK; + 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); + + if (n != write(fdout, buffer, n)) { + ret = -EIO; + } + + return ret; +} +/**************************************************************************** + * write_dump_footer + ****************************************************************************/ +static int write_dump_header(char *caller, int fdout, struct timespec *ts, + char *buffer, unsigned int sz) +{ + return write_dump_time(caller, "Begin", fdout, ts, buffer, sz); +} +/**************************************************************************** + * write_dump_footer + ****************************************************************************/ +static int write_dump_footer(char *caller, int fdout, struct timespec *ts, + char *buffer, unsigned int sz) +{ + return write_dump_time(caller, "END", fdout, ts, buffer, sz); +} +/**************************************************************************** + * write_intterupt_satck + ****************************************************************************/ +static int write_intterupt_stack(int fdin, int fdout, info_s *pi, char *buffer, + unsigned int sz) +{ + int ret = ENOENT; + + if ((pi->flags & eIntStackPresent) != 0) { + lseek(fdin, offsetof(fullcontext_s, istack), SEEK_SET); + ret = write_stack((pi->flags & eInvalidIntStackPrt) != 0, + CONFIG_ISTACK_SIZE, + pi->stacks.interrupt.sp + CONFIG_ISTACK_SIZE / 2, + pi->stacks.interrupt.top, + pi->stacks.interrupt.sp, + pi->stacks.interrupt.top - pi->stacks.interrupt.size, + "Interrupt sp", buffer, sz, fdin, fdout); + } + + return ret; +} + + +/**************************************************************************** + * write_user_stack + ****************************************************************************/ +static int write_user_stack(int fdin, int fdout, info_s *pi, char *buffer, + unsigned int sz) +{ + int ret = ENOENT; + + if ((pi->flags & eUserStackPresent) != 0) { + lseek(fdin, offsetof(fullcontext_s, ustack), SEEK_SET); + ret = write_stack((pi->flags & eInvalidUserStackPtr) != 0, + CONFIG_USTACK_SIZE, + pi->stacks.user.sp + CONFIG_USTACK_SIZE / 2, + pi->stacks.user.top, + pi->stacks.user.sp, + pi->stacks.user.top - pi->stacks.user.size, + "User sp", buffer, sz, fdin, fdout); + } + + 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; +} + + +/**************************************************************************** + * hardfault_dowrite + ****************************************************************************/ +static int hardfault_dowrite(char *caller, int infd, int outfd, + struct bbsramd_s *desc, int format) +{ + int ret = -ENOMEM; + char *line = zalloc(OUT_BUFFER_LEN); + + if (line) { + char *info = zalloc(sizeof(info_s)); + + if (info) { + lseek(infd, offsetof(fullcontext_s, info), SEEK_SET); + ret = read(infd, info, sizeof(info_s)); + + if (ret < 0) { + identify(caller); + syslog(LOG_INFO, "Failed to read Fault Log file [%s] (%d)\n", HARDFAULT_PATH, ret); + ret = -EIO; + + } else { + info_s *pinfo = (info_s *) info; + ret = write_dump_header(caller, outfd, &desc->lastwrite, line, OUT_BUFFER_LEN); + + if (ret == OK) { + + switch (format) { + case HARDFAULT_DISPLAY_FORMAT: + ret = write_intterupt_stack(infd, outfd, pinfo, line, OUT_BUFFER_LEN); + + if (ret >= OK) { + ret = write_user_stack(infd, outfd, pinfo, line, OUT_BUFFER_LEN); + + if (ret >= OK) { + ret = write_dump_info(outfd, pinfo, desc, line, OUT_BUFFER_LEN); + + if (ret >= OK) { + ret = write_registers_info(outfd, pinfo, line, OUT_BUFFER_LEN); + + if (ret >= OK) { + ret = write_interrupt_stack_info(outfd, pinfo, line, OUT_BUFFER_LEN); + + if (ret >= OK) { + ret = write_user_stack_info(outfd, pinfo, line, OUT_BUFFER_LEN); + } + } + } + } + } + + break; + + case HARDFAULT_FILE_FORMAT: + ret = write_dump_info(outfd, pinfo, desc, line, OUT_BUFFER_LEN); + + if (ret == OK) { + ret = write_registers_info(outfd, pinfo, line, OUT_BUFFER_LEN); + + if (ret >= OK) { + ret = write_interrupt_stack_info(outfd, pinfo, line, OUT_BUFFER_LEN); + + if (ret >= OK) { + ret = write_user_stack_info(outfd, pinfo, line, OUT_BUFFER_LEN); + + if (ret >= OK) { + ret = write_intterupt_stack(infd, outfd, pinfo, line, OUT_BUFFER_LEN); + + if (ret >= OK) { + ret = write_user_stack(infd, outfd, pinfo, line, OUT_BUFFER_LEN); + } + } + } + } + } + + break; + + default: + ret = -EINVAL; + break; + } + } + + if (ret >= OK) { + ret = write_dump_footer(caller, outfd, &desc->lastwrite, line, OUT_BUFFER_LEN); + } + } + + free(info); + } + + free(line); + } + + 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 { + + ret = OK; + + if (!reset) { + if (read(fd, &count, sizeof(count)) != sizeof(count)) { + ret = -EIO; + close(fd); + + } else { + lseek(fd, 0, SEEK_SET); + count++; + } + } + + if (ret == OK) { + ret = write(fd, &count, sizeof(count)); + + if (ret != sizeof(count)) { + ret = -EIO; + + } else { + ret = close(fd); + + if (ret == OK) { + ret = count; + } + } + } + } + + return ret; +} +/**************************************************************************** + * hardfault_write + ****************************************************************************/ + +__EXPORT int hardfault_write(char *caller, int fd, int format, bool rearm) +{ + struct bbsramd_s desc; + + switch (format) { + + case HARDFAULT_FILE_FORMAT: + case HARDFAULT_DISPLAY_FORMAT: + break; + + default: + return -EINVAL; + } + + int ret = hardfault_get_desc(caller, &desc, false); + + if (ret >= 0) { + int hffd = ret; + + + int rv = hardfault_dowrite(caller, hffd, fd, &desc, format); + + ret = close(hffd); + + if (ret < 0) { + identify(caller); + syslog(LOG_INFO, "Failed to Close Fault Log (%d)\n", ret); + + } + + if (rv == OK && rearm) { + ret = hardfault_rearm(caller); + + if (ret < 0) { + identify(caller); + syslog(LOG_INFO, "Failed to re-arm Fault Log (%d)\n", ret); + } + } + + if (ret == OK) { + ret = rv; + } + + if (ret != OK) { + identify(caller); + syslog(LOG_INFO, "Failed to Write Fault Log (%d)\n", ret); + } + } + + 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/ver/ver.c b/src/systemcmds/ver/ver.c index b72a14e528..e1cf703618 100644 --- a/src/systemcmds/ver/ver.c +++ b/src/systemcmds/ver/ver.c @@ -50,20 +50,24 @@ /* string constants for version commands */ static const char sz_ver_hw_str[] = "hw"; -static const char sz_ver_hwcmp_str[] = "hwcmp"; +static const char sz_ver_hwcmp_str[] = "hwcmp"; static const char sz_ver_git_str[] = "git"; -static const char sz_ver_bdate_str[] = "bdate"; +static const char sz_ver_bdate_str[] = "bdate"; +static const char sz_ver_buri_str[] = "uri"; static const char sz_ver_gcc_str[] = "gcc"; static const char sz_ver_all_str[] = "all"; static const char mcu_ver_str[] = "mcu"; -static const char mcu_uid_str[] = "uid"; +static const char mcu_uid_str[] = "uid"; const char *px4_git_version = PX4_GIT_VERSION_STR; const uint64_t px4_git_version_binary = PX4_GIT_VERSION_BINARY; +#if !defined(CONFIG_CDCACM_PRODUCTID) +# define CONFIG_CDCACM_PRODUCTID 0 +#endif const char *px4_git_tag = PX4_GIT_TAG_STR; #if defined(__PX4_NUTTX) -__EXPORT const char *os_git_tag = "6.27"; +__EXPORT const char *os_git_tag = "7.18"; __EXPORT const uint32_t px4_board_version = CONFIG_CDCACM_PRODUCTID; #else __EXPORT const char *os_git_tag = ""; @@ -178,7 +182,7 @@ static void usage(const char *reason) printf("%s\n", reason); } - printf("usage: ver {hw|hwcmp|git|bdate|gcc|all|mcu|uid}\n\n"); + printf("usage: ver {hw|hwcmp|git|bdate|gcc|all|mcu|uid|uri}\n\n"); } __EXPORT int ver_main(int argc, char *argv[]); @@ -239,6 +243,13 @@ int ver_main(int argc, char *argv[]) } + if (show_all || !strncmp(argv[1], sz_ver_buri_str, sizeof(sz_ver_buri_str))) { + printf("Build uri: %s\n", FW_BUILD_URI); + ret = 0; + + } + + if (show_all || !strncmp(argv[1], sz_ver_gcc_str, sizeof(sz_ver_gcc_str))) { printf("Toolchain: %s\n", __VERSION__); ret = 0;