aboutsummaryrefslogtreecommitdiff
path: root/src/platforms/px4_subscriber.h
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-18 12:11:35 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-18 12:11:35 +0100
commite697413667579ffb1c5900193a03da257c05d11a (patch)
treeeae619c30f4e0179cb1f4fd2f6f6ef753df34d40 /src/platforms/px4_subscriber.h
parent16618f1adac7f33817fb968b285288beb360b012 (diff)
downloadpx4-firmware-e697413667579ffb1c5900193a03da257c05d11a.tar.gz
px4-firmware-e697413667579ffb1c5900193a03da257c05d11a.tar.bz2
px4-firmware-e697413667579ffb1c5900193a03da257c05d11a.zip
multiplatform subscription: uorb: separate class for no callback case
Diffstat (limited to 'src/platforms/px4_subscriber.h')
-rw-r--r--src/platforms/px4_subscriber.h61
1 files changed, 40 insertions, 21 deletions
diff --git a/src/platforms/px4_subscriber.h b/src/platforms/px4_subscriber.h
index 5d4e67ad0..8c299c748 100644
--- a/src/platforms/px4_subscriber.h
+++ b/src/platforms/px4_subscriber.h
@@ -161,46 +161,72 @@ class SubscriberUORB :
public uORB::Subscription<M>
{
public:
+
/**
- * Construct SubscriberUORB by providing orb meta data
+ * Construct SubscriberUORB by providing orb meta data without callback
* @param meta orb metadata for the topic which is used
- * @param callback Callback, executed on receiving a new message
* @param interval Minimal interval between calls to callback
* @param list subscriber is added to this list
*/
SubscriberUORB(const struct orb_metadata *meta,
unsigned interval,
- std::function<void(const M &)> callback,
List<uORB::SubscriptionNode *> *list) :
Subscriber<M>(),
- uORB::Subscription<M>(meta, interval, list),
- _callback(callback)
- //XXX store callback
+ uORB::Subscription<M>(meta, interval, list)
{}
+ ~SubscriberUORB() {};
+
/**
- * Construct SubscriberUORB by providing orb meta data without callback
+ * Update Subscription
+ * Invoked by the list traversal in NodeHandle::spinOnce
+ */
+ virtual void update()
+ {
+ if (!uORB::Subscription<M>::updated()) {
+ /* Topic not updated */
+ return;
+ }
+
+ /* get latest data */
+ uORB::Subscription<M>::update();
+ };
+
+ /* Accessors*/
+ /**
+ * Get the last message value
+ */
+ const M& get() { return uORB::Subscription<M>::getData(); }
+};
+
+template<typename M>
+class SubscriberUORBCallback :
+ public SubscriberUORB<M>
+{
+public:
+ /**
+ * Construct SubscriberUORBCallback by providing orb meta data
* @param meta orb metadata for the topic which is used
+ * @param callback Callback, executed on receiving a new message
* @param interval Minimal interval between calls to callback
* @param list subscriber is added to this list
*/
- SubscriberUORB(const struct orb_metadata *meta,
+ SubscriberUORBCallback(const struct orb_metadata *meta,
unsigned interval,
+ std::function<void(const M &)> callback,
List<uORB::SubscriptionNode *> *list) :
- Subscriber<M>(),
- uORB::Subscription<M>(meta, interval, list),
- _callback(nullptr)
- //XXX store callback
+ SubscriberUORB<M>(meta, interval, list),
+ _callback(callback)
{}
- ~SubscriberUORB() {};
+ ~SubscriberUORBCallback() {};
/**
* Update Subscription
* Invoked by the list traversal in NodeHandle::spinOnce
* If new data is available the callback is called
*/
- void update()
+ virtual void update()
{
if (!uORB::Subscription<M>::updated()) {
/* Topic not updated, do not call callback */
@@ -221,16 +247,9 @@ public:
};
- /* Accessors*/
- /**
- * Get the last message value
- */
- const M& get() { return uORB::Subscription<M>::getData(); }
-
protected:
std::function<void(const M &)> _callback; /**< Callback handle,
called when new data is available */
-
};
#endif