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/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 
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;
108  onInitPostProcess();
109  }
110 
112  // message_filters::Synchronizer needs to be called reset
113  // before message_filters::Subscriber is freed.
114  // Calling reset fixes the following error on shutdown of the nodelet:
115  // terminate called after throwing an instance of
116  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
117  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
118  // Also see https://github.com/ros/ros_comm/issues/720 .
119  sync_.reset();
120  sync_offset_.reset();
121  sync_reference_.reset();
122  }
123 
125  {
127  // Subscription
129  sub_camera_info_ = pnh_->subscribe("input/camera_info", 1,
131  this);
132  if (!synchronize_reference_) {
133  if (align_box_) {
134  sub_input_.subscribe(*pnh_, "input", 1);
135  sub_box_.subscribe(*pnh_, "input_box", 1);
136  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
137  sync_->connectInput(sub_input_, sub_box_);
138  sync_->registerCallback(boost::bind(
140  this, _1, _2));
141  }
142  else if (use_offset_pose_) {
143  sub_input_.subscribe(*pnh_, "input", 1);
144  sub_offset_.subscribe(*pnh_, "input_offset", 1);
145  sync_offset_ = boost::make_shared<message_filters::Synchronizer<OffsetSyncPolicy> >(100);
146  sync_offset_->connectInput(sub_input_, sub_offset_);
147  sync_offset_->registerCallback(boost::bind(&ICPRegistration::alignWithOffset, this, _1, _2));
148  }
149  else {
150  sub_ = pnh_->subscribe("input", 1,
152  this);
153  }
154  }
155  else {
156  sub_sync_input_.subscribe(*pnh_, "input", 1);
157  sub_sync_reference_.subscribe(*pnh_, "reference", 1);
158  sync_reference_ = boost::make_shared<message_filters::Synchronizer<ReferenceSyncPolicy> >(100);
160  sync_reference_->registerCallback(boost::bind(&ICPRegistration::align, this, _1, _2));
161  }
162  }
163 
165  {
167  if (!synchronize_reference_) {
168  if (align_box_) {
171  }
172  else {
173  sub_.shutdown();
174  }
175  }
176  else {
179  }
180  }
181 
184  const pcl::PointCloud<PointT>& cloud,
185  const std_msgs::Header& header)
186  {
187  if (pub.getNumSubscribers() > 0) {
188  sensor_msgs::PointCloud2 ros_cloud;
189  pcl::toROSMsg(cloud, ros_cloud);
190  ros_cloud.header = header;
191  pub.publish(ros_cloud);
192  }
193  }
194 
195  void ICPRegistration::configCallback(Config &config, uint32_t level)
196  {
197  boost::mutex::scoped_lock lock(mutex_);
198  algorithm_ = config.algorithm;
199  correspondence_algorithm_ = config.correspondence_algorithm;
200  use_flipped_initial_pose_ = config.use_flipped_initial_pose;
201  max_iteration_ = config.max_iteration;
202  correspondence_distance_ = config.correspondence_distance;
203  transform_epsilon_ = config.transform_epsilon;
204  euclidean_fittness_epsilon_ = config.euclidean_fittness_epsilon;
205  rotation_epsilon_ = config.rotation_epsilon;
206  ransac_iterations_ = config.ransac_iterations;
207  ransac_outlier_threshold_ = config.ransac_outlier_threshold;
208  correspondence_randomness_ = config.correspondence_randomness;
209  maximum_optimizer_iterations_ = config.maximum_optimizer_iterations;
210  ndt_resolution_ = config.ndt_resolution;
211  ndt_step_size_ = config.ndt_step_size;
212  ndt_outlier_ratio_ = config.ndt_outlier_ratio;
213  }
214 
216  jsk_recognition_msgs::ICPAlignWithBox::Request& req,
217  jsk_recognition_msgs::ICPAlignWithBox::Response& res)
218  {
219  boost::mutex::scoped_lock lock(mutex_);
220  if (reference_cloud_list_.size() == 0) {
221  NODELET_FATAL("no reference is specified");
222  return false;
223  }
224  try
225  {
226  Eigen::Affine3f offset;
227  pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
228  jsk_pcl_ros_utils::transformPointcloudInBoundingBox<PointT>(
229  req.target_box, req.target_cloud,
230  *output, offset,
231  *tf_listener_);
232  Eigen::Affine3f inversed_offset = offset.inverse();
233  res.result = alignPointcloudWithReferences(output, inversed_offset, req.target_cloud.header);
234  }
235  catch (tf2::ConnectivityException &e)
236  {
237  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
238  return false;
239  }
241  {
242  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
243  return false;
244  }
245  return true;
246  }
247 
249  jsk_recognition_msgs::ICPAlign::Request& req,
250  jsk_recognition_msgs::ICPAlign::Response& res)
251  {
252  boost::mutex::scoped_lock lock(mutex_);
253  std::vector<pcl::PointCloud<PointT>::Ptr> tmp_reference_cloud_list
254  = reference_cloud_list_; // escape
255  try
256  {
257  // first, update reference
258  std::vector<pcl::PointCloud<PointT>::Ptr> new_references;
259  pcl::PointCloud<PointT>::Ptr reference_cloud (new pcl::PointCloud<PointT>);
260  pcl::fromROSMsg(req.reference_cloud, *reference_cloud);
261  pcl::PointCloud<PointT>::Ptr non_nan_reference_cloud (new pcl::PointCloud<PointT>);
262  for (size_t i = 0; i < reference_cloud->points.size(); i++) {
263  PointT p = reference_cloud->points[i];
264  if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
265  non_nan_reference_cloud->points.push_back(p);
266  }
267  }
268  new_references.push_back(non_nan_reference_cloud);
269  reference_cloud_list_ = new_references; // replace references
270  NODELET_INFO("reference points: %lu/%lu",
271  non_nan_reference_cloud->points.size(),
272  reference_cloud->points.size());
273  Eigen::Affine3f offset = Eigen::Affine3f::Identity();
274  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
275  pcl::fromROSMsg(req.target_cloud, *cloud);
277  offset,
278  req.target_cloud.header);
279  }
281  {
282  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
283  reference_cloud_list_ = tmp_reference_cloud_list;
284  return false;
285  }
287  {
288  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
289  reference_cloud_list_ = tmp_reference_cloud_list;
290  return false;
291  }
292  reference_cloud_list_ = tmp_reference_cloud_list;
293  return true;
294  }
295 
296 
298  const sensor_msgs::PointCloud2::ConstPtr& msg,
299  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
300  {
301  boost::mutex::scoped_lock lock(mutex_);
302  if (!done_init_) {
303  NODELET_WARN("not yet initialized");
304  return;
305  }
306  if (reference_cloud_list_.size() == 0) {
307  NODELET_FATAL("no reference is specified");
308  jsk_recognition_msgs::ICPResult result;
309  result.name = std::string("NONE");
310  result.score = DBL_MAX;
311  result.header = box_msg->header;
312  result.pose = box_msg->pose;
313  pub_icp_result.publish(result);
314  return;
315  }
316  try
317  {
318  Eigen::Affine3f offset;
319  pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
320  jsk_pcl_ros_utils::transformPointcloudInBoundingBox<PointT>(
321  *box_msg, *msg,
322  *output, offset,
323  *tf_listener_);
324  Eigen::Affine3f inversed_offset = offset.inverse();
325  jsk_recognition_msgs::ICPResult result = alignPointcloudWithReferences(output, inversed_offset, msg->header);
326  pub_icp_result.publish(result);
327  }
328  catch (tf2::ConnectivityException &e)
329  {
330  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
331  }
333  {
334  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
335  }
336  }
337 
339  const sensor_msgs::PointCloud2::ConstPtr& msg,
340  const geometry_msgs::PoseStamped::ConstPtr& offset_msg)
341  {
342  boost::mutex::scoped_lock lock(mutex_);
343  if (!done_init_) {
344  NODELET_WARN("not yet initialized");
345  return;
346  }
347  if (reference_cloud_list_.size() == 0) {
348  NODELET_FATAL("no reference is specified");
349  jsk_recognition_msgs::ICPResult result;
350  result.name = std::string("NONE");
351  result.score = DBL_MAX;
352  result.header = offset_msg->header;
353  result.pose = offset_msg->pose;
354  pub_icp_result.publish(result);
355  return;
356  }
357  try
358  {
359  if (!jsk_recognition_utils::isSameFrameId(msg->header.frame_id,
360  offset_msg->header.frame_id)) {
361  NODELET_ERROR("frame_id does not match. cloud: %s, pose: %s",
362  msg->header.frame_id.c_str(),
363  offset_msg->header.frame_id.c_str());
364  return;
365  }
366  Eigen::Affine3f offset;
367  pcl::PointCloud<PointT>::Ptr input (new pcl::PointCloud<PointT>);
369  pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
370  tf::poseMsgToEigen(offset_msg->pose, offset);
371 
372  Eigen::Affine3f inversed_offset = offset.inverse();
373  pcl::transformPointCloud(*input, *output, inversed_offset);
374  jsk_recognition_msgs::ICPResult result = alignPointcloudWithReferences(output, offset, msg->header);
375  pub_icp_result.publish(result);
376  }
377  catch (tf2::ConnectivityException &e)
378  {
379  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
380  }
382  {
383  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
384  }
385  }
386 
387 
388  void ICPRegistration::align(const sensor_msgs::PointCloud2::ConstPtr& msg)
389  {
390  boost::mutex::scoped_lock lock(mutex_);
391  if (!done_init_) {
392  NODELET_WARN("not yet initialized");
393  return;
394  }
395  if (reference_cloud_list_.size() == 0) {
396  NODELET_FATAL("no reference is specified");
397  return;
398  }
399 
400  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
401  pcl::fromROSMsg(*msg, *cloud);
402  Eigen::Affine3f offset = Eigen::Affine3f::Identity();
403  // remove nan
404  pcl::PointCloud<PointT>::Ptr non_nan_cloud (new pcl::PointCloud<PointT>);
405  for (size_t i = 0; i < cloud->points.size(); i++) {
406  PointT p = cloud->points[i];
407  if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
408  non_nan_cloud->points.push_back(p);
409  }
410  }
411  jsk_recognition_msgs::ICPResult result = alignPointcloudWithReferences(non_nan_cloud, offset, msg->header);
412  pub_icp_result.publish(result);
413  }
414 
415  void ICPRegistration::align(const sensor_msgs::PointCloud2::ConstPtr& msg,
416  const sensor_msgs::PointCloud2::ConstPtr& reference_msg)
417  {
418  {
419  boost::mutex::scoped_lock lock(mutex_);
420  if (!done_init_) {
421  NODELET_WARN("not yet initialized");
422  return;
423  }
424  reference_cloud_list_.resize(0);
425  pcl::PointCloud<PointT>::Ptr reference_cloud (new pcl::PointCloud<PointT>);
426  pcl::fromROSMsg(*reference_msg, *reference_cloud);
427  // remove nan
428  pcl::PointCloud<PointT>::Ptr non_nan_reference_cloud (new pcl::PointCloud<PointT>);
429  for (size_t i = 0; i < reference_cloud->points.size(); i++) {
430  PointT p = reference_cloud->points[i];
431  if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
432  non_nan_reference_cloud->points.push_back(p);
433  }
434  }
435  reference_cloud_list_.push_back(non_nan_reference_cloud);
436  }
437  align(msg);
438  }
439 
440  jsk_recognition_msgs::ICPResult ICPRegistration::alignPointcloudWithReferences(
441  pcl::PointCloud<PointT>::Ptr& cloud,
442  const Eigen::Affine3f& offset,
443  const std_msgs::Header& header)
444  {
447  double min_score = DBL_MAX;
448  size_t max_index = 0;
449  pcl::PointCloud<PointT>::Ptr best_transformed_cloud;
450  pcl::PointCloud<PointT>::Ptr best_reference;
451  Eigen::Affine3d best_transform_result;
452  Eigen::Affine3f best_offset_result;
453  jsk_recognition_msgs::ICPResult result;
454  if (cloud->empty()) {
455  sensor_msgs::PointCloud2 empty_cloud;
456  empty_cloud.header = header;
457  pub_result_cloud_.publish(empty_cloud);
458 
459  pcl::PointCloud<PointT> empty_pcl_cloud;
463 
464  geometry_msgs::PoseStamped empty_pose;
465  empty_pose.header = header;
466  pub_result_pose_.publish(empty_pose);
467 
468  result.header = header;
469  result.score = min_score;
470  result.name = "nan";
471  return result;
472  }
473  for (size_t i = 0; i < reference_cloud_list_.size(); i++) {
474  Eigen::Affine3f offset_result;
475  pcl::PointCloud<PointT>::Ptr transformed_cloud(new pcl::PointCloud<PointT>);
476  Eigen::Affine3d transform_result;
477  double score = scorePointcloudAlignment(
478  cloud,
480  offset,
481  offset_result,
482  transformed_cloud,
483  transform_result);
484  if (score < min_score) {
485  max_index = i;
486  min_score = score;
487  best_transform_result = transform_result;
488  best_transformed_cloud = transformed_cloud;
489  best_reference = reference_cloud_list_[i];
490  best_offset_result = offset_result;
491  }
492  }
493 
494  NODELET_INFO("best score is: %f", min_score);
495  if ( min_score == DBL_MAX ) {
496  NODELET_INFO("could get valid scorePointcloudAlignment()");
497  geometry_msgs::PoseStamped empty_pose;
498  empty_pose.header = header;
499  pub_result_pose_.publish(empty_pose);
500 
501  result.header = header;
502  result.score = min_score;
503  result.name = "nan";
504  return result;
505  }
507  sensor_msgs::PointCloud2 ros_final;
508  pcl::toROSMsg(*best_transformed_cloud, ros_final);
509  ros_final.header = header;
510  pub_result_cloud_.publish(ros_final);
511  }
512  geometry_msgs::PoseStamped ros_result_pose;
513  ros_result_pose.header = header;
514  tf::poseEigenToMsg(best_transform_result, ros_result_pose.pose);
515  pub_result_pose_.publish(ros_result_pose);
518  pcl::PointCloud<PointT>::Ptr transformed_cloud_for_debug_result
519  (new pcl::PointCloud<PointT>);
520  pcl::transformPointCloud(
521  *best_transformed_cloud, *transformed_cloud_for_debug_result,
522  best_offset_result.inverse());
524  *transformed_cloud_for_debug_result, header);
525  result.header = ros_result_pose.header;
526  result.pose = ros_result_pose.pose;
527  result.score = min_score;
528  std::stringstream ss;
529  ss << max_index;
530  result.name = ss.str();
531  return result;
532  }
533 
535  const sensor_msgs::CameraInfo::ConstPtr& msg)
536  {
537  boost::mutex::scoped_lock lock(mutex_);
539  }
540 
542  pcl::PointCloud<PointT>::Ptr& cloud,
543  pcl::PointCloud<PointT>::Ptr& reference,
544  const Eigen::Affine3f& offset,
545  pcl::PointCloud<PointT>::Ptr& output_cloud,
546  Eigen::Affine3d& output_transform)
547  {
548  if (algorithm_ == 0 || algorithm_ == 1) {
549  return alignPointcloudWithICP(cloud, reference, offset, output_cloud, output_transform);
550  }
551  else {
552  return alignPointcloudWithNDT(cloud, reference, offset, output_cloud, output_transform);
553  }
554  }
555 
556 
558  pcl::PointCloud<PointT>::Ptr& cloud,
559  pcl::PointCloud<PointT>::Ptr& reference,
560  const Eigen::Affine3f& offset,
561  pcl::PointCloud<PointT>::Ptr& output_cloud,
562  Eigen::Affine3d& output_transform)
563  {
564  pcl::NormalDistributionsTransform<PointT, PointT> ndt;
565  if (reference->points.empty ()) {
566  NODELET_ERROR("Input Reference Cloud is empty!");
567  return DBL_MAX;
568  }
569  ndt.setInputSource(reference);
570  if (cloud->points.empty ()) {
571  NODELET_ERROR("Input Target Cloud is empty!");
572  return DBL_MAX;
573  }
574  ndt.setInputTarget(cloud);
575  pcl::PointCloud<PointT> final;
576  ndt.align(final);
577  pcl::transformPointCloud(final, *output_cloud, offset);
578  Eigen::Matrix4f transformation = ndt.getFinalTransformation ();
579  Eigen::Matrix4d transformation_d;
580  jsk_recognition_utils::convertMatrix4<Eigen::Matrix4f, Eigen::Matrix4d>(
581  transformation, transformation_d);
582  Eigen::Affine3d offsetd;
583  convertEigenAffine3(offset, offsetd);
584  output_transform = offsetd * Eigen::Affine3d(transformation_d);
585  return ndt.getFitnessScore();
586  }
587 
589  pcl::PointCloud<PointT>::Ptr& cloud,
590  pcl::PointCloud<PointT>::Ptr& reference,
591  const Eigen::Affine3f& offset,
592  pcl::PointCloud<PointT>::Ptr& output_cloud,
593  Eigen::Affine3d& output_transform)
594  {
595 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
596  pcl::GeneralizedIterativeClosestPoint<PointT, PointT> icp;
597  icp.setRotationEpsilon(rotation_epsilon_);
598  icp.setCorrespondenceRandomness(correspondence_randomness_);
599  icp.setMaximumOptimizerIterations(maximum_optimizer_iterations_);
600 #else
601  pcl::IterativeClosestPoint<PointT, PointT> icp;
602  if (use_normal_) {
603  pcl::IterativeClosestPointWithNormals<PointT, PointT> icp_with_normal;
604  icp = icp_with_normal;
605  }
606  // icp.setInputSource(cloud);
607  // icp.setInputTarget(reference_cloud_);
608  if (algorithm_ == 1) {
609  pcl::GeneralizedIterativeClosestPoint<PointT, PointT> gicp;
610  gicp.setRotationEpsilon(rotation_epsilon_);
611  gicp.setCorrespondenceRandomness(correspondence_randomness_);
612  gicp.setMaximumOptimizerIterations(maximum_optimizer_iterations_);
613  icp = gicp;
614  }
615 #endif
616  if (correspondence_algorithm_ == 1) { // Projective
617  if (!camera_info_msg_) {
618  NODELET_ERROR("no camera info is available yet");
619  return DBL_MAX;
620  }
622  bool model_success_p = model.fromCameraInfo(camera_info_msg_);
623  if (!model_success_p) {
624  NODELET_ERROR("failed to create camera model");
625  return DBL_MAX;
626  }
627  pcl::registration::CorrespondenceEstimationOrganizedProjection<PointT, PointT, float>::Ptr
628  corr_projection (new pcl::registration::CorrespondenceEstimationOrganizedProjection<PointT, PointT, float>);
629  corr_projection->setFocalLengths(model.fx(), model.fy());
630  corr_projection->setCameraCenters(model.cx(), model.cy());
631  icp.setCorrespondenceEstimation(corr_projection);
632  }
633 
634  if (reference->points.empty ()) {
635  NODELET_ERROR("Input Reference Cloud is empty!");
636  return DBL_MAX;
637  }
638  icp.setInputSource(reference);
639  if (cloud->points.empty ()) {
640  NODELET_ERROR("Input Target Cloud is empty!");
641  return DBL_MAX;
642  }
643  icp.setInputTarget(cloud);
644 
645  if (transform_3dof_) {
646 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
647  pcl::registration::WarpPointRigid3D<PointT, PointT>::Ptr warp_func
648  (new pcl::registration::WarpPointRigid3D<PointT, PointT>);
649  pcl::registration::TransformationEstimationLM<PointT, PointT>::Ptr te
650  (new pcl::registration::TransformationEstimationLM<PointT, PointT>);
651 #else
653  (new pcl::registration::WarpPointRigid3D<PointT, PointT>);
655  (new pcl::registration::TransformationEstimationLM<PointT, PointT>);
656 #endif
657  te->setWarpFunction(warp_func);
658  icp.setTransformationEstimation(te);
659  }
660 
661  icp.setMaxCorrespondenceDistance (correspondence_distance_);
662  icp.setMaximumIterations (max_iteration_);
663  icp.setTransformationEpsilon (transform_epsilon_);
664  icp.setEuclideanFitnessEpsilon (euclidean_fittness_epsilon_);
665  icp.setRANSACIterations(ransac_iterations_);
666  icp.setRANSACOutlierRejectionThreshold(ransac_outlier_threshold_);
667  pcl::PointCloud<PointT> final;
668  icp.align(final);
669  pcl::transformPointCloud(final, *output_cloud, offset);
670  // NODELET_INFO_STREAM("ICP converged: " << icp.hasConverged());
671  // NODELET_INFO_STREAM("ICP score: " << icp.getFitnessScore());
672  Eigen::Matrix4f transformation = icp.getFinalTransformation ();
673  Eigen::Matrix4d transformation_d;
674  jsk_recognition_utils::convertMatrix4<Eigen::Matrix4f, Eigen::Matrix4d>(
675  transformation, transformation_d);
676  Eigen::Affine3d offsetd;
677  convertEigenAffine3(offset, offsetd);
678  output_transform = offsetd * Eigen::Affine3d(transformation_d);
679  return icp.getFitnessScore();
680  }
681 
682  // compute ICP and return score
684  pcl::PointCloud<PointT>::Ptr& cloud,
685  pcl::PointCloud<PointT>::Ptr& reference,
686  const Eigen::Affine3f& offset,
687  Eigen::Affine3f& offset_result,
688  pcl::PointCloud<PointT>::Ptr transformed_cloud,
689  Eigen::Affine3d& transform_result)
690  {
691  pcl::PointCloud<PointT>::Ptr transformed_cloud_for_debug_result
692  (new pcl::PointCloud<PointT>);
693  double score = alignPointcloud(cloud, reference, offset,
694  transformed_cloud, transform_result);
695  pcl::transformPointCloud(
696  *transformed_cloud, *transformed_cloud_for_debug_result,
697  offset.inverse());
698  offset_result = offset;
700  pcl::PointCloud<PointT>::Ptr flipped_transformed_cloud
701  (new pcl::PointCloud<PointT>);
702  Eigen::Affine3d flipped_transform_result;
703  Eigen::Affine3f flipped_offset
704  = offset * Eigen::AngleAxisf(M_PI, Eigen::Vector3f(0, 0, 1));
705  pcl::PointCloud<PointT>::Ptr flipped_cloud (new pcl::PointCloud<PointT>);
706  pcl::transformPointCloud(
707  *cloud, *flipped_cloud,
708  Eigen::Affine3f(Eigen::AngleAxisf(M_PI, Eigen::Vector3f(0, 0, 1))));
709  double flipped_score
710  = alignPointcloud(flipped_cloud, reference, flipped_offset,
711  flipped_transformed_cloud,
712  flipped_transform_result);
713  NODELET_INFO("flipped score: %f", flipped_score);
714  if (flipped_score < score) {
715  score = flipped_score;
716  transformed_cloud = flipped_transformed_cloud;
717  transform_result = flipped_transform_result;
718  pcl::transformPointCloud(
719  *transformed_cloud, *transformed_cloud_for_debug_result,
720  flipped_offset.inverse());
721  offset_result = flipped_offset;
722  }
723  }
724  return score;
725  }
726 
728  const sensor_msgs::PointCloud2::ConstPtr& msg)
729  {
730  boost::mutex::scoped_lock lock(mutex_);
731  if (!done_init_) {
732  NODELET_WARN("not yet initialized");
733  return;
734  }
735  reference_cloud_list_.resize(0);
736  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
737  pcl::fromROSMsg(*msg, *cloud);
738  pcl::PointCloud<PointT>::Ptr non_nan_cloud (new pcl::PointCloud<PointT>);
739  for (size_t i = 0; i < cloud->points.size(); i++) {
740  PointT p = cloud->points[i];
741  if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
742  non_nan_cloud->points.push_back(p);
743  }
744  }
745  reference_cloud_list_.push_back(non_nan_cloud);
746  }
747 
749  const jsk_recognition_msgs::PointsArray::ConstPtr& msg)
750  {
751  boost::mutex::scoped_lock lock(mutex_);
752  if (!done_init_) {
753  NODELET_WARN("not yet initialized");
754  return;
755  }
756  reference_cloud_list_.resize(0);
757  for (size_t i = 0; i < msg->cloud_list.size(); i++) {
758  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
759  pcl::fromROSMsg(msg->cloud_list[i], *cloud);
760  reference_cloud_list_.push_back(cloud);
761  }
762  }
763 
765  const sensor_msgs::PointCloud2::ConstPtr& msg)
766  {
767  boost::mutex::scoped_lock lock(mutex_);
768  if (!done_init_) {
769  NODELET_WARN("not yet initialized");
770  return;
771  }
772  //reference_cloud_list_.resize(0); //not 0
773  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
774  pcl::fromROSMsg(*msg, *cloud);
775  reference_cloud_list_.push_back(cloud);
776  ROS_INFO("reference_num: %zd", reference_cloud_list_.size()-1);
777  }
778 }
779 
tf::poseMsgToEigen
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
result
def result
jsk_pcl_ros::ICPRegistration
Definition: icp_registration.h:91
NODELET_FATAL
#define NODELET_FATAL(...)
jsk_pcl_ros::ICPRegistration::align_box_
bool align_box_
Definition: icp_registration.h:227
jsk_pcl_ros::ICPRegistration::sub_reference_
ros::Subscriber sub_reference_
Definition: icp_registration.h:210
NODELET_ERROR
#define NODELET_ERROR(...)
jsk_pcl_ros::ICPRegistration::ransac_iterations_
double ransac_iterations_
Definition: icp_registration.h:268
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
jsk_pcl_ros::ICPRegistration::correspondence_algorithm_
int correspondence_algorithm_
Definition: icp_registration.h:262
ros::Publisher
jsk_pcl_ros::ICPRegistration::unsubscribe
virtual void unsubscribe()
Definition: icp_registration_nodelet.cpp:196
jsk_pcl_ros::ICPRegistration::pub_average_time_
ros::Publisher pub_average_time_
Definition: icp_registration.h:218
boost::shared_ptr
jsk_pcl_ros::ICPRegistration::sub_reference_add
ros::Subscriber sub_reference_add
Definition: icp_registration.h:211
i
int i
jsk_pcl_ros::ICPRegistration::sync_reference_
boost::shared_ptr< message_filters::Synchronizer< ReferenceSyncPolicy > > sync_reference_
Definition: icp_registration.h:235
pinhole_camera_model.h
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
jsk_pcl_ros::ICPRegistration::pub_result_cloud_
ros::Publisher pub_result_cloud_
Definition: icp_registration.h:216
jsk_pcl_ros::ICPRegistration::reference_cloud_list_
std::vector< pcl::PointCloud< PointT >::Ptr > reference_cloud_list_
Definition: icp_registration.h:263
jsk_recognition_utils::isSameFrameId
bool isSameFrameId(const std::string &a, const std::string &b)
jsk_pcl_ros::ICPRegistration::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: icp_registration_nodelet.cpp:227
box_msg
jsk_recognition_msgs::BoundingBoxArray::ConstPtr box_msg
jsk_pcl_ros::ICPRegistration::alignPointcloudWithICP
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)
Definition: icp_registration_nodelet.cpp:620
p
p
jsk_pcl_ros::ICPRegistration::ransac_outlier_threshold_
double ransac_outlier_threshold_
Definition: icp_registration.h:269
pcl_ros_util.h
jsk_pcl_ros::ICPRegistration::scorePointcloudAlignment
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)
Definition: icp_registration_nodelet.cpp:715
jsk_pcl_ros::ICPRegistration::~ICPRegistration
virtual ~ICPRegistration()
Definition: icp_registration_nodelet.cpp:143
jsk_pcl_ros::ICPRegistration::onInit
virtual void onInit()
Definition: icp_registration_nodelet.cpp:86
jsk_pcl_ros::ICPRegistration::referenceAddCallback
virtual void referenceAddCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: icp_registration_nodelet.cpp:796
NODELET_WARN
#define NODELET_WARN(...)
jsk_pcl_ros::ICPRegistration::use_offset_pose_
bool use_offset_pose_
set via ~use_offset_pose parameter. default is false.
Definition: icp_registration.h:247
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ICPRegistration, nodelet::Nodelet)
attention_pose_set.pub
pub
Definition: attention_pose_set.py:8
ros::Subscriber::shutdown
void shutdown()
jsk_pcl_ros::ICPRegistration::max_iteration_
int max_iteration_
Definition: icp_registration.h:264
jsk_pcl_ros::ICPRegistration::sub_camera_info_
ros::Subscriber sub_camera_info_
Definition: icp_registration.h:208
jsk_pcl_ros::ICPRegistration::alignWithOffset
virtual void alignWithOffset(const sensor_msgs::PointCloud2::ConstPtr &msg, const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
Definition: icp_registration_nodelet.cpp:370
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
jsk_pcl_ros::ICPRegistration::pub_debug_target_cloud_
ros::Publisher pub_debug_target_cloud_
Definition: icp_registration.h:220
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros::ICPRegistration::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: icp_registration.h:233
jsk_pcl_ros::ICPRegistration::rotation_epsilon_
double rotation_epsilon_
Definition: icp_registration.h:275
cloud
cloud
jsk_pcl_ros::ICPRegistration::sub_reference_array_
ros::Subscriber sub_reference_array_
Definition: icp_registration.h:212
convertEigenAffine3
void convertEigenAffine3(const Eigen::Affine3d &from, Eigen::Affine3f &to)
class_list_macros.h
jsk_pcl_ros::ICPRegistration::referenceCallback
virtual void referenceCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: icp_registration_nodelet.cpp:759
jsk_pcl_ros::ICPRegistration::pub_debug_flipped_cloud_
ros::Publisher pub_debug_flipped_cloud_
Definition: icp_registration.h:222
transform_pointcloud_in_bounding_box.h
jsk_pcl_ros::ICPRegistration::pub_debug_result_cloud_
ros::Publisher pub_debug_result_cloud_
Definition: icp_registration.h:221
jsk_pcl_ros::ICPRegistration::PointT
pcl::PointXYZRGBNormal PointT
Definition: icp_registration.h:126
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::ICPRegistration::alignPointcloudWithReferences
virtual jsk_recognition_msgs::ICPResult alignPointcloudWithReferences(pcl::PointCloud< PointT >::Ptr &cloud, const Eigen::Affine3f &offset, const std_msgs::Header &header)
Definition: icp_registration_nodelet.cpp:472
jsk_pcl_ros::ICPRegistration::srv_icp_align_
ros::ServiceServer srv_icp_align_
Definition: icp_registration.h:226
jsk_pcl_ros::ICPRegistration::sub_box_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBox > sub_box_
Definition: icp_registration.h:231
jsk_pcl_ros::ICPRegistration::euclidean_fittness_epsilon_
double euclidean_fittness_epsilon_
Definition: icp_registration.h:267
PointT
pcl::PointXYZRGB PointT
jsk_pcl_ros::ICPRegistration::sub_offset_
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_offset_
Definition: icp_registration.h:232
eigen_msg.h
jsk_pcl_ros::ICPRegistration::alignPointcloudWithNDT
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)
Definition: icp_registration_nodelet.cpp:589
jsk_pcl_ros::ICPRegistration::correspondence_distance_
double correspondence_distance_
Definition: icp_registration.h:265
jsk_pcl_ros::ICPRegistration::maximum_optimizer_iterations_
int maximum_optimizer_iterations_
Definition: icp_registration.h:277
jsk_pcl_ros::ICPRegistration::camera_info_msg_
sensor_msgs::CameraInfo::ConstPtr camera_info_msg_
Definition: icp_registration.h:270
jsk_pcl_ros::ICPRegistration::done_init_
bool done_init_
Definition: icp_registration.h:286
attention_pose_set.r
r
Definition: attention_pose_set.py:9
jsk_pcl_ros::ICPRegistration::sync_offset_
boost::shared_ptr< message_filters::Synchronizer< OffsetSyncPolicy > > sync_offset_
Definition: icp_registration.h:234
jsk_pcl_ros::ICPRegistration::alignWithBox
virtual void alignWithBox(const sensor_msgs::PointCloud2::ConstPtr &msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
Definition: icp_registration_nodelet.cpp:329
tf::poseEigenToMsg
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
jsk_pcl_ros::ICPRegistration::referenceArrayCallback
virtual void referenceArrayCallback(const jsk_recognition_msgs::PointsArray::ConstPtr &msg)
Definition: icp_registration_nodelet.cpp:780
jsk_pcl_ros::ICPRegistration::srv_icp_align_with_box_
ros::ServiceServer srv_icp_align_with_box_
Definition: icp_registration.h:225
jsk_pcl_ros::ICPRegistration::transform_3dof_
bool transform_3dof_
set via ~transform_3dof parameter. default is false.
Definition: icp_registration.h:242
pcl_conversion_util.h
icp_registration.h
tf2::ConnectivityException
jsk_pcl_ros::ICPRegistration::correspondence_randomness_
int correspondence_randomness_
Definition: icp_registration.h:276
jsk_pcl_ros::ICPRegistration::publishDebugCloud
virtual void publishDebugCloud(ros::Publisher &pub, const pcl::PointCloud< PointT > &cloud, const std_msgs::Header &header)
Definition: icp_registration_nodelet.cpp:214
jsk_pcl_ros::ICPRegistration::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: icp_registration.h:228
jsk_pcl_ros::ICPRegistration::tf_listener_
tf::TransformListener * tf_listener_
Definition: icp_registration.h:236
jsk_pcl_ros::ICPRegistration::alignPointcloud
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)
Definition: icp_registration_nodelet.cpp:573
depth_error_calibration.model
model
Definition: depth_error_calibration.py:37
message_filters::Subscriber::subscribe
void subscribe()
NODELET_INFO
#define NODELET_INFO(...)
jsk_pcl_ros::ICPRegistration::sub_
ros::Subscriber sub_
Definition: icp_registration.h:209
jsk_recognition_utils::WallDurationTimer::reporter
virtual ScopedWallDurationReporter reporter()
jsk_pcl_ros::ICPRegistration::algorithm_
int algorithm_
Definition: icp_registration.h:261
nodelet::Nodelet
jsk_pcl_ros::ICPRegistration::synchronize_reference_
bool synchronize_reference_
Definition: icp_registration.h:259
jsk_pcl_ros::ICPRegistration::transform_epsilon_
double transform_epsilon_
Definition: icp_registration.h:266
image_geometry::PinholeCameraModel
jsk_pcl_ros::ICPRegistration::timer_
jsk_recognition_utils::WallDurationTimer timer_
Definition: icp_registration.h:224
jsk_pcl_ros::ICPRegistration::use_flipped_initial_pose_
bool use_flipped_initial_pose_
Definition: icp_registration.h:260
jsk_pcl_ros::ICPRegistration::cameraInfoCallback
virtual void cameraInfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg)
Definition: icp_registration_nodelet.cpp:566
dump_depth_error.f
f
Definition: dump_depth_error.py:39
jsk_pcl_ros::ICPRegistration::pub_debug_source_cloud_
ros::Publisher pub_debug_source_cloud_
Definition: icp_registration.h:219
jsk_pcl_ros::ICPRegistration::sub_sync_reference_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_sync_reference_
Definition: icp_registration.h:214
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
jsk_pcl_ros::ICPRegistration::pub_latest_time_
ros::Publisher pub_latest_time_
Definition: icp_registration.h:217
jsk_recognition_utils::ScopedWallDurationReporter
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
jsk_pcl_ros::ICPRegistration::alignService
virtual bool alignService(jsk_recognition_msgs::ICPAlign::Request &req, jsk_recognition_msgs::ICPAlign::Response &res)
Definition: icp_registration_nodelet.cpp:280
jsk_recognition_utils::TfListenerSingleton::getInstance
static tf::TransformListener * getInstance()
jsk_pcl_ros::ICPRegistration::alignWithBoxService
virtual bool alignWithBoxService(jsk_recognition_msgs::ICPAlignWithBox::Request &req, jsk_recognition_msgs::ICPAlignWithBox::Response &res)
Definition: icp_registration_nodelet.cpp:247
jsk_pcl_ros::ICPRegistration::subscribe
virtual void subscribe()
Definition: icp_registration_nodelet.cpp:156
jsk_pcl_ros::ICPRegistration::use_normal_
bool use_normal_
Store value of ~use_normal. If this parameter is true, ICPRegistration nodelet expects reference and ...
Definition: icp_registration.h:254
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
tf2::InvalidArgumentException
ROS_INFO
#define ROS_INFO(...)
config
config
jsk_pcl_ros::ICPRegistration::mutex_
boost::mutex mutex_
Definition: icp_registration.h:229
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
jsk_pcl_ros::ICPRegistration::ndt_step_size_
double ndt_step_size_
Definition: icp_registration.h:283
jsk_pcl_ros::ICPRegistration::align
virtual void align(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: icp_registration_nodelet.cpp:420
sample_pointcloud_localization_client.req
req
Definition: sample_pointcloud_localization_client.py:15
jsk_pcl_ros::ICPRegistration::sub_sync_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_sync_input_
Definition: icp_registration.h:213
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14
jsk_pcl_ros::ICPRegistration::ndt_outlier_ratio_
double ndt_outlier_ratio_
Definition: icp_registration.h:284
jsk_pcl_ros::ICPRegistration::ndt_resolution_
double ndt_resolution_
Definition: icp_registration.h:282
jsk_pcl_ros::ICPRegistration::pub_icp_result
ros::Publisher pub_icp_result
Definition: icp_registration.h:223
jsk_pcl_ros::ICPRegistration::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: icp_registration.h:230
jsk_pcl_ros::ICPRegistration::pub_result_pose_
ros::Publisher pub_result_pose_
Definition: icp_registration.h:215


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