mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_QURT: make in_main_thread const and override
# Conflicts: # libraries/AP_HAL_QURT/Scheduler.cpp # libraries/AP_HAL_QURT/Scheduler.h
This commit is contained in:
parent
9d897f5da6
commit
844bcf33c9
@ -266,6 +266,11 @@ bool Scheduler::in_timerprocess()
|
|||||||
return getpid() != _main_task_pid;
|
return getpid() != _main_task_pid;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool Scheduler::in_main_thread() const
|
||||||
|
{
|
||||||
|
return getpid() == _main_task_pid;
|
||||||
|
}
|
||||||
|
|
||||||
void Scheduler::system_initialized() {
|
void Scheduler::system_initialized() {
|
||||||
if (_initialized) {
|
if (_initialized) {
|
||||||
AP_HAL::panic("PANIC: scheduler::system_initialized called"
|
AP_HAL::panic("PANIC: scheduler::system_initialized called"
|
||||||
|
@ -32,6 +32,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();
|
void hal_initialized();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user