mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 14:13:42 -04:00
0ad53e53eb
This allows us to move a lot of delay handling from vehicle classes into HAL Scheduler. The most notable improvement is that it moves the detection of recursion into the Scheduler, out of each separate vehicle.
25 lines
481 B
C++
25 lines
481 B
C++
#include "Scheduler.h"
|
|
|
|
using namespace AP_HAL;
|
|
|
|
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::call_delay_cb()
|
|
{
|
|
if (_delay_cb == nullptr) {
|
|
return;
|
|
}
|
|
if (_in_delay_callback) {
|
|
// don't recurse!
|
|
return;
|
|
}
|
|
_in_delay_callback = true;
|
|
_delay_cb();
|
|
_in_delay_callback = false;
|
|
}
|