diff --git a/libraries/AP_HAL_PX4/Scheduler.cpp b/libraries/AP_HAL_PX4/Scheduler.cpp index 8441b9046b..78b730c7db 100644 --- a/libraries/AP_HAL_PX4/Scheduler.cpp +++ b/libraries/AP_HAL_PX4/Scheduler.cpp @@ -443,7 +443,7 @@ void *PX4Scheduler::_uavcan_thread(void *arg) } #endif -bool PX4Scheduler::in_main_thread() +bool PX4Scheduler::in_main_thread() const { return getpid() == _main_task_pid; } diff --git a/libraries/AP_HAL_PX4/Scheduler.h b/libraries/AP_HAL_PX4/Scheduler.h index 4ca33698c9..46baf58163 100644 --- a/libraries/AP_HAL_PX4/Scheduler.h +++ b/libraries/AP_HAL_PX4/Scheduler.h @@ -58,7 +58,7 @@ public: void resume_timer_procs(); void reboot(bool hold_in_bootloader); - bool in_main_thread(); + bool in_main_thread() const override; void system_initialized(); void hal_initialized() { _hal_initialized = true; }