diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index 36b1d7a551..5d4717eee0 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -752,7 +752,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_ be used to prevent watchdog reset during expected long delays A value of zero cancels the previous expected delay */ -void Scheduler::_expect_delay_ms(uint32_t ms) +void Scheduler::expect_delay_ms(uint32_t ms) { if (!in_main_thread()) { // only for main thread @@ -762,8 +762,6 @@ void Scheduler::_expect_delay_ms(uint32_t ms) // pat once immediately watchdog_pat(); - WITH_SEMAPHORE(expect_delay_sem); - if (ms == 0) { if (expect_delay_nesting > 0) { expect_delay_nesting--; @@ -789,18 +787,6 @@ void Scheduler::_expect_delay_ms(uint32_t ms) } } -/* - this is _expect_delay_ms() with check that we are in the main thread - */ -void Scheduler::expect_delay_ms(uint32_t ms) -{ - if (!in_main_thread()) { - // only for main thread - return; - } - _expect_delay_ms(ms); -} - // pat the watchdog void Scheduler::watchdog_pat(void) { diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.h b/libraries/AP_HAL_ChibiOS/Scheduler.h index 47052d79d7..f0178b3495 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.h +++ b/libraries/AP_HAL_ChibiOS/Scheduler.h @@ -115,7 +115,6 @@ public: be used to prevent watchdog reset during expected long delays A value of zero cancels the previous expected delay */ - void _expect_delay_ms(uint32_t ms); void expect_delay_ms(uint32_t ms) override; /* @@ -153,7 +152,6 @@ private: uint32_t expect_delay_start; uint32_t expect_delay_length; uint32_t expect_delay_nesting; - HAL_Semaphore expect_delay_sem; AP_HAL::MemberProc _timer_proc[CHIBIOS_SCHEDULER_MAX_TIMER_PROCS]; uint8_t _num_timer_procs;