AP_HAL_PX4: move delay callback handling to base HAL Scheduler class

This commit is contained in:
Peter Barker 2018-05-08 15:55:31 +10:00 committed by Andrew Tridgell
parent d5cad015dc
commit 83bb6e4a9a
2 changed files with 1 additions and 11 deletions

View File

@ -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++) {

View File

@ -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);