Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00045 #ifndef PCL_ROS_PUBLISHER_H_
00046 #define PCL_ROS_PUBLISHER_H_
00047
00048 #include <ros/ros.h>
00049 #include "pcl/ros/conversions.h"
00050
00051 namespace pcl_ros
00052 {
00053 class BasePublisher
00054 {
00055 public:
00056 void
00057 advertise (ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size)
00058 {
00059 pub_ = nh.advertise<sensor_msgs::PointCloud2>(topic, queue_size);
00060 }
00061
00062 std::string
00063 getTopic ()
00064 {
00065 return (pub_.getTopic ());
00066 }
00067
00068 uint32_t
00069 getNumSubscribers () const
00070 {
00071 return (pub_.getNumSubscribers ());
00072 }
00073
00074 void
00075 shutdown ()
00076 {
00077 pub_.shutdown ();
00078 }
00079
00080 operator void*() const
00081 {
00082 return (pub_) ? (void*)1 : (void*)0;
00083 }
00084
00085 protected:
00086 ros::Publisher pub_;
00087 };
00088
00089 template <typename PointT>
00090 class Publisher : public BasePublisher
00091 {
00092 public:
00093 Publisher () {}
00094
00095 Publisher (ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size)
00096 {
00097 advertise (nh, topic, queue_size);
00098 }
00099
00100 ~Publisher () {}
00101
00102 inline void
00103 publish (const boost::shared_ptr<const pcl::PointCloud<PointT> > &point_cloud) const
00104 {
00105 publish (*point_cloud);
00106 }
00107
00108 inline void
00109 publish (const pcl::PointCloud<PointT>& point_cloud) const
00110 {
00111
00112 sensor_msgs::PointCloud2 msg;
00113 pcl::toROSMsg (point_cloud, msg);
00114 pub_.publish (boost::make_shared<const sensor_msgs::PointCloud2> (msg));
00115 }
00116 };
00117
00118 template <>
00119 class Publisher<sensor_msgs::PointCloud2> : public BasePublisher
00120 {
00121 public:
00122 Publisher () {}
00123
00124 Publisher (ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size)
00125 {
00126 advertise (nh, topic, queue_size);
00127 }
00128
00129 ~Publisher () {}
00130
00131 void
00132 publish (const sensor_msgs::PointCloud2Ptr& point_cloud) const
00133 {
00134 pub_.publish (point_cloud);
00135
00136 }
00137
00138 void
00139 publish (const sensor_msgs::PointCloud2& point_cloud) const
00140 {
00141 pub_.publish (boost::make_shared<const sensor_msgs::PointCloud2> (point_cloud));
00142
00143 }
00144 };
00145 }
00146 #endif //#ifndef PCL_ROS_PUBLISHER_H_