Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "jsk_pcl_ros/geometric_consistency_grouping.h"
00037 #include "jsk_pcl_ros/pcl_conversion_util.h"
00038 #include <pcl/recognition/cg/geometric_consistency.h>
00039 #include <pcl/kdtree/kdtree_flann.h>
00040 #include <pcl/kdtree/impl/kdtree_flann.hpp>
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 }
00062
00063 void GeometricConsistencyGrouping::subscribe()
00064 {
00065 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00066 sub_input_.subscribe(*pnh_, "input", 1);
00067 sub_feature_.subscribe(*pnh_, "input/feature", 1);
00068 sync_->connectInput(sub_input_, sub_feature_);
00069 sync_->registerCallback(boost::bind(&GeometricConsistencyGrouping::recognize,
00070 this, _1, _2));
00071 }
00072
00073 void GeometricConsistencyGrouping::unsubscribe()
00074 {
00075 sub_input_.unsubscribe();
00076 sub_feature_.unsubscribe();
00077 }
00078
00079 void GeometricConsistencyGrouping::configCallback(
00080 Config& config, uint32_t level)
00081 {
00082 boost::mutex::scoped_lock lock(mutex_);
00083 gc_size_ = config.gc_size;
00084 gc_thresh_ = config.gc_thresh;
00085 }
00086
00087 void GeometricConsistencyGrouping::referenceCallback(
00088 const sensor_msgs::PointCloud2::ConstPtr& model_cloud_msg,
00089 const sensor_msgs::PointCloud2::ConstPtr& model_feature_msg)
00090 {
00091 boost::mutex::scoped_lock lock(mutex_);
00092
00093 reference_cloud_.reset(new pcl::PointCloud<pcl::PointNormal>);
00094 reference_feature_.reset(new pcl::PointCloud<pcl::SHOT352>);
00095
00096 pcl::fromROSMsg(*model_cloud_msg, *reference_cloud_);
00097 pcl::fromROSMsg(*model_feature_msg, *reference_feature_);
00098 }
00099
00100 void GeometricConsistencyGrouping::recognize(
00101 const sensor_msgs::PointCloud2::ConstPtr& scene_cloud_msg,
00102 const sensor_msgs::PointCloud2::ConstPtr& scene_feature_msg)
00103 {
00104 boost::mutex::scoped_lock lock(mutex_);
00105 if (!reference_cloud_ || !reference_feature_) {
00106 NODELET_ERROR_THROTTLE(1.0, "Not yet reference is available");
00107 return;
00108 }
00109
00110 pcl::PointCloud<pcl::SHOT352>::Ptr
00111 scene_feature (new pcl::PointCloud<pcl::SHOT352>);
00112 pcl::PointCloud<pcl::PointNormal>::Ptr
00113 scene_cloud (new pcl::PointCloud<pcl::PointNormal>);
00114 pcl::fromROSMsg(*scene_cloud_msg, *scene_cloud);
00115 pcl::fromROSMsg(*scene_feature_msg, *scene_feature);
00116
00117 pcl::CorrespondencesPtr model_scene_corrs (new pcl::Correspondences ());
00118 pcl::KdTreeFLANN<pcl::SHOT352> match_search;
00119 match_search.setInputCloud (reference_feature_);
00120
00121 for (size_t i = 0; i < scene_feature->size(); ++i)
00122 {
00123 std::vector<int> neigh_indices(1);
00124 std::vector<float> neigh_sqr_dists(1);
00125 if (!pcl_isfinite (scene_feature->at(i).descriptor[0])) {
00126 continue;
00127 }
00128 int found_neighs
00129 = match_search.nearestKSearch(scene_feature->at(i), 1,
00130 neigh_indices, neigh_sqr_dists);
00131
00132
00133 if (found_neighs == 1 && neigh_sqr_dists[0] < 0.25f) {
00134 pcl::Correspondence corr (neigh_indices[0], static_cast<int> (i), neigh_sqr_dists[0]);
00135 model_scene_corrs->push_back (corr);
00136 }
00137 }
00138
00139 pcl::GeometricConsistencyGrouping<pcl::PointNormal, pcl::PointNormal> gc_clusterer;
00140 gc_clusterer.setGCSize(gc_size_);
00141 gc_clusterer.setGCThreshold(gc_thresh_);
00142
00143 gc_clusterer.setInputCloud(reference_cloud_);
00144 gc_clusterer.setSceneCloud(scene_cloud);
00145 gc_clusterer.setModelSceneCorrespondences(model_scene_corrs);
00146
00147
00148 std::vector<pcl::Correspondences> clustered_corrs;
00149 std::vector<Eigen::Matrix4f,
00150 Eigen::aligned_allocator<Eigen::Matrix4f> > rototranslations;
00151 gc_clusterer.recognize(rototranslations, clustered_corrs);
00152 if (rototranslations.size() > 0) {
00153 JSK_NODELET_INFO("detected %lu objects", rototranslations.size());
00154 Eigen::Matrix4f result_mat = rototranslations[0];
00155 Eigen::Affine3f affine(result_mat);
00156 geometry_msgs::PoseStamped ros_pose;
00157 tf::poseEigenToMsg(affine, ros_pose.pose);
00158 ros_pose.header = scene_cloud_msg->header;
00159 pub_output_.publish(ros_pose);
00160 }
00161 else {
00162 JSK_NODELET_WARN("Failed to find object");
00163 }
00164
00165 }
00166
00167 }
00168
00169
00170 #include <pluginlib/class_list_macros.h>
00171 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::GeometricConsistencyGrouping, nodelet::Nodelet);