geometric_consistency_grouping_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
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>
41 
42 namespace jsk_pcl_ros
43 {
45  {
46  DiagnosticNodelet::onInit();
47  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
48  typename dynamic_reconfigure::Server<Config>::CallbackType f =
49  boost::bind (&GeometricConsistencyGrouping::configCallback, this, _1, _2);
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);
53 
54  reference_sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
55  sub_reference_cloud_.subscribe(*pnh_, "input/reference", 1);
56  sub_reference_feature_.subscribe(*pnh_, "input/reference/feature", 1);
58  reference_sync_->registerCallback(
60  this, _1, _2));
61  onInitPostProcess();
62  }
63 
65  // message_filters::Synchronizer needs to be called reset
66  // before message_filters::Subscriber is freed.
67  // Calling reset fixes the following error on shutdown of the nodelet:
68  // terminate called after throwing an instance of
69  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
70  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
71  // Also see https://github.com/ros/ros_comm/issues/720 .
72  sync_.reset();
73  reference_sync_.reset();
74  }
75 
77  {
78  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
79  sub_input_.subscribe(*pnh_, "input", 1);
80  sub_feature_.subscribe(*pnh_, "input/feature", 1);
81  sync_->connectInput(sub_input_, sub_feature_);
82  sync_->registerCallback(boost::bind(&GeometricConsistencyGrouping::recognize,
83  this, _1, _2));
84  }
85 
87  {
90  }
91 
93  Config& config, uint32_t level)
94  {
95  boost::mutex::scoped_lock lock(mutex_);
96  gc_size_ = config.gc_size;
97  gc_thresh_ = config.gc_thresh;
98  }
99 
101  const sensor_msgs::PointCloud2::ConstPtr& model_cloud_msg,
102  const sensor_msgs::PointCloud2::ConstPtr& model_feature_msg)
103  {
104  boost::mutex::scoped_lock lock(mutex_);
105 
106  reference_cloud_.reset(new pcl::PointCloud<pcl::PointNormal>);
107  reference_feature_.reset(new pcl::PointCloud<pcl::SHOT352>);
108 
109  pcl::fromROSMsg(*model_cloud_msg, *reference_cloud_);
110  pcl::fromROSMsg(*model_feature_msg, *reference_feature_);
111  }
112 
113  // pcl removed the method by 1.13, no harm in defining it ourselves to use below
114 #if __cplusplus >= 201103L
115 #define pcl_isfinite(x) std::isfinite(x)
116 #endif
117 
119  const sensor_msgs::PointCloud2::ConstPtr& scene_cloud_msg,
120  const sensor_msgs::PointCloud2::ConstPtr& scene_feature_msg)
121  {
122  boost::mutex::scoped_lock lock(mutex_);
124  NODELET_ERROR_THROTTLE(1.0, "Not yet reference is available");
125  return;
126  }
127 
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>);
132  pcl::fromROSMsg(*scene_cloud_msg, *scene_cloud);
133  pcl::fromROSMsg(*scene_feature_msg, *scene_feature);
134 
135  pcl::CorrespondencesPtr model_scene_corrs (new pcl::Correspondences ());
136  pcl::KdTreeFLANN<pcl::SHOT352> match_search;
137  match_search.setInputCloud (reference_feature_);
138 
139  for (size_t i = 0; i < scene_feature->size(); ++i)
140  {
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])) { //skipping NaNs
144  continue;
145  }
146  int found_neighs
147  = match_search.nearestKSearch(scene_feature->at(i), 1,
148  neigh_indices, neigh_sqr_dists);
149  // add match only if the squared descriptor distance is less than 0.25
150  // (SHOT descriptor distances are between 0 and 1 by design)
151  if (found_neighs == 1 && neigh_sqr_dists[0] < 0.25f) {
152  pcl::Correspondence corr (neigh_indices[0], static_cast<int> (i), neigh_sqr_dists[0]);
153  model_scene_corrs->push_back (corr);
154  }
155  }
156 
157  pcl::GeometricConsistencyGrouping<pcl::PointNormal, pcl::PointNormal> gc_clusterer;
158  gc_clusterer.setGCSize(gc_size_);
159  gc_clusterer.setGCThreshold(gc_thresh_);
160 
161  gc_clusterer.setInputCloud(reference_cloud_);
162  gc_clusterer.setSceneCloud(scene_cloud);
163  gc_clusterer.setModelSceneCorrespondences(model_scene_corrs);
164 
165  //gc_clusterer.cluster (clustered_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;
175  tf::poseEigenToMsg(affine, ros_pose.pose);
176  ros_pose.header = scene_cloud_msg->header;
177  pub_output_.publish(ros_pose);
178  }
179  else {
180  NODELET_WARN("Failed to find object");
181  }
182 
183  }
184 
185 }
186 
187 
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
_2
boost::arg< 2 > _2
jsk_pcl_ros::GeometricConsistencyGrouping::referenceCallback
virtual void referenceCallback(const sensor_msgs::PointCloud2::ConstPtr &model_cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &model_feature_msg)
Definition: geometric_consistency_grouping_nodelet.cpp:100
i
int i
jsk_pcl_ros::GeometricConsistencyGrouping::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: geometric_consistency_grouping.h:157
NODELET_ERROR_THROTTLE
#define NODELET_ERROR_THROTTLE(rate,...)
jsk_pcl_ros::GeometricConsistencyGrouping::reference_sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > reference_sync_
Definition: geometric_consistency_grouping.h:165
jsk_pcl_ros::GeometricConsistencyGrouping::configCallback
virtual void configCallback(Config &config, uint32_t level)
callback for dynamic_reconfigure
Definition: geometric_consistency_grouping_nodelet.cpp:92
jsk_pcl_ros::GeometricConsistencyGrouping::recognize
virtual void recognize(const sensor_msgs::PointCloud2::ConstPtr &scene_cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &scene_feature_msg)
Definition: geometric_consistency_grouping_nodelet.cpp:118
NODELET_WARN
#define NODELET_WARN(...)
jsk_pcl_ros::GeometricConsistencyGrouping::sub_reference_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_reference_cloud_
Definition: geometric_consistency_grouping.h:163
jsk_pcl_ros::GeometricConsistencyGrouping::sub_feature_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_feature_
Definition: geometric_consistency_grouping.h:160
jsk_pcl_ros::GeometricConsistencyGrouping::~GeometricConsistencyGrouping
virtual ~GeometricConsistencyGrouping()
Definition: geometric_consistency_grouping_nodelet.cpp:64
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
jsk_pcl_ros::GeometricConsistencyGrouping
Nodelet implementation of jsk_pcl/GeometricConsistencyGrouping.
Definition: geometric_consistency_grouping.h:93
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
class_list_macros.h
jsk_pcl_ros::GeometricConsistencyGrouping::onInit
virtual void onInit()
Definition: geometric_consistency_grouping_nodelet.cpp:44
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::GeometricConsistencyGrouping::sub_reference_feature_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_reference_feature_
Definition: geometric_consistency_grouping.h:164
geometric_consistency_grouping.h
jsk_pcl_ros::GeometricConsistencyGrouping::reference_feature_
pcl::PointCloud< pcl::SHOT352 >::Ptr reference_feature_
Definition: geometric_consistency_grouping.h:167
jsk_pcl_ros::GeometricConsistencyGrouping::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: geometric_consistency_grouping.h:159
_1
boost::arg< 1 > _1
jsk_pcl_ros::GeometricConsistencyGrouping::Config
GeometricConsistencyGroupingConfig Config
Definition: geometric_consistency_grouping.h:128
tf::poseEigenToMsg
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
jsk_pcl_ros::GeometricConsistencyGrouping::mutex_
boost::mutex mutex_
Definition: geometric_consistency_grouping.h:154
pcl_conversion_util.h
message_filters::Subscriber::subscribe
void subscribe()
jsk_pcl_ros::GeometricConsistencyGrouping::unsubscribe
virtual void unsubscribe()
Definition: geometric_consistency_grouping_nodelet.cpp:86
NODELET_INFO
#define NODELET_INFO(...)
nodelet::Nodelet
jsk_pcl_ros::GeometricConsistencyGrouping::subscribe
virtual void subscribe()
Definition: geometric_consistency_grouping_nodelet.cpp:76
dump_depth_error.f
f
Definition: dump_depth_error.py:39
jsk_pcl_ros::GeometricConsistencyGrouping::gc_size_
double gc_size_
Definition: geometric_consistency_grouping.h:170
jsk_pcl_ros::GeometricConsistencyGrouping::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: geometric_consistency_grouping.h:161
jsk_pcl_ros::GeometricConsistencyGrouping::reference_cloud_
pcl::PointCloud< pcl::PointNormal >::Ptr reference_cloud_
Definition: geometric_consistency_grouping.h:168
jsk_pcl_ros::GeometricConsistencyGrouping::pub_output_
ros::Publisher pub_output_
Definition: geometric_consistency_grouping.h:155
jsk_pcl_ros::GeometricConsistencyGrouping::pub_output_cloud_
ros::Publisher pub_output_cloud_
Definition: geometric_consistency_grouping.h:156
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::GeometricConsistencyGrouping, nodelet::Nodelet)
config
config
jsk_pcl_ros::GeometricConsistencyGrouping::gc_thresh_
double gc_thresh_
Definition: geometric_consistency_grouping.h:171


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44