mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_QURT: 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
9e66938f68
commit
1aaba01622
|
@ -70,7 +70,7 @@ void Scheduler::delay_microseconds(uint16_t usec)
|
||||||
|
|
||||||
void Scheduler::delay(uint16_t ms)
|
void Scheduler::delay(uint16_t ms)
|
||||||
{
|
{
|
||||||
if (in_timerprocess()) {
|
if (!in_main_thread()) {
|
||||||
::printf("ERROR: delay() from timer process\n");
|
::printf("ERROR: delay() from timer process\n");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -266,6 +266,11 @@ bool Scheduler::in_timerprocess()
|
||||||
return getpid() != _main_task_pid;
|
return getpid() != _main_task_pid;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool Scheduler::in_main_thread()
|
||||||
|
{
|
||||||
|
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"
|
||||||
|
|
|
@ -31,6 +31,7 @@ public:
|
||||||
void resume_timer_procs();
|
void resume_timer_procs();
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
||||||
|
bool in_main_thread();
|
||||||
bool in_timerprocess();
|
bool in_timerprocess();
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
void hal_initialized();
|
void hal_initialized();
|
||||||
|
|
Loading…
Reference in New Issue