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  NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
89  " - use_surface : %s\n"
90  " - k_search : %d\n"
91  " - radius_search : %f\n"
92  " - spatial_locator: %d",
93  getName ().c_str (),
94  (use_surface_) ? "true" : "false", k_, search_radius_, spatial_locator_type_);
95 
97 }
98 
100 void
102 {
103  // If we're supposed to look for PointIndices (indices) or PointCloud (surface) messages
104  if (use_indices_ || use_surface_)
105  {
106  // Create the objects here
107  if (approximate_sync_)
108  sync_input_surface_indices_a_ = boost::make_shared<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloudIn, PointCloudIn, PointIndices> > >(max_queue_size_);
109  else
110  sync_input_surface_indices_e_ = boost::make_shared<message_filters::Synchronizer<sync_policies::ExactTime<PointCloudIn, PointCloudIn, PointIndices> > >(max_queue_size_);
111 
112  // Subscribe to the input using a filter
114  if (use_indices_)
115  {
116  // If indices are enabled, subscribe to the indices
118  if (use_surface_) // Use both indices and surface
119  {
120  // If surface is enabled, subscribe to the surface, connect the input-indices-surface trio and register
122  if (approximate_sync_)
124  else
125  sync_input_surface_indices_e_->connectInput (sub_input_filter_, sub_surface_filter_, sub_indices_filter_);
126  }
127  else // Use only indices
128  {
130  // surface not enabled, connect the input-indices duo and register
131  if (approximate_sync_)
133  else
134  sync_input_surface_indices_e_->connectInput (sub_input_filter_, nf_pc_, sub_indices_filter_);
135  }
136  }
137  else // Use only surface
138  {
140  // indices not enabled, connect the input-surface duo and register
142  if (approximate_sync_)
144  else
145  sync_input_surface_indices_e_->connectInput (sub_input_filter_, sub_surface_filter_, nf_pi_);
146  }
147  // Register callbacks
148  if (approximate_sync_)
149  sync_input_surface_indices_a_->registerCallback (bind (&Feature::input_surface_indices_callback, this, _1, _2, _3));
150  else
151  sync_input_surface_indices_e_->registerCallback (bind (&Feature::input_surface_indices_callback, this, _1, _2, _3));
152  }
153  else
154  // Subscribe in an old fashion to input only (no filters)
156 }
157 
159 void
161 {
162  if (use_indices_ || use_surface_)
163  {
165  if (use_indices_)
166  {
168  if (use_surface_)
170  }
171  else
173  }
174  else
175  sub_input_.shutdown ();
176 }
177 
179 void
180 pcl_ros::Feature::config_callback (FeatureConfig &config, uint32_t level)
181 {
182  if (k_ != config.k_search)
183  {
184  k_ = config.k_search;
185  NODELET_DEBUG ("[config_callback] Setting the number of K nearest neighbors to use for each point: %d.", k_);
186  }
187  if (search_radius_ != config.radius_search)
188  {
189  search_radius_ = config.radius_search;
190  NODELET_DEBUG ("[config_callback] Setting the nearest neighbors search radius for each point: %f.", search_radius_);
191  }
192 }
193 
195 void
197  const PointCloudInConstPtr &cloud_surface, const PointIndicesConstPtr &indices)
198 {
199  // No subscribers, no work
200  if (pub_output_.getNumSubscribers () <= 0)
201  return;
202 
203  // If cloud is given, check if it's valid
204  if (!isValid (cloud))
205  {
206  NODELET_ERROR ("[%s::input_surface_indices_callback] Invalid input!", getName ().c_str ());
207  emptyPublish (cloud);
208  return;
209  }
210 
211  // If surface is given, check if it's valid
212  if (cloud_surface && !isValid (cloud_surface, "surface"))
213  {
214  NODELET_ERROR ("[%s::input_surface_indices_callback] Invalid input surface!", getName ().c_str ());
215  emptyPublish (cloud);
216  return;
217  }
218 
219  // If indices are given, check if they are valid
220  if (indices && !isValid (indices))
221  {
222  NODELET_ERROR ("[%s::input_surface_indices_callback] Invalid input indices!", getName ().c_str ());
223  emptyPublish (cloud);
224  return;
225  }
226 
228  if (cloud_surface)
229  if (indices)
230  NODELET_DEBUG ("[input_surface_indices_callback]\n"
231  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
232  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
233  " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
234  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
235  cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), fromPCL(cloud_surface->header).stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str (),
236  indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ());
237  else
238  NODELET_DEBUG ("[input_surface_indices_callback]\n"
239  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
240  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
241  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
242  cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), fromPCL(cloud_surface->header).stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str ());
243 
244  else
245  if (indices)
246  NODELET_DEBUG ("[input_surface_indices_callback]\n"
247  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
248  " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
249  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
250  indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ());
251  else
252  NODELET_DEBUG ("[input_surface_indices_callback] PointCloud with %d data points, stamp %f, and frame %s on topic %s received.", cloud->width * cloud->height, fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str ());
254 
255 
256  if ((int)(cloud->width * cloud->height) < k_)
257  {
258  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));
259  emptyPublish (cloud);
260  return;
261  }
262 
263  // If indices given...
264  IndicesPtr vindices;
265  if (indices && !indices->header.frame_id.empty ())
266  vindices.reset (new std::vector<int> (indices->indices));
267 
268  computePublish (cloud, cloud_surface, vindices);
269 }
270 
274 
276 void
278 {
279  // Call the super onInit ()
281 
282  // Call the child init
283  childInit (*pnh_);
284 
285  // Allow each individual class that inherits from us to declare their own Publisher
286  // This is useful for Publisher<pcl::PointCloud<T> >, as NormalEstimation can publish PointCloud<Normal>, etc
287  //pub_output_ = pnh_->template advertise<PointCloud2> ("output", max_queue_size_);
288 
289  // ---[ Mandatory parameters
290  if (!pnh_->getParam ("k_search", k_) && !pnh_->getParam ("radius_search", search_radius_))
291  {
292  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 ());
293  return;
294  }
295  if (!pnh_->getParam ("spatial_locator", spatial_locator_type_))
296  {
297  NODELET_ERROR ("[%s::onInit] Need a 'spatial_locator' parameter to be set before continuing!", getName ().c_str ());
298  return;
299  }
300  // ---[ Optional parameters
301  pnh_->getParam ("use_surface", use_surface_);
302 
303  // Enable the dynamic reconfigure service
304  srv_ = boost::make_shared<dynamic_reconfigure::Server<FeatureConfig> > (*pnh_);
305  dynamic_reconfigure::Server<FeatureConfig>::CallbackType f = boost::bind (&FeatureFromNormals::config_callback, this, _1, _2);
306  srv_->setCallback (f);
307 
308  NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
309  " - use_surface : %s\n"
310  " - k_search : %d\n"
311  " - radius_search : %f\n"
312  " - spatial_locator: %d",
313  getName ().c_str (),
314  (use_surface_) ? "true" : "false", k_, search_radius_, spatial_locator_type_);
315 
317 }
318 
320 void
322 {
324  sub_normals_filter_.subscribe (*pnh_, "normals", max_queue_size_);
325 
326  // Create the objects here
327  if (approximate_sync_)
328  sync_input_normals_surface_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloudIn, PointCloudN, PointCloudIn, PointIndices> > > (max_queue_size_);
329  else
330  sync_input_normals_surface_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloudIn, PointCloudN, PointCloudIn, PointIndices> > > (max_queue_size_);
331 
332  // If we're supposed to look for PointIndices (indices) or PointCloud (surface) messages
333  if (use_indices_ || use_surface_)
334  {
335  if (use_indices_)
336  {
337  // If indices are enabled, subscribe to the indices
339  if (use_surface_) // Use both indices and surface
340  {
341  // If surface is enabled, subscribe to the surface, connect the input-indices-surface trio and register
343  if (approximate_sync_)
344  sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, sub_indices_filter_);
345  else
346  sync_input_normals_surface_indices_e_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, sub_indices_filter_);
347  }
348  else // Use only indices
349  {
351  if (approximate_sync_)
352  // surface not enabled, connect the input-indices duo and register
353  sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, sub_indices_filter_);
354  else
355  // surface not enabled, connect the input-indices duo and register
356  sync_input_normals_surface_indices_e_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, sub_indices_filter_);
357  }
358  }
359  else // Use only surface
360  {
361  // indices not enabled, connect the input-surface duo and register
363 
365  if (approximate_sync_)
366  sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, nf_pi_);
367  else
368  sync_input_normals_surface_indices_e_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, nf_pi_);
369  }
370  }
371  else
372  {
374 
375  if (approximate_sync_)
376  sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, nf_pi_);
377  else
378  sync_input_normals_surface_indices_e_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, nf_pi_);
379  }
380 
381  // Register callbacks
382  if (approximate_sync_)
383  sync_input_normals_surface_indices_a_->registerCallback (bind (&FeatureFromNormals::input_normals_surface_indices_callback, this, _1, _2, _3, _4));
384  else
385  sync_input_normals_surface_indices_e_->registerCallback (bind (&FeatureFromNormals::input_normals_surface_indices_callback, this, _1, _2, _3, _4));
386 }
387 
389 void
391 {
393  sub_normals_filter_.unsubscribe ();
394  if (use_indices_ || use_surface_)
395  {
396  if (use_indices_)
397  {
399  if (use_surface_)
401  }
402  else
404  }
405 }
406 
408 void
410  const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &cloud_normals,
411  const PointCloudInConstPtr &cloud_surface, const PointIndicesConstPtr &indices)
412 {
413  // No subscribers, no work
414  if (pub_output_.getNumSubscribers () <= 0)
415  return;
416 
417  // If cloud+normals is given, check if it's valid
418  if (!isValid (cloud))// || !isValid (cloud_normals, "normals"))
419  {
420  NODELET_ERROR ("[%s::input_normals_surface_indices_callback] Invalid input!", getName ().c_str ());
421  emptyPublish (cloud);
422  return;
423  }
424 
425  // If surface is given, check if it's valid
426  if (cloud_surface && !isValid (cloud_surface, "surface"))
427  {
428  NODELET_ERROR ("[%s::input_normals_surface_indices_callback] Invalid input surface!", getName ().c_str ());
429  emptyPublish (cloud);
430  return;
431  }
432 
433  // If indices are given, check if they are valid
434  if (indices && !isValid (indices))
435  {
436  NODELET_ERROR ("[%s::input_normals_surface_indices_callback] Invalid input indices!", getName ().c_str ());
437  emptyPublish (cloud);
438  return;
439  }
440 
442  if (cloud_surface)
443  if (indices)
444  NODELET_DEBUG ("[%s::input_normals_surface_indices_callback]\n"
445  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
446  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
447  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
448  " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
449  getName ().c_str (),
450  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
451  cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), fromPCL(cloud_surface->header).stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str (),
452  cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), fromPCL(cloud_normals->header).stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str (),
453  indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ());
454  else
455  NODELET_DEBUG ("[%s::input_normals_surface_indices_callback]\n"
456  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
457  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
458  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
459  getName ().c_str (),
460  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
461  cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), fromPCL(cloud_surface->header).stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str (),
462  cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), fromPCL(cloud_normals->header).stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str ());
463  else
464  if (indices)
465  NODELET_DEBUG ("[%s::input_normals_surface_indices_callback]\n"
466  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
467  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
468  " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
469  getName ().c_str (),
470  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
471  cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), fromPCL(cloud_normals->header).stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str (),
472  indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ());
473  else
474  NODELET_DEBUG ("[%s::input_normals_surface_indices_callback]\n"
475  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
476  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
477  getName ().c_str (),
478  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
479  cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), fromPCL(cloud_normals->header).stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str ());
481 
482  if ((int)(cloud->width * cloud->height) < k_)
483  {
484  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));
485  emptyPublish (cloud);
486  return;
487  }
488 
489  // If indices given...
490  IndicesPtr vindices;
491  if (indices && !indices->header.frame_id.empty ())
492  vindices.reset (new std::vector<int> (indices->indices));
493 
494  computePublish (cloud, cloud_normals, cloud_surface, vindices);
495 }
496 
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)
virtual void subscribe()
NodeletLazy connection routine.
#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
PointCloudN::ConstPtr PointCloudNConstPtr
Definition: feature.h:195
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
double search_radius_
The nearest neighbors search radius for each point.
Definition: feature.h:101
boost::shared_ptr< ros::NodeHandle > pnh_
virtual void subscribe()
NodeletLazy connection routine.
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
virtual void unsubscribe()
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 Wed Jun 5 2019 19:52:52