mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_HAL_VRBRAIN: Scheduler: replace use of in_timerprocess()
This function actually checks if we are not in the main thread rather than if we are in the timer thread. Add a new function that does what it's supposed to do.
This commit is contained in:
parent
1aaba01622
commit
08637f1dcc
@ -138,7 +138,7 @@ void VRBRAINScheduler::delay_microseconds_boost(uint16_t usec)
|
||||
|
||||
void VRBRAINScheduler::delay(uint16_t ms)
|
||||
{
|
||||
if (in_timerprocess()) {
|
||||
if (!in_main_thread()) {
|
||||
::printf("ERROR: delay() from timer process\n");
|
||||
return;
|
||||
}
|
||||
@ -375,6 +375,11 @@ bool VRBRAINScheduler::in_timerprocess()
|
||||
return getpid() != _main_task_pid;
|
||||
}
|
||||
|
||||
bool VRBRAINScheduler::in_main_thread()
|
||||
{
|
||||
return getpid() == _main_task_pid;
|
||||
}
|
||||
|
||||
void VRBRAINScheduler::system_initialized() {
|
||||
if (_initialized) {
|
||||
AP_HAL::panic("PANIC: scheduler::system_initialized called"
|
||||
|
Loading…
Reference in New Issue
Block a user