HAL_PX4: set thread names for main threads

This commit is contained in:
Andrew Tridgell 2016-11-28 09:47:49 +11:00
parent 4ef4016e5e
commit 12e0c840e8
1 changed files with 8 additions and 0 deletions

View File

@ -266,6 +266,8 @@ void *PX4Scheduler::_timer_thread(void *arg)
PX4Scheduler *sched = (PX4Scheduler *)arg;
uint32_t last_ran_overtime = 0;
pthread_setname_np(pthread_self(), "apm_timer");
while (!sched->_hal_initialized) {
poll(nullptr, 0, 1);
}
@ -317,6 +319,8 @@ void *PX4Scheduler::_uart_thread(void *arg)
{
PX4Scheduler *sched = (PX4Scheduler *)arg;
pthread_setname_np(pthread_self(), "apm_uart");
while (!sched->_hal_initialized) {
poll(nullptr, 0, 1);
}
@ -338,6 +342,8 @@ void *PX4Scheduler::_io_thread(void *arg)
{
PX4Scheduler *sched = (PX4Scheduler *)arg;
pthread_setname_np(pthread_self(), "apm_io");
while (!sched->_hal_initialized) {
poll(nullptr, 0, 1);
}
@ -356,6 +362,8 @@ void *PX4Scheduler::_storage_thread(void *arg)
{
PX4Scheduler *sched = (PX4Scheduler *)arg;
pthread_setname_np(pthread_self(), "apm_storage");
while (!sched->_hal_initialized) {
poll(nullptr, 0, 1);
}