Browse Source

AP_HAL: move delay callback handling to base HAL Scheduler class

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.
master
Peter Barker 7 years ago committed by Andrew Tridgell
parent
commit
0ad53e53eb
  1. 24
      libraries/AP_HAL/Scheduler.cpp
  2. 23
      libraries/AP_HAL/Scheduler.h

24
libraries/AP_HAL/Scheduler.cpp

@ -0,0 +1,24 @@ @@ -0,0 +1,24 @@
#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;
}

23
libraries/AP_HAL/Scheduler.h

@ -33,9 +33,15 @@ public: @@ -33,9 +33,15 @@ public:
end the priority boost from delay_microseconds_boost()
*/
virtual void boost_end(void) {}
// register a function to be called by the scheduler if it needs
// to sleep for more than min_time_ms
virtual void register_delay_callback(AP_HAL::Proc,
uint16_t min_time_ms) = 0;
uint16_t min_time_ms);
// returns true if the Scheduler has called the delay callback
// function. If you are on the main thread that means your call
// stack has the scheduler on it somewhere.
virtual bool in_delay_callback() const { return _in_delay_callback; }
// register a high priority timer task
virtual void register_timer_process(AP_HAL::MemberProc) = 0;
@ -76,5 +82,16 @@ public: @@ -76,5 +82,16 @@ public:
restore interrupt state from disable_interrupts_save()
*/
virtual void restore_interrupts(void *) {}
protected:
// called by subclasses when they need to delay for some time
virtual void call_delay_cb();
uint16_t _min_delay_cb_ms;
private:
AP_HAL::Proc _delay_cb;
bool _in_delay_callback : 1;
};

Loading…
Cancel
Save