geometric_consistency_grouping_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include <pcl/kdtree/kdtree_flann.h>
00037 #include <pcl/kdtree/impl/kdtree_flann.hpp>
00038 #include "jsk_pcl_ros/geometric_consistency_grouping.h"
00039 #include "jsk_recognition_utils/pcl_conversion_util.h"
00040 #include <pcl/recognition/cg/geometric_consistency.h>
00041 
00042 namespace jsk_pcl_ros
00043 {
00044   void GeometricConsistencyGrouping::onInit()
00045   {
00046     DiagnosticNodelet::onInit();
00047     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00048     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00049       boost::bind (&GeometricConsistencyGrouping::configCallback, this, _1, _2);
00050     srv_->setCallback (f);
00051     pub_output_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output", 1);
00052     pub_output_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output/cloud", 1);
00053 
00054     reference_sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00055     sub_reference_cloud_.subscribe(*pnh_, "input/reference", 1);
00056     sub_reference_feature_.subscribe(*pnh_, "input/reference/feature", 1);
00057     reference_sync_->connectInput(sub_reference_cloud_, sub_reference_feature_);
00058     reference_sync_->registerCallback(
00059       boost::bind(&GeometricConsistencyGrouping::referenceCallback,
00060                   this, _1, _2));
00061     onInitPostProcess();
00062   }
00063 
00064   void GeometricConsistencyGrouping::subscribe()
00065   {
00066     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00067     sub_input_.subscribe(*pnh_, "input", 1);
00068     sub_feature_.subscribe(*pnh_, "input/feature", 1);
00069     sync_->connectInput(sub_input_, sub_feature_);
00070     sync_->registerCallback(boost::bind(&GeometricConsistencyGrouping::recognize,
00071                                         this, _1, _2));
00072   }
00073 
00074   void GeometricConsistencyGrouping::unsubscribe()
00075   {
00076     sub_input_.unsubscribe();
00077     sub_feature_.unsubscribe();
00078   }
00079 
00080   void GeometricConsistencyGrouping::configCallback(
00081     Config& config, uint32_t level)
00082   {
00083     boost::mutex::scoped_lock lock(mutex_);
00084     gc_size_ = config.gc_size;
00085     gc_thresh_ = config.gc_thresh;
00086   }
00087 
00088   void GeometricConsistencyGrouping::referenceCallback(
00089       const sensor_msgs::PointCloud2::ConstPtr& model_cloud_msg,
00090       const sensor_msgs::PointCloud2::ConstPtr& model_feature_msg)
00091   {
00092     boost::mutex::scoped_lock lock(mutex_);
00093 
00094     reference_cloud_.reset(new pcl::PointCloud<pcl::PointNormal>);
00095     reference_feature_.reset(new pcl::PointCloud<pcl::SHOT352>);
00096     
00097     pcl::fromROSMsg(*model_cloud_msg, *reference_cloud_);
00098     pcl::fromROSMsg(*model_feature_msg, *reference_feature_);
00099   }
00100 
00101   void GeometricConsistencyGrouping::recognize(
00102     const sensor_msgs::PointCloud2::ConstPtr& scene_cloud_msg,
00103     const sensor_msgs::PointCloud2::ConstPtr& scene_feature_msg)
00104   {
00105     boost::mutex::scoped_lock lock(mutex_);
00106     if (!reference_cloud_ || !reference_feature_) {
00107       NODELET_ERROR_THROTTLE(1.0, "Not yet reference is available");
00108       return;
00109     }
00110 
00111     pcl::PointCloud<pcl::SHOT352>::Ptr
00112       scene_feature (new pcl::PointCloud<pcl::SHOT352>);
00113     pcl::PointCloud<pcl::PointNormal>::Ptr
00114       scene_cloud (new pcl::PointCloud<pcl::PointNormal>);
00115     pcl::fromROSMsg(*scene_cloud_msg, *scene_cloud);
00116     pcl::fromROSMsg(*scene_feature_msg, *scene_feature);
00117 
00118     pcl::CorrespondencesPtr model_scene_corrs (new pcl::Correspondences ());
00119     pcl::KdTreeFLANN<pcl::SHOT352> match_search;
00120     match_search.setInputCloud (reference_feature_);
00121 
00122     for (size_t i = 0; i < scene_feature->size(); ++i)
00123     {
00124       std::vector<int> neigh_indices(1);
00125       std::vector<float> neigh_sqr_dists(1);
00126       if (!pcl_isfinite (scene_feature->at(i).descriptor[0])) { //skipping NaNs
00127         continue;
00128       }
00129       int found_neighs
00130         = match_search.nearestKSearch(scene_feature->at(i), 1,
00131                                       neigh_indices, neigh_sqr_dists);
00132       //  add match only if the squared descriptor distance is less than 0.25
00133       // (SHOT descriptor distances are between 0 and 1 by design)
00134       if (found_neighs == 1 && neigh_sqr_dists[0] < 0.25f) {
00135         pcl::Correspondence corr (neigh_indices[0], static_cast<int> (i), neigh_sqr_dists[0]);
00136         model_scene_corrs->push_back (corr);
00137       }
00138     }
00139 
00140     pcl::GeometricConsistencyGrouping<pcl::PointNormal, pcl::PointNormal> gc_clusterer;
00141     gc_clusterer.setGCSize(gc_size_);
00142     gc_clusterer.setGCThreshold(gc_thresh_);
00143 
00144     gc_clusterer.setInputCloud(reference_cloud_);
00145     gc_clusterer.setSceneCloud(scene_cloud);
00146     gc_clusterer.setModelSceneCorrespondences(model_scene_corrs);
00147 
00148     //gc_clusterer.cluster (clustered_corrs);
00149     std::vector<pcl::Correspondences> clustered_corrs;
00150     std::vector<Eigen::Matrix4f,
00151                 Eigen::aligned_allocator<Eigen::Matrix4f> > rototranslations;
00152     gc_clusterer.recognize(rototranslations, clustered_corrs);
00153     if (rototranslations.size() > 0) {
00154       NODELET_INFO("detected %lu objects", rototranslations.size());
00155       Eigen::Matrix4f result_mat = rototranslations[0];
00156       Eigen::Affine3f affine(result_mat);
00157       geometry_msgs::PoseStamped ros_pose;
00158       tf::poseEigenToMsg(affine, ros_pose.pose);
00159       ros_pose.header = scene_cloud_msg->header;
00160       pub_output_.publish(ros_pose);
00161     }
00162     else {
00163       NODELET_WARN("Failed to find object");
00164     }
00165     
00166   }
00167 
00168 }
00169 
00170 
00171 #include <pluginlib/class_list_macros.h>
00172 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::GeometricConsistencyGrouping, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:41:43