mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_PX4: 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
93a558ce5c
commit
9e66938f68
@ -173,7 +173,7 @@ void PX4Scheduler::delay_microseconds_boost(uint16_t usec)
|
||||
|
||||
void PX4Scheduler::delay(uint16_t ms)
|
||||
{
|
||||
if (in_timerprocess()) {
|
||||
if (!in_main_thread()) {
|
||||
::printf("ERROR: delay() from timer process\n");
|
||||
return;
|
||||
}
|
||||
@ -448,6 +448,11 @@ bool PX4Scheduler::in_timerprocess()
|
||||
return getpid() != _main_task_pid;
|
||||
}
|
||||
|
||||
bool PX4Scheduler::in_main_thread()
|
||||
{
|
||||
return getpid() == _main_task_pid;
|
||||
}
|
||||
|
||||
void PX4Scheduler::system_initialized()
|
||||
{
|
||||
if (_initialized) {
|
||||
|
@ -59,6 +59,7 @@ public:
|
||||
void reboot(bool hold_in_bootloader);
|
||||
|
||||
bool in_timerprocess();
|
||||
bool in_main_thread();
|
||||
void system_initialized();
|
||||
void hal_initialized() { _hal_initialized = true; }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user