Browse Source

AP_HAL: update Device interface for periodic tasks

Replace the previous not-implemented interface with a set of new methods
that can be resonably implemented:

    - register_periodic_callback() now receives a functor returning bool
      to easily allow "oneshot" timers

    - adjust_periodic_callback() allows the caller to change the timer
      for a specific handle. This way drivers like MS5611 can adjust the
      timer depending on its state machine: the time to sample
      temperature is smaller than the time to get a pressure sample

    - add unregister_callback(): since we have an opaque pointer, we
      can't tell the user to just delete it in order to unregister the
      callback
master
Lucas De Marchi 9 years ago
parent
commit
37de995960
  1. 26
      libraries/AP_HAL/Device.h
  2. 8
      libraries/AP_HAL/I2CDevice.h
  3. 8
      libraries/AP_HAL/SPIDevice.h

26
libraries/AP_HAL/Device.h

@ -19,7 +19,7 @@ @@ -19,7 +19,7 @@
#include <inttypes.h>
#include "AP_HAL_Namespace.h"
#include "utility/functor.h"
/*
* This is an interface abstracting I2C and SPI devices
@ -36,7 +36,8 @@ public: @@ -36,7 +36,8 @@ public:
SPEED_LOW,
};
typedef void PeriodicHandle;
FUNCTOR_TYPEDEF(PeriodicCb, bool);
typedef void* PeriodicHandle;
const enum BusType bus_type;
@ -118,9 +119,26 @@ public: @@ -118,9 +119,26 @@ public:
* lock must be taken.
*
* Return: A handle for this periodic callback. To cancel the callback
* delete the handle.
* call #unregister_callback() or return false on the callback.
*/
virtual PeriodicHandle *register_periodic_callback(uint32_t period_usec, AP_HAL::MemberProc) = 0;
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb) = 0;
/*
* Adjust the time for the periodic callback registered with
* #register_periodic_callback. Note that the time will be re-calculated
* from the moment this call is made and expire after @period_usec.
*
* Return: true if periodic callback was sucessfully adjusted, false otherwise.
*/
virtual bool adjust_periodic_callback(PeriodicHandle h, uint32_t period_usec) = 0;
/*
* Cancel a periodic callback on this bus.
*
* Return: true if callback was successfully unregistered, false
* otherwise.
*/
virtual bool unregister_callback(PeriodicHandle h) { return false; }
/*
* Temporary method to get the fd used by this device: it's here only for

8
libraries/AP_HAL/I2CDevice.h

@ -60,8 +60,12 @@ public: @@ -60,8 +60,12 @@ public:
virtual Semaphore *get_semaphore() override = 0;
/* See Device::register_periodic_callback() */
virtual Device::PeriodicHandle *register_periodic_callback(
uint32_t period_usec, MemberProc) override = 0;
virtual Device::PeriodicHandle register_periodic_callback(
uint32_t period_usec, Device::PeriodicCb) override = 0;
/* See Device::adjust_periodic_callback() */
virtual bool adjust_periodic_callback(
Device::PeriodicHandle h, uint32_t period_usec) override = 0;
/* See Device::get_fd() */
virtual int get_fd() override = 0;

8
libraries/AP_HAL/SPIDevice.h

@ -50,8 +50,12 @@ public: @@ -50,8 +50,12 @@ public:
virtual Semaphore *get_semaphore() override = 0;
/* See Device::register_periodic_callback() */
virtual Device::PeriodicHandle *register_periodic_callback(
uint32_t period_usec, MemberProc) override = 0;
virtual Device::PeriodicHandle register_periodic_callback(
uint32_t period_usec, Device::PeriodicCb) override = 0;
/* See Device::adjust_periodic_callback() */
virtual bool adjust_periodic_callback(
PeriodicHandle h, uint32_t period_usec) override { return false; }
virtual int get_fd() override = 0;
};

Loading…
Cancel
Save