aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--src/platforms/px4_nodehandle.h4
-rw-r--r--src/platforms/px4_publisher.h7
2 files changed, 5 insertions, 6 deletions
diff --git a/src/platforms/px4_nodehandle.h b/src/platforms/px4_nodehandle.h
index f2d09c15c..c85b8118b 100644
--- a/src/platforms/px4_nodehandle.h
+++ b/src/platforms/px4_nodehandle.h
@@ -116,8 +116,7 @@ public:
template<typename T>
Publisher<T>* advertise()
{
- ros::Publisher ros_pub = ros::NodeHandle::advertise<typename std::remove_reference<decltype(((T*)nullptr)->data())>::type &>(T::handle(), kQueueSizeDefault);
- PublisherROS<T> *pub = new PublisherROS<T>(ros_pub);
+ PublisherROS<T> *pub = new PublisherROS<T>((ros::NodeHandle*)this);
_pubs.push_back((PublisherBase*)pub);
return (Publisher<T>*)pub;
}
@@ -134,7 +133,6 @@ public:
private:
- static const uint32_t kQueueSizeDefault = 1; /**< Size of queue for ROS */
std::list<SubscriberBase *> _subs; /**< Subcriptions of node */
std::list<PublisherBase *> _pubs; /**< Publications of node */
};
diff --git a/src/platforms/px4_publisher.h b/src/platforms/px4_publisher.h
index afedbbee7..ea675e67b 100644
--- a/src/platforms/px4_publisher.h
+++ b/src/platforms/px4_publisher.h
@@ -84,9 +84,9 @@ public:
* Construct Publisher by providing a ros::Publisher
* @param ros_pub the ros publisher which will be used to perform the publications
*/
- PublisherROS(ros::Publisher ros_pub) :
+ PublisherROS(ros::NodeHandle *rnh) :
Publisher<T>(),
- _ros_pub(ros_pub)
+ _ros_pub(rnh->advertise<typename std::remove_reference<decltype(((T*)nullptr)->data())>::type &>(T::handle(), kQueueSizeDefault))
{}
~PublisherROS() {};
@@ -99,7 +99,8 @@ public:
_ros_pub.publish(msg.data());
return 0;
}
-private:
+protected:
+ static const uint32_t kQueueSizeDefault = 1; /**< Size of queue for ROS */
ros::Publisher _ros_pub; /**< Handle to the ros publisher */
};
#else