diff options
author | Thomas Gubler <thomasgubler@gmail.com> | 2015-01-21 18:23:18 +0100 |
---|---|---|
committer | Thomas Gubler <thomasgubler@gmail.com> | 2015-01-21 18:23:18 +0100 |
commit | 358c91932575c191c7717d9c083611d651721476 (patch) | |
tree | 31a0113a96d0d2cab721cff5015878c9af0d0cde /src/platforms | |
parent | a761df4ffa0e77e1bd34a6e02ba621ca71523389 (diff) | |
download | px4-firmware-358c91932575c191c7717d9c083611d651721476.tar.gz px4-firmware-358c91932575c191c7717d9c083611d651721476.tar.bz2 px4-firmware-358c91932575c191c7717d9c083611d651721476.zip |
clean up px4_subscriber
Diffstat (limited to 'src/platforms')
-rw-r--r-- | src/platforms/px4_subscriber.h | 43 |
1 files changed, 10 insertions, 33 deletions
diff --git a/src/platforms/px4_subscriber.h b/src/platforms/px4_subscriber.h index 8e8b786b1..2b289771b 100644 --- a/src/platforms/px4_subscriber.h +++ b/src/platforms/px4_subscriber.h @@ -104,7 +104,6 @@ public: /** * Construct Subscriber by providing a callback function */ - // SubscriberROS(std::function<void(const typename std::remove_reference<decltype(((T*)nullptr)->data())>::type &)> cbf) : SubscriberROS(std::function<void(const T &)> cbf) : Subscriber<T>(), _ros_sub(), @@ -195,16 +194,8 @@ public: /** * Construct SubscriberUORB by providing orb meta data without callback - * @param meta orb metadata for the topic which is used * @param interval Minimal interval between calls to callback - * @param list subscriber is added to this list */ - // SubscriberUORB(const struct orb_metadata *meta, - // unsigned interval, - // List<uORB::SubscriptionNode *> *list) : - // Subscriber<M>(), - // uORB::Subscription<M>(meta, interval, list) - // {} SubscriberUORB(uORB::SubscriptionBase * uorb_sub, unsigned interval) : SubscriberNode(interval), _uorb_sub(uorb_sub) @@ -227,25 +218,21 @@ public: }; /* Accessors*/ - /** - * Get the last message value - */ - // T get() { return (T)(typename std::remove_reference<decltype(((T*)nullptr)->data())>::type)*_uorb_sub; } - // T get() { - // typename std::remove_reference<decltype(((T*)nullptr)->data())>::type msg = (typename std::remove_reference<decltype(((T*)nullptr)->data())>::type)*_uorb_sub; - // return (T)msg; - // } + int getUORBHandle() { return _uorb_sub->getHandle(); } + +protected: + uORB::SubscriptionBase * _uorb_sub; /**< Handle to the subscription */ + + typename std::remove_reference<decltype(((T*)nullptr)->data())>::type getUORBData() + { + return (typename std::remove_reference<decltype(((T*)nullptr)->data())>::type)*_uorb_sub; + } /** * Get void pointer to last message value */ void *get_void_ptr() { return (void *)&(this->_msg_current.data()); } - int getUORBHandle() { return _uorb_sub->getHandle(); } - -protected: - uORB::SubscriptionBase * _uorb_sub; /**< Handle to the subscription */ - typename std::remove_reference<decltype(((T*)nullptr)->data())>::type getUORBData() { return (typename std::remove_reference<decltype(((T*)nullptr)->data())>::type)*_uorb_sub; } }; //XXX reduce to one class with overloaded constructor? @@ -256,18 +243,9 @@ class __EXPORT SubscriberUORBCallback : 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 cbf Callback, executed on receiving a new message * @param interval Minimal interval between calls to callback - * @param list subscriber is added to this list */ - // SubscriberUORBCallback(const struct orb_metadata *meta, - // unsigned interval, - // std::function<void(const M &)> callback, - // List<uORB::SubscriptionNode *> *list) : - // SubscriberUORB<M>(meta, interval, list), - // _callback(callback) - // {} SubscriberUORBCallback(uORB::SubscriptionBase * uorb_sub, unsigned interval, std::function<void(const T &)> cbf) : @@ -304,7 +282,6 @@ public: }; protected: - // std::function<void(const typename std::remove_reference<decltype(((T*)nullptr)->data())>::type &)> _callback; [>*< Callback handle, called when new data is available */ std::function<void(const T &)> _cbf; /**< Callback that the user provided on the subscription */ }; #endif |