Browse Source

move ros::subscriber into constructor of subscriber

sbg
Thomas Gubler 10 years ago
parent
commit
1e504478a0
  1. 15
      src/platforms/px4_nodehandle.h
  2. 29
      src/platforms/px4_subscriber.h

15
src/platforms/px4_nodehandle.h

@ -81,9 +81,7 @@ public:
template<typename T> template<typename T>
Subscriber<T> *subscribe(void(*fp)(const 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, SubscriberBase *sub = new SubscriberROS<T>((ros::NodeHandle*)this, std::bind(fp, std::placeholders::_1));
&SubscriberROS<T>::callback, (SubscriberROS<T> *)sub);
((SubscriberROS<T> *)sub)->set_ros_sub(ros_sub);
_subs.push_back(sub); _subs.push_back(sub);
return (Subscriber<T> *)sub; return (Subscriber<T> *)sub;
} }
@ -96,11 +94,7 @@ public:
template<typename T, typename C> template<typename T, typename C>
Subscriber<T> *subscribe(void(C::*fp)(const T &), C *obj) Subscriber<T> *subscribe(void(C::*fp)(const T &), C *obj)
{ {
SubscriberBase *sub = new SubscriberROS<T>(std::bind(fp, obj, std::placeholders::_1)); SubscriberBase *sub = new SubscriberROS<T>((ros::NodeHandle*)this, 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);
_subs.push_back(sub); _subs.push_back(sub);
return (Subscriber<T> *)sub; return (Subscriber<T> *)sub;
} }
@ -111,10 +105,7 @@ public:
template<typename T> template<typename T>
Subscriber<T> *subscribe() Subscriber<T> *subscribe()
{ {
SubscriberBase *sub = new SubscriberROS<T>(); SubscriberBase *sub = new SubscriberROS<T>((ros::NodeHandle*)this);
ros::Subscriber ros_sub = ros::NodeHandle::subscribe(T::handle(), kQueueSizeDefault,
&SubscriberROS<T>::callback, (SubscriberROS<T> *)sub);
((SubscriberROS<T> *)sub)->set_ros_sub(ros_sub);
_subs.push_back(sub); _subs.push_back(sub);
return (Subscriber<T> *)sub; return (Subscriber<T> *)sub;
} }

29
src/platforms/px4_subscriber.h

@ -102,24 +102,23 @@ class SubscriberROS :
public: public:
/** /**
* Construct Subscriber by providing a callback function * Construct Subscriber without a callback function
*/ */
SubscriberROS(std::function<void(const T &)> cbf) : SubscriberROS(ros::NodeHandle *rnh) :
Subscriber<T>(), px4::Subscriber<T>(),
_ros_sub(), _cbf(NULL),
_cbf(cbf) _ros_sub(rnh->subscribe(T::handle(), 1, &SubscriberROS<T>::callback, this))
{} {}
/** /**
* Construct Subscriber without a callback function * Construct Subscriber by providing a callback function
*/ */
SubscriberROS() : //XXX queue default
Subscriber<T>(), SubscriberROS(ros::NodeHandle *rnh, std::function<void(const T &)> cbf) :
_ros_sub(), _cbf(cbf),
_cbf(NULL) _ros_sub(rnh->subscribe(T::handle(), 1, &SubscriberROS<T>::callback, this))
{} {}
virtual ~SubscriberROS() {}; virtual ~SubscriberROS() {};
protected: protected:
@ -139,14 +138,6 @@ protected:
} }
/**
* Saves the ros subscriber to keep ros subscription alive
*/
void set_ros_sub(ros::Subscriber ros_sub)
{
_ros_sub = ros_sub;
}
ros::Subscriber _ros_sub; /**< Handle to ros subscriber */ ros::Subscriber _ros_sub; /**< Handle to ros subscriber */
std::function<void(const T &)> _cbf; /**< Callback that the user provided on the subscription */ std::function<void(const T &)> _cbf; /**< Callback that the user provided on the subscription */

Loading…
Cancel
Save