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>
108 publish (*point_cloud);
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_
void publish(const pcl::PointCloud< PointT > &point_cloud) const
void publish(const boost::shared_ptr< M > &message) const
void publish(const sensor_msgs::PointCloud2 &point_cloud) const
Publisher(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size)
void publish(const boost::shared_ptr< const pcl::PointCloud< PointT > > &point_cloud) const
Publisher(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void publish(const sensor_msgs::PointCloud2Ptr &point_cloud) const
uint32_t getNumSubscribers() const
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
std::string getTopic() const
uint32_t getNumSubscribers() const
void advertise(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size)