mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_HAL_VRBRAIN: move delay callback handling to base HAL Scheduler class
This commit is contained in:
parent
190bd18769
commit
864f41406d
@ -184,9 +184,7 @@ void VRBRAINScheduler::delay(uint16_t ms)
|
||||
!_vrbrain_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 VRBRAINScheduler::delay(uint16_t ms)
|
||||
}
|
||||
}
|
||||
|
||||
void VRBRAINScheduler::register_delay_callback(AP_HAL::Proc proc,
|
||||
uint16_t min_time_ms)
|
||||
{
|
||||
_delay_cb = proc;
|
||||
_min_delay_cb_ms = min_time_ms;
|
||||
}
|
||||
|
||||
void VRBRAINScheduler::register_timer_process(AP_HAL::MemberProc proc)
|
||||
{
|
||||
for (uint8_t i = 0; i < _num_timer_procs; i++) {
|
||||
|
@ -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);
|
||||
@ -67,8 +66,6 @@ public:
|
||||
private:
|
||||
bool _initialized;
|
||||
volatile bool _hal_initialized;
|
||||
AP_HAL::Proc _delay_cb;
|
||||
uint16_t _min_delay_cb_ms;
|
||||
AP_HAL::Proc _failsafe;
|
||||
|
||||
volatile bool _timer_suspended;
|
||||
|
Loading…
Reference in New Issue
Block a user