ppf_registration_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016, 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/o2r 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 
36 #define BOOST_PARAMETER_MAX_ARITY 7
37 
38 #include <pcl/features/ppf.h>
39 #include <pcl/features/normal_3d.h>
40 #include <pcl/registration/ppf_registration.h>
42 
43 namespace jsk_pcl_ros
44 {
46  {
47  DiagnosticNodelet::onInit();
48  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
49  dynamic_reconfigure::Server<Config>::CallbackType f =
50  boost::bind (&PPFRegistration::configCallback, this, _1, _2);
51  srv_->setCallback (f);
52 
53  pub_points_array_ = advertise<jsk_recognition_msgs::PointsArray>(*pnh_, "output/points_array", 1);
54  pub_pose_array_ = advertise<geometry_msgs::PoseArray>(*pnh_, "output/pose_array", 1);
55  pub_pose_stamped_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output/pose_stamped", 1);
56  pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output/cloud", 1);
58  }
59 
61  {
62  sub_input_.subscribe(*pnh_, "input/cloud", 1);
63  sub_reference_array_.subscribe(*pnh_, "input/reference_array", 1);
64  sub_reference_cloud_.subscribe(*pnh_, "input/reference_cloud", 1);
65  if (use_array_)
66  {
68  {
69  array_async_ = boost::make_shared<message_filters::Synchronizer<ArrayApproximateSyncPolicy> >(queue_size_);
71  array_async_->registerCallback(boost::bind(&PPFRegistration::ArrayRegistration, this, _1, _2));
72  }
73  else
74  {
75  array_sync_ = boost::make_shared<message_filters::Synchronizer<ArraySyncPolicy> >(queue_size_);
77  array_sync_->registerCallback(boost::bind(&PPFRegistration::ArrayRegistration, this, _1, _2));
78  }
79  }
80  else
81  {
83  {
84  cloud_async_ = boost::make_shared<message_filters::Synchronizer<CloudApproximateSyncPolicy> >(queue_size_);
86  cloud_async_->registerCallback(boost::bind(&PPFRegistration::CloudRegistration, this, _1, _2));
87  }
88  else
89  {
90  cloud_sync_ = boost::make_shared<message_filters::Synchronizer<CloudSyncPolicy> >(queue_size_);
92  cloud_sync_->registerCallback(boost::bind(&PPFRegistration::CloudRegistration, this, _1, _2));
93  }
94  }
95  }
96 
98  {
102  }
103 
104  pcl::PointCloud<pcl::PointNormal>::Ptr PPFRegistration::calculateNormals (pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
105  {
106  float normal_estimation_search_radius = float(search_radius_);
107  pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal> ());
108  pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> normal_estimation_filter;
109  pcl::search::KdTree<pcl::PointXYZ>::Ptr search_tree (new pcl::search::KdTree<pcl::PointXYZ> ());
110  pcl::PointCloud<pcl::PointNormal>::Ptr cloud_calculated (new pcl::PointCloud<pcl::PointNormal> ());
111  normal_estimation_filter.setInputCloud (cloud);
112  normal_estimation_filter.setSearchMethod (search_tree);
113  normal_estimation_filter.setRadiusSearch (normal_estimation_search_radius);
114  normal_estimation_filter.compute (*cloud_normals);
115  pcl::concatenateFields (*cloud, *cloud_normals, *cloud_calculated);
116 
117  // DEBUG
118  NODELET_INFO_STREAM("cloud with normals size:" << cloud_calculated->points.size());
119  return cloud_calculated;
120  }
121 
122  void PPFRegistration::configCallback(Config &config, uint32_t level)
123  {
124  boost::mutex::scoped_lock lock(mutex_);
125  use_array_ = config.use_array;
126  queue_size_ = config.queue_size;
127  approximate_sync_ = config.approximate_sync;
128  search_radius_ = config.search_radius;
129  sampling_rate_ = config.sampling_rate;
130  }
131 
133  (const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
134  const sensor_msgs::PointCloud2::ConstPtr& input_reference_cloud)
135  {
136  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ> ());
137  pcl::fromROSMsg(*input_cloud, *cloud);
138 
139  //calculate normals for target
141 
142  // training from reference
143  // convert from ROSMsg -> pcl PointCloud
144  pcl::PointCloud<pcl::PointXYZ>::Ptr reference_cloud (new pcl::PointCloud<pcl::PointXYZ> ());
145  pcl::fromROSMsg(*input_reference_cloud, *reference_cloud);
146 
147  // calculate normal for reference
149 
150  // ppf estimation registration
151  pcl::PointCloud<pcl::PPFSignature>::Ptr reference_cloud_ppf (new pcl::PointCloud<pcl::PPFSignature> ());
154  ppf_estimator.compute (*reference_cloud_ppf);
155 
156  // hashmap search
157  pcl::PPFHashMapSearch::Ptr hashmap_search (new pcl::PPFHashMapSearch (12.0f / 180.0f * float (M_PI), 0.05f));
158  hashmap_search->setInputFeatureCloud (reference_cloud_ppf);
159 
160  // register references to target
161  // set parameters for the PPF registration procedure
162  ppf_registration.setSceneReferencePointSamplingRate (sampling_rate_);
163  ppf_registration.setPositionClusteringThreshold (float(position_clustering_threshold_));
164  ppf_registration.setRotationClusteringThreshold (float(rotation_clustering_threshold_) / 180.0f * float (M_PI));
165  ppf_registration.setSearchMethod (hashmap_search);
167  ppf_registration.setInputTarget (cloud_with_normals);
168  pcl::PointCloud<pcl::PointNormal> cloud_output_subsampled;
169  ppf_registration.align (cloud_output_subsampled);
170 
171  // get ppf transformation
172  Eigen::Matrix4f mat = ppf_registration.getFinalTransformation ();
173  Eigen::Affine3f pose (mat);
174  // DEBUG
175  Eigen::IOFormat CleanFmt(4, 0, ", ", "\n", "[", "]");
176  NODELET_INFO_STREAM( "Matrix:\n" << mat.format(CleanFmt));
177 
178  // transform reference
179  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_output (new pcl::PointCloud<pcl::PointXYZ> ());
180  pcl::transformPointCloud (*reference_cloud, *cloud_output, pose);
181 
182  //convert pcl to ROSMsg
183  sensor_msgs::PointCloud2 cloud_msg;
184  toROSMsg(*cloud_output, cloud_msg);
185  geometry_msgs::Pose pose_msg_;
186  geometry_msgs::PoseStamped pose_stamped_msg;
187  tf::poseEigenToMsg(pose, pose_msg_);
188  pose_stamped_msg.pose = pose_msg_;
189 
190  // publish
191  pose_stamped_msg.header = input_cloud->header;
192  cloud_msg.header = input_cloud->header;
193  pub_pose_stamped_.publish(pose_stamped_msg);
194  pub_cloud_.publish(cloud_msg);
195  }
196 
198  (const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
199  const jsk_recognition_msgs::PointsArray::ConstPtr& input_reference_points_array)
200  {
201  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ> ());
202  pcl::fromROSMsg(*input_cloud, *cloud);
203 
204  //calculate normals for target
206 
207  jsk_recognition_msgs::PointsArray::Ptr points_array_msg (new jsk_recognition_msgs::PointsArray ());
208  geometry_msgs::PoseArray::Ptr pose_array_msg (new geometry_msgs::PoseArray ());
209  std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr > reference_cloud_vector;
210  std::vector<pcl::PointCloud<pcl::PointNormal>::Ptr > reference_cloud_with_normals_vector;
211  std::vector<pcl::PPFHashMapSearch::Ptr > hashmap_search_vector;
212 
213  // training from reference
214  for (size_t reference_i=0; reference_i < input_reference_points_array->cloud_list.size(); reference_i++)
215  {
216  sensor_msgs::PointCloud2 input_reference_cloud = input_reference_points_array->cloud_list[reference_i];
217 
218  // convert from ROSMsg -> pcl PointCloud
219  pcl::PointCloud<pcl::PointXYZ>::Ptr reference_cloud (new pcl::PointCloud<pcl::PointXYZ> ());
220  pcl::fromROSMsg(input_reference_cloud, *reference_cloud);
221  reference_cloud_vector.push_back(reference_cloud);
222 
223  // calculate normal for reference
225  reference_cloud_with_normals_vector.push_back(reference_cloud_with_normals);
226 
227  // ppf estimation registration
228  pcl::PointCloud<pcl::PPFSignature>::Ptr reference_cloud_ppf (new pcl::PointCloud<pcl::PPFSignature> ());
231  ppf_estimator.compute (*reference_cloud_ppf);
232 
233  // hashmap search
234  pcl::PPFHashMapSearch::Ptr hashmap_search (new pcl::PPFHashMapSearch (12.0f / 180.0f * float (M_PI), 0.05f));
235  hashmap_search->setInputFeatureCloud (reference_cloud_ppf);
236  hashmap_search_vector.push_back(hashmap_search);
237  }
238 
239  // register references to target
240  for (size_t reference_i=0; reference_i < input_reference_points_array->cloud_list.size(); reference_i++)
241  {
242  // set parameters for the PPF registration procedure
243  ppf_registration.setSceneReferencePointSamplingRate (sampling_rate_);
244  ppf_registration.setPositionClusteringThreshold (float(position_clustering_threshold_));
245  ppf_registration.setRotationClusteringThreshold (float(rotation_clustering_threshold_) / 180.0f * float (M_PI));
246  ppf_registration.setSearchMethod (hashmap_search_vector[reference_i]);
247  ppf_registration.setInputSource (reference_cloud_with_normals_vector[reference_i]);
248  ppf_registration.setInputTarget (cloud_with_normals);
249  pcl::PointCloud<pcl::PointNormal> cloud_output_subsampled;
250  ppf_registration.align (cloud_output_subsampled);
251 
252  // get ppf transformation
253  Eigen::Matrix4f mat = ppf_registration.getFinalTransformation ();
254  Eigen::Affine3f pose (mat);
255  // DEBUG
256  Eigen::IOFormat CleanFmt(4, 0, ", ", "\n", "[", "]");
257  NODELET_INFO_STREAM( "Matrix:\n" << mat.format(CleanFmt));
258 
259  // transform reference
260  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_output (new pcl::PointCloud<pcl::PointXYZ> ());
261  pcl::transformPointCloud (*reference_cloud_vector[reference_i], *cloud_output, pose);
262 
263  //convert pcl to ROSMsg
264  sensor_msgs::PointCloud2 cloud_msg_;
265  toROSMsg(*cloud_output, cloud_msg_);
266  geometry_msgs::Pose pose_msg_;
267  tf::poseEigenToMsg(pose, pose_msg_);
268  points_array_msg->cloud_list.push_back(cloud_msg_);
269  pose_array_msg->poses.push_back(pose_msg_);
270  }
271  // publish
272  pose_array_msg->header = input_cloud->header;
273  points_array_msg->header = input_cloud->header;
274  pub_pose_array_.publish(pose_array_msg);
275  pub_points_array_.publish(points_array_msg);
276  }
277 }
278 
#define NODELET_INFO_STREAM(...)
pcl::PointCloud< pcl::PointNormal >::Ptr reference_cloud_with_normals
virtual void configCallback(Config &config, uint32_t level)
void publish(const boost::shared_ptr< M > &message) const
virtual void CloudRegistration(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const sensor_msgs::PointCloud2::ConstPtr &input_reference_cloud)
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
boost::shared_ptr< message_filters::Synchronizer< ArraySyncPolicy > > array_sync_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
pose
boost::shared_ptr< message_filters::Synchronizer< CloudSyncPolicy > > cloud_sync_
virtual void ArrayRegistration(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::PointsArray::ConstPtr &input_reference_points_array)
float
jsk_pcl_ros::PPFRegistrationConfig Config
#define M_PI
boost::shared_ptr< ros::NodeHandle > pnh_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::PPFRegistration, nodelet::Nodelet)
pcl::PPFEstimation< pcl::PointNormal, pcl::PointNormal, pcl::PPFSignature > ppf_estimator
void concatenateFields(PointCloud< PointXYZ > &cloud_xyz, PointCloud< RGB > &cloud_rgb, PointCloud< PointXYZRGB > &cloud)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_reference_cloud_
boost::shared_ptr< message_filters::Synchronizer< CloudApproximateSyncPolicy > > cloud_async_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
pcl::PointCloud< pcl::PointNormal >::Ptr cloud_with_normals
boost::shared_ptr< message_filters::Synchronizer< ArrayApproximateSyncPolicy > > array_async_
cloud
message_filters::Subscriber< jsk_recognition_msgs::PointsArray > sub_reference_array_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
pcl::PPFRegistration< pcl::PointNormal, pcl::PointNormal > ppf_registration
virtual pcl::PointCloud< pcl::PointNormal >::Ptr calculateNormals(pcl::PointCloud< pcl::PointXYZ >::Ptr cloud)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47