mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_HAL_Linux: move delay callback handling to base HAL Scheduler class
This commit is contained in:
parent
f2d73bb9b0
commit
d5cad015dc
@ -164,9 +164,7 @@ void Scheduler::delay(uint16_t ms)
|
|||||||
// this yields the CPU to other apps
|
// this yields the CPU to other apps
|
||||||
microsleep(1000);
|
microsleep(1000);
|
||||||
if (_min_delay_cb_ms <= ms) {
|
if (_min_delay_cb_ms <= ms) {
|
||||||
if (_delay_cb) {
|
call_delay_cb();
|
||||||
_delay_cb();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -179,13 +177,6 @@ void Scheduler::delay_microseconds(uint16_t us)
|
|||||||
microsleep(us);
|
microsleep(us);
|
||||||
}
|
}
|
||||||
|
|
||||||
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)
|
void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
|
||||||
{
|
{
|
||||||
for (uint8_t i = 0; i < _num_timer_procs; i++) {
|
for (uint8_t i = 0; i < _num_timer_procs; i++) {
|
||||||
|
@ -27,8 +27,6 @@ public:
|
|||||||
void init();
|
void init();
|
||||||
void delay(uint16_t ms);
|
void delay(uint16_t ms);
|
||||||
void delay_microseconds(uint16_t us);
|
void delay_microseconds(uint16_t us);
|
||||||
void register_delay_callback(AP_HAL::Proc,
|
|
||||||
uint16_t min_time_ms);
|
|
||||||
|
|
||||||
void register_timer_process(AP_HAL::MemberProc);
|
void register_timer_process(AP_HAL::MemberProc);
|
||||||
void register_io_process(AP_HAL::MemberProc);
|
void register_io_process(AP_HAL::MemberProc);
|
||||||
@ -69,9 +67,6 @@ private:
|
|||||||
|
|
||||||
void _debug_stack();
|
void _debug_stack();
|
||||||
|
|
||||||
AP_HAL::Proc _delay_cb;
|
|
||||||
uint16_t _min_delay_cb_ms;
|
|
||||||
|
|
||||||
AP_HAL::Proc _failsafe;
|
AP_HAL::Proc _failsafe;
|
||||||
|
|
||||||
bool _initialized;
|
bool _initialized;
|
||||||
|
Loading…
Reference in New Issue
Block a user