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:
Lucas De Marchi 2017-08-02 01:44:21 -07:00
parent 9e66938f68
commit 1aaba01622
2 changed files with 7 additions and 1 deletions

View File

@ -70,7 +70,7 @@ void Scheduler::delay_microseconds(uint16_t usec)
void Scheduler::delay(uint16_t ms)
{
if (in_timerprocess()) {
if (!in_main_thread()) {
::printf("ERROR: delay() from timer process\n");
return;
}
@ -266,6 +266,11 @@ bool Scheduler::in_timerprocess()
return getpid() != _main_task_pid;
}
bool Scheduler::in_main_thread()
{
return getpid() == _main_task_pid;
}
void Scheduler::system_initialized() {
if (_initialized) {
AP_HAL::panic("PANIC: scheduler::system_initialized called"

View File

@ -31,6 +31,7 @@ public:
void resume_timer_procs();
void reboot(bool hold_in_bootloader);
bool in_main_thread();
bool in_timerprocess();
void system_initialized();
void hal_initialized();