mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_F4Light: call delay callback on scheduler instance
Also correct name of superclass method
This commit is contained in:
parent
939aec090e
commit
75c8644fb5
|
@ -266,8 +266,8 @@ void Scheduler::_delay(uint16_t ms)
|
||||||
uint32_t now;
|
uint32_t now;
|
||||||
|
|
||||||
while((now=_micros()) - start < dt) {
|
while((now=_micros()) - start < dt) {
|
||||||
if (_min_delay_cb_ms <= ms) { // MAVlink callback uses 5ms
|
if (hal.scheduler->_min_delay_cb_ms <= ms) { // MAVlink callback uses 5ms
|
||||||
call_delay_cb();
|
hal.scheduler->call_delay_cb();
|
||||||
yield(1000 - (_micros() - now)); // to not stop MAVlink callback
|
yield(1000 - (_micros() - now)); // to not stop MAVlink callback
|
||||||
} else {
|
} else {
|
||||||
yield(dt); // for full time
|
yield(dt); // for full time
|
||||||
|
@ -352,7 +352,7 @@ void Scheduler::register_delay_callback(AP_HAL::Proc proc, uint16_t min_time_ms)
|
||||||
init_done=true;
|
init_done=true;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_HAL::register_delay_callback(proc, min_time_ms);
|
AP_HAL::Scheduler::register_delay_callback(proc, min_time_ms);
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
Loading…
Reference in New Issue