diff options
author | Thomas Gubler <thomasgubler@gmail.com> | 2015-01-23 07:06:02 +0100 |
---|---|---|
committer | Thomas Gubler <thomasgubler@gmail.com> | 2015-01-23 07:06:02 +0100 |
commit | 1e504478a00f08c4d7ab381aa9bec5cdbee5513f (patch) | |
tree | 3522af2c74d67e9a5f3d901826f3cd73da610817 /src/platforms/px4_nodehandle.h | |
parent | b2a911b88d6a541218ef6e633be0d6693de31c8e (diff) | |
download | px4-firmware-1e504478a00f08c4d7ab381aa9bec5cdbee5513f.tar.gz px4-firmware-1e504478a00f08c4d7ab381aa9bec5cdbee5513f.tar.bz2 px4-firmware-1e504478a00f08c4d7ab381aa9bec5cdbee5513f.zip |
move ros::subscriber into constructor of subscriber
Diffstat (limited to 'src/platforms/px4_nodehandle.h')
-rw-r--r-- | src/platforms/px4_nodehandle.h | 15 |
1 files changed, 3 insertions, 12 deletions
diff --git a/src/platforms/px4_nodehandle.h b/src/platforms/px4_nodehandle.h index d78c865de..40604aa86 100644 --- a/src/platforms/px4_nodehandle.h +++ b/src/platforms/px4_nodehandle.h @@ -81,9 +81,7 @@ public: template<typename T> Subscriber<T> *subscribe(void(*fp)(const T &)) { - SubscriberBase *sub = new SubscriberROS<T>(std::bind(fp, std::placeholders::_1)); ros::Subscriber ros_sub = ros::NodeHandle::subscribe(T::handle(), kQueueSizeDefault, - &SubscriberROS<T>::callback, (SubscriberROS<T> *)sub); - ((SubscriberROS<T> *)sub)->set_ros_sub(ros_sub); + SubscriberBase *sub = new SubscriberROS<T>((ros::NodeHandle*)this, std::bind(fp, std::placeholders::_1)); _subs.push_back(sub); return (Subscriber<T> *)sub; } @@ -96,11 +94,7 @@ public: template<typename T, typename C> Subscriber<T> *subscribe(void(C::*fp)(const T &), C *obj) { - SubscriberBase *sub = new SubscriberROS<T>(std::bind(fp, obj, std::placeholders::_1)); - ros::Subscriber ros_sub = ros::NodeHandle::subscribe(T::handle(), kQueueSizeDefault, - &SubscriberROS<T>::callback, (SubscriberROS<T> *)sub);//XXX needs cleanup in destructor ore move into class - - ((SubscriberROS<T> *)sub)->set_ros_sub(ros_sub); + SubscriberBase *sub = new SubscriberROS<T>((ros::NodeHandle*)this, std::bind(fp, obj, std::placeholders::_1)); _subs.push_back(sub); return (Subscriber<T> *)sub; } @@ -111,10 +105,7 @@ public: template<typename T> Subscriber<T> *subscribe() { - SubscriberBase *sub = new SubscriberROS<T>(); - ros::Subscriber ros_sub = ros::NodeHandle::subscribe(T::handle(), kQueueSizeDefault, - &SubscriberROS<T>::callback, (SubscriberROS<T> *)sub); - ((SubscriberROS<T> *)sub)->set_ros_sub(ros_sub); + SubscriberBase *sub = new SubscriberROS<T>((ros::NodeHandle*)this); _subs.push_back(sub); return (Subscriber<T> *)sub; } |