mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_PX4: make in_main_thread const and override
This commit is contained in:
parent
044cac42e8
commit
8d208ea514
|
@ -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;
|
||||
}
|
||||
|
|
|
@ -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; }
|
||||
|
||||
|
|
Loading…
Reference in New Issue