publisher.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id: publisher.h 33238 2010-03-11 00:46:58Z rusu $
35  *
36  */
45 #ifndef PCL_ROS_PUBLISHER_H_
46 #define PCL_ROS_PUBLISHER_H_
47 
48 #include <ros/ros.h>
49 #include <sensor_msgs/PointCloud2.h>
50 #include <pcl/conversions.h>
51 
53 
54 namespace pcl_ros
55 {
57  {
58  public:
59  void
60  advertise (ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size)
61  {
62  pub_ = nh.advertise<sensor_msgs::PointCloud2>(topic, queue_size);
63  }
64 
65  std::string
67  {
68  return (pub_.getTopic ());
69  }
70 
71  uint32_t
73  {
74  return (pub_.getNumSubscribers ());
75  }
76 
77  void
79  {
80  pub_.shutdown ();
81  }
82 
83  operator void*() const
84  {
85  return (pub_) ? (void*)1 : (void*)0;
86  }
87 
88  protected:
90  };
91 
92  template <typename PointT>
93  class Publisher : public BasePublisher
94  {
95  public:
96  Publisher () {}
97 
98  Publisher (ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size)
99  {
100  advertise (nh, topic, queue_size);
101  }
102 
104 
105  inline void
106  publish (const boost::shared_ptr<const pcl::PointCloud<PointT> > &point_cloud) const
107  {
108  publish (*point_cloud);
109  }
110 
111  inline void
112  publish (const pcl::PointCloud<PointT>& point_cloud) const
113  {
114  // Fill point cloud binary data
115  sensor_msgs::PointCloud2 msg;
116  pcl::toROSMsg (point_cloud, msg);
117  pub_.publish (boost::make_shared<const sensor_msgs::PointCloud2> (msg));
118  }
119  };
120 
121  template <>
122  class Publisher<sensor_msgs::PointCloud2> : public BasePublisher
123  {
124  public:
125  Publisher () {}
126 
127  Publisher (ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size)
128  {
129  advertise (nh, topic, queue_size);
130  }
131 
133 
134  void
135  publish (const sensor_msgs::PointCloud2Ptr& point_cloud) const
136  {
137  pub_.publish (point_cloud);
138  //pub_.publish (*point_cloud);
139  }
140 
141  void
142  publish (const sensor_msgs::PointCloud2& point_cloud) const
143  {
144  pub_.publish (boost::make_shared<const sensor_msgs::PointCloud2> (point_cloud));
145  //pub_.publish (point_cloud);
146  }
147  };
148 }
149 #endif //#ifndef PCL_ROS_PUBLISHER_H_
pcl_ros::BasePublisher::getTopic
std::string getTopic()
Definition: publisher.h:66
ros::Publisher
boost::shared_ptr
pcl_ros
Definition: boundary.h:46
pcl_ros::Publisher::publish
void publish(const pcl::PointCloud< PointT > &point_cloud) const
Definition: publisher.h:112
ros.h
pcl_ros::Publisher< sensor_msgs::PointCloud2 >::publish
void publish(const sensor_msgs::PointCloud2 &point_cloud) const
Definition: publisher.h:142
pcl_ros::BasePublisher::getNumSubscribers
uint32_t getNumSubscribers() const
Definition: publisher.h:72
pcl_ros::Publisher< sensor_msgs::PointCloud2 >::Publisher
Publisher()
Definition: publisher.h:125
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
pcl_ros::Publisher< sensor_msgs::PointCloud2 >::publish
void publish(const sensor_msgs::PointCloud2Ptr &point_cloud) const
Definition: publisher.h:135
pcl_ros::Publisher::publish
void publish(const boost::shared_ptr< const pcl::PointCloud< PointT > > &point_cloud) const
Definition: publisher.h:106
pcl_ros::BasePublisher::pub_
ros::Publisher pub_
Definition: publisher.h:89
ros::Publisher::shutdown
void shutdown()
pcl_ros::Publisher
Definition: publisher.h:93
pcl_ros::Publisher::Publisher
Publisher()
Definition: publisher.h:96
pcl_ros::BasePublisher
Definition: publisher.h:56
ros::Publisher::getTopic
std::string getTopic() const
pcl_ros::BasePublisher::advertise
void advertise(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size)
Definition: publisher.h:60
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
pcl_ros::Publisher::Publisher
Publisher(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size)
Definition: publisher.h:98
sensor_msgs
pcl_ros::Publisher::~Publisher
~Publisher()
Definition: publisher.h:103
pcl_ros::Publisher< sensor_msgs::PointCloud2 >::~Publisher
~Publisher()
Definition: publisher.h:132
pcl_ros::BasePublisher::shutdown
void shutdown()
Definition: publisher.h:78
pcl_ros::Publisher< sensor_msgs::PointCloud2 >::Publisher
Publisher(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size)
Definition: publisher.h:127
ros::NodeHandle
pcl_conversions.h


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Fri Jul 12 2024 02:54:40