69     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 ());
 
   74     NODELET_ERROR (
"[%s::onInit] Need a 'spatial_locator' parameter to be set before continuing!", 
getName ().c_str ());
 
   82   srv_ = boost::make_shared<dynamic_reconfigure::Server<FeatureConfig> > (*pnh_);
 
   84   srv_->setCallback (
f);
 
   86   NODELET_DEBUG (
"[%s::onInit] Nodelet successfully created with the following parameters:\n" 
   87                  " - use_surface    : %s\n" 
   89                  " - radius_search  : %f\n" 
   90                  " - spatial_locator: %d",
 
  102   if (use_indices_ || use_surface_)
 
  105     if (approximate_sync_)
 
  106       sync_input_surface_indices_a_ = boost::make_shared<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloudIn, PointCloudIn, PointIndices> > >(max_queue_size_);
 
  108       sync_input_surface_indices_e_ = boost::make_shared<message_filters::Synchronizer<sync_policies::ExactTime<PointCloudIn, PointCloudIn, PointIndices> > >(max_queue_size_);
 
  111     sub_input_filter_.subscribe (*pnh_, 
"input", max_queue_size_);
 
  115       sub_indices_filter_.subscribe (*pnh_, 
"indices", max_queue_size_);
 
  119         sub_surface_filter_.subscribe (*pnh_, 
"surface", max_queue_size_);
 
  120         if (approximate_sync_)
 
  121           sync_input_surface_indices_a_->connectInput (sub_input_filter_, sub_surface_filter_, sub_indices_filter_);
 
  123           sync_input_surface_indices_e_->connectInput (sub_input_filter_, sub_surface_filter_, sub_indices_filter_);
 
  129         if (approximate_sync_)
 
  130           sync_input_surface_indices_a_->connectInput (sub_input_filter_, nf_pc_, sub_indices_filter_);
 
  132           sync_input_surface_indices_e_->connectInput (sub_input_filter_, nf_pc_, sub_indices_filter_);
 
  139       sub_surface_filter_.subscribe (*pnh_, 
"surface", max_queue_size_);
 
  140       if (approximate_sync_)
 
  141         sync_input_surface_indices_a_->connectInput (sub_input_filter_, sub_surface_filter_, nf_pi_);
 
  143         sync_input_surface_indices_e_->connectInput (sub_input_filter_, sub_surface_filter_, nf_pi_);
 
  146     if (approximate_sync_)
 
  160   if (use_indices_ || use_surface_)
 
  162     sub_input_filter_.unsubscribe ();
 
  165       sub_indices_filter_.unsubscribe ();
 
  167         sub_surface_filter_.unsubscribe ();
 
  170       sub_surface_filter_.unsubscribe ();
 
  173     sub_input_.shutdown ();
 
  180   if (k_ != config.k_search)
 
  182     k_ = config.k_search;
 
  183     NODELET_DEBUG (
"[config_callback] Setting the number of K nearest neighbors to use for each point: %d.", k_);
 
  185   if (search_radius_ != config.radius_search)
 
  187     search_radius_ = config.radius_search;
 
  188     NODELET_DEBUG (
"[config_callback] Setting the nearest neighbors search radius for each point: %f.", search_radius_);
 
  198   if (pub_output_.getNumSubscribers () <= 0)
 
  202   if (!isValid (cloud))
 
  205     emptyPublish (cloud);
 
  210   if (cloud_surface && !isValid (cloud_surface, 
"surface"))
 
  212     NODELET_ERROR (
"[%s::input_surface_indices_callback] Invalid input surface!", 
getName ().c_str ());
 
  213     emptyPublish (cloud);
 
  218   if (indices && !isValid (indices))
 
  220     NODELET_ERROR (
"[%s::input_surface_indices_callback] Invalid input indices!", 
getName ().c_str ());
 
  221     emptyPublish (cloud);
 
  229                      "                                         - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  230                      "                                         - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  231                      "                                         - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
 
  232                  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 (),
 
  233                  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 (),
 
  234                  indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName (
"indices").c_str ());
 
  237                      "                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  238                      "                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
 
  239                      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 (),
 
  240                      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 ());
 
  245                      "                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  246                      "                                 - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
 
  247                      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 (),
 
  248                      indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName (
"indices").c_str ());
 
  250       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   if ((
int)(cloud->width * cloud->height) < k_)
 
  256     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));
 
  257     emptyPublish (cloud);
 
  263   if (indices && !indices->header.frame_id.empty ())
 
  264     vindices.reset (
new std::vector<int> (indices->indices));
 
  266   computePublish (cloud, cloud_surface, vindices);
 
  288   if (!pnh_->getParam (
"k_search", k_) && !pnh_->getParam (
"radius_search", search_radius_))
 
  290     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   if (!pnh_->getParam (
"spatial_locator", spatial_locator_type_))
 
  295     NODELET_ERROR (
"[%s::onInit] Need a 'spatial_locator' parameter to be set before continuing!", 
getName ().c_str ());
 
  299   pnh_->getParam (
"use_surface", use_surface_);
 
  302   srv_ = boost::make_shared<dynamic_reconfigure::Server<FeatureConfig> > (*pnh_);
 
  304   srv_->setCallback (
f);
 
  306   NODELET_DEBUG (
"[%s::onInit] Nodelet successfully created with the following parameters:\n" 
  307                  " - use_surface    : %s\n" 
  309                  " - radius_search  : %f\n" 
  310                  " - spatial_locator: %d",
 
  312                  (use_surface_) ? 
"true" : 
"false", k_, search_radius_, spatial_locator_type_);
 
  314   onInitPostProcess ();
 
  321   sub_input_filter_.subscribe (*pnh_, 
"input", max_queue_size_);
 
  322   sub_normals_filter_.subscribe (*pnh_, 
"normals", max_queue_size_);
 
  325   if (approximate_sync_)
 
  326     sync_input_normals_surface_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloudIn, PointCloudN, PointCloudIn, PointIndices> > > (max_queue_size_);
 
  328     sync_input_normals_surface_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloudIn, PointCloudN, PointCloudIn, PointIndices> > > (max_queue_size_);
 
  331   if (use_indices_ || use_surface_)
 
  336       sub_indices_filter_.subscribe (*pnh_, 
"indices", max_queue_size_);
 
  340         sub_surface_filter_.subscribe (*pnh_, 
"surface", max_queue_size_);
 
  341         if (approximate_sync_)
 
  342           sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, sub_indices_filter_);
 
  344           sync_input_normals_surface_indices_e_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, sub_indices_filter_);
 
  349         if (approximate_sync_)
 
  351           sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, sub_indices_filter_);
 
  354           sync_input_normals_surface_indices_e_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, sub_indices_filter_);
 
  360       sub_surface_filter_.subscribe (*pnh_, 
"surface", max_queue_size_);
 
  363       if (approximate_sync_)
 
  364         sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, nf_pi_);
 
  366         sync_input_normals_surface_indices_e_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, nf_pi_);
 
  373     if (approximate_sync_)
 
  374       sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, nf_pi_);
 
  376       sync_input_normals_surface_indices_e_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, nf_pi_);
 
  380   if (approximate_sync_)
 
  390   sub_input_filter_.unsubscribe ();
 
  391   sub_normals_filter_.unsubscribe ();
 
  392   if (use_indices_ || use_surface_)
 
  396       sub_indices_filter_.unsubscribe ();
 
  398         sub_surface_filter_.unsubscribe ();
 
  401       sub_surface_filter_.unsubscribe ();
 
  412   if (pub_output_.getNumSubscribers () <= 0)
 
  416   if (!isValid (cloud))
 
  418     NODELET_ERROR (
"[%s::input_normals_surface_indices_callback] Invalid input!", 
getName ().c_str ());
 
  419     emptyPublish (cloud);
 
  424   if (cloud_surface && !isValid (cloud_surface, 
"surface"))
 
  426     NODELET_ERROR (
"[%s::input_normals_surface_indices_callback] Invalid input surface!", 
getName ().c_str ());
 
  427     emptyPublish (cloud);
 
  432   if (indices && !isValid (indices))
 
  434     NODELET_ERROR (
"[%s::input_normals_surface_indices_callback] Invalid input indices!", 
getName ().c_str ());
 
  435     emptyPublish (cloud);
 
  442       NODELET_DEBUG (
"[%s::input_normals_surface_indices_callback]\n" 
  443                      "                                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  444                      "                                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  445                      "                                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  446                      "                                                 - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
 
  448                      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 (),
 
  449                      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 (),
 
  450                      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 (),
 
  451                      indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName (
"indices").c_str ());
 
  453       NODELET_DEBUG (
"[%s::input_normals_surface_indices_callback]\n" 
  454                      "                                         - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  455                      "                                         - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  456                      "                                         - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
 
  458                      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 (),
 
  459                      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 (),
 
  460                      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       NODELET_DEBUG (
"[%s::input_normals_surface_indices_callback]\n" 
  464                      "                                         - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  465                      "                                         - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  466                      "                                         - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
 
  468                      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 (),
 
  469                      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 (),
 
  470                      indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName (
"indices").c_str ());
 
  472       NODELET_DEBUG (
"[%s::input_normals_surface_indices_callback]\n" 
  473                      "                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  474                      "                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
 
  476                      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 (),
 
  477                      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 ());
 
  480   if ((
int)(cloud->width * cloud->height) < k_)
 
  482     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));
 
  483     emptyPublish (cloud);
 
  489   if (indices && !indices->header.frame_id.empty ())
 
  490     vindices.reset (
new std::vector<int> (indices->indices));
 
  492   computePublish (cloud, cloud_normals, cloud_surface, vindices);