aboutsummaryrefslogtreecommitdiff
path: root/src/platforms/px4_publisher.h
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-01-23 08:03:07 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-01-23 08:03:15 +0100
commit59f05a7195ae4a2d57e276c31e12bcf6af477408 (patch)
tree17b1274f69887a72373aa1cc43e46898b9158a6e /src/platforms/px4_publisher.h
parent2dfd30c25e2839b762ca127fd4af696284df34b9 (diff)
downloadpx4-firmware-59f05a7195ae4a2d57e276c31e12bcf6af477408.tar.gz
px4-firmware-59f05a7195ae4a2d57e276c31e12bcf6af477408.tar.bz2
px4-firmware-59f05a7195ae4a2d57e276c31e12bcf6af477408.zip
move ros::publisher into constructor of publisher
Diffstat (limited to 'src/platforms/px4_publisher.h')
-rw-r--r--src/platforms/px4_publisher.h7
1 files changed, 4 insertions, 3 deletions
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