filters/features/feature.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, 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 OWNERff 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: feature.cpp 35422 2011-01-24 20:04:44Z rusu $
35  *
36  */
37 
38 //#include <pluginlib/class_list_macros.h>
39 // Include the implementations here instead of compiling them separately to speed up compile time
40 //#include "normal_3d.cpp"
41 //#include "boundary.cpp"
42 //#include "fpfh.cpp"
43 //#include "fpfh_omp.cpp"
44 //#include "moment_invariants.cpp"
45 //#include "normal_3d_omp.cpp"
46 //#include "normal_3d_tbb.cpp"
47 //#include "pfh.cpp"
48 //#include "principal_curvatures.cpp"
49 //#include "vfh.cpp"
50 #include <pcl/io/io.h>
53 
55 void
57 {
58  // Call the super onInit ()
60 
61  // Call the child init
62  childInit (*pnh_);
63 
64  // Allow each individual class that inherits from us to declare their own Publisher
65  // This is useful for Publisher<pcl::PointCloud<T> >, as NormalEstimation can publish PointCloud<Normal>, etc
66  //pub_output_ = pnh_->template advertise<PointCloud2> ("output", max_queue_size_);
67 
68  // ---[ Mandatory parameters
69  if (!pnh_->getParam ("k_search", k_) && !pnh_->getParam ("radius_search", search_radius_))
70  {
71  NODELET_ERROR ("[%s::onInit] Neither 'k_search' nor 'radius_search' set! Need to set at least one of these parameters before continuing.", getName ().c_str ());
72  return;
73  }
74  if (!pnh_->getParam ("spatial_locator", spatial_locator_type_))
75  {
76  NODELET_ERROR ("[%s::onInit] Need a 'spatial_locator' parameter to be set before continuing!", getName ().c_str ());
77  return;
78  }
79 
80  // ---[ Optional parameters
81  pnh_->getParam ("use_surface", use_surface_);
82 
83  // Enable the dynamic reconfigure service
84  srv_ = boost::make_shared<dynamic_reconfigure::Server<FeatureConfig> > (*pnh_);
85  dynamic_reconfigure::Server<FeatureConfig>::CallbackType f = boost::bind (&Feature::config_callback, this, _1, _2);
86  srv_->setCallback (f);
87 
88  // If we're supposed to look for PointIndices (indices) or PointCloud (surface) messages
90  {
91  // Create the objects here
93  sync_input_surface_indices_a_ = boost::make_shared<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloudIn, PointCloudIn, PointIndices> > >(max_queue_size_);
94  else
95  sync_input_surface_indices_e_ = boost::make_shared<message_filters::Synchronizer<sync_policies::ExactTime<PointCloudIn, PointCloudIn, PointIndices> > >(max_queue_size_);
96 
97  // Subscribe to the input using a filter
99  if (use_indices_)
100  {
101  // If indices are enabled, subscribe to the indices
102  sub_indices_filter_.subscribe (*pnh_, "indices", max_queue_size_);
103  if (use_surface_) // Use both indices and surface
104  {
105  // If surface is enabled, subscribe to the surface, connect the input-indices-surface trio and register
106  sub_surface_filter_.subscribe (*pnh_, "surface", max_queue_size_);
107  if (approximate_sync_)
109  else
110  sync_input_surface_indices_e_->connectInput (sub_input_filter_, sub_surface_filter_, sub_indices_filter_);
111  }
112  else // Use only indices
113  {
115  // surface not enabled, connect the input-indices duo and register
116  if (approximate_sync_)
118  else
119  sync_input_surface_indices_e_->connectInput (sub_input_filter_, nf_pc_, sub_indices_filter_);
120  }
121  }
122  else // Use only surface
123  {
125  // indices not enabled, connect the input-surface duo and register
126  sub_surface_filter_.subscribe (*pnh_, "surface", max_queue_size_);
127  if (approximate_sync_)
129  else
130  sync_input_surface_indices_e_->connectInput (sub_input_filter_, sub_surface_filter_, nf_pi_);
131  }
132  // Register callbacks
133  if (approximate_sync_)
134  sync_input_surface_indices_a_->registerCallback (bind (&Feature::input_surface_indices_callback, this, _1, _2, _3));
135  else
136  sync_input_surface_indices_e_->registerCallback (bind (&Feature::input_surface_indices_callback, this, _1, _2, _3));
137  }
138  else
139  // Subscribe in an old fashion to input only (no filters)
141 
142  NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
143  " - use_surface : %s\n"
144  " - k_search : %d\n"
145  " - radius_search : %f\n"
146  " - spatial_locator: %d",
147  getName ().c_str (),
148  (use_surface_) ? "true" : "false", k_, search_radius_, spatial_locator_type_);
149 }
150 
152 void
153 pcl_ros::Feature::config_callback (FeatureConfig &config, uint32_t level)
154 {
155  if (k_ != config.k_search)
156  {
157  k_ = config.k_search;
158  NODELET_DEBUG ("[config_callback] Setting the number of K nearest neighbors to use for each point: %d.", k_);
159  }
160  if (search_radius_ != config.radius_search)
161  {
162  search_radius_ = config.radius_search;
163  NODELET_DEBUG ("[config_callback] Setting the nearest neighbors search radius for each point: %f.", search_radius_);
164  }
165 }
166 
168 void
170  const PointCloudInConstPtr &cloud_surface, const PointIndicesConstPtr &indices)
171 {
172  // No subscribers, no work
173  if (pub_output_.getNumSubscribers () <= 0)
174  return;
175 
176  // If cloud is given, check if it's valid
177  if (!isValid (cloud))
178  {
179  NODELET_ERROR ("[%s::input_surface_indices_callback] Invalid input!", getName ().c_str ());
180  emptyPublish (cloud);
181  return;
182  }
183 
184  // If surface is given, check if it's valid
185  if (cloud_surface && !isValid (cloud_surface, "surface"))
186  {
187  NODELET_ERROR ("[%s::input_surface_indices_callback] Invalid input surface!", getName ().c_str ());
188  emptyPublish (cloud);
189  return;
190  }
191 
192  // If indices are given, check if they are valid
193  if (indices && !isValid (indices))
194  {
195  NODELET_ERROR ("[%s::input_surface_indices_callback] Invalid input indices!", getName ().c_str ());
196  emptyPublish (cloud);
197  return;
198  }
199 
201  if (cloud_surface)
202  if (indices)
203  NODELET_DEBUG ("[input_surface_indices_callback]\n"
204  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
205  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
206  " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
207  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
208  cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), cloud_surface->header.stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str (),
209  indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ());
210  else
211  NODELET_DEBUG ("[input_surface_indices_callback]\n"
212  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
213  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
214  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
215  cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), cloud_surface->header.stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str ());
216 
217  else
218  if (indices)
219  NODELET_DEBUG ("[input_surface_indices_callback]\n"
220  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
221  " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
222  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
223  indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ());
224  else
225  NODELET_DEBUG ("[input_surface_indices_callback] PointCloud with %d data points, stamp %f, and frame %s on topic %s received.", cloud->width * cloud->height, cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str ());
227 
228 
229  if ((int)(cloud->width * cloud->height) < k_)
230  {
231  NODELET_ERROR ("[input_surface_indices_callback] Requested number of k-nearest neighbors (%d) is larger than the PointCloud size (%d)!", k_, (int)(cloud->width * cloud->height));
232  emptyPublish (cloud);
233  return;
234  }
235 
236  // If indices given...
237  IndicesPtr vindices;
238  if (indices && !indices->header.frame_id.empty ())
239  vindices.reset (new std::vector<int> (indices->indices));
240 
241  computePublish (cloud, cloud_surface, vindices);
242 }
243 
247 
249 void
251 {
252  // Call the super onInit ()
254 
255  // Call the child init
256  childInit (*pnh_);
257 
258  // Allow each individual class that inherits from us to declare their own Publisher
259  // This is useful for Publisher<pcl::PointCloud<T> >, as NormalEstimation can publish PointCloud<Normal>, etc
260  //pub_output_ = pnh_->template advertise<PointCloud2> ("output", max_queue_size_);
261 
262  // ---[ Mandatory parameters
263  if (!pnh_->getParam ("k_search", k_) && !pnh_->getParam ("radius_search", search_radius_))
264  {
265  NODELET_ERROR ("[%s::onInit] Neither 'k_search' nor 'radius_search' set! Need to set at least one of these parameters before continuing.", getName ().c_str ());
266  return;
267  }
268  if (!pnh_->getParam ("spatial_locator", spatial_locator_type_))
269  {
270  NODELET_ERROR ("[%s::onInit] Need a 'spatial_locator' parameter to be set before continuing!", getName ().c_str ());
271  return;
272  }
273  // ---[ Optional parameters
274  pnh_->getParam ("use_surface", use_surface_);
275 
276  sub_input_filter_.subscribe (*pnh_, "input", max_queue_size_);
277  sub_normals_filter_.subscribe (*pnh_, "normals", max_queue_size_);
278 
279  // Enable the dynamic reconfigure service
280  srv_ = boost::make_shared<dynamic_reconfigure::Server<FeatureConfig> > (*pnh_);
281  dynamic_reconfigure::Server<FeatureConfig>::CallbackType f = boost::bind (&FeatureFromNormals::config_callback, this, _1, _2);
282  srv_->setCallback (f);
283 
284  // Create the objects here
285  if (approximate_sync_)
286  sync_input_normals_surface_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloudIn, PointCloudN, PointCloudIn, PointIndices> > > (max_queue_size_);
287  else
288  sync_input_normals_surface_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloudIn, PointCloudN, PointCloudIn, PointIndices> > > (max_queue_size_);
289 
290  // If we're supposed to look for PointIndices (indices) or PointCloud (surface) messages
291  if (use_indices_ || use_surface_)
292  {
293  if (use_indices_)
294  {
295  // If indices are enabled, subscribe to the indices
296  sub_indices_filter_.subscribe (*pnh_, "indices", max_queue_size_);
297  if (use_surface_) // Use both indices and surface
298  {
299  // If surface is enabled, subscribe to the surface, connect the input-indices-surface trio and register
300  sub_surface_filter_.subscribe (*pnh_, "surface", max_queue_size_);
301  if (approximate_sync_)
302  sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, sub_indices_filter_);
303  else
304  sync_input_normals_surface_indices_e_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, sub_indices_filter_);
305  }
306  else // Use only indices
307  {
309  if (approximate_sync_)
310  // surface not enabled, connect the input-indices duo and register
311  sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, sub_indices_filter_);
312  else
313  // surface not enabled, connect the input-indices duo and register
314  sync_input_normals_surface_indices_e_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, sub_indices_filter_);
315  }
316  }
317  else // Use only surface
318  {
319  // indices not enabled, connect the input-surface duo and register
320  sub_surface_filter_.subscribe (*pnh_, "surface", max_queue_size_);
321 
323  if (approximate_sync_)
324  sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, nf_pi_);
325  else
326  sync_input_normals_surface_indices_e_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, nf_pi_);
327  }
328  }
329  else
330  {
332 
333  if (approximate_sync_)
334  sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, nf_pi_);
335  else
336  sync_input_normals_surface_indices_e_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, nf_pi_);
337  }
338 
339  // Register callbacks
340  if (approximate_sync_)
341  sync_input_normals_surface_indices_a_->registerCallback (bind (&FeatureFromNormals::input_normals_surface_indices_callback, this, _1, _2, _3, _4));
342  else
343  sync_input_normals_surface_indices_e_->registerCallback (bind (&FeatureFromNormals::input_normals_surface_indices_callback, this, _1, _2, _3, _4));
344 
345  NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
346  " - use_surface : %s\n"
347  " - k_search : %d\n"
348  " - radius_search : %f\n"
349  " - spatial_locator: %d",
350  getName ().c_str (),
351  (use_surface_) ? "true" : "false", k_, search_radius_, spatial_locator_type_);
352 }
353 
355 void
357  const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &cloud_normals,
358  const PointCloudInConstPtr &cloud_surface, const PointIndicesConstPtr &indices)
359 {
360  // No subscribers, no work
361  if (pub_output_.getNumSubscribers () <= 0)
362  return;
363 
364  // If cloud+normals is given, check if it's valid
365  if (!isValid (cloud))// || !isValid (cloud_normals, "normals"))
366  {
367  NODELET_ERROR ("[%s::input_normals_surface_indices_callback] Invalid input!", getName ().c_str ());
368  emptyPublish (cloud);
369  return;
370  }
371 
372  // If surface is given, check if it's valid
373  if (cloud_surface && !isValid (cloud_surface, "surface"))
374  {
375  NODELET_ERROR ("[%s::input_normals_surface_indices_callback] Invalid input surface!", getName ().c_str ());
376  emptyPublish (cloud);
377  return;
378  }
379 
380  // If indices are given, check if they are valid
381  if (indices && !isValid (indices))
382  {
383  NODELET_ERROR ("[%s::input_normals_surface_indices_callback] Invalid input indices!", getName ().c_str ());
384  emptyPublish (cloud);
385  return;
386  }
387 
389  if (cloud_surface)
390  if (indices)
391  NODELET_DEBUG ("[%s::input_normals_surface_indices_callback]\n"
392  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
393  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
394  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
395  " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
396  getName ().c_str (),
397  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
398  cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), cloud_surface->header.stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str (),
399  cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), cloud_normals->header.stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str (),
400  indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ());
401  else
402  NODELET_DEBUG ("[%s::input_normals_surface_indices_callback]\n"
403  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
404  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
405  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
406  getName ().c_str (),
407  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
408  cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), cloud_surface->header.stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str (),
409  cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), cloud_normals->header.stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str ());
410  else
411  if (indices)
412  NODELET_DEBUG ("[%s::input_normals_surface_indices_callback]\n"
413  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
414  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
415  " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
416  getName ().c_str (),
417  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
418  cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), cloud_normals->header.stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str (),
419  indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ());
420  else
421  NODELET_DEBUG ("[%s::input_normals_surface_indices_callback]\n"
422  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
423  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
424  getName ().c_str (),
425  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
426  cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), cloud_normals->header.stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str ());
428 
429  if ((int)(cloud->width * cloud->height) < k_)
430  {
431  NODELET_ERROR ("[%s::input_normals_surface_indices_callback] Requested number of k-nearest neighbors (%d) is larger than the PointCloud size (%d)!", getName ().c_str (), k_, (int)(cloud->width * cloud->height));
432  emptyPublish (cloud);
433  return;
434  }
435 
436  // If indices given...
437  IndicesPtr vindices;
438  if (indices && !indices->header.frame_id.empty ())
439  vindices.reset (new std::vector<int> (indices->indices));
440 
441  computePublish (cloud, cloud_normals, cloud_surface, vindices);
442 }
443 
virtual void emptyPublish(const PointCloudInConstPtr &cloud)=0
Publish an empty point cloud of the feature output type.
virtual void onInit()
Nodelet initialization routine.
std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
#define NODELET_ERROR(...)
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
Definition: pcl_nodelet.h:203
virtual void onInit()
Nodelet initialization routine.
f
bool use_surface_
Set to true if the nodelet needs to listen for incoming point clouds representing the search surface...
Definition: feature.h:111
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloudIn, PointCloudIn, PointIndices > > > sync_input_surface_indices_a_
Synchronized input, surface, and point indices.
Definition: feature.h:162
const std::string & getName() const
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloudIn, PointCloudIn, PointIndices > > > sync_input_surface_indices_e_
Definition: feature.h:163
message_filters::Subscriber< PointIndices > sub_indices_filter_
The message filter subscriber for PointIndices.
Definition: pcl_nodelet.h:121
void config_callback(FeatureConfig &config, uint32_t level)
Dynamic reconfigure callback.
message_filters::PassThrough< PointCloudIn > nf_pc_
Definition: feature.h:143
void input_normals_surface_indices_callback(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &cloud_normals, const PointCloudInConstPtr &cloud_surface, const PointIndicesConstPtr &indices)
Input point cloud callback. Used when use_indices and use_surface are set.
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
int k_
The number of K nearest neighbors to use for each point.
Definition: feature.h:98
boost::shared_ptr< std::vector< int > > IndicesPtr
Definition: feature.h:76
double search_radius_
The nearest neighbors search radius for each point.
Definition: feature.h:101
boost::shared_ptr< ros::NodeHandle > pnh_
boost::shared_ptr< dynamic_reconfigure::Server< FeatureConfig > > srv_
Pointer to a dynamic reconfigure service.
Definition: feature.h:121
pcl::PointCloud< pcl::PointXYZ > PointCloudIn
Definition: feature.h:72
void input_surface_indices_callback(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &cloud_surface, const PointIndicesConstPtr &indices)
Input point cloud callback. Used when use_indices and use_surface are set.
message_filters::PassThrough< PointIndices > nf_pi_
Null passthrough filter, used for pushing empty elements in the synchronizer.
Definition: feature.h:142
message_filters::Subscriber< PointCloudIn > sub_surface_filter_
The surface PointCloud subscriber filter.
Definition: feature.h:105
ros::Subscriber sub_input_
The input PointCloud subscriber.
Definition: feature.h:108
uint32_t getNumSubscribers() const
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
int spatial_locator_type_
Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Near...
Definition: feature.h:118
bool approximate_sync_
True if we use an approximate time synchronizer versus an exact one (false by default).
Definition: pcl_nodelet.h:130
int max_queue_size_
The maximum queue size (default: 3).
Definition: pcl_nodelet.h:127
ros::Publisher pub_output_
The output PointCloud publisher.
Definition: pcl_nodelet.h:124
PointCloudIn::ConstPtr PointCloudInConstPtr
Definition: feature.h:74
virtual void computePublish(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)=0
Compute the feature and publish it. Internal method.
#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
virtual bool childInit(ros::NodeHandle &nh)=0
Child initialization routine. Internal method.
message_filters::Subscriber< PointCloud > sub_input_filter_
The message filter subscriber for PointCloud2.
Definition: pcl_nodelet.h:118
void input_callback(const PointCloudInConstPtr &input)
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty e...
Definition: feature.h:150
Connection registerCallback(const C &callback)


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Mon Jun 10 2019 14:19:18