mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-14 12:48:31 -04:00
b1ed77bee9
this prevents nesting errors in use of EXPECT_DELAY(), ensuring we always close the expected delay
36 lines
694 B
C++
36 lines
694 B
C++
#include "Scheduler.h"
|
|
#include "AP_HAL.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;
|
|
}
|
|
|
|
ExpectDelay::ExpectDelay(const AP_HAL::HAL &hal, uint32_t ms) : _hal(hal)
|
|
{
|
|
_hal.scheduler->expect_delay_ms(ms);
|
|
}
|
|
|
|
ExpectDelay::~ExpectDelay()
|
|
{
|
|
_hal.scheduler->expect_delay_ms(0);
|
|
}
|