mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 23:18:29 -04:00
AP_HAL_PX4: make in_main_thread const and override
# Conflicts: # libraries/AP_HAL_PX4/Scheduler.cpp # libraries/AP_HAL_PX4/Scheduler.h
This commit is contained in:
parent
3ef150e9f7
commit
8b472919da
@ -448,6 +448,11 @@ bool PX4Scheduler::in_timerprocess()
|
|||||||
return getpid() != _main_task_pid;
|
return getpid() != _main_task_pid;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool PX4Scheduler::in_main_thread() const
|
||||||
|
{
|
||||||
|
return getpid() == _main_task_pid;
|
||||||
|
}
|
||||||
|
|
||||||
void PX4Scheduler::system_initialized()
|
void PX4Scheduler::system_initialized()
|
||||||
{
|
{
|
||||||
if (_initialized) {
|
if (_initialized) {
|
||||||
|
@ -59,6 +59,7 @@ public:
|
|||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
||||||
bool in_timerprocess();
|
bool in_timerprocess();
|
||||||
|
bool in_main_thread() const override;
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
void hal_initialized() { _hal_initialized = true; }
|
void hal_initialized() { _hal_initialized = true; }
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user