Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/debug/crash_debugger.py
Views: 1798
#!/usr/bin/env python1# -*- coding: utf-8 -*-23"""4Script to catch and give backtrace of a HardFault Crash56Usage:7python crash_debugger.py <elf_file> --ser-debug --ser-port <serial_port> --dump-fileout <dump_fileout>8python crash_debugger.py <elf_file> --swd-debug --gdb-port <gdb_port> --dump-fileout <dump_fileout>9python crash_debugger.py <elf_file> --dump-debug --dump-fileout <dump_fileout>10Copyright Siddharth Bharat Purohit, CubePilot Pty. Ltd. 202111based on http://www.cyrilfougeray.com/2020/07/27/firmware-logs-with-stack-trace.html12Released under GNU GPL version 3 or later13"""1415from serial import Serial16import sys17import subprocess18import argparse19import os20import time21from queue import Queue, Empty22from threading import Thread23import signal2425def serial_debug(args):26global spinner, process_cmd27try:28ser = Serial(args.ser_port, 921600) # Configure speed depending on your config29print('Detecting Crash...')30ser.write("dump_crash_log".encode('utf-8')) # Send a newline to start the dump31while 1:32# Read line by line (waiting for '\n')33sys.stdout.write(next(spinner))34sys.stdout.flush()35line = ser.readline()36sys.stdout.write('\b')3738if not line:39break40# When crash is detected41# Crash dump is added into a temporary file42# GDB is used to back trace the crash43if b"Enable logging" in line.strip():44print("Crash detected, retrieving crash info, please be patient...")45dump_file = open(args.dump_fileout, 'wb+')4647# We are now storing the stack dump into the file48ser.write("dump_crash_log".encode('utf-8')) # Send a newline to start the dump49line = ser.readline()50dumping = False51while b"End of dump" not in line.strip():52sys.stdout.write(next(spinner))53sys.stdout.flush()54if b"6343" in line.strip(): # Look for the start of dump55dumping = True56if dumping:57dump_file.write(line)58line = ser.readline()59sys.stdout.write('\b')6061print("Crash info retrieved.\n")6263dump_file.close()64return True65except KeyboardInterrupt:66ser.close()67return False6869def swd_debug(args):70global spinner, process_cmd71openocd_proc = None72try:73# Get BackTrace74ON_POSIX = 'posix' in sys.builtin_module_names7576def enqueue_output(out, queue):77for line in iter(out.readline, b''):78queue.put(line)79out.close()80hardfault_detected = False81# Check if already in hardfault82# p = subprocess.Popen(['arm-none-eabi-gdb', '-nx', '--batch',83# '-ex', 'target extended-remote {}'.format(args.gdb_port),84# '-ex', 'bt',85# args.elf_file], stdout=subprocess.PIPE, close_fds=ON_POSIX)86# q = Queue()87# t = Thread(target=enqueue_output, args=(p.stdout, q))88# t.daemon = True # thread dies with the program89# t.start()9091# print("Checking if already Crashed")92# while p.poll() is None:93# try:94# line = q.get(False)95# if b"HardFault_Handler" in line:96# hardfault_detected = True97# break98# except Empty:99# pass100# sys.stdout.write(next(spinner))101# sys.stdout.flush()102# sys.stdout.write('\b')103if not hardfault_detected:104# lets place breakpoint at HardFault_Handler and wait for it to hit105cmd = ['arm-none-eabi-gdb', '-nx', '--batch',106'-ex', 'target extended-remote {}'.format(args.gdb_port),107'-ex', 'b *&HardFault_Handler',108'-ex', 'continue',109'-ex', 'run',110args.elf_file]111p = subprocess.Popen(cmd, stdout=subprocess.PIPE, close_fds=ON_POSIX)112q = Queue()113t = Thread(target=enqueue_output, args=(p.stdout, q))114t.daemon = True # thread dies with the program115t.start()116print(' '.join(cmd))117# Wait for HardFault_Handler to hit118running = False119while p.poll() is None:120try:121line = q.get(False)122# print(line.decode('utf-8'))123if b"Breakpoint" in line:124time.sleep(1)125p.send_signal(signal.SIGINT)126running = True127if b"HardFault_Handler" in line and running:128hardfault_detected = True129break130except Empty:131pass132sys.stdout.write(next(spinner))133sys.stdout.flush()134sys.stdout.write('\b')135if hardfault_detected:136dir_path = os.path.dirname(os.path.realpath(__file__))137# generate crash log138print("Crash detected, retrieving crash info, please be patient...")139cmd = ['arm-none-eabi-gdb', '-nx', '--batch',140'-ex', 'target extended-remote {}'.format(args.gdb_port),141'-ex', 'set logging file {}'.format(args.dump_fileout),142'-x', os.path.join(dir_path, 'crash_dump.scr'),143args.elf_file]144# We are now storing the stack dump into the file145p = subprocess.Popen(cmd, stdout=subprocess.PIPE, close_fds=ON_POSIX)146q = Queue()147t = Thread(target=enqueue_output, args=(p.stdout, q))148t.daemon = True # thread dies with the program149t.start()150print(' '.join(cmd))151# Wait for HardFault_Handler to hit152# TODO: a progress bar would be nice here153while p.poll() is None:154sys.stdout.write(next(spinner))155sys.stdout.flush()156sys.stdout.write('\b')157print("Crash info retrieved.\n")158return True159else:160print("No crash detected")161raise KeyboardInterrupt162except KeyboardInterrupt:163# kill openocd if running164if openocd_proc is not None and openocd_proc.poll() is None:165openocd_proc.kill()166return False167168if __name__ == '__main__':169global spinner, process_cmd170parser = argparse.ArgumentParser(description='manipulate parameter defaults in an ArduPilot firmware')171172parser.add_argument('elf_file')173parser.add_argument('--ser-debug', action='store_true', help='enable serial debug')174parser.add_argument('--ser-port', help='serial port to use')175parser.add_argument('--dump-debug', action='store_true', help='generate stack trace from dump file')176parser.add_argument('--dump-filein', help='log file to use to generate stack trace')177parser.add_argument('--swd-debug', action='store_true', help='enable swd debug')178parser.add_argument('--gdb-port', default=':3333', help='set gdb port')179parser.add_argument('--dump-fileout', help='filename to dump crash dump')180181args = parser.parse_args()182183if not args.ser_debug and not args.swd_debug and not args.dump_debug:184parser.error('Must enable either --ser-debug or --swd-debug')185186if args.ser_debug and not args.ser_port:187parser.error('--ser-debug requires --port')188189if args.dump_debug and not args.dump_filein:190parser.error('--dump-debug requires --dump-filein')191192#get directory of the script193dir_path = os.path.dirname(os.path.realpath(__file__))194crashdebug_exe = None195if sys.platform == "linux" or sys.platform == "linux2":196crashdebug_exe = str(os.path.join(dir_path, "../../modules/CrashDebug/bins/lin64/CrashDebug"))197elif sys.platform == "darwin":198crashdebug_exe = str(os.path.join(dir_path, "../../modules/CrashDebug/bins/osx/CrashDebug"))199elif sys.platform == "win32":200crashdebug_exe = str(os.path.join(dir_path, "../../modules/CrashDebug/bins/win32/CrashDebug"))201def spinning_cursor():202while True:203for cursor in '|/-\\':204yield cursor205206spinner = spinning_cursor()207dump_file = None208if args.ser_debug:209if args.dump_fileout is None:210args.dump_fileout = "last_crash_dump_ser.txt"211if (serial_debug(args)):212dump_file = args.dump_fileout213elif args.swd_debug:214if args.dump_fileout is None:215args.dump_fileout = "last_crash_dump_gdb.txt"216if (swd_debug(args)):217dump_file = args.dump_fileout218elif args.dump_debug:219dump_file = args.dump_filein220221if dump_file is not None:222print(crashdebug_exe)223print("Processing Crash Dump.\n")224process_cmd = "arm-none-eabi-gdb -nx --batch --quiet " + args.elf_file + " -ex \"set target-charset ASCII\" -ex \"target remote | " + crashdebug_exe + " --elf " + args.elf_file + " --dump " + dump_file + "\" -ex \"set print pretty on\" -ex \"bt full\" -ex \"quit\""225print(process_cmd)226# We can call GDB and CrashDebug using the command and print the results227process = subprocess.Popen(process_cmd, shell=True, stdout=subprocess.PIPE)228output, error = process.communicate()229230print(output.decode("utf-8"))231print("---------\n")232line = b""233else:234print("No crash detected")235print("\nExiting!")236237238