AP_HAL_ChibiOS: move delay callback handling to base HAL Scheduler class

This commit is contained in:
Peter Barker 2018-05-08 15:52:48 +10:00 committed by Andrew Tridgell
parent 0ad53e53eb
commit b2a81405ea
2 changed files with 1 additions and 13 deletions

View File

@ -179,20 +179,11 @@ void Scheduler::delay(uint16_t ms)
while ((AP_HAL::micros64() - start)/1000 < ms) {
delay_microseconds(1000);
if (_min_delay_cb_ms <= ms) {
if (_delay_cb) {
_delay_cb();
}
call_delay_cb();
}
}
}
void Scheduler::register_delay_callback(AP_HAL::Proc proc,
uint16_t min_time_ms)
{
_delay_cb = proc;
_min_delay_cb_ms = min_time_ms;
}
void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
{
for (uint8_t i = 0; i < _num_timer_procs; i++) {

View File

@ -70,7 +70,6 @@ public:
void delay_microseconds(uint16_t us) override;
void delay_microseconds_boost(uint16_t us) override;
void boost_end(void) override;
void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms) override;
void register_timer_process(AP_HAL::MemberProc) override;
void register_io_process(AP_HAL::MemberProc) override;
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) override;
@ -99,8 +98,6 @@ public:
private:
bool _initialized;
volatile bool _hal_initialized;
AP_HAL::Proc _delay_cb;
uint16_t _min_delay_cb_ms;
AP_HAL::Proc _failsafe;
bool _called_boost;
bool _priority_boosted;