PX4 Firmware
PX4 Autopilot Software http://px4.io
hardfault_log.c
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (C) 2015 PX4 Development Team. All rights reserved.
4  * Author: @author David Sidrane <david_s5@nscdg.com>
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions
8  * are met:
9  *
10  * 1. Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * 2. Redistributions in binary form must reproduce the above copyright
13  * notice, this list of conditions and the following disclaimer in
14  * the documentation and/or other materials provided with the
15  * distribution.
16  * 3. Neither the name PX4 nor the names of its contributors may be
17  * used to endorse or promote products derived from this software
18  * without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
27  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
28  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  ****************************************************************************/
34 
35 /****************************************************************************
36  * Included Files
37  ****************************************************************************/
38 
39 #include <px4_platform_common/px4_config.h>
40 #include <px4_platform_common/module.h>
41 #include <nuttx/compiler.h>
42 #include <nuttx/arch.h>
43 
44 #include <sys/ioctl.h>
45 #include <sys/stat.h>
46 
47 #include <stdio.h>
48 #include <stdint.h>
49 #include <stddef.h>
50 #include <stdlib.h>
51 #include <fcntl.h>
52 #include <string.h>
53 #include <errno.h>
54 #include <debug.h>
55 
56 #include <stm32_bbsram.h>
57 
58 #include <systemlib/px4_macros.h>
60 #include <lib/version/version.h>
61 
62 
63 /****************************************************************************
64  * Public Function Prototypes
65  ****************************************************************************/
66 __EXPORT int hardfault_log_main(int argc, char *argv[]);
67 
68 /****************************************************************************
69  * Pre-processor Definitions
70  ****************************************************************************/
71 #define OUT_BUFFER_LEN 200
72 /****************************************************************************
73  * Private Types
74  ****************************************************************************/
75 
76 /****************************************************************************
77  * Private Function Prototypes
78  ****************************************************************************/
79 static int genfault(int fault);
80 /****************************************************************************
81  * Private Data
82  ****************************************************************************/
83 /****************************************************************************
84  * Public Data
85  ****************************************************************************/
86 
87 /****************************************************************************
88  * Private Functions
89  ****************************************************************************/
90 /****************************************************************************
91  * genfault
92  ****************************************************************************/
93 
94 static int genfault(int fault)
95 {
96 
97  /* Pointer to System Control Block's System Control Register */
98 
99  uint32_t *pCCR = (uint32_t *)0xE000ED14;
100 
101  static volatile int k = 0;
102 
103  switch (fault) {
104  case 0:
105 
106  /* Enable divide by 0 fault generation */
107 
108  *pCCR |= 0x10;
109 
110  k = 1 / fault;
111 
112  /* This is not going to happen
113  * Disable divide by 0 fault generation
114  */
115 
116  *pCCR &= ~0x10;
117  break;
118 
119  case 1:
120  ASSERT(fault == 0);
121  /* This is not going to happen */
122  break;
123 
124  default:
125  break;
126 
127  }
128 
129  UNUSED(k);
130  return OK;
131 }
132 
133 
134 /****************************************************************************
135  * format_fault_time
136  ****************************************************************************/
137 /* Ensure Size is the same foe formats or rewrite this */
139 static int format_fault_time(char *format, struct timespec *ts, char *buffer, unsigned int maxsz)
140 {
141  int ret = -EINVAL;
142 
143  if (buffer != NULL && format != NULL) {
144  ret = -ENOMEM;
145 
146  if (maxsz >= TIME_FMT_LEN + 1) {
147  struct tm tt;
148  time_t time_sec = ts->tv_sec + (ts->tv_nsec / 1e9);
149  gmtime_r(&time_sec, &tt);
150 
151  if (TIME_FMT_LEN == strftime(buffer, maxsz, format, &tt)) {
152  ret = OK;
153  }
154  }
155  }
156 
157  return ret;
158 }
159 
160 /****************************************************************************
161  * format_fault_file_name
162  ****************************************************************************/
163 
164 static int format_fault_file_name(struct timespec *ts, char *buffer, unsigned int maxsz)
165 {
166  char fmtbuff[ TIME_FMT_LEN + 1];
167  int ret = -EINVAL;
168 
169  if (buffer) {
170 
171  ret = -ENOMEM;
172  unsigned int plen = LOG_PATH_BASE_LEN;
173 
174  if (maxsz >= LOG_PATH_LEN) {
175  memcpy(buffer, LOG_PATH_BASE, plen);
176  maxsz -= plen;
177  int rv = format_fault_time(TIME_FMT, ts, fmtbuff, arraySize(fmtbuff));
178 
179  if (rv == OK) {
180  int n = snprintf(&buffer[plen], maxsz, LOG_NAME_FMT, fmtbuff);
181 
182  if (n == (int) LOG_NAME_LEN + TIME_FMT_LEN) {
183  ret = OK;
184  }
185  }
186  }
187  }
188 
189  return ret;
190 }
191 
192 /****************************************************************************
193  * identify
194  ****************************************************************************/
195 static void identify(const char *caller)
196 {
197  if (caller) {
198  syslog(LOG_INFO, "[%s] ", caller);
199  }
200 }
201 
202 
203 /****************************************************************************
204  * hardfault_get_desc
205  ****************************************************************************/
206 static int hardfault_get_desc(char *caller, struct bbsramd_s *desc, bool silent)
207 {
208  int ret = -ENOENT;
209  int fd = open(HARDFAULT_PATH, O_RDONLY);
210 
211  if (fd < 0) {
212  if (!silent) {
213  identify(caller);
214  syslog(LOG_INFO, "Failed to open Fault Log file [%s] (%d)\n", HARDFAULT_PATH, fd);
215  }
216 
217  } else {
218  ret = -EIO;
219  int rv = ioctl(fd, PX4_BBSRAM_GETDESC_IOCTL, (unsigned long)((uintptr_t)desc));
220 
221  if (rv >= 0) {
222  ret = fd;
223 
224  } else {
225  identify(caller);
226  syslog(LOG_INFO, "Failed to get Fault Log descriptor (%d)\n", rv);
227  }
228  }
229 
230  return ret;
231 }
232 
233 /****************************************************************************
234  * write_stack_detail
235  ****************************************************************************/
236 static int write_stack_detail(bool inValid, _stack_s *si, char *sp_name,
237  char *buffer, int max, int fd)
238 {
239 
240  int n = 0;
241  uint32_t sbot = si->top - si->size;
242  n = snprintf(&buffer[n], max - n, " %s stack: \n", sp_name);
243  n += snprintf(&buffer[n], max - n, " top: 0x%08x\n", si->top);
244  n += snprintf(&buffer[n], max - n, " sp: 0x%08x %s\n", si->sp, (inValid ? "Invalid" : "Valid"));
245 
246  if (n != write(fd, buffer, n)) {
247  return -EIO;
248  }
249 
250  n = 0;
251  n += snprintf(&buffer[n], max - n, " bottom: 0x%08x\n", sbot);
252  n += snprintf(&buffer[n], max - n, " size: 0x%08x\n", si->size);
253 
254  if (n != write(fd, buffer, n)) {
255  return -EIO;
256  }
257 
258 #ifdef CONFIG_STACK_COLORATION
259  FAR struct tcb_s tcb;
260  tcb.stack_alloc_ptr = (void *) sbot;
261  tcb.adj_stack_size = si->size;
262  n = snprintf(buffer, max, " used: %08x\n", up_check_tcbstack(&tcb));
263 
264  if (n != write(fd, buffer, n)) {
265  return -EIO;
266  }
267 
268 #endif
269  return OK;
270 }
271 
272 /****************************************************************************
273  * write_stack
274  ****************************************************************************/
275 static int read_stack(int fd, stack_word_t *words, int num)
276 {
277  int bytes = read(fd, (char *) words, sizeof(stack_word_t) * num);
278 
279  if (bytes > 0) {
280  bytes /= sizeof(stack_word_t);
281  }
282 
283  return bytes;
284 }
285 static int write_stack(bool inValid, int winsize, uint32_t wtopaddr,
286  uint32_t topaddr, uint32_t spaddr, uint32_t botaddr,
287  char *sp_name, char *buffer, int max, int infd, int outfd)
288 {
289  char marker[30];
290  stack_word_t stack[32];
291  int ret = OK;
292 
293  int n = snprintf(buffer, max, "%s memory region, stack pointer lies %s stack\n",
294  sp_name, (inValid ? "outside of" : "within"));
295 
296  if (n != write(outfd, buffer, n)) {
297 
298  ret = -EIO;
299 
300  } else {
301 
302  while (winsize > 0 && ret == OK) {
303  int chunk = read_stack(infd, stack, arraySize(stack));
304 
305  if (chunk <= 0) {
306  ret = -EIO;
307 
308  } else {
309  winsize -= chunk;
310 
311  for (int i = 0; i < chunk; i++) {
312  if (wtopaddr == topaddr) {
313  strncpy(marker, "<-- ", sizeof(marker));
314  strncat(marker, sp_name, sizeof(marker) - 1);
315  strncat(marker, " top", sizeof(marker) - 1);
316 
317  } else if (wtopaddr == spaddr) {
318  strncpy(marker, "<-- ", sizeof(marker));
319  strncat(marker, sp_name, sizeof(marker) - 1);
320 
321  } else if (wtopaddr == botaddr) {
322  strncpy(marker, "<-- ", sizeof(marker));
323  strncat(marker, sp_name, sizeof(marker) - 1);
324  strncat(marker, " bottom", sizeof(marker) - 1);
325 
326  } else {
327  marker[0] = '\0';
328  }
329 
330  n = snprintf(buffer, max, "0x%08x 0x%08x%s\n", wtopaddr, stack[i], marker);
331 
332  if (n != write(outfd, buffer, n)) {
333  ret = -EIO;
334  }
335 
336  wtopaddr--;
337  }
338  }
339  }
340  }
341 
342  return ret;
343 }
344 
345 /****************************************************************************
346  * write_registers
347  ****************************************************************************/
348 static int write_registers(uint32_t regs[], char *buffer, int max, int fd)
349 {
350  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",
351  regs[REG_R0], regs[REG_R1],
352  regs[REG_R2], regs[REG_R3],
353  regs[REG_R4], regs[REG_R5],
354  regs[REG_R6], regs[REG_R7]);
355 
356  if (n != write(fd, buffer, n)) {
357  return -EIO;
358  }
359 
360  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",
361  regs[REG_R8], regs[REG_R9],
362  regs[REG_R10], regs[REG_R11],
363  regs[REG_R12], regs[REG_R13],
364  regs[REG_R14], regs[REG_R15]);
365 
366  if (n != write(fd, buffer, n)) {
367  return -EIO;
368  }
369 
370 #ifdef CONFIG_ARMV7M_USEBASEPRI
371  n = snprintf(buffer, max, " xpsr:0x%08x basepri:0x%08x control:0x%08x\n",
372  regs[REG_XPSR], regs[REG_BASEPRI],
373  getcontrol());
374 #else
375  n = snprintf(buffer, max, " xpsr:0x%08x primask:0x%08x control:0x%08x\n",
376  regs[REG_XPSR], regs[REG_PRIMASK],
377  getcontrol());
378 #endif
379 
380  if (n != write(fd, buffer, n)) {
381  return -EIO;
382  }
383 
384 #ifdef REG_EXC_RETURN
385  n = snprintf(buffer, max, " exe return:0x%08x\n", regs[REG_EXC_RETURN]);
386 
387  if (n != write(fd, buffer, n)) {
388  return -EIO;
389  }
390 
391 #endif
392  return OK;
393 }
394 
395 /****************************************************************************
396  * write_registers_info
397  ****************************************************************************/
398 static int write_registers_info(int fdout, info_s *pi, char *buffer, int sz)
399 {
400  int ret = ENOENT;
401 
402  if (pi->flags & eRegsPresent) {
403  ret = -EIO;
404  int n = snprintf(buffer, sz, " Processor registers: from 0x%08x\n", pi->current_regs);
405 
406  if (n == write(fdout, buffer, n)) {
407  ret = write_registers(pi->regs, buffer, sz, fdout);
408  }
409  }
410 
411  return ret;
412 }
413 
414 /****************************************************************************
415  * write_interrupt_stack_info
416  ****************************************************************************/
417 static int write_interrupt_stack_info(int fdout, info_s *pi, char *buffer,
418  unsigned int sz)
419 {
420  int ret = ENOENT;
421 
422  if (pi->flags & eIntStackPresent) {
423  ret = write_stack_detail((pi->flags & eInvalidIntStackPrt) != 0,
424  &pi->stacks.interrupt, "IRQ",
425  buffer, sz, fdout);
426  }
427 
428  return ret;
429 }
430 
431 /****************************************************************************
432  * write_user_stack_info
433  ****************************************************************************/
434 static int write_user_stack_info(int fdout, info_s *pi, char *buffer,
435  unsigned int sz)
436 {
437  int ret = ENOENT;
438 
439  if (pi->flags & eUserStackPresent) {
440  ret = write_stack_detail((pi->flags & eInvalidUserStackPtr) != 0,
441  &pi->stacks.user, "User", buffer, sz, fdout);
442  }
443 
444  return ret;
445 }
446 
447 /****************************************************************************
448  * write_dump_info
449  ****************************************************************************/
450 static int write_dump_info(int fdout, info_s *info, struct bbsramd_s *desc,
451  char *buffer, unsigned int sz)
452 {
453  char fmtbuff[ TIME_FMT_LEN + 1];
454  format_fault_time(HEADER_TIME_FMT, &desc->lastwrite, fmtbuff, sizeof(fmtbuff));
455 
456  bool isFault = (info->current_regs != 0 || info->pid == 0);
457  int n;
458  n = snprintf(buffer, sz, "System fault Occurred on: %s\n", fmtbuff);
459 
460  if (n != write(fdout, buffer, n)) {
461  return -EIO;
462  }
463 
464  if (isFault) {
465  n = snprintf(buffer, sz, " Type:Hard Fault");
466 
467  } else {
468  n = snprintf(buffer, sz, " Type:Assertion failed");
469  }
470 
471  if (n != write(fdout, buffer, n)) {
472  return -EIO;
473  }
474 
475 #ifdef CONFIG_TASK_NAME_SIZE
476  n = snprintf(buffer, sz, " in file:%s at line: %d running task: %s\n",
477  info->filename, info->lineno, info->name);
478 #else
479  n = snprintf(buffer, sz, " in file:%s at line: %d \n",
480  info->filename, info->lineno);
481 #endif
482 
483  if (n != write(fdout, buffer, n)) {
484  return -EIO;
485  }
486 
487  n = snprintf(buffer, sz, " FW git-hash: %s\n", px4_firmware_version_string());
488 
489  if (n != write(fdout, buffer, n)) {
490  return -EIO;
491  }
492 
493  n = snprintf(buffer, sz, " Build datetime: %s %s\n", __DATE__, __TIME__);
494 
495  if (n != write(fdout, buffer, n)) {
496  return -EIO;
497  }
498 
499  n = snprintf(buffer, sz, " Build url: %s \n", px4_build_uri());
500 
501  if (n != write(fdout, buffer, n)) {
502  return -EIO;
503  }
504 
505  return OK;
506 }
507 
508 /****************************************************************************
509  * write_dump_time
510  ****************************************************************************/
511 static int write_dump_time(char *caller, char *tag, int fdout,
512  struct timespec *ts, char *buffer, unsigned int sz)
513 {
514  int ret = OK;
515  char fmtbuff[ TIME_FMT_LEN + 1];
516  format_fault_time(HEADER_TIME_FMT, ts, fmtbuff, sizeof(fmtbuff));
517  int n = snprintf(buffer, sz, "[%s] -- %s %s Fault Log --\n", caller, fmtbuff, tag);
518 
519  if (n != write(fdout, buffer, n)) {
520  ret = -EIO;
521  }
522 
523  return ret;
524 }
525 /****************************************************************************
526  * write_dump_footer
527  ****************************************************************************/
528 static int write_dump_header(char *caller, int fdout, struct timespec *ts,
529  char *buffer, unsigned int sz)
530 {
531  return write_dump_time(caller, "Begin", fdout, ts, buffer, sz);
532 }
533 /****************************************************************************
534  * write_dump_footer
535  ****************************************************************************/
536 static int write_dump_footer(char *caller, int fdout, struct timespec *ts,
537  char *buffer, unsigned int sz)
538 {
539  return write_dump_time(caller, "END", fdout, ts, buffer, sz);
540 }
541 /****************************************************************************
542  * write_intterupt_satck
543  ****************************************************************************/
544 static int write_intterupt_stack(int fdin, int fdout, info_s *pi, char *buffer,
545  unsigned int sz)
546 {
547  int ret = ENOENT;
548 
549  if ((pi->flags & eIntStackPresent) != 0) {
550  lseek(fdin, offsetof(fullcontext_s, istack), SEEK_SET);
551  ret = write_stack((pi->flags & eInvalidIntStackPrt) != 0,
553  pi->stacks.interrupt.sp + CONFIG_ISTACK_SIZE / 2,
554  pi->stacks.interrupt.top,
555  pi->stacks.interrupt.sp,
556  pi->stacks.interrupt.top - pi->stacks.interrupt.size,
557  "Interrupt sp", buffer, sz, fdin, fdout);
558  }
559 
560  return ret;
561 }
562 
563 
564 /****************************************************************************
565  * write_user_stack
566  ****************************************************************************/
567 static int write_user_stack(int fdin, int fdout, info_s *pi, char *buffer,
568  unsigned int sz)
569 {
570  int ret = ENOENT;
571 
572  if ((pi->flags & eUserStackPresent) != 0) {
573  lseek(fdin, offsetof(fullcontext_s, ustack), SEEK_SET);
574  ret = write_stack((pi->flags & eInvalidUserStackPtr) != 0,
576  pi->stacks.user.sp + CONFIG_USTACK_SIZE / 2,
577  pi->stacks.user.top,
578  pi->stacks.user.sp,
579  pi->stacks.user.top - pi->stacks.user.size,
580  "User sp", buffer, sz, fdin, fdout);
581  }
582 
583  return ret;
584 }
585 
586 /**
587  * Append hardfault data to the stored ULog file (the log path is stored in BBSRAM).
588  * @param caller
589  * @param fdin file descriptor for plain-text hardhault log to read from
590  * @return 0 on success, -errno otherwise
591  */
592 static int hardfault_append_to_ulog(const char *caller, int fdin)
593 {
594 
595  int ret = 0;
596  int write_size_remaining = lseek(fdin, 0, SEEK_END);
597 
598  if (write_size_remaining < 0) {
599  return -EINVAL;
600  }
601 
602  lseek(fdin, 0, SEEK_SET);
603 
604  // get the last ulog file
605  char ulog_file_name[HARDFAULT_MAX_ULOG_FILE_LEN];
606  int fd = open(HARDFAULT_ULOG_PATH, O_RDONLY);
607 
608  if (fd < 0) {
609  return -errno;
610  }
611 
612  if (read(fd, ulog_file_name, HARDFAULT_MAX_ULOG_FILE_LEN) != HARDFAULT_MAX_ULOG_FILE_LEN) {
613  close(fd);
614  return -errno;
615  }
616 
617  close(fd);
618  ulog_file_name[HARDFAULT_MAX_ULOG_FILE_LEN - 1] = 0; //ensure null-termination
619 
620  if (strlen(ulog_file_name) == 0) {
621  return -ENOENT;
622  }
623 
624  identify(caller);
625  syslog(LOG_INFO, "Appending to ULog %s\n", ulog_file_name);
626 
627  // get the ulog file size
628  struct stat st;
629 
630  if (stat(ulog_file_name, &st) == -1) {
631  return -errno;
632  }
633 
634  const off_t ulog_file_size = st.st_size;
635 
636  // open the ulog file
637  int ulog_fd = open(ulog_file_name, O_RDWR);
638 
639  if (ulog_fd < 0) {
640  return -errno;
641  }
642 
643  uint8_t chunk[256];
644 
645  //verify it's an ULog file
646  char magic[8];
647  magic[0] = 'U';
648  magic[1] = 'L';
649  magic[2] = 'o';
650  magic[3] = 'g';
651  magic[4] = 0x01;
652  magic[5] = 0x12;
653  magic[6] = 0x35;
654 
655  if (read(ulog_fd, chunk, 8) != 8) {
656  identify(caller);
657  syslog(LOG_INFO, "Reading ULog header failed\n");
658  return -EINVAL;
659  }
660 
661  if (memcmp(magic, chunk, 7) != 0) {
662  return -EINVAL;
663  }
664 
665  // set the 'appended data' bit
666  const int flag_offset = 16 + 3 + 8; // ulog header+message header+compat flags
667  lseek(ulog_fd, flag_offset, SEEK_SET);
668 
669  if (read(ulog_fd, chunk, 1) != 1) {
670  ret = -errno;
671  goto out;
672  }
673 
674  chunk[0] |= 1 << 0;
675  lseek(ulog_fd, flag_offset, SEEK_SET);
676 
677  if (write(ulog_fd, chunk, 1) != 1) {
678  ret = -errno;
679  goto out;
680  }
681 
682  // set the offset (find the first that is 0, assuming we're on little endian), see definition of FLAG_BITS message
683  const int append_file_offset = 16 + 3 + 8 + 8; // ulog header+message header+compat flags+incompat flags
684  bool found = false;
685 
686  for (int i = 0; i < 3; ++i) { // there is a maximum of 3 offsets we can use
687  int current_offset = append_file_offset + i * 8;
688  lseek(ulog_fd, current_offset, SEEK_SET);
689  uint64_t offset;
690 
691  if (read(ulog_fd, &offset, sizeof(offset)) != sizeof(offset)) {
692  ret = -errno;
693  goto out;
694  }
695 
696  if (offset == 0) { // nothing appended yet
697  lseek(ulog_fd, current_offset, SEEK_SET);
698  offset = ulog_file_size;
699 
700  if (write(ulog_fd, &offset, sizeof(offset)) != sizeof(offset)) {
701  ret = -errno;
702  goto out;
703  }
704 
705  found = true;
706  break;
707  }
708  }
709 
710  if (!found) {
711  identify(caller);
712  syslog(LOG_ERR, "Cannot append more data to ULog (no offsets left)\n");
713  ret = -EINVAL;
714  goto out;
715  }
716 
717 
718  // now append the data
719  lseek(ulog_fd, 0, SEEK_END);
720 
721  const int max_bytes_to_write = (1 << 16) - 100; // limit is given by max uint16 minus message header and key
722  uint8_t is_continued = 0;
723 
724  while (write_size_remaining > 0) { // we might need to split into several ULog messages
725  int bytes_to_write = write_size_remaining;
726 
727  if (bytes_to_write > max_bytes_to_write) {
728  bytes_to_write = max_bytes_to_write;
729  }
730 
731  chunk[2] = 'M'; // msg_type
732  chunk[3] = is_continued;
733  is_continued = 1;
734  const int key_len = snprintf((char *)chunk + 5, sizeof(chunk) - 5, "char[%i] hardfault_plain", bytes_to_write);
735  chunk[4] = key_len;
736  const uint16_t ulog_msg_len = bytes_to_write + key_len + 5 - 3; // subtract ULog msg header
737  memcpy(chunk, &ulog_msg_len, sizeof(uint16_t));
738 
739  if (write(ulog_fd, chunk, key_len + 5) != key_len + 5) {
740  ret = -errno;
741  goto out;
742  }
743 
744  int num_read;
745 
746  while (bytes_to_write > 0) {
747  // read a chunk from fdin to memory and then write it to the file
748  int max_read = sizeof(chunk);
749 
750  if (max_read > bytes_to_write) {
751  max_read = bytes_to_write;
752  }
753 
754  num_read = read(fdin, chunk, max_read);
755 
756  if (num_read <= 0) {
757  identify(caller);
758  syslog(LOG_ERR, "read() failed: %i, %i\n", num_read, errno);
759  ret = -1;
760  goto out;
761  }
762 
763  ret = write(ulog_fd, chunk, num_read);
764 
765  if (ret != num_read) {
766  ret = -errno;
767  goto out;
768  }
769 
770  bytes_to_write -= num_read;
771  write_size_remaining -= num_read;
772  }
773  }
774 
775  ret = 0;
776 
777 out:
778  close(ulog_fd);
779 
780  return ret;
781 }
782 
783 
784 /****************************************************************************
785  * commit
786  ****************************************************************************/
787 static int hardfault_commit(char *caller)
788 {
789  int ret = -ENOENT;
790  int state = -1;
791  struct bbsramd_s desc;
792  char path[LOG_PATH_LEN + 1];
793  ret = hardfault_get_desc(caller, &desc, false);
794 
795  if (ret >= 0) {
796 
797  int fd = ret;
798  state = (desc.lastwrite.tv_sec || desc.lastwrite.tv_nsec) ? OK : 1;
799  int rv = close(fd);
800 
801  if (rv < 0) {
802  identify(caller);
803  syslog(LOG_INFO, "Failed to Close Fault Log (%d)\n", rv);
804 
805  } else {
806 
807  if (state != OK) {
808  identify(caller);
809  syslog(LOG_INFO, "Nothing to save\n", path);
810  ret = -ENOENT;
811 
812  } else {
813  ret = format_fault_file_name(&desc.lastwrite, path, arraySize(path));
814 
815  if (ret == OK) {
816  int fdout = open(path, O_RDWR | O_CREAT);
817 
818  if (fdout >= 0) {
819  identify(caller);
820  syslog(LOG_INFO, "Saving Fault Log file %s\n", path);
821  ret = hardfault_write(caller, fdout, HARDFAULT_FILE_FORMAT, true);
822  identify(caller);
823  syslog(LOG_INFO, "Done saving Fault Log file\n");
824 
825  // now save the same data to the last ulog file by copying from the txt file
826  // (not the fastest, but a simple way to do it). We also want to keep a separate
827  // .txt file around, since that is a bit less prone to FS errors than the ULog
828  if (ret == OK) {
829  ret = hardfault_append_to_ulog(caller, fdout);
830  identify(caller);
831 
832  switch (ret) {
833  case OK:
834  syslog(LOG_INFO, "Successfully appended to ULog\n");
835  break;
836 
837  case -ENOENT:
838  syslog(LOG_INFO, "No ULog to append to\n");
839  ret = OK;
840  break;
841 
842  default:
843  syslog(LOG_INFO, "Failed to append to ULog (%i)\n", ret);
844  break;
845  }
846  }
847 
848  close(fdout);
849  }
850  }
851  }
852  }
853  }
854 
855  return ret;
856 }
857 
858 
859 /****************************************************************************
860  * hardfault_dowrite
861  ****************************************************************************/
862 static int hardfault_dowrite(char *caller, int infd, int outfd,
863  struct bbsramd_s *desc, int format)
864 {
865  int ret = -ENOMEM;
866  char *line = zalloc(OUT_BUFFER_LEN);
867 
868  if (line) {
869  char *info = zalloc(sizeof(info_s));
870 
871  if (info) {
872  lseek(infd, offsetof(fullcontext_s, info), SEEK_SET);
873  ret = read(infd, info, sizeof(info_s));
874 
875  if (ret < 0) {
876  identify(caller);
877  syslog(LOG_INFO, "Failed to read Fault Log file [%s] (%d)\n", HARDFAULT_PATH, ret);
878  ret = -EIO;
879 
880  } else {
881  info_s *pinfo = (info_s *) info;
882  ret = write_dump_header(caller, outfd, &desc->lastwrite, line, OUT_BUFFER_LEN);
883 
884  if (ret == OK) {
885 
886  switch (format) {
888  ret = write_intterupt_stack(infd, outfd, pinfo, line, OUT_BUFFER_LEN);
889 
890  if (ret >= OK) {
891  ret = write_user_stack(infd, outfd, pinfo, line, OUT_BUFFER_LEN);
892 
893  if (ret >= OK) {
894  ret = write_dump_info(outfd, pinfo, desc, line, OUT_BUFFER_LEN);
895 
896  if (ret >= OK) {
897  ret = write_registers_info(outfd, pinfo, line, OUT_BUFFER_LEN);
898 
899  if (ret >= OK) {
900  ret = write_interrupt_stack_info(outfd, pinfo, line, OUT_BUFFER_LEN);
901 
902  if (ret >= OK) {
903  ret = write_user_stack_info(outfd, pinfo, line, OUT_BUFFER_LEN);
904  }
905  }
906  }
907  }
908  }
909 
910  break;
911 
913  ret = write_dump_info(outfd, pinfo, desc, line, OUT_BUFFER_LEN);
914 
915  if (ret == OK) {
916  ret = write_registers_info(outfd, pinfo, line, OUT_BUFFER_LEN);
917 
918  if (ret >= OK) {
919  ret = write_interrupt_stack_info(outfd, pinfo, line, OUT_BUFFER_LEN);
920 
921  if (ret >= OK) {
922  ret = write_user_stack_info(outfd, pinfo, line, OUT_BUFFER_LEN);
923 
924  if (ret >= OK) {
925  ret = write_intterupt_stack(infd, outfd, pinfo, line, OUT_BUFFER_LEN);
926 
927  if (ret >= OK) {
928  ret = write_user_stack(infd, outfd, pinfo, line, OUT_BUFFER_LEN);
929  }
930  }
931  }
932  }
933  }
934 
935  break;
936 
937  default:
938  ret = -EINVAL;
939  break;
940  }
941  }
942 
943  if (ret >= OK) {
944  ret = write_dump_footer(caller, outfd, &desc->lastwrite, line, OUT_BUFFER_LEN);
945  }
946  }
947 
948  free(info);
949  }
950 
951  free(line);
952  }
953 
954  return ret;
955 }
956 
957 
958 /****************************************************************************
959  * Public Functions
960  ****************************************************************************/
961 /****************************************************************************
962  * hardfault_rearm
963  ****************************************************************************/
964 __EXPORT int hardfault_rearm(char *caller)
965 {
966  int ret = OK;
967  int rv = unlink(HARDFAULT_PATH);
968 
969  if (rv < 0) {
970  identify(caller);
971  syslog(LOG_INFO, "Failed to re arming Fault Log (%d)\n", rv);
972  ret = -EIO;
973 
974  } else {
975  identify(caller);
976  syslog(LOG_INFO, "Fault Log is Armed\n");
977  }
978 
979  return ret;
980 }
981 
982 /****************************************************************************
983  * hardfault_check_status
984  ****************************************************************************/
986 {
987  int state = -1;
988  struct bbsramd_s desc;
989  int ret = hardfault_get_desc(caller, &desc, true);
990 
991  if (ret < 0) {
992  identify(caller);
993 
994  if (ret == -ENOENT) {
995  syslog(LOG_INFO, "Fault Log is Armed\n");
996 
997  } else {
998  syslog(LOG_INFO, "Failed to open Fault Log file [%s] (%d)\n", HARDFAULT_PATH, ret);
999  }
1000 
1001  } else {
1002  int fd = ret;
1003  state = (desc.lastwrite.tv_sec || desc.lastwrite.tv_nsec) ? OK : 1;
1004  int rv = close(fd);
1005 
1006  if (rv < 0) {
1007  identify(caller);
1008  syslog(LOG_INFO, "Failed to Close Fault Log (%d)\n", rv);
1009 
1010  } else {
1011  ret = state;
1012  identify(caller);
1013  syslog(LOG_INFO, "Fault Log info File No %d Length %d flags:0x%02x state:%d\n",
1014  (unsigned int)desc.fileno, (unsigned int) desc.len, (unsigned int)desc.flags, state);
1015 
1016  if (state == OK) {
1017  char buf[TIME_FMT_LEN + 1];
1018  format_fault_time(HEADER_TIME_FMT, &desc.lastwrite, buf, arraySize(buf));
1019  identify(caller);
1020  syslog(LOG_INFO, "Fault Logged on %s - Valid\n", buf);
1021 
1022  } else {
1023  rv = hardfault_rearm(caller);
1024 
1025  if (rv < 0) {
1026  ret = rv;
1027  }
1028  }
1029  }
1030  }
1031 
1032  return ret;
1033 }
1034 
1035 /****************************************************************************
1036  * hardfault_increment_reboot
1037  ****************************************************************************/
1039 {
1040  int ret = -EIO;
1041  int count = 0;
1042  int fd = open(HARDFAULT_REBOOT_PATH, O_RDWR | O_CREAT);
1043 
1044  if (fd < 0) {
1045  identify(caller);
1046  syslog(LOG_INFO, "Failed to open Fault reboot count file [%s] (%d)\n", HARDFAULT_REBOOT_PATH, ret);
1047 
1048  } else {
1049 
1050  ret = OK;
1051 
1052  if (!reset) {
1053  if (read(fd, &count, sizeof(count)) != sizeof(count)) {
1054  ret = -EIO;
1055  close(fd);
1056 
1057  } else {
1058  lseek(fd, 0, SEEK_SET);
1059  count++;
1060  }
1061  }
1062 
1063  if (ret == OK) {
1064  ret = write(fd, &count, sizeof(count));
1065 
1066  if (ret != sizeof(count)) {
1067  ret = -EIO;
1068 
1069  } else {
1070  ret = close(fd);
1071 
1072  if (ret == OK) {
1073  ret = count;
1074  }
1075  }
1076  }
1077  }
1078 
1079  return ret;
1080 }
1081 /****************************************************************************
1082  * hardfault_write
1083  ****************************************************************************/
1084 
1085 __EXPORT int hardfault_write(char *caller, int fd, int format, bool rearm)
1086 {
1087  struct bbsramd_s desc;
1088 
1089  switch (format) {
1090 
1091  case HARDFAULT_FILE_FORMAT:
1093  break;
1094 
1095  default:
1096  return -EINVAL;
1097  }
1098 
1099  int ret = hardfault_get_desc(caller, &desc, false);
1100 
1101  if (ret >= 0) {
1102  int hffd = ret;
1103 
1104 
1105  int rv = hardfault_dowrite(caller, hffd, fd, &desc, format);
1106 
1107  ret = close(hffd);
1108 
1109  if (ret < 0) {
1110  identify(caller);
1111  syslog(LOG_INFO, "Failed to Close Fault Log (%d)\n", ret);
1112 
1113  }
1114 
1115  if (rv == OK && rearm) {
1116  ret = hardfault_rearm(caller);
1117 
1118  if (ret < 0) {
1119  identify(caller);
1120  syslog(LOG_INFO, "Failed to re-arm Fault Log (%d)\n", ret);
1121  }
1122  }
1123 
1124  if (ret == OK) {
1125  ret = rv;
1126  }
1127 
1128  if (ret != OK) {
1129  identify(caller);
1130  syslog(LOG_INFO, "Failed to Write Fault Log (%d)\n", ret);
1131  }
1132  }
1133 
1134  return ret;
1135 }
1136 
1137 static void print_usage(void)
1138 {
1139  PRINT_MODULE_DESCRIPTION("Hardfault utility\n"
1140  "\n"
1141  "Used in startup scripts to handle hardfaults\n"
1142  );
1143 
1144 
1145  PRINT_MODULE_USAGE_NAME("hardfault_log", "command");
1146  PRINT_MODULE_USAGE_COMMAND_DESCR("check", "Check if there's an uncommited hardfault");
1147  PRINT_MODULE_USAGE_COMMAND_DESCR("rearm", "Drop an uncommited hardfault");
1148 
1149  PRINT_MODULE_USAGE_COMMAND_DESCR("fault", "Generate a hardfault (this command crashes the system :)");
1150  PRINT_MODULE_USAGE_ARG("0|1", "Hardfault type: 0=divide by 0, 1=Assertion (default=0)", true);
1151 
1152  PRINT_MODULE_USAGE_COMMAND_DESCR("commit",
1153  "Write uncommited hardfault to /fs/microsd/fault_%i.txt (and rearm, but don't reset)");
1154  PRINT_MODULE_USAGE_COMMAND_DESCR("count",
1155  "Read the reboot counter, counts the number of reboots of an uncommited hardfault (returned as the exit code of the program)");
1156  PRINT_MODULE_USAGE_COMMAND_DESCR("reset", "Reset the reboot counter");
1157 }
1158 
1159 /****************************************************************************
1160  * Name: hardfault_log_main
1161  ****************************************************************************/
1162 __EXPORT int hardfault_log_main(int argc, char *argv[])
1163 {
1164  char *self = "hardfault_log";
1165 
1166  if (argc <= 1) {
1167  print_usage();
1168  return 1;
1169  }
1170 
1171  if (!strcmp(argv[1], "check")) {
1172 
1173  return hardfault_check_status(self);
1174 
1175  } else if (!strcmp(argv[1], "rearm")) {
1176 
1177  return hardfault_rearm(self);
1178 
1179  } else if (!strcmp(argv[1], "fault")) {
1180 
1181  int fault = 0;
1182 
1183  if (argc > 2) {
1184  fault = atol(argv[2]);
1185  }
1186 
1187  return genfault(fault);
1188 
1189  } else if (!strcmp(argv[1], "commit")) {
1190 
1191  return hardfault_commit(self);
1192 
1193  } else if (!strcmp(argv[1], "count")) {
1194 
1195  return hardfault_increment_reboot(self, false);
1196 
1197  } else if (!strcmp(argv[1], "reset")) {
1198 
1199  return hardfault_increment_reboot(self, true);
1200 
1201  }
1202 
1203  print_usage();
1204  return -EINVAL;
1205 }
#define HEADER_TIME_FMT
static int write_user_stack_info(int fdout, info_s *pi, char *buffer, unsigned int sz)
CCASSERT(TIME_FMT_LEN==HEADER_TIME_FMT_LEN)
static int read_stack(int fd, stack_word_t *words, int num)
#define HARDFAULT_FILE_FORMAT
__EXPORT int hardfault_rearm(char *caller)
static enum @74 state
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)
#define LOG_NAME_FMT
static int write_dump_info(int fdout, info_s *info, struct bbsramd_s *desc, char *buffer, unsigned int sz)
static int write_stack_detail(bool inValid, _stack_s *si, char *sp_name, char *buffer, int max, int fd)
#define HARDFAULT_ULOG_PATH
Definition: hardfault_log.h:47
#define HARDFAULT_MAX_ULOG_FILE_LEN
Definition: hardfault_log.h:51
Definition: I2C.hpp:51
#define LOG_PATH_BASE
Definition: hardfault_log.h:99
int info()
Print a little info about the driver.
A set of useful macros for enhanced runtime and compile time error detection and warning suppression...
#define HEADER_TIME_FMT_LEN
int reset(enum LPS22HB_BUS busid)
Reset the driver.
fault_flags_t flags
uint32_t top
#define CONFIG_ISTACK_SIZE
Definition: hardfault_log.h:75
static int hardfault_dowrite(char *caller, int infd, int outfd, struct bbsramd_s *desc, int format)
#define LOG_NAME_LEN
static int write_registers_info(int fdout, info_s *pi, char *buffer, int sz)
static void read(bootloader_app_shared_t *pshared)
static int hardfault_commit(char *caller)
static int format_fault_file_name(struct timespec *ts, char *buffer, unsigned int maxsz)
static int genfault(int fault)
Definition: hardfault_log.c:94
#define LOG_PATH_BASE_LEN
uintptr_t current_regs
#define TIME_FMT
static int format_fault_time(char *format, struct timespec *ts, char *buffer, unsigned int maxsz)
static int write_dump_footer(char *caller, int fdout, struct timespec *ts, char *buffer, unsigned int sz)
static void print_usage(void)
static int hardfault_get_desc(char *caller, struct bbsramd_s *desc, bool silent)
#define HARDFAULT_PATH
Definition: hardfault_log.h:49
#define HARDFAULT_DISPLAY_FORMAT
int lineno
stack_t stacks
__EXPORT int hardfault_log_main(int argc, char *argv[])
int fd
Definition: dataman.cpp:146
#define HARDFAULT_REBOOT_PATH
Definition: hardfault_log.h:45
const char * px4_firmware_version_string(void)
Firmware version as human readable string (git tag)
Definition: version.c:338
const char * px4_build_uri(void)
get the build URI (used for crash logging)
Definition: version.c:61
Tools for system version detection.
uint32_t sp
static void write(bootloader_app_shared_t *pshared)
__EXPORT int hardfault_check_status(char *caller)
#define OUT_BUFFER_LEN
Definition: hardfault_log.c:71
constexpr _Tp max(_Tp a, _Tp b)
Definition: Limits.hpp:60
#define arraySize(a)
#define TIME_FMT_LEN
uint32_t stack_word_t
uint32_t size
#define UNUSED(x)
Definition: spektrum_rc.cpp:58
uint32_t regs[XCPTCONTEXT_REGS]
#define LOG_PATH_LEN
static int write_interrupt_stack_info(int fdout, info_s *pi, char *buffer, unsigned int sz)
__EXPORT int hardfault_increment_reboot(char *caller, bool reset)
#define OK
Definition: uavcan_main.cpp:71
static int write_user_stack(int fdin, int fdout, info_s *pi, char *buffer, unsigned int sz)
_stack_s user
static void identify(const char *caller)
static int write_dump_header(char *caller, int fdout, struct timespec *ts, char *buffer, unsigned int sz)
static int write_intterupt_stack(int fdin, int fdout, info_s *pi, char *buffer, unsigned int sz)
static int hardfault_append_to_ulog(const char *caller, int fdin)
Append hardfault data to the stored ULog file (the log path is stored in BBSRAM). ...
char filename[MAX_FILE_PATH_LENGTH]
static int write_registers(uint32_t regs[], char *buffer, int max, int fd)
#define CONFIG_USTACK_SIZE
Definition: hardfault_log.h:76
__EXPORT int hardfault_write(char *caller, int fd, int format, bool rearm)
static int write_dump_time(char *caller, char *tag, int fdout, struct timespec *ts, char *buffer, unsigned int sz)