mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_HAL: added EXPECT_DELAY() macro
this prevents nesting errors in use of EXPECT_DELAY(), ensuring we always close the expected delay
This commit is contained in:
parent
3772f58be9
commit
b1ed77bee9
@ -1,4 +1,5 @@
|
||||
#include "Scheduler.h"
|
||||
#include "AP_HAL.h"
|
||||
|
||||
using namespace AP_HAL;
|
||||
|
||||
@ -22,3 +23,13 @@ void Scheduler::call_delay_cb()
|
||||
_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);
|
||||
}
|
||||
|
@ -121,3 +121,19 @@ private:
|
||||
bool _in_delay_callback : 1;
|
||||
|
||||
};
|
||||
|
||||
/*
|
||||
helper macro and class to make using expect_delay_ms() safer and easier
|
||||
*/
|
||||
class ExpectDelay {
|
||||
public:
|
||||
ExpectDelay(const AP_HAL::HAL &hal, uint32_t ms);
|
||||
~ExpectDelay();
|
||||
|
||||
private:
|
||||
const AP_HAL::HAL &_hal;
|
||||
};
|
||||
|
||||
#define EXPECT_DELAY(hal, ms) DELAY_JOIN( hal, ms, __COUNTER__ )
|
||||
#define DELAY_JOIN( hal, ms, counter) _DO_DELAY_JOIN( hal, ms, counter )
|
||||
#define _DO_DELAY_JOIN( hal, ms, counter ) ExpectDelay _getdelay ## counter(hal, ms)
|
||||
|
Loading…
Reference in New Issue
Block a user