icp_registration_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++; indent-tabs-mode: nil; -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include "jsk_pcl_ros/icp_registration.h"
00037 #include <pcl/registration/icp.h>
00038 #include <pcl/registration/gicp.h>
00039 #include <pcl/registration/ndt.h>
00040 #include "jsk_recognition_utils/pcl_conversion_util.h"
00041 #include <eigen_conversions/eigen_msg.h>
00042 #include <pcl/common/transforms.h>
00043 #include <eigen_conversions/eigen_msg.h>
00044 #include "jsk_pcl_ros_utils/transform_pointcloud_in_bounding_box.h"
00045 #include <image_geometry/pinhole_camera_model.h>
00046 #include <pcl/registration/correspondence_estimation_organized_projection.h>
00047 #include <pcl/registration/correspondence_estimation_normal_shooting.h>
00048 #include <jsk_recognition_utils/pcl_ros_util.h>
00049 
00050 namespace jsk_pcl_ros
00051 {
00052   void ICPRegistration::onInit()
00053   {
00054     pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
00055     ConnectionBasedNodelet::onInit();
00056     tf_listener_ = TfListenerSingleton::getInstance();
00058     // Dynamic Reconfigure
00060     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00061     dynamic_reconfigure::Server<Config>::CallbackType f =
00062       boost::bind(
00063         &ICPRegistration::configCallback, this, _1, _2);
00064     srv_->setCallback (f);
00065     pnh_->param("use_normal", use_normal_, false);
00066     pnh_->param("align_box", align_box_, false);
00067     pnh_->param("synchronize_reference", synchronize_reference_, false);
00068     pnh_->param("use_offset_pose", use_offset_pose_, false);
00070     // Publishers
00072     pub_result_pose_ = advertise<geometry_msgs::PoseStamped>(*pnh_,
00073       "output_pose", 1);
00074     pub_result_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
00075       "output", 1);
00076     pub_debug_source_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
00077       "debug/source", 1);
00078     pub_debug_target_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
00079       "debug/target", 1);
00080     pub_debug_flipped_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
00081       "debug/flipped", 1);
00082     pub_debug_result_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
00083       "debug/result", 1);
00084     pub_icp_result = advertise<jsk_recognition_msgs::ICPResult>(*pnh_,
00085       "icp_result", 1);
00086     pub_latest_time_ = advertise<std_msgs::Float32>(
00087       *pnh_, "output/latest_time", 1);
00088     pub_average_time_ = advertise<std_msgs::Float32>(
00089       *pnh_, "output/average_time", 1);
00090     srv_icp_align_with_box_ = pnh_->advertiseService("icp_service", &ICPRegistration::alignWithBoxService, this);
00091     srv_icp_align_ = pnh_->advertiseService(
00092       "icp_align", &ICPRegistration::alignService, this);
00093     if (!synchronize_reference_) {
00094       sub_reference_ = pnh_->subscribe("input_reference", 1,
00095                                        &ICPRegistration::referenceCallback,
00096                                        this);
00097       sub_reference_array_ = pnh_->subscribe("input_reference_array", 1,
00098                                            &ICPRegistration::referenceArrayCallback,
00099                                              this);
00100       sub_reference_add = pnh_->subscribe("input_reference_add", 1,
00101                                           &ICPRegistration::referenceAddCallback,
00102                                           this);
00103     }
00104     done_init_ = true;
00105     onInitPostProcess();
00106   }
00107 
00108   void ICPRegistration::subscribe()
00109   {
00111     // Subscription
00113     sub_camera_info_ = pnh_->subscribe("input/camera_info", 1,
00114                                        &ICPRegistration::cameraInfoCallback,
00115                                        this);
00116     if (!synchronize_reference_) {
00117       if (align_box_) {
00118         sub_input_.subscribe(*pnh_, "input", 1);
00119         sub_box_.subscribe(*pnh_, "input_box", 1);
00120         sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00121         sync_->connectInput(sub_input_, sub_box_);
00122         sync_->registerCallback(boost::bind(
00123                                             &ICPRegistration::alignWithBox,
00124                                             this, _1, _2));
00125       }
00126       else if (use_offset_pose_) {
00127         sub_input_.subscribe(*pnh_, "input", 1);
00128         sub_offset_.subscribe(*pnh_, "input_offset", 1);
00129         sync_offset_ = boost::make_shared<message_filters::Synchronizer<OffsetSyncPolicy> >(100);
00130         sync_offset_->connectInput(sub_input_, sub_offset_);
00131         sync_offset_->registerCallback(boost::bind(&ICPRegistration::alignWithOffset, this, _1, _2));
00132       }
00133       else {
00134         sub_ = pnh_->subscribe("input", 1,
00135                                &ICPRegistration::align,
00136                                this);
00137       }
00138     }
00139     else {
00140       sub_sync_input_.subscribe(*pnh_, "input", 1);
00141       sub_sync_reference_.subscribe(*pnh_, "reference", 1);
00142       sync_reference_ = boost::make_shared<message_filters::Synchronizer<ReferenceSyncPolicy> >(100);
00143       sync_reference_->connectInput(sub_sync_input_, sub_sync_reference_);
00144       sync_reference_->registerCallback(boost::bind(&ICPRegistration::align, this, _1, _2));
00145     }
00146   }
00147 
00148   void ICPRegistration::unsubscribe()
00149   {
00150     sub_camera_info_.shutdown();
00151     if (!synchronize_reference_) {
00152       if (align_box_) {
00153         sub_input_.unsubscribe();
00154         sub_box_.unsubscribe();
00155       }
00156       else {
00157         sub_.shutdown();
00158       }
00159     }
00160     else {
00161       sub_sync_input_.unsubscribe();
00162       sub_sync_reference_.unsubscribe();
00163     }
00164   }
00165   
00166   void ICPRegistration::publishDebugCloud(
00167       ros::Publisher& pub,
00168       const pcl::PointCloud<PointT>& cloud)
00169   {
00170     if (pub.getNumSubscribers() > 0) {
00171       sensor_msgs::PointCloud2 ros_cloud;
00172       pcl::toROSMsg(cloud, ros_cloud);
00173       ros_cloud.header.frame_id = "base_link";
00174       ros_cloud.header.stamp = ros::Time::now();
00175       pub.publish(ros_cloud);
00176     }
00177   }
00178   
00179   void ICPRegistration::configCallback(Config &config, uint32_t level)
00180   {
00181     boost::mutex::scoped_lock lock(mutex_);
00182     algorithm_ = config.algorithm;
00183     correspondence_algorithm_ = config.correspondence_algorithm;
00184     use_flipped_initial_pose_ = config.use_flipped_initial_pose;
00185     max_iteration_ = config.max_iteration;
00186     correspondence_distance_ = config.correspondence_distance;
00187     transform_epsilon_ = config.transform_epsilon;
00188     euclidean_fittness_epsilon_ = config.euclidean_fittness_epsilon;
00189     rotation_epsilon_ = config.rotation_epsilon;
00190     ransac_iterations_ = config.ransac_iterations;
00191     ransac_outlier_threshold_ = config.ransac_outlier_threshold;
00192     maximum_optimizer_iterations_ = config.maximum_optimizer_iterations;
00193     ndt_resolution_ = config.ndt_resolution;
00194     ndt_step_size_ = config.ndt_step_size;
00195     ndt_outlier_ratio_ = config.ndt_outlier_ratio;
00196   }
00197 
00198   bool ICPRegistration::alignWithBoxService(
00199     jsk_recognition_msgs::ICPAlignWithBox::Request& req, 
00200     jsk_recognition_msgs::ICPAlignWithBox::Response& res)
00201   {
00202     boost::mutex::scoped_lock lock(mutex_);
00203     if (reference_cloud_list_.size() == 0) {
00204       NODELET_FATAL("no reference is specified");
00205       return false;
00206     }
00207     try
00208     {
00209       Eigen::Affine3f offset;
00210       pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
00211       jsk_pcl_ros_utils::transformPointcloudInBoundingBox<PointT>(
00212         req.target_box, req.target_cloud,
00213         *output, offset,
00214         *tf_listener_);
00215       Eigen::Affine3f inversed_offset = offset.inverse();
00216       res.result = alignPointcloudWithReferences(output, inversed_offset, req.target_cloud.header);
00217     }
00218     catch (tf2::ConnectivityException &e)
00219     {
00220       NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00221       return false;
00222     }
00223     catch (tf2::InvalidArgumentException &e)
00224     {
00225       NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00226       return false;
00227     }
00228     return true;
00229   }
00230 
00231   bool ICPRegistration::alignService(
00232     jsk_recognition_msgs::ICPAlign::Request& req, 
00233     jsk_recognition_msgs::ICPAlign::Response& res)
00234   {
00235     boost::mutex::scoped_lock lock(mutex_);
00236     std::vector<pcl::PointCloud<PointT>::Ptr> tmp_reference_cloud_list
00237       = reference_cloud_list_;  // escape
00238     try
00239     {
00240       // first, update reference
00241       std::vector<pcl::PointCloud<PointT>::Ptr> new_references;
00242       pcl::PointCloud<PointT>::Ptr reference_cloud (new pcl::PointCloud<PointT>);
00243       pcl::fromROSMsg(req.reference_cloud, *reference_cloud);
00244       pcl::PointCloud<PointT>::Ptr non_nan_reference_cloud (new pcl::PointCloud<PointT>);
00245       for (size_t i = 0; i < reference_cloud->points.size(); i++) {
00246         PointT p = reference_cloud->points[i];
00247         if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
00248           non_nan_reference_cloud->points.push_back(p);
00249         }
00250       }
00251       new_references.push_back(non_nan_reference_cloud);
00252       reference_cloud_list_ = new_references; // replace references
00253       NODELET_INFO("reference points: %lu/%lu",
00254                    non_nan_reference_cloud->points.size(),
00255                    reference_cloud->points.size());
00256       Eigen::Affine3f offset = Eigen::Affine3f::Identity();
00257       pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00258       pcl::fromROSMsg(req.target_cloud, *cloud);
00259       res.result = alignPointcloudWithReferences(cloud,
00260                                                  offset,
00261                                                  req.target_cloud.header);
00262     }
00263     catch (tf2::ConnectivityException &e)
00264     {
00265       NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00266       reference_cloud_list_ = tmp_reference_cloud_list;
00267       return false;
00268     }
00269     catch (tf2::InvalidArgumentException &e)
00270     {
00271       NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00272       reference_cloud_list_ = tmp_reference_cloud_list;
00273       return false;
00274     }
00275     reference_cloud_list_ = tmp_reference_cloud_list;
00276     return true;
00277   }
00278 
00279   
00280   void ICPRegistration::alignWithBox(
00281       const sensor_msgs::PointCloud2::ConstPtr& msg,
00282       const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
00283   {
00284     boost::mutex::scoped_lock lock(mutex_);
00285     if (!done_init_) {
00286       NODELET_WARN("not yet initialized");
00287       return;
00288     }
00289     if (reference_cloud_list_.size() == 0) {
00290       NODELET_FATAL("no reference is specified");
00291       jsk_recognition_msgs::ICPResult result;
00292       result.name = std::string("NONE");
00293       result.score = DBL_MAX;
00294       result.header = box_msg->header;
00295       result.pose = box_msg->pose;
00296       pub_icp_result.publish(result);
00297       return;
00298     }
00299     try
00300     {
00301       Eigen::Affine3f offset;
00302       pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
00303       jsk_pcl_ros_utils::transformPointcloudInBoundingBox<PointT>(
00304         *box_msg, *msg,
00305         *output, offset,
00306         *tf_listener_);
00307       Eigen::Affine3f inversed_offset = offset.inverse();
00308       jsk_recognition_msgs::ICPResult result = alignPointcloudWithReferences(output, inversed_offset, msg->header);
00309       pub_icp_result.publish(result);
00310     }
00311     catch (tf2::ConnectivityException &e)
00312     {
00313       NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00314     }
00315     catch (tf2::InvalidArgumentException &e)
00316     {
00317       NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00318     }
00319   }
00320 
00321   void ICPRegistration::alignWithOffset(
00322       const sensor_msgs::PointCloud2::ConstPtr& msg,
00323       const geometry_msgs::PoseStamped::ConstPtr& offset_msg)
00324   {
00325     boost::mutex::scoped_lock lock(mutex_);
00326     if (!done_init_) {
00327       NODELET_WARN("not yet initialized");
00328       return;
00329     }
00330     if (reference_cloud_list_.size() == 0) {
00331       NODELET_FATAL("no reference is specified");
00332       jsk_recognition_msgs::ICPResult result;
00333       result.name = std::string("NONE");
00334       result.score = DBL_MAX;
00335       result.header = offset_msg->header;
00336       result.pose = offset_msg->pose;
00337       pub_icp_result.publish(result);
00338       return;
00339     }
00340     try
00341     {
00342       if (!jsk_recognition_utils::isSameFrameId(msg->header.frame_id,
00343                                                 offset_msg->header.frame_id)) {
00344         NODELET_ERROR("frame_id does not match. cloud: %s, pose: %s",
00345                           msg->header.frame_id.c_str(),
00346                           offset_msg->header.frame_id.c_str());
00347         return;
00348       }
00349       Eigen::Affine3f offset;
00350       pcl::PointCloud<PointT>::Ptr input (new pcl::PointCloud<PointT>);
00351       pcl::fromROSMsg(*msg, *input);
00352       pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
00353       tf::poseMsgToEigen(offset_msg->pose, offset);
00354       
00355       Eigen::Affine3f inversed_offset = offset.inverse();
00356       pcl::transformPointCloud(*input, *output, inversed_offset);
00357       jsk_recognition_msgs::ICPResult result = alignPointcloudWithReferences(output, offset, msg->header);
00358       pub_icp_result.publish(result);
00359     }
00360     catch (tf2::ConnectivityException &e)
00361     {
00362       NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00363     }
00364     catch (tf2::InvalidArgumentException &e)
00365     {
00366       NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00367     }
00368   }
00369 
00370 
00371   void ICPRegistration::align(const sensor_msgs::PointCloud2::ConstPtr& msg)
00372   {
00373     boost::mutex::scoped_lock lock(mutex_);
00374     if (!done_init_) {
00375       NODELET_WARN("not yet initialized");
00376       return;
00377     }
00378     if (reference_cloud_list_.size() == 0) {
00379       NODELET_FATAL("no reference is specified");
00380       return;
00381     }
00382     
00383     pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00384     pcl::fromROSMsg(*msg, *cloud);
00385     Eigen::Affine3f offset = Eigen::Affine3f::Identity();
00386     // remove nan
00387     pcl::PointCloud<PointT>::Ptr non_nan_cloud (new pcl::PointCloud<PointT>);
00388     for (size_t i = 0; i < cloud->points.size(); i++) {
00389       PointT p = cloud->points[i];
00390       if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
00391         non_nan_cloud->points.push_back(p);
00392       }
00393     }
00394     jsk_recognition_msgs::ICPResult result = alignPointcloudWithReferences(non_nan_cloud, offset, msg->header);
00395     pub_icp_result.publish(result);
00396   }
00397   
00398   void ICPRegistration::align(const sensor_msgs::PointCloud2::ConstPtr& msg,
00399                               const sensor_msgs::PointCloud2::ConstPtr& reference_msg)
00400   {
00401     {
00402       boost::mutex::scoped_lock lock(mutex_);
00403       if (!done_init_) {
00404         NODELET_WARN("not yet initialized");
00405         return;
00406       }
00407       reference_cloud_list_.resize(0);
00408       pcl::PointCloud<PointT>::Ptr reference_cloud (new pcl::PointCloud<PointT>);
00409       pcl::fromROSMsg(*reference_msg, *reference_cloud);
00410       // remove nan
00411       pcl::PointCloud<PointT>::Ptr non_nan_reference_cloud (new pcl::PointCloud<PointT>);
00412       for (size_t i = 0; i < reference_cloud->points.size(); i++) {
00413         PointT p = reference_cloud->points[i];
00414         if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
00415           non_nan_reference_cloud->points.push_back(p);
00416         }
00417       }
00418       reference_cloud_list_.push_back(non_nan_reference_cloud);
00419     }
00420     align(msg);
00421   }
00422 
00423   jsk_recognition_msgs::ICPResult ICPRegistration::alignPointcloudWithReferences(
00424     pcl::PointCloud<PointT>::Ptr& cloud,
00425     const Eigen::Affine3f& offset,
00426     const std_msgs::Header& header)
00427   {
00428     jsk_recognition_utils::ScopedWallDurationReporter r
00429       = timer_.reporter(pub_latest_time_, pub_average_time_);
00430     double min_score = DBL_MAX;
00431     size_t max_index = 0;
00432     pcl::PointCloud<PointT>::Ptr best_transformed_cloud;
00433     pcl::PointCloud<PointT>::Ptr best_reference;
00434     Eigen::Affine3d best_transform_result;
00435     Eigen::Affine3f best_offset_result;
00436     jsk_recognition_msgs::ICPResult result;
00437     if (cloud->empty()) {
00438       sensor_msgs::PointCloud2 empty_cloud;
00439       empty_cloud.header = header;
00440       pub_result_cloud_.publish(empty_cloud);
00441 
00442       pcl::PointCloud<PointT> empty_pcl_cloud;
00443       publishDebugCloud(pub_debug_source_cloud_, empty_pcl_cloud);
00444       publishDebugCloud(pub_debug_target_cloud_, empty_pcl_cloud);
00445       publishDebugCloud(pub_debug_result_cloud_, empty_pcl_cloud);
00446 
00447       geometry_msgs::PoseStamped empty_pose;
00448       empty_pose.header = header;
00449       pub_result_pose_.publish(empty_pose);
00450 
00451       result.header = header;
00452       result.score = min_score;
00453       result.name = "nan";
00454       return result;
00455     }
00456     for (size_t i = 0; i < reference_cloud_list_.size(); i++) {
00457       Eigen::Affine3f offset_result;
00458       pcl::PointCloud<PointT>::Ptr transformed_cloud(new pcl::PointCloud<PointT>);
00459       Eigen::Affine3d transform_result;
00460       double score = scorePointcloudAlignment(
00461         cloud,
00462         reference_cloud_list_[i],
00463         offset,
00464         offset_result,
00465         transformed_cloud,
00466         transform_result);
00467       if (score < min_score) {
00468         max_index = i;
00469         min_score = score;
00470         best_transform_result = transform_result;
00471         best_transformed_cloud = transformed_cloud;
00472         best_reference = reference_cloud_list_[i];
00473         best_offset_result = offset_result;
00474       }
00475     }
00476     
00477     NODELET_INFO("best score is: %f", min_score);
00478     if (pub_result_cloud_.getNumSubscribers() > 0) {
00479       sensor_msgs::PointCloud2 ros_final;
00480       pcl::toROSMsg(*best_transformed_cloud, ros_final);
00481       ros_final.header = header;
00482       pub_result_cloud_.publish(ros_final);
00483     }
00484     geometry_msgs::PoseStamped ros_result_pose;
00485     ros_result_pose.header = header;
00486     tf::poseEigenToMsg(best_transform_result, ros_result_pose.pose);
00487     pub_result_pose_.publish(ros_result_pose);
00488     publishDebugCloud(pub_debug_source_cloud_, *best_reference);
00489     publishDebugCloud(pub_debug_target_cloud_, *cloud);
00490     pcl::PointCloud<PointT>::Ptr transformed_cloud_for_debug_result
00491       (new pcl::PointCloud<PointT>);
00492     pcl::transformPointCloud(
00493       *best_transformed_cloud, *transformed_cloud_for_debug_result,
00494       best_offset_result.inverse());
00495     publishDebugCloud(pub_debug_result_cloud_,
00496                       *transformed_cloud_for_debug_result);
00497     result.header = ros_result_pose.header;
00498     result.pose = ros_result_pose.pose;
00499     result.score = min_score;
00500     std::stringstream ss;
00501     ss << max_index;
00502     result.name = ss.str();
00503     return result;
00504   }
00505 
00506   void ICPRegistration::cameraInfoCallback(
00507     const sensor_msgs::CameraInfo::ConstPtr& msg)
00508   {
00509     boost::mutex::scoped_lock lock(mutex_);
00510     camera_info_msg_ = msg;
00511   }
00512 
00513   double ICPRegistration::alignPointcloud(
00514     pcl::PointCloud<PointT>::Ptr& cloud,
00515     pcl::PointCloud<PointT>::Ptr& reference,
00516     const Eigen::Affine3f& offset,
00517     pcl::PointCloud<PointT>::Ptr& output_cloud,
00518     Eigen::Affine3d& output_transform)
00519   {
00520     if (algorithm_ == 0 || algorithm_ == 1) {
00521       return alignPointcloudWithICP(cloud, reference, offset, output_cloud, output_transform);
00522     }
00523     else {
00524       return alignPointcloudWithNDT(cloud, reference, offset, output_cloud, output_transform);
00525     }
00526   }
00527 
00528   
00529   double ICPRegistration::alignPointcloudWithNDT(
00530     pcl::PointCloud<PointT>::Ptr& cloud,
00531     pcl::PointCloud<PointT>::Ptr& reference,
00532     const Eigen::Affine3f& offset,
00533     pcl::PointCloud<PointT>::Ptr& output_cloud,
00534     Eigen::Affine3d& output_transform)
00535   {
00536     pcl::NormalDistributionsTransform<PointT, PointT> ndt;
00537     if (reference->points.empty ()) {
00538       NODELET_ERROR("Input Reference Cloud is empty!");
00539       return DBL_MAX;
00540     }
00541     ndt.setInputSource(reference);
00542     if (cloud->points.empty ()) {
00543       NODELET_ERROR("Input Target Cloud is empty!");
00544       return DBL_MAX;
00545     }
00546     ndt.setInputTarget(cloud);
00547     pcl::PointCloud<PointT> final;
00548     ndt.align(final);
00549     pcl::transformPointCloud(final, *output_cloud, offset);
00550     Eigen::Matrix4f transformation = ndt.getFinalTransformation ();
00551     Eigen::Matrix4d transformation_d;
00552     jsk_recognition_utils::convertMatrix4<Eigen::Matrix4f, Eigen::Matrix4d>(
00553       transformation, transformation_d);
00554     Eigen::Affine3d offsetd;
00555     convertEigenAffine3(offset, offsetd);
00556     output_transform = offsetd * Eigen::Affine3d(transformation_d);
00557     return ndt.getFitnessScore();
00558   }
00559   
00560   double ICPRegistration::alignPointcloudWithICP(
00561     pcl::PointCloud<PointT>::Ptr& cloud,
00562     pcl::PointCloud<PointT>::Ptr& reference,
00563     const Eigen::Affine3f& offset,
00564     pcl::PointCloud<PointT>::Ptr& output_cloud,
00565     Eigen::Affine3d& output_transform)
00566   {
00567     pcl::IterativeClosestPoint<PointT, PointT> icp;
00568     if (use_normal_) {
00569       pcl::IterativeClosestPointWithNormals<PointT, PointT> icp_with_normal;
00570       icp = icp_with_normal;
00571     }
00572     // icp.setInputSource(cloud);
00573     // icp.setInputTarget(reference_cloud_);
00574     if (algorithm_ == 1) {
00575       pcl::GeneralizedIterativeClosestPoint<PointT, PointT> gicp;
00576       gicp.setRotationEpsilon(rotation_epsilon_);
00577       gicp.setCorrespondenceRandomness(correspondence_randomness_);
00578       gicp.setMaximumOptimizerIterations(maximum_optimizer_iterations_);
00579       icp = gicp;
00580     }
00581     if (correspondence_algorithm_ == 1) { // Projective
00582       if (!camera_info_msg_) {
00583         NODELET_ERROR("no camera info is available yet");
00584         return DBL_MAX;
00585       }
00586       image_geometry::PinholeCameraModel model;
00587       bool model_success_p = model.fromCameraInfo(camera_info_msg_);
00588       if (!model_success_p) {
00589         NODELET_ERROR("failed to create camera model");
00590         return DBL_MAX;
00591       }
00592       pcl::registration::CorrespondenceEstimationOrganizedProjection<PointT, PointT, float>::Ptr
00593         corr_projection (new pcl::registration::CorrespondenceEstimationOrganizedProjection<PointT, PointT, float>);
00594       corr_projection->setFocalLengths(model.fx(), model.fy());
00595       corr_projection->setCameraCenters(model.cx(), model.cy());
00596       icp.setCorrespondenceEstimation(corr_projection);
00597     }
00598     
00599     if (reference->points.empty ()) {
00600       NODELET_ERROR("Input Reference Cloud is empty!");
00601       return DBL_MAX;
00602     }
00603     icp.setInputSource(reference);
00604     if (cloud->points.empty ()) {
00605       NODELET_ERROR("Input Target Cloud is empty!");
00606       return DBL_MAX;
00607     }
00608     icp.setInputTarget(cloud);
00609     icp.setMaxCorrespondenceDistance (correspondence_distance_);
00610     icp.setMaximumIterations (max_iteration_);
00611     icp.setTransformationEpsilon (transform_epsilon_);
00612     icp.setEuclideanFitnessEpsilon (euclidean_fittness_epsilon_);
00613     icp.setRANSACIterations(ransac_iterations_);
00614     icp.setRANSACOutlierRejectionThreshold(ransac_outlier_threshold_);
00615     pcl::PointCloud<PointT> final;
00616     icp.align(final);
00617     pcl::transformPointCloud(final, *output_cloud, offset);
00618     // NODELET_INFO_STREAM("ICP converged: " << icp.hasConverged());
00619     // NODELET_INFO_STREAM("ICP score: " << icp.getFitnessScore());
00620     Eigen::Matrix4f transformation = icp.getFinalTransformation ();
00621     Eigen::Matrix4d transformation_d;
00622     jsk_recognition_utils::convertMatrix4<Eigen::Matrix4f, Eigen::Matrix4d>(
00623       transformation, transformation_d);
00624     Eigen::Affine3d offsetd;
00625     convertEigenAffine3(offset, offsetd);
00626     output_transform = offsetd * Eigen::Affine3d(transformation_d);
00627     return icp.getFitnessScore();
00628   }
00629 
00630   // compute ICP and return score
00631   double ICPRegistration::scorePointcloudAlignment(
00632     pcl::PointCloud<PointT>::Ptr& cloud,
00633     pcl::PointCloud<PointT>::Ptr& reference,
00634     const Eigen::Affine3f& offset,
00635     Eigen::Affine3f& offset_result,
00636     pcl::PointCloud<PointT>::Ptr transformed_cloud,
00637     Eigen::Affine3d& transform_result)
00638   {
00639     pcl::PointCloud<PointT>::Ptr transformed_cloud_for_debug_result
00640       (new pcl::PointCloud<PointT>);
00641     double score = alignPointcloud(cloud, reference, offset,
00642                                    transformed_cloud, transform_result);
00643     pcl::transformPointCloud(
00644       *transformed_cloud, *transformed_cloud_for_debug_result,
00645       offset.inverse());
00646     offset_result = offset;
00647     if (use_flipped_initial_pose_) {
00648       pcl::PointCloud<PointT>::Ptr flipped_transformed_cloud
00649         (new pcl::PointCloud<PointT>);
00650       Eigen::Affine3d flipped_transform_result;
00651       Eigen::Affine3f flipped_offset
00652       = offset * Eigen::AngleAxisf(M_PI, Eigen::Vector3f(0, 0, 1));
00653       pcl::PointCloud<PointT>::Ptr flipped_cloud (new pcl::PointCloud<PointT>);
00654       pcl::transformPointCloud(
00655         *cloud, *flipped_cloud,
00656         Eigen::Affine3f(Eigen::AngleAxisf(M_PI, Eigen::Vector3f(0, 0, 1))));
00657       double flipped_score
00658         = alignPointcloud(flipped_cloud, reference, flipped_offset,
00659                           flipped_transformed_cloud,
00660                           flipped_transform_result);
00661       NODELET_INFO("flipped score: %f", flipped_score);
00662       if (flipped_score < score) {
00663         score = flipped_score;
00664         transformed_cloud = flipped_transformed_cloud;
00665         transform_result = flipped_transform_result;
00666         pcl::transformPointCloud(
00667           *transformed_cloud, *transformed_cloud_for_debug_result,
00668           flipped_offset.inverse());
00669         offset_result = flipped_offset;
00670       }
00671     }
00672     return score;
00673   }
00674 
00675   void ICPRegistration::referenceCallback(
00676     const sensor_msgs::PointCloud2::ConstPtr& msg)
00677   {
00678     boost::mutex::scoped_lock lock(mutex_);
00679     if (!done_init_) {
00680       NODELET_WARN("not yet initialized");
00681       return;
00682     }
00683     reference_cloud_list_.resize(0);
00684     pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00685     pcl::fromROSMsg(*msg, *cloud);
00686     pcl::PointCloud<PointT>::Ptr non_nan_cloud (new pcl::PointCloud<PointT>);
00687     for (size_t i = 0; i < cloud->points.size(); i++) {
00688       PointT p = cloud->points[i];
00689       if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
00690         non_nan_cloud->points.push_back(p);
00691       }
00692     }
00693     reference_cloud_list_.push_back(non_nan_cloud);
00694   }
00695 
00696   void ICPRegistration::referenceArrayCallback(
00697     const jsk_recognition_msgs::PointsArray::ConstPtr& msg)
00698   {
00699     boost::mutex::scoped_lock lock(mutex_);
00700     if (!done_init_) {
00701       NODELET_WARN("not yet initialized");
00702       return;
00703     }
00704     reference_cloud_list_.resize(0);
00705     for (size_t i = 0; i < msg->cloud_list.size(); i++) {
00706       pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00707       pcl::fromROSMsg(msg->cloud_list[i], *cloud);
00708       reference_cloud_list_.push_back(cloud);
00709     }
00710   }
00711   
00712   void ICPRegistration::referenceAddCallback(
00713     const sensor_msgs::PointCloud2::ConstPtr& msg)
00714   {
00715     boost::mutex::scoped_lock lock(mutex_);
00716     if (!done_init_) {
00717       NODELET_WARN("not yet initialized");
00718       return;
00719     }
00720     //reference_cloud_list_.resize(0); //not 0
00721     pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00722     pcl::fromROSMsg(*msg, *cloud);
00723     reference_cloud_list_.push_back(cloud);
00724     ROS_INFO("reference_num: %zd", reference_cloud_list_.size()-1);
00725   }  
00726 }
00727 
00728 #include <pluginlib/class_list_macros.h>
00729 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::ICPRegistration, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:49