mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_VRBRAIN: make in_main_thread const and override
This commit is contained in:
parent
8d208ea514
commit
9cb23f6108
|
@ -370,7 +370,7 @@ void *VRBRAINScheduler::_storage_thread(void *arg)
|
|||
return nullptr;
|
||||
}
|
||||
|
||||
bool VRBRAINScheduler::in_main_thread()
|
||||
bool VRBRAINScheduler::in_main_thread() const
|
||||
{
|
||||
return getpid() == _main_task_pid;
|
||||
}
|
||||
|
|
|
@ -55,6 +55,7 @@ public:
|
|||
void resume_timer_procs();
|
||||
void reboot(bool hold_in_bootloader);
|
||||
|
||||
bool in_main_thread() const override;
|
||||
void system_initialized();
|
||||
void hal_initialized() { _hal_initialized = true; }
|
||||
|
||||
|
|
Loading…
Reference in New Issue