mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_HAL_Linux: set thread name for ease debug
Use pthread_setname_np() to set thread name so it's easier to debug what't going on with each of them. This is the example output of the relevant par of "ps -Leo class,rtprio,wchan,comm": FF 12 futex_ ArduCopter.elf FF 15 usleep sched-timer FF 14 hrtime sched-uart FF 13 poll_s sched-rcin FF 11 hrtime sched-tonealarm FF 10 hrtime sched-io
This commit is contained in:
parent
2c48434110
commit
b7355dc62b
@ -49,6 +49,10 @@ void LinuxScheduler::_create_realtime_thread(pthread_t *ctx, int rtprio,
|
||||
panic(PSTR("Failed to create thread"));
|
||||
}
|
||||
pthread_attr_destroy(&attr);
|
||||
|
||||
if (name) {
|
||||
pthread_setname_np(*ctx, name);
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxScheduler::init(void* machtnichts)
|
||||
|
Loading…
Reference in New Issue
Block a user