diff --git a/libraries/AP_HAL_PX4/Scheduler.cpp b/libraries/AP_HAL_PX4/Scheduler.cpp index a3a02f7e2e..96adc4cb5f 100644 --- a/libraries/AP_HAL_PX4/Scheduler.cpp +++ b/libraries/AP_HAL_PX4/Scheduler.cpp @@ -184,9 +184,7 @@ void PX4Scheduler::delay(uint16_t ms) !_px4_thread_should_exit) { delay_microseconds_semaphore(1000); if (_min_delay_cb_ms <= ms) { - if (_delay_cb) { - _delay_cb(); - } + call_delay_cb(); } } perf_end(_perf_delay); @@ -195,13 +193,6 @@ void PX4Scheduler::delay(uint16_t ms) } } -void PX4Scheduler::register_delay_callback(AP_HAL::Proc proc, - uint16_t min_time_ms) -{ - _delay_cb = proc; - _min_delay_cb_ms = min_time_ms; -} - void PX4Scheduler::register_timer_process(AP_HAL::MemberProc proc) { for (uint8_t i = 0; i < _num_timer_procs; i++) { diff --git a/libraries/AP_HAL_PX4/Scheduler.h b/libraries/AP_HAL_PX4/Scheduler.h index cc8989189e..a9b4f59df9 100644 --- a/libraries/AP_HAL_PX4/Scheduler.h +++ b/libraries/AP_HAL_PX4/Scheduler.h @@ -50,7 +50,6 @@ public: void delay(uint16_t ms); void delay_microseconds(uint16_t us); void delay_microseconds_boost(uint16_t us); - void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms); void register_timer_process(AP_HAL::MemberProc); void register_io_process(AP_HAL::MemberProc); void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);