Browse Source

AP_HAL: removed hal argument to EXPECT_DELAY_MS()

mission-4.1.18
Andrew Tridgell 6 years ago
parent
commit
911a99b79e
  1. 8
      libraries/AP_HAL/Scheduler.cpp
  2. 11
      libraries/AP_HAL/Scheduler.h

8
libraries/AP_HAL/Scheduler.cpp

@ -3,6 +3,8 @@
using namespace AP_HAL; using namespace AP_HAL;
extern const AP_HAL::HAL& hal;
void Scheduler::register_delay_callback(AP_HAL::Proc proc, void Scheduler::register_delay_callback(AP_HAL::Proc proc,
uint16_t min_time_ms) uint16_t min_time_ms)
{ {
@ -24,12 +26,12 @@ void Scheduler::call_delay_cb()
_in_delay_callback = false; _in_delay_callback = false;
} }
ExpectDelay::ExpectDelay(const AP_HAL::HAL &hal, uint32_t ms) : _hal(hal) ExpectDelay::ExpectDelay(uint32_t ms)
{ {
_hal.scheduler->expect_delay_ms(ms); hal.scheduler->expect_delay_ms(ms);
} }
ExpectDelay::~ExpectDelay() ExpectDelay::~ExpectDelay()
{ {
_hal.scheduler->expect_delay_ms(0); hal.scheduler->expect_delay_ms(0);
} }

11
libraries/AP_HAL/Scheduler.h

@ -127,13 +127,10 @@ private:
*/ */
class ExpectDelay { class ExpectDelay {
public: public:
ExpectDelay(const AP_HAL::HAL &hal, uint32_t ms); ExpectDelay(uint32_t ms);
~ExpectDelay(); ~ExpectDelay();
private:
const AP_HAL::HAL &_hal;
}; };
#define EXPECT_DELAY(hal, ms) DELAY_JOIN( hal, ms, __COUNTER__ ) #define EXPECT_DELAY_MS(ms) DELAY_JOIN( ms, __COUNTER__ )
#define DELAY_JOIN( hal, ms, counter) _DO_DELAY_JOIN( hal, ms, counter ) #define DELAY_JOIN( ms, counter) _DO_DELAY_JOIN( ms, counter )
#define _DO_DELAY_JOIN( hal, ms, counter ) ExpectDelay _getdelay ## counter(hal, ms) #define _DO_DELAY_JOIN( ms, counter ) ExpectDelay _getdelay ## counter(ms)

Loading…
Cancel
Save