35 #define BOOST_PARAMETER_MAX_ARITY 7 
   36 #include <pcl/kdtree/kdtree_flann.h> 
   37 #include <pcl/kdtree/impl/kdtree_flann.hpp> 
   40 #include <pcl/recognition/cg/geometric_consistency.h> 
   46     DiagnosticNodelet::onInit();
 
   47     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
 
   48     typename dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
   50     srv_->setCallback (
f);
 
   51     pub_output_ = advertise<geometry_msgs::PoseStamped>(*pnh_, 
"output", 1);
 
   52     pub_output_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_, 
"output/cloud", 1);
 
   54     reference_sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
 
   78     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
 
   93     Config& config, uint32_t level)
 
  101       const sensor_msgs::PointCloud2::ConstPtr& model_cloud_msg,
 
  102       const sensor_msgs::PointCloud2::ConstPtr& model_feature_msg)
 
  114 #if __cplusplus >= 201103L 
  115 #define pcl_isfinite(x) std::isfinite(x) 
  119     const sensor_msgs::PointCloud2::ConstPtr& scene_cloud_msg,
 
  120     const sensor_msgs::PointCloud2::ConstPtr& scene_feature_msg)
 
  128     pcl::PointCloud<pcl::SHOT352>::Ptr
 
  129       scene_feature (
new pcl::PointCloud<pcl::SHOT352>);
 
  130     pcl::PointCloud<pcl::PointNormal>::Ptr
 
  131       scene_cloud (
new pcl::PointCloud<pcl::PointNormal>);
 
  135     pcl::CorrespondencesPtr model_scene_corrs (
new pcl::Correspondences ());
 
  136     pcl::KdTreeFLANN<pcl::SHOT352> match_search;
 
  139     for (
size_t i = 0; 
i < scene_feature->size(); ++
i)
 
  141       std::vector<int> neigh_indices(1);
 
  142       std::vector<float> neigh_sqr_dists(1);
 
  143       if (!pcl_isfinite (scene_feature->at(
i).descriptor[0])) { 
 
  147         = match_search.nearestKSearch(scene_feature->at(
i), 1,
 
  148                                       neigh_indices, neigh_sqr_dists);
 
  151       if (found_neighs == 1 && neigh_sqr_dists[0] < 0.25
f) {
 
  152         pcl::Correspondence corr (neigh_indices[0], 
static_cast<int> (
i), neigh_sqr_dists[0]);
 
  153         model_scene_corrs->push_back (corr);
 
  157     pcl::GeometricConsistencyGrouping<pcl::PointNormal, pcl::PointNormal> gc_clusterer;
 
  162     gc_clusterer.setSceneCloud(scene_cloud);
 
  163     gc_clusterer.setModelSceneCorrespondences(model_scene_corrs);
 
  166     std::vector<pcl::Correspondences> clustered_corrs;
 
  167     std::vector<Eigen::Matrix4f,
 
  168                 Eigen::aligned_allocator<Eigen::Matrix4f> > rototranslations;
 
  169     gc_clusterer.recognize(rototranslations, clustered_corrs);
 
  170     if (rototranslations.size() > 0) {
 
  171       NODELET_INFO(
"detected %lu objects", rototranslations.size());
 
  172       Eigen::Matrix4f result_mat = rototranslations[0];
 
  173       Eigen::Affine3f affine(result_mat);
 
  174       geometry_msgs::PoseStamped ros_pose;
 
  176       ros_pose.header = scene_cloud_msg->header;