45 #ifndef PCL_ROS_PUBLISHER_H_
46 #define PCL_ROS_PUBLISHER_H_
49 #include <sensor_msgs/PointCloud2.h>
50 #include <pcl/conversions.h>
62 pub_ = nh.
advertise<sensor_msgs::PointCloud2>(topic, queue_size);
83 operator void*()
const
85 return (
pub_) ? (
void*)1 : (
void*)0;
92 template <
typename Po
intT>
112 publish (
const pcl::PointCloud<PointT>& point_cloud)
const
115 sensor_msgs::PointCloud2 msg;
117 pub_.
publish (boost::make_shared<const sensor_msgs::PointCloud2> (msg));
135 publish (
const sensor_msgs::PointCloud2Ptr& point_cloud)
const
142 publish (
const sensor_msgs::PointCloud2& point_cloud)
const
144 pub_.
publish (boost::make_shared<const sensor_msgs::PointCloud2> (point_cloud));
149 #endif //#ifndef PCL_ROS_PUBLISHER_H_