icp_registration_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++; indent-tabs-mode: nil; -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, 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 
37 #include <pcl/registration/icp.h>
38 #include <pcl/registration/gicp.h>
39 #include <pcl/registration/ndt.h>
40 #include <pcl/registration/transformation_estimation_lm.h>
41 #include <pcl/registration/warp_point_rigid_3d.h>
44 #include <pcl/common/transforms.h>
48 #include <pcl/registration/correspondence_estimation_organized_projection.h>
49 #include <pcl/registration/correspondence_estimation_normal_shooting.h>
51 
52 namespace jsk_pcl_ros
53 {
55  {
56  pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
57  ConnectionBasedNodelet::onInit();
60  // Dynamic Reconfigure
62  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
63  dynamic_reconfigure::Server<Config>::CallbackType f =
64  boost::bind(
65  &ICPRegistration::configCallback, this, _1, _2);
66  srv_->setCallback (f);
67  pnh_->param("use_normal", use_normal_, false);
68  pnh_->param("align_box", align_box_, false);
69  pnh_->param("synchronize_reference", synchronize_reference_, false);
70  pnh_->param("transform_3dof", transform_3dof_, false);
71  pnh_->param("use_offset_pose", use_offset_pose_, false);
73  // Publishers
75  pub_result_pose_ = advertise<geometry_msgs::PoseStamped>(*pnh_,
76  "output_pose", 1);
77  pub_result_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
78  "output", 1);
79  pub_debug_source_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
80  "debug/source", 1);
81  pub_debug_target_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
82  "debug/target", 1);
83  pub_debug_flipped_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
84  "debug/flipped", 1);
85  pub_debug_result_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
86  "debug/result", 1);
87  pub_icp_result = advertise<jsk_recognition_msgs::ICPResult>(*pnh_,
88  "icp_result", 1);
89  pub_latest_time_ = advertise<std_msgs::Float32>(
90  *pnh_, "output/latest_time", 1);
91  pub_average_time_ = advertise<std_msgs::Float32>(
92  *pnh_, "output/average_time", 1);
93  srv_icp_align_with_box_ = pnh_->advertiseService("icp_service", &ICPRegistration::alignWithBoxService, this);
94  srv_icp_align_ = pnh_->advertiseService(
95  "icp_align", &ICPRegistration::alignService, this);
97  sub_reference_ = pnh_->subscribe("input_reference", 1,
99  this);
100  sub_reference_array_ = pnh_->subscribe("input_reference_array", 1,
102  this);
103  sub_reference_add = pnh_->subscribe("input_reference_add", 1,
105  this);
106  }
107  done_init_ = true;
109  }
110 
112  {
114  // Subscription
116  sub_camera_info_ = pnh_->subscribe("input/camera_info", 1,
118  this);
119  if (!synchronize_reference_) {
120  if (align_box_) {
121  sub_input_.subscribe(*pnh_, "input", 1);
122  sub_box_.subscribe(*pnh_, "input_box", 1);
123  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
124  sync_->connectInput(sub_input_, sub_box_);
125  sync_->registerCallback(boost::bind(
127  this, _1, _2));
128  }
129  else if (use_offset_pose_) {
130  sub_input_.subscribe(*pnh_, "input", 1);
131  sub_offset_.subscribe(*pnh_, "input_offset", 1);
132  sync_offset_ = boost::make_shared<message_filters::Synchronizer<OffsetSyncPolicy> >(100);
133  sync_offset_->connectInput(sub_input_, sub_offset_);
134  sync_offset_->registerCallback(boost::bind(&ICPRegistration::alignWithOffset, this, _1, _2));
135  }
136  else {
137  sub_ = pnh_->subscribe("input", 1,
139  this);
140  }
141  }
142  else {
143  sub_sync_input_.subscribe(*pnh_, "input", 1);
144  sub_sync_reference_.subscribe(*pnh_, "reference", 1);
145  sync_reference_ = boost::make_shared<message_filters::Synchronizer<ReferenceSyncPolicy> >(100);
147  sync_reference_->registerCallback(boost::bind(&ICPRegistration::align, this, _1, _2));
148  }
149  }
150 
152  {
154  if (!synchronize_reference_) {
155  if (align_box_) {
158  }
159  else {
160  sub_.shutdown();
161  }
162  }
163  else {
166  }
167  }
168 
171  const pcl::PointCloud<PointT>& cloud,
172  const std_msgs::Header& header)
173  {
174  if (pub.getNumSubscribers() > 0) {
175  sensor_msgs::PointCloud2 ros_cloud;
176  pcl::toROSMsg(cloud, ros_cloud);
177  ros_cloud.header = header;
178  pub.publish(ros_cloud);
179  }
180  }
181 
182  void ICPRegistration::configCallback(Config &config, uint32_t level)
183  {
184  boost::mutex::scoped_lock lock(mutex_);
185  algorithm_ = config.algorithm;
186  correspondence_algorithm_ = config.correspondence_algorithm;
187  use_flipped_initial_pose_ = config.use_flipped_initial_pose;
188  max_iteration_ = config.max_iteration;
189  correspondence_distance_ = config.correspondence_distance;
190  transform_epsilon_ = config.transform_epsilon;
191  euclidean_fittness_epsilon_ = config.euclidean_fittness_epsilon;
192  rotation_epsilon_ = config.rotation_epsilon;
193  ransac_iterations_ = config.ransac_iterations;
194  ransac_outlier_threshold_ = config.ransac_outlier_threshold;
195  correspondence_randomness_ = config.correspondence_randomness;
196  maximum_optimizer_iterations_ = config.maximum_optimizer_iterations;
197  ndt_resolution_ = config.ndt_resolution;
198  ndt_step_size_ = config.ndt_step_size;
199  ndt_outlier_ratio_ = config.ndt_outlier_ratio;
200  }
201 
203  jsk_recognition_msgs::ICPAlignWithBox::Request& req,
204  jsk_recognition_msgs::ICPAlignWithBox::Response& res)
205  {
206  boost::mutex::scoped_lock lock(mutex_);
207  if (reference_cloud_list_.size() == 0) {
208  NODELET_FATAL("no reference is specified");
209  return false;
210  }
211  try
212  {
213  Eigen::Affine3f offset;
214  pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
215  jsk_pcl_ros_utils::transformPointcloudInBoundingBox<PointT>(
216  req.target_box, req.target_cloud,
217  *output, offset,
218  *tf_listener_);
219  Eigen::Affine3f inversed_offset = offset.inverse();
220  res.result = alignPointcloudWithReferences(output, inversed_offset, req.target_cloud.header);
221  }
222  catch (tf2::ConnectivityException &e)
223  {
224  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
225  return false;
226  }
228  {
229  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
230  return false;
231  }
232  return true;
233  }
234 
236  jsk_recognition_msgs::ICPAlign::Request& req,
237  jsk_recognition_msgs::ICPAlign::Response& res)
238  {
239  boost::mutex::scoped_lock lock(mutex_);
240  std::vector<pcl::PointCloud<PointT>::Ptr> tmp_reference_cloud_list
241  = reference_cloud_list_; // escape
242  try
243  {
244  // first, update reference
245  std::vector<pcl::PointCloud<PointT>::Ptr> new_references;
246  pcl::PointCloud<PointT>::Ptr reference_cloud (new pcl::PointCloud<PointT>);
247  pcl::fromROSMsg(req.reference_cloud, *reference_cloud);
248  pcl::PointCloud<PointT>::Ptr non_nan_reference_cloud (new pcl::PointCloud<PointT>);
249  for (size_t i = 0; i < reference_cloud->points.size(); i++) {
250  PointT p = reference_cloud->points[i];
251  if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
252  non_nan_reference_cloud->points.push_back(p);
253  }
254  }
255  new_references.push_back(non_nan_reference_cloud);
256  reference_cloud_list_ = new_references; // replace references
257  NODELET_INFO("reference points: %lu/%lu",
258  non_nan_reference_cloud->points.size(),
259  reference_cloud->points.size());
260  Eigen::Affine3f offset = Eigen::Affine3f::Identity();
261  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
262  pcl::fromROSMsg(req.target_cloud, *cloud);
263  res.result = alignPointcloudWithReferences(cloud,
264  offset,
265  req.target_cloud.header);
266  }
267  catch (tf2::ConnectivityException &e)
268  {
269  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
270  reference_cloud_list_ = tmp_reference_cloud_list;
271  return false;
272  }
274  {
275  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
276  reference_cloud_list_ = tmp_reference_cloud_list;
277  return false;
278  }
279  reference_cloud_list_ = tmp_reference_cloud_list;
280  return true;
281  }
282 
283 
285  const sensor_msgs::PointCloud2::ConstPtr& msg,
286  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
287  {
288  boost::mutex::scoped_lock lock(mutex_);
289  if (!done_init_) {
290  NODELET_WARN("not yet initialized");
291  return;
292  }
293  if (reference_cloud_list_.size() == 0) {
294  NODELET_FATAL("no reference is specified");
295  jsk_recognition_msgs::ICPResult result;
296  result.name = std::string("NONE");
297  result.score = DBL_MAX;
298  result.header = box_msg->header;
299  result.pose = box_msg->pose;
300  pub_icp_result.publish(result);
301  return;
302  }
303  try
304  {
305  Eigen::Affine3f offset;
306  pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
307  jsk_pcl_ros_utils::transformPointcloudInBoundingBox<PointT>(
308  *box_msg, *msg,
309  *output, offset,
310  *tf_listener_);
311  Eigen::Affine3f inversed_offset = offset.inverse();
312  jsk_recognition_msgs::ICPResult result = alignPointcloudWithReferences(output, inversed_offset, msg->header);
313  pub_icp_result.publish(result);
314  }
315  catch (tf2::ConnectivityException &e)
316  {
317  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
318  }
320  {
321  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
322  }
323  }
324 
326  const sensor_msgs::PointCloud2::ConstPtr& msg,
327  const geometry_msgs::PoseStamped::ConstPtr& offset_msg)
328  {
329  boost::mutex::scoped_lock lock(mutex_);
330  if (!done_init_) {
331  NODELET_WARN("not yet initialized");
332  return;
333  }
334  if (reference_cloud_list_.size() == 0) {
335  NODELET_FATAL("no reference is specified");
336  jsk_recognition_msgs::ICPResult result;
337  result.name = std::string("NONE");
338  result.score = DBL_MAX;
339  result.header = offset_msg->header;
340  result.pose = offset_msg->pose;
341  pub_icp_result.publish(result);
342  return;
343  }
344  try
345  {
346  if (!jsk_recognition_utils::isSameFrameId(msg->header.frame_id,
347  offset_msg->header.frame_id)) {
348  NODELET_ERROR("frame_id does not match. cloud: %s, pose: %s",
349  msg->header.frame_id.c_str(),
350  offset_msg->header.frame_id.c_str());
351  return;
352  }
353  Eigen::Affine3f offset;
354  pcl::PointCloud<PointT>::Ptr input (new pcl::PointCloud<PointT>);
355  pcl::fromROSMsg(*msg, *input);
356  pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
357  tf::poseMsgToEigen(offset_msg->pose, offset);
358 
359  Eigen::Affine3f inversed_offset = offset.inverse();
360  pcl::transformPointCloud(*input, *output, inversed_offset);
361  jsk_recognition_msgs::ICPResult result = alignPointcloudWithReferences(output, offset, msg->header);
362  pub_icp_result.publish(result);
363  }
364  catch (tf2::ConnectivityException &e)
365  {
366  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
367  }
369  {
370  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
371  }
372  }
373 
374 
375  void ICPRegistration::align(const sensor_msgs::PointCloud2::ConstPtr& msg)
376  {
377  boost::mutex::scoped_lock lock(mutex_);
378  if (!done_init_) {
379  NODELET_WARN("not yet initialized");
380  return;
381  }
382  if (reference_cloud_list_.size() == 0) {
383  NODELET_FATAL("no reference is specified");
384  return;
385  }
386 
387  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
388  pcl::fromROSMsg(*msg, *cloud);
389  Eigen::Affine3f offset = Eigen::Affine3f::Identity();
390  // remove nan
391  pcl::PointCloud<PointT>::Ptr non_nan_cloud (new pcl::PointCloud<PointT>);
392  for (size_t i = 0; i < cloud->points.size(); i++) {
393  PointT p = cloud->points[i];
394  if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
395  non_nan_cloud->points.push_back(p);
396  }
397  }
398  jsk_recognition_msgs::ICPResult result = alignPointcloudWithReferences(non_nan_cloud, offset, msg->header);
399  pub_icp_result.publish(result);
400  }
401 
402  void ICPRegistration::align(const sensor_msgs::PointCloud2::ConstPtr& msg,
403  const sensor_msgs::PointCloud2::ConstPtr& reference_msg)
404  {
405  {
406  boost::mutex::scoped_lock lock(mutex_);
407  if (!done_init_) {
408  NODELET_WARN("not yet initialized");
409  return;
410  }
411  reference_cloud_list_.resize(0);
412  pcl::PointCloud<PointT>::Ptr reference_cloud (new pcl::PointCloud<PointT>);
413  pcl::fromROSMsg(*reference_msg, *reference_cloud);
414  // remove nan
415  pcl::PointCloud<PointT>::Ptr non_nan_reference_cloud (new pcl::PointCloud<PointT>);
416  for (size_t i = 0; i < reference_cloud->points.size(); i++) {
417  PointT p = reference_cloud->points[i];
418  if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
419  non_nan_reference_cloud->points.push_back(p);
420  }
421  }
422  reference_cloud_list_.push_back(non_nan_reference_cloud);
423  }
424  align(msg);
425  }
426 
427  jsk_recognition_msgs::ICPResult ICPRegistration::alignPointcloudWithReferences(
428  pcl::PointCloud<PointT>::Ptr& cloud,
429  const Eigen::Affine3f& offset,
430  const std_msgs::Header& header)
431  {
434  double min_score = DBL_MAX;
435  size_t max_index = 0;
436  pcl::PointCloud<PointT>::Ptr best_transformed_cloud;
437  pcl::PointCloud<PointT>::Ptr best_reference;
438  Eigen::Affine3d best_transform_result;
439  Eigen::Affine3f best_offset_result;
440  jsk_recognition_msgs::ICPResult result;
441  if (cloud->empty()) {
442  sensor_msgs::PointCloud2 empty_cloud;
443  empty_cloud.header = header;
444  pub_result_cloud_.publish(empty_cloud);
445 
446  pcl::PointCloud<PointT> empty_pcl_cloud;
447  publishDebugCloud(pub_debug_source_cloud_, empty_pcl_cloud, header);
448  publishDebugCloud(pub_debug_target_cloud_, empty_pcl_cloud, header);
449  publishDebugCloud(pub_debug_result_cloud_, empty_pcl_cloud, header);
450 
451  geometry_msgs::PoseStamped empty_pose;
452  empty_pose.header = header;
453  pub_result_pose_.publish(empty_pose);
454 
455  result.header = header;
456  result.score = min_score;
457  result.name = "nan";
458  return result;
459  }
460  for (size_t i = 0; i < reference_cloud_list_.size(); i++) {
461  Eigen::Affine3f offset_result;
462  pcl::PointCloud<PointT>::Ptr transformed_cloud(new pcl::PointCloud<PointT>);
463  Eigen::Affine3d transform_result;
464  double score = scorePointcloudAlignment(
465  cloud,
467  offset,
468  offset_result,
469  transformed_cloud,
470  transform_result);
471  if (score < min_score) {
472  max_index = i;
473  min_score = score;
474  best_transform_result = transform_result;
475  best_transformed_cloud = transformed_cloud;
476  best_reference = reference_cloud_list_[i];
477  best_offset_result = offset_result;
478  }
479  }
480 
481  NODELET_INFO("best score is: %f", min_score);
483  sensor_msgs::PointCloud2 ros_final;
484  pcl::toROSMsg(*best_transformed_cloud, ros_final);
485  ros_final.header = header;
486  pub_result_cloud_.publish(ros_final);
487  }
488  geometry_msgs::PoseStamped ros_result_pose;
489  ros_result_pose.header = header;
490  tf::poseEigenToMsg(best_transform_result, ros_result_pose.pose);
491  pub_result_pose_.publish(ros_result_pose);
492  publishDebugCloud(pub_debug_source_cloud_, *best_reference, header);
494  pcl::PointCloud<PointT>::Ptr transformed_cloud_for_debug_result
495  (new pcl::PointCloud<PointT>);
496  pcl::transformPointCloud(
497  *best_transformed_cloud, *transformed_cloud_for_debug_result,
498  best_offset_result.inverse());
500  *transformed_cloud_for_debug_result, header);
501  result.header = ros_result_pose.header;
502  result.pose = ros_result_pose.pose;
503  result.score = min_score;
504  std::stringstream ss;
505  ss << max_index;
506  result.name = ss.str();
507  return result;
508  }
509 
511  const sensor_msgs::CameraInfo::ConstPtr& msg)
512  {
513  boost::mutex::scoped_lock lock(mutex_);
515  }
516 
518  pcl::PointCloud<PointT>::Ptr& cloud,
519  pcl::PointCloud<PointT>::Ptr& reference,
520  const Eigen::Affine3f& offset,
521  pcl::PointCloud<PointT>::Ptr& output_cloud,
522  Eigen::Affine3d& output_transform)
523  {
524  if (algorithm_ == 0 || algorithm_ == 1) {
525  return alignPointcloudWithICP(cloud, reference, offset, output_cloud, output_transform);
526  }
527  else {
528  return alignPointcloudWithNDT(cloud, reference, offset, output_cloud, output_transform);
529  }
530  }
531 
532 
534  pcl::PointCloud<PointT>::Ptr& cloud,
535  pcl::PointCloud<PointT>::Ptr& reference,
536  const Eigen::Affine3f& offset,
537  pcl::PointCloud<PointT>::Ptr& output_cloud,
538  Eigen::Affine3d& output_transform)
539  {
540  pcl::NormalDistributionsTransform<PointT, PointT> ndt;
541  if (reference->points.empty ()) {
542  NODELET_ERROR("Input Reference Cloud is empty!");
543  return DBL_MAX;
544  }
545  ndt.setInputSource(reference);
546  if (cloud->points.empty ()) {
547  NODELET_ERROR("Input Target Cloud is empty!");
548  return DBL_MAX;
549  }
550  ndt.setInputTarget(cloud);
551  pcl::PointCloud<PointT> final;
552  ndt.align(final);
553  pcl::transformPointCloud(final, *output_cloud, offset);
554  Eigen::Matrix4f transformation = ndt.getFinalTransformation ();
555  Eigen::Matrix4d transformation_d;
556  jsk_recognition_utils::convertMatrix4<Eigen::Matrix4f, Eigen::Matrix4d>(
557  transformation, transformation_d);
558  Eigen::Affine3d offsetd;
559  convertEigenAffine3(offset, offsetd);
560  output_transform = offsetd * Eigen::Affine3d(transformation_d);
561  return ndt.getFitnessScore();
562  }
563 
565  pcl::PointCloud<PointT>::Ptr& cloud,
566  pcl::PointCloud<PointT>::Ptr& reference,
567  const Eigen::Affine3f& offset,
568  pcl::PointCloud<PointT>::Ptr& output_cloud,
569  Eigen::Affine3d& output_transform)
570  {
571  pcl::IterativeClosestPoint<PointT, PointT> icp;
572  if (use_normal_) {
573  pcl::IterativeClosestPointWithNormals<PointT, PointT> icp_with_normal;
574  icp = icp_with_normal;
575  }
576  // icp.setInputSource(cloud);
577  // icp.setInputTarget(reference_cloud_);
578  if (algorithm_ == 1) {
579  pcl::GeneralizedIterativeClosestPoint<PointT, PointT> gicp;
580  gicp.setRotationEpsilon(rotation_epsilon_);
581  gicp.setCorrespondenceRandomness(correspondence_randomness_);
582  gicp.setMaximumOptimizerIterations(maximum_optimizer_iterations_);
583  icp = gicp;
584  }
585  if (correspondence_algorithm_ == 1) { // Projective
586  if (!camera_info_msg_) {
587  NODELET_ERROR("no camera info is available yet");
588  return DBL_MAX;
589  }
591  bool model_success_p = model.fromCameraInfo(camera_info_msg_);
592  if (!model_success_p) {
593  NODELET_ERROR("failed to create camera model");
594  return DBL_MAX;
595  }
596  pcl::registration::CorrespondenceEstimationOrganizedProjection<PointT, PointT, float>::Ptr
597  corr_projection (new pcl::registration::CorrespondenceEstimationOrganizedProjection<PointT, PointT, float>);
598  corr_projection->setFocalLengths(model.fx(), model.fy());
599  corr_projection->setCameraCenters(model.cx(), model.cy());
600  icp.setCorrespondenceEstimation(corr_projection);
601  }
602 
603  if (reference->points.empty ()) {
604  NODELET_ERROR("Input Reference Cloud is empty!");
605  return DBL_MAX;
606  }
607  icp.setInputSource(reference);
608  if (cloud->points.empty ()) {
609  NODELET_ERROR("Input Target Cloud is empty!");
610  return DBL_MAX;
611  }
612  icp.setInputTarget(cloud);
613 
614  if (transform_3dof_) {
616  (new pcl::registration::WarpPointRigid3D<PointT, PointT>);
618  (new pcl::registration::TransformationEstimationLM<PointT, PointT>);
619  te->setWarpFunction(warp_func);
620  icp.setTransformationEstimation(te);
621  }
622 
623  icp.setMaxCorrespondenceDistance (correspondence_distance_);
624  icp.setMaximumIterations (max_iteration_);
625  icp.setTransformationEpsilon (transform_epsilon_);
626  icp.setEuclideanFitnessEpsilon (euclidean_fittness_epsilon_);
627  icp.setRANSACIterations(ransac_iterations_);
628  icp.setRANSACOutlierRejectionThreshold(ransac_outlier_threshold_);
629  pcl::PointCloud<PointT> final;
630  icp.align(final);
631  pcl::transformPointCloud(final, *output_cloud, offset);
632  // NODELET_INFO_STREAM("ICP converged: " << icp.hasConverged());
633  // NODELET_INFO_STREAM("ICP score: " << icp.getFitnessScore());
634  Eigen::Matrix4f transformation = icp.getFinalTransformation ();
635  Eigen::Matrix4d transformation_d;
636  jsk_recognition_utils::convertMatrix4<Eigen::Matrix4f, Eigen::Matrix4d>(
637  transformation, transformation_d);
638  Eigen::Affine3d offsetd;
639  convertEigenAffine3(offset, offsetd);
640  output_transform = offsetd * Eigen::Affine3d(transformation_d);
641  return icp.getFitnessScore();
642  }
643 
644  // compute ICP and return score
646  pcl::PointCloud<PointT>::Ptr& cloud,
647  pcl::PointCloud<PointT>::Ptr& reference,
648  const Eigen::Affine3f& offset,
649  Eigen::Affine3f& offset_result,
650  pcl::PointCloud<PointT>::Ptr transformed_cloud,
651  Eigen::Affine3d& transform_result)
652  {
653  pcl::PointCloud<PointT>::Ptr transformed_cloud_for_debug_result
654  (new pcl::PointCloud<PointT>);
655  double score = alignPointcloud(cloud, reference, offset,
656  transformed_cloud, transform_result);
657  pcl::transformPointCloud(
658  *transformed_cloud, *transformed_cloud_for_debug_result,
659  offset.inverse());
660  offset_result = offset;
662  pcl::PointCloud<PointT>::Ptr flipped_transformed_cloud
663  (new pcl::PointCloud<PointT>);
664  Eigen::Affine3d flipped_transform_result;
665  Eigen::Affine3f flipped_offset
666  = offset * Eigen::AngleAxisf(M_PI, Eigen::Vector3f(0, 0, 1));
667  pcl::PointCloud<PointT>::Ptr flipped_cloud (new pcl::PointCloud<PointT>);
668  pcl::transformPointCloud(
669  *cloud, *flipped_cloud,
670  Eigen::Affine3f(Eigen::AngleAxisf(M_PI, Eigen::Vector3f(0, 0, 1))));
671  double flipped_score
672  = alignPointcloud(flipped_cloud, reference, flipped_offset,
673  flipped_transformed_cloud,
674  flipped_transform_result);
675  NODELET_INFO("flipped score: %f", flipped_score);
676  if (flipped_score < score) {
677  score = flipped_score;
678  transformed_cloud = flipped_transformed_cloud;
679  transform_result = flipped_transform_result;
680  pcl::transformPointCloud(
681  *transformed_cloud, *transformed_cloud_for_debug_result,
682  flipped_offset.inverse());
683  offset_result = flipped_offset;
684  }
685  }
686  return score;
687  }
688 
690  const sensor_msgs::PointCloud2::ConstPtr& msg)
691  {
692  boost::mutex::scoped_lock lock(mutex_);
693  if (!done_init_) {
694  NODELET_WARN("not yet initialized");
695  return;
696  }
697  reference_cloud_list_.resize(0);
698  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
699  pcl::fromROSMsg(*msg, *cloud);
700  pcl::PointCloud<PointT>::Ptr non_nan_cloud (new pcl::PointCloud<PointT>);
701  for (size_t i = 0; i < cloud->points.size(); i++) {
702  PointT p = cloud->points[i];
703  if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
704  non_nan_cloud->points.push_back(p);
705  }
706  }
707  reference_cloud_list_.push_back(non_nan_cloud);
708  }
709 
711  const jsk_recognition_msgs::PointsArray::ConstPtr& msg)
712  {
713  boost::mutex::scoped_lock lock(mutex_);
714  if (!done_init_) {
715  NODELET_WARN("not yet initialized");
716  return;
717  }
718  reference_cloud_list_.resize(0);
719  for (size_t i = 0; i < msg->cloud_list.size(); i++) {
720  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
721  pcl::fromROSMsg(msg->cloud_list[i], *cloud);
722  reference_cloud_list_.push_back(cloud);
723  }
724  }
725 
727  const sensor_msgs::PointCloud2::ConstPtr& msg)
728  {
729  boost::mutex::scoped_lock lock(mutex_);
730  if (!done_init_) {
731  NODELET_WARN("not yet initialized");
732  return;
733  }
734  //reference_cloud_list_.resize(0); //not 0
735  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
736  pcl::fromROSMsg(*msg, *cloud);
737  reference_cloud_list_.push_back(cloud);
738  ROS_INFO("reference_num: %zd", reference_cloud_list_.size()-1);
739  }
740 }
741 
virtual double alignPointcloudWithICP(pcl::PointCloud< PointT >::Ptr &cloud, pcl::PointCloud< PointT >::Ptr &reference, const Eigen::Affine3f &offset, pcl::PointCloud< PointT >::Ptr &output_cloud, Eigen::Affine3d &output_transform)
#define NODELET_ERROR(...)
virtual bool alignService(jsk_recognition_msgs::ICPAlign::Request &req, jsk_recognition_msgs::ICPAlign::Response &res)
bool use_normal_
Store value of ~use_normal. If this parameter is true, ICPRegistration nodelet expects reference and ...
#define NODELET_WARN(...)
ros::Subscriber sub_reference_array_
void publish(const boost::shared_ptr< M > &message) const
virtual double scorePointcloudAlignment(pcl::PointCloud< PointT >::Ptr &cloud, pcl::PointCloud< PointT >::Ptr &reference, const Eigen::Affine3f &offset, Eigen::Affine3f &offset_result, pcl::PointCloud< PointT >::Ptr transformed_cloud, Eigen::Affine3d &transform_result)
virtual void publishDebugCloud(ros::Publisher &pub, const pcl::PointCloud< PointT > &cloud, const std_msgs::Header &header)
ros::Publisher pub_debug_flipped_cloud_
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
virtual ScopedWallDurationReporter reporter()
virtual void alignWithOffset(const sensor_msgs::PointCloud2::ConstPtr &msg, const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
tf::TransformListener * tf_listener_
ros::Publisher pub_debug_target_cloud_
virtual void align(const sensor_msgs::PointCloud2::ConstPtr &msg)
ros::ServiceServer srv_icp_align_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
ros::Publisher pub_debug_result_cloud_
sensor_msgs::CameraInfo::ConstPtr camera_info_msg_
virtual void cameraInfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
boost::shared_ptr< message_filters::Synchronizer< ReferenceSyncPolicy > > sync_reference_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBox > sub_box_
result
void output(int index, double value)
#define M_PI
pcl::PointXYZRGBNormal PointT
jsk_recognition_utils::WallDurationTimer timer_
#define ROS_INFO(...)
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
boost::shared_ptr< ros::NodeHandle > pnh_
int max_index
virtual void referenceCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
void convertEigenAffine3(const Eigen::Affine3d &from, Eigen::Affine3f &to)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
virtual double alignPointcloudWithNDT(pcl::PointCloud< PointT >::Ptr &cloud, pcl::PointCloud< PointT >::Ptr &reference, const Eigen::Affine3f &offset, pcl::PointCloud< PointT >::Ptr &output_cloud, Eigen::Affine3d &output_transform)
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_offset_
virtual void configCallback(Config &config, uint32_t level)
ros::Publisher pub_debug_source_cloud_
virtual jsk_recognition_msgs::ICPResult alignPointcloudWithReferences(pcl::PointCloud< PointT >::Ptr &cloud, const Eigen::Affine3f &offset, const std_msgs::Header &header)
virtual void referenceArrayCallback(const jsk_recognition_msgs::PointsArray::ConstPtr &msg)
virtual void referenceAddCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
#define NODELET_INFO(...)
std::vector< pcl::PointCloud< PointT >::Ptr > reference_cloud_list_
uint32_t getNumSubscribers() const
bool use_offset_pose_
set via ~use_offset_pose parameter. default is false.
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)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_sync_input_
boost::shared_ptr< message_filters::Synchronizer< OffsetSyncPolicy > > sync_offset_
p
bool isSameFrameId(const std::string &a, const std::string &b)
virtual bool alignWithBoxService(jsk_recognition_msgs::ICPAlignWithBox::Request &req, jsk_recognition_msgs::ICPAlignWithBox::Response &res)
ros::ServiceServer srv_icp_align_with_box_
static tf::TransformListener * getInstance()
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_sync_reference_
#define NODELET_FATAL(...)
cloud
bool transform_3dof_
set via ~transform_3dof parameter. default is false.
virtual void alignWithBox(const sensor_msgs::PointCloud2::ConstPtr &msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
jsk_pcl_ros::ICPRegistrationConfig Config
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ICPRegistration, nodelet::Nodelet)
virtual double alignPointcloud(pcl::PointCloud< PointT >::Ptr &cloud, pcl::PointCloud< PointT >::Ptr &reference, const Eigen::Affine3f &offset, pcl::PointCloud< PointT >::Ptr &output_cloud, Eigen::Affine3d &output_transform)


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