mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_HAL_SITL: generate a core file for a given PID
Similarly to dumpstack.sh, uses gdb to dump a core file
This commit is contained in:
parent
2f7603e08e
commit
7a9dd8127a
@ -53,6 +53,7 @@ static void _sig_fpe(int signum)
|
|||||||
{
|
{
|
||||||
fprintf(stderr, "ERROR: Floating point exception - aborting\n");
|
fprintf(stderr, "ERROR: Floating point exception - aborting\n");
|
||||||
AP_HAL::dump_stack_trace();
|
AP_HAL::dump_stack_trace();
|
||||||
|
AP_HAL::dump_core_file();
|
||||||
abort();
|
abort();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -61,6 +62,7 @@ static void _sig_segv(int signum)
|
|||||||
{
|
{
|
||||||
fprintf(stderr, "ERROR: segmentation fault - aborting\n");
|
fprintf(stderr, "ERROR: segmentation fault - aborting\n");
|
||||||
AP_HAL::dump_stack_trace();
|
AP_HAL::dump_stack_trace();
|
||||||
|
AP_HAL::dump_core_file();
|
||||||
abort();
|
abort();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -37,6 +37,7 @@ void panic(const char *errormsg, ...)
|
|||||||
printf("\n");
|
printf("\n");
|
||||||
|
|
||||||
dump_stack_trace();
|
dump_stack_trace();
|
||||||
|
dump_core_file();
|
||||||
|
|
||||||
if (getenv("SITL_PANIC_EXIT")) {
|
if (getenv("SITL_PANIC_EXIT")) {
|
||||||
// this is used on the autotest server to prevent us waiting
|
// this is used on the autotest server to prevent us waiting
|
||||||
@ -47,52 +48,54 @@ void panic(const char *errormsg, ...)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// partly flogged from: https://github.com/tridge/junkcode/blob/master/segv_handler/segv_handler.c
|
// partly flogged from: https://github.com/tridge/junkcode/blob/master/segv_handler/segv_handler.c
|
||||||
void dump_stack_trace()
|
void run_command_on_ownpid(const char *commandname)
|
||||||
{
|
{
|
||||||
// find dumpstack command:
|
// find dumpstack command:
|
||||||
const char *dumpstack = "dumpstack.sh"; // if we can't find it trust in PATH
|
const char *command_filepath = commandname; // if we can't find it trust in PATH
|
||||||
struct stat statbuf;
|
struct stat statbuf;
|
||||||
const char *paths[] {
|
const char *paths[] {
|
||||||
"Tools/scripts/dumpstack.sh",
|
"Tools/scripts/%s",
|
||||||
"APM/Tools/scripts/dumpstack.sh", // for autotest server
|
"APM/Tools/scripts/%s", // for autotest server
|
||||||
"../Tools/scripts/dumpstack.sh", // when run from e.g. ArduCopter subdirectory
|
"../Tools/scripts/%s", // when run from e.g. ArduCopter subdirectory
|
||||||
};
|
};
|
||||||
|
char buffer[60];
|
||||||
for (uint8_t i=0; i<ARRAY_SIZE(paths); i++) {
|
for (uint8_t i=0; i<ARRAY_SIZE(paths); i++) {
|
||||||
if (::stat(paths[i], &statbuf) != -1) {
|
// form up a filepath from each path and commandname; if it
|
||||||
dumpstack = paths[i];
|
// exists, use it
|
||||||
|
snprintf(buffer, sizeof(buffer), paths[i], commandname);
|
||||||
|
if (::stat(buffer, &statbuf) != -1) {
|
||||||
|
command_filepath = buffer;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
char cmd[100];
|
|
||||||
char progname[100];
|
char progname[100];
|
||||||
char *p;
|
int n = readlink("/proc/self/exe", progname, sizeof(progname)-1);
|
||||||
int n;
|
|
||||||
|
|
||||||
n = readlink("/proc/self/exe", progname, sizeof(progname)-1);
|
|
||||||
if (n == -1) {
|
if (n == -1) {
|
||||||
strncpy(progname, "unknown", sizeof(progname));
|
strncpy(progname, "unknown", sizeof(progname));
|
||||||
n = strlen(progname);
|
n = strlen(progname);
|
||||||
}
|
}
|
||||||
progname[n] = 0;
|
progname[n] = 0;
|
||||||
|
|
||||||
p = strrchr(progname, '/');
|
char *p = strrchr(progname, '/');
|
||||||
if (p != nullptr) {
|
if (p != nullptr) {
|
||||||
*p = 0;
|
*p = 0;
|
||||||
} else {
|
} else {
|
||||||
p = progname;
|
p = progname;
|
||||||
}
|
}
|
||||||
|
|
||||||
char output_filepath[30];
|
char output_filepath[80];
|
||||||
snprintf(output_filepath,
|
snprintf(output_filepath,
|
||||||
ARRAY_SIZE(output_filepath),
|
ARRAY_SIZE(output_filepath),
|
||||||
"dumpstack_%s.%d.out",
|
"%s_%s.%d.out",
|
||||||
|
commandname,
|
||||||
p+1,
|
p+1,
|
||||||
(int)getpid());
|
(int)getpid());
|
||||||
|
char cmd[200];
|
||||||
snprintf(cmd,
|
snprintf(cmd,
|
||||||
sizeof(cmd),
|
sizeof(cmd),
|
||||||
"sh %s %d >%s 2>&1",
|
"sh %s %d >%s 2>&1",
|
||||||
dumpstack,
|
command_filepath,
|
||||||
(int)getpid(),
|
(int)getpid(),
|
||||||
output_filepath);
|
output_filepath);
|
||||||
fprintf(stderr, "Running: %s\n", cmd);
|
fprintf(stderr, "Running: %s\n", cmd);
|
||||||
@ -101,8 +104,8 @@ void dump_stack_trace()
|
|||||||
fprintf(stderr, "Failed\n");
|
fprintf(stderr, "Failed\n");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
fprintf(stderr, "Stack dumped\n");
|
fprintf(stderr, "%s has been run. Output was:\n", commandname);
|
||||||
|
fprintf(stderr, "-------------- begin %s output ----------------\n", commandname);
|
||||||
// print the trace on stderr:
|
// print the trace on stderr:
|
||||||
int fd = open(output_filepath, O_RDONLY);
|
int fd = open(output_filepath, O_RDONLY);
|
||||||
if (fd == -1) {
|
if (fd == -1) {
|
||||||
@ -124,8 +127,17 @@ void dump_stack_trace()
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
fprintf(stderr, "-------------- end %s output ----------------\n", commandname);
|
||||||
close(fd);
|
close(fd);
|
||||||
}
|
}
|
||||||
|
void dump_stack_trace()
|
||||||
|
{
|
||||||
|
run_command_on_ownpid("dumpstack.sh");
|
||||||
|
}
|
||||||
|
void dump_core_file()
|
||||||
|
{
|
||||||
|
run_command_on_ownpid("dumpcore.sh");
|
||||||
|
}
|
||||||
|
|
||||||
uint32_t micros()
|
uint32_t micros()
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user