pcl_nodelet.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: pcl_nodelet.h 33238 2010-03-11 00:46:58Z rusu $
35  *
36  */
37 
44 #ifndef PCL_NODELET_H_
45 #define PCL_NODELET_H_
46 
47 #include <sensor_msgs/PointCloud2.h>
48 // PCL includes
49 #include <pcl_msgs/PointIndices.h>
50 #include <pcl_msgs/ModelCoefficients.h>
51 #include <pcl/point_types.h>
53 #include "pcl_ros/point_cloud.h"
54 // ROS Nodelet includes
60 
61 // Include TF
62 #include <tf/transform_listener.h>
63 
65 
66 namespace pcl_ros
67 {
71 
73  {
74  public:
75  typedef sensor_msgs::PointCloud2 PointCloud2;
76 
77  typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
78  typedef PointCloud::Ptr PointCloudPtr;
79  typedef PointCloud::ConstPtr PointCloudConstPtr;
80 
81  typedef pcl_msgs::PointIndices PointIndices;
82  typedef PointIndices::Ptr PointIndicesPtr;
83  typedef PointIndices::ConstPtr PointIndicesConstPtr;
84 
85  typedef pcl_msgs::ModelCoefficients ModelCoefficients;
86  typedef ModelCoefficients::Ptr ModelCoefficientsPtr;
87  typedef ModelCoefficients::ConstPtr ModelCoefficientsConstPtr;
88 
91 
93  PCLNodelet () : use_indices_ (false), latched_indices_ (false),
95 
96  protected:
107  bool use_indices_;
116 
119 
122 
125 
128 
131 
134 
139  inline bool
140  isValid (const PointCloud2::ConstPtr &cloud, const std::string &topic_name = "input")
141  {
142  if (cloud->width * cloud->height * cloud->point_step != cloud->data.size ())
143  {
144  NODELET_WARN ("[%s] Invalid PointCloud (data = %zu, width = %d, height = %d, step = %d) with stamp %f, and frame %s on topic %s received!", getName ().c_str (), cloud->data.size (), cloud->width, cloud->height, cloud->point_step, cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (topic_name).c_str ());
145 
146  return (false);
147  }
148  return (true);
149  }
150 
155  inline bool
156  isValid (const PointCloudConstPtr &cloud, const std::string &topic_name = "input")
157  {
158  if (cloud->width * cloud->height != cloud->points.size ())
159  {
160  NODELET_WARN ("[%s] Invalid PointCloud (points = %zu, width = %d, height = %d) with stamp %f, and frame %s on topic %s received!", getName ().c_str (), cloud->points.size (), cloud->width, cloud->height, fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (topic_name).c_str ());
161 
162  return (false);
163  }
164  return (true);
165  }
166 
171  inline bool
172  isValid (const PointIndicesConstPtr &indices, const std::string &topic_name = "indices")
173  {
174  /*if (indices->indices.empty ())
175  {
176  NODELET_WARN ("[%s] Empty indices (values = %zu) with stamp %f, and frame %s on topic %s received!", getName ().c_str (), indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName (topic_name).c_str ());
177  return (true);
178  }*/
179  return (true);
180  }
181 
186  inline bool
187  isValid (const ModelCoefficientsConstPtr &model, const std::string &topic_name = "model")
188  {
189  /*if (model->values.empty ())
190  {
191  NODELET_WARN ("[%s] Empty model (values = %zu) with stamp %f, and frame %s on topic %s received!", getName ().c_str (), model->values.size (), model->header.stamp.toSec (), model->header.frame_id.c_str (), pnh_->resolveName (topic_name).c_str ());
192  return (false);
193  }*/
194  return (true);
195  }
196 
198  virtual void subscribe () {}
199  virtual void unsubscribe () {}
200 
202  virtual void
204  {
206 
207  // Parameters that we care about only at startup
208  pnh_->getParam ("max_queue_size", max_queue_size_);
209 
210  // ---[ Optional parameters
211  pnh_->getParam ("use_indices", use_indices_);
212  pnh_->getParam ("latched_indices", latched_indices_);
213  pnh_->getParam ("approximate_sync", approximate_sync_);
214 
215  NODELET_DEBUG ("[%s::onInit] PCL Nodelet successfully created with the following parameters:\n"
216  " - approximate_sync : %s\n"
217  " - use_indices : %s\n"
218  " - latched_indices : %s\n"
219  " - max_queue_size : %d",
220  getName ().c_str (),
221  (approximate_sync_) ? "true" : "false",
222  (use_indices_) ? "true" : "false",
223  (latched_indices_) ? "true" : "false",
224  max_queue_size_);
225  }
226 
227  public:
228  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
229  };
230 }
231 
232 #endif //#ifndef PCL_NODELET_H_
pcl_msgs::ModelCoefficients ModelCoefficients
Definition: pcl_nodelet.h:85
PointIndices::Ptr PointIndicesPtr
Definition: pcl_nodelet.h:82
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
Definition: pcl_nodelet.h:203
#define NODELET_WARN(...)
bool isValid(const ModelCoefficientsConstPtr &model, const std::string &topic_name="model")
Test whether a given ModelCoefficients message is "valid" (i.e., has values).
Definition: pcl_nodelet.h:187
boost::shared_ptr< std::vector< int > > IndicesPtr
Definition: pcl_nodelet.h:89
ModelCoefficients::Ptr ModelCoefficientsPtr
Definition: pcl_nodelet.h:86
PCLNodelet()
Empty constructor.
Definition: pcl_nodelet.h:93
const std::string & getName() const
bool isValid(const PointCloudConstPtr &cloud, const std::string &topic_name="input")
Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-ze...
Definition: pcl_nodelet.h:156
message_filters::Subscriber< PointIndices > sub_indices_filter_
The message filter subscriber for PointIndices.
Definition: pcl_nodelet.h:121
bool latched_indices_
Set to true if the indices topic is latched.
Definition: pcl_nodelet.h:115
bool isValid(const PointCloud2::ConstPtr &cloud, const std::string &topic_name="input")
Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-ze...
Definition: pcl_nodelet.h:140
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
boost::shared_ptr< const std::vector< int > > IndicesConstPtr
Definition: pcl_nodelet.h:90
boost::shared_ptr< ros::NodeHandle > pnh_
sensor_msgs::PointCloud2 PointCloud2
Definition: pcl_nodelet.h:75
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class...
Definition: pcl_nodelet.h:72
pcl_msgs::PointIndices PointIndices
Definition: pcl_nodelet.h:81
virtual void unsubscribe()
Definition: pcl_nodelet.h:199
bool isValid(const PointIndicesConstPtr &indices, const std::string &topic_name="indices")
Test whether a given PointIndices message is "valid" (i.e., has values).
Definition: pcl_nodelet.h:172
pcl::PointCloud< pcl::PointXYZ > PointCloud
Definition: pcl_nodelet.h:77
tf::TransformListener tf_listener_
TF listener object.
Definition: pcl_nodelet.h:133
PointCloud::ConstPtr PointCloudConstPtr
Definition: pcl_nodelet.h:79
bool approximate_sync_
True if we use an approximate time synchronizer versus an exact one (false by default).
Definition: pcl_nodelet.h:130
virtual void subscribe()
Lazy transport subscribe/unsubscribe routine. It is optional for backward compatibility.
Definition: pcl_nodelet.h:198
int max_queue_size_
The maximum queue size (default: 3).
Definition: pcl_nodelet.h:127
ModelCoefficients::ConstPtr ModelCoefficientsConstPtr
Definition: pcl_nodelet.h:87
ros::Publisher pub_output_
The output PointCloud publisher.
Definition: pcl_nodelet.h:124
#define NODELET_DEBUG(...)
bool use_indices_
Set to true if point indices are used.
Definition: pcl_nodelet.h:94
PointIndices::ConstPtr PointIndicesConstPtr
Definition: pcl_nodelet.h:83
message_filters::Subscriber< PointCloud > sub_input_filter_
The message filter subscriber for PointCloud2.
Definition: pcl_nodelet.h:118
PointCloud::Ptr PointCloudPtr
Definition: pcl_nodelet.h:78


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Jun 5 2019 19:52:52