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_pcl_ros/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/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 
00049 namespace jsk_pcl_ros
00050 {
00051   void ICPRegistration::onInit()
00052   {
00053     pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
00054     ConnectionBasedNodelet::onInit();
00055     tf_listener_ = TfListenerSingleton::getInstance();
00057     // Dynamic Reconfigure
00059     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00060     dynamic_reconfigure::Server<Config>::CallbackType f =
00061       boost::bind(
00062         &ICPRegistration::configCallback, this, _1, _2);
00063     srv_->setCallback (f);
00064     pnh_->param("use_normal", use_normal_, false);
00065     pnh_->param("align_box", align_box_, false);
00066     pnh_->param("synchronize_reference", synchronize_reference_, false);
00068     // Publishers
00070     pub_result_pose_ = advertise<geometry_msgs::PoseStamped>(*pnh_,
00071       "output_pose", 1);
00072     pub_result_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
00073       "output", 1);
00074     pub_debug_source_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
00075       "debug/source", 1);
00076     pub_debug_target_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
00077       "debug/target", 1);
00078     pub_debug_flipped_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
00079       "debug/flipped", 1);
00080     pub_debug_result_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
00081       "debug/result", 1);
00082     pub_icp_result = advertise<jsk_recognition_msgs::ICPResult>(*pnh_,
00083       "icp_result", 1);
00084     srv_icp_align_with_box_ = pnh_->advertiseService("icp_service", &ICPRegistration::alignWithBoxService, this);
00085     srv_icp_align_ = pnh_->advertiseService(
00086       "icp_align", &ICPRegistration::alignService, this);
00087     if (!synchronize_reference_) {
00088       sub_reference_ = pnh_->subscribe("input_reference", 1,
00089                                        &ICPRegistration::referenceCallback,
00090                                        this);
00091       sub_reference_array_ = pnh_->subscribe("input_reference_array", 1,
00092                                            &ICPRegistration::referenceArrayCallback,
00093                                              this);
00094       sub_reference_add = pnh_->subscribe("input_reference_add", 1,
00095                                           &ICPRegistration::referenceAddCallback,
00096                                           this);
00097     }
00098   }
00099 
00100   void ICPRegistration::subscribe()
00101   {
00103     // Subscription
00105     sub_camera_info_ = pnh_->subscribe("input/camera_info", 1,
00106                                        &ICPRegistration::cameraInfoCallback,
00107                                        this);
00108     if (!synchronize_reference_) {
00109       if (align_box_) {
00110         sub_input_.subscribe(*pnh_, "input", 1);
00111         sub_box_.subscribe(*pnh_, "input_box", 1);
00112         sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00113         sync_->connectInput(sub_input_, sub_box_);
00114         sync_->registerCallback(boost::bind(
00115                                             &ICPRegistration::alignWithBox,
00116                                             this, _1, _2));
00117       }
00118       else {
00119         sub_ = pnh_->subscribe("input", 1,
00120                                &ICPRegistration::align,
00121                                this);
00122       }
00123     }
00124     else {
00125       sub_sync_input_.subscribe(*pnh_, "input", 1);
00126       sub_sync_reference_.subscribe(*pnh_, "reference", 1);
00127       sync_reference_ = boost::make_shared<message_filters::Synchronizer<ReferenceSyncPolicy> >(100);
00128       sync_reference_->connectInput(sub_sync_input_, sub_sync_reference_);
00129       sync_reference_->registerCallback(boost::bind(&ICPRegistration::align, this, _1, _2));
00130     }
00131   }
00132 
00133   void ICPRegistration::unsubscribe()
00134   {
00135     sub_camera_info_.shutdown();
00136     if (!synchronize_reference_) {
00137       if (align_box_) {
00138         sub_input_.unsubscribe();
00139         sub_box_.unsubscribe();
00140       }
00141       else {
00142         sub_.shutdown();
00143       }
00144     }
00145     else {
00146       sub_sync_input_.unsubscribe();
00147       sub_sync_reference_.unsubscribe();
00148     }
00149   }
00150   
00151   void ICPRegistration::publishDebugCloud(
00152       ros::Publisher& pub,
00153       const pcl::PointCloud<PointT>& cloud)
00154   {
00155     if (pub.getNumSubscribers() > 0) {
00156       sensor_msgs::PointCloud2 ros_cloud;
00157       pcl::toROSMsg(cloud, ros_cloud);
00158       ros_cloud.header.frame_id = "base_link";
00159       ros_cloud.header.stamp = ros::Time::now();
00160       pub.publish(ros_cloud);
00161     }
00162   }
00163   
00164   void ICPRegistration::configCallback(Config &config, uint32_t level)
00165   {
00166     boost::mutex::scoped_lock lock(mutex_);
00167     algorithm_ = config.algorithm;
00168     correspondence_algorithm_ = config.correspondence_algorithm;
00169     use_flipped_initial_pose_ = config.use_flipped_initial_pose;
00170     max_iteration_ = config.max_iteration;
00171     correspondence_distance_ = config.correspondence_distance;
00172     transform_epsilon_ = config.transform_epsilon;
00173     euclidean_fittness_epsilon_ = config.euclidean_fittness_epsilon;
00174     rotation_epsilon_ = config.rotation_epsilon;
00175     ransac_iterations_ = config.ransac_iterations;
00176     ransac_outlier_threshold_ = config.ransac_outlier_threshold;
00177     maximum_optimizer_iterations_ = config.maximum_optimizer_iterations;
00178     ndt_resolution_ = config.ndt_resolution;
00179     ndt_step_size_ = config.ndt_step_size;
00180     ndt_outlier_ratio_ = config.ndt_outlier_ratio;
00181   }
00182 
00183   bool ICPRegistration::alignWithBoxService(
00184     jsk_pcl_ros::ICPAlignWithBox::Request& req, 
00185     jsk_pcl_ros::ICPAlignWithBox::Response& res)
00186   {
00187      boost::mutex::scoped_lock lock(mutex_);
00188     if (reference_cloud_list_.size() == 0) {
00189       JSK_NODELET_FATAL("no reference is specified");
00190       return false;
00191     }
00192     try
00193     {
00194       Eigen::Affine3f offset;
00195       pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
00196       transformPointcloudInBoundingBox<PointT>(
00197         req.target_box, req.target_cloud,
00198         *output, offset,
00199         *tf_listener_);
00200       Eigen::Affine3f inversed_offset = offset.inverse();
00201       res.result = alignPointcloudWithReferences(output, inversed_offset, req.target_cloud.header);
00202     }
00203     catch (tf2::ConnectivityException &e)
00204     {
00205       JSK_NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00206       return false;
00207     }
00208     catch (tf2::InvalidArgumentException &e)
00209     {
00210       JSK_NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00211       return false;
00212     }
00213     return true;
00214   }
00215 
00216   bool ICPRegistration::alignService(
00217     jsk_pcl_ros::ICPAlign::Request& req, 
00218     jsk_pcl_ros::ICPAlign::Response& res)
00219   {
00220     boost::mutex::scoped_lock lock(mutex_);
00221     std::vector<pcl::PointCloud<PointT>::Ptr> tmp_reference_cloud_list
00222       = reference_cloud_list_;  // escape
00223     try
00224     {
00225       // first, update reference
00226       std::vector<pcl::PointCloud<PointT>::Ptr> new_references;
00227       pcl::PointCloud<PointT>::Ptr reference_cloud (new pcl::PointCloud<PointT>);
00228       pcl::fromROSMsg(req.reference_cloud, *reference_cloud);
00229       pcl::PointCloud<PointT>::Ptr non_nan_reference_cloud (new pcl::PointCloud<PointT>);
00230       for (size_t i = 0; i < reference_cloud->points.size(); i++) {
00231         PointT p = reference_cloud->points[i];
00232         if (!isnan(p.x) && !isnan(p.y) && !isnan(p.z)) {
00233           non_nan_reference_cloud->points.push_back(p);
00234         }
00235       }
00236       new_references.push_back(non_nan_reference_cloud);
00237       reference_cloud_list_ = new_references; // replace references
00238       JSK_NODELET_INFO("reference points: %lu/%lu",
00239                    non_nan_reference_cloud->points.size(),
00240                    reference_cloud->points.size());
00241       Eigen::Affine3f offset = Eigen::Affine3f::Identity();
00242       pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00243       pcl::fromROSMsg(req.target_cloud, *cloud);
00244       res.result = alignPointcloudWithReferences(cloud,
00245                                                  offset,
00246                                                  req.target_cloud.header);
00247     }
00248     catch (tf2::ConnectivityException &e)
00249     {
00250       JSK_NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00251       reference_cloud_list_ = tmp_reference_cloud_list;
00252       return false;
00253     }
00254     catch (tf2::InvalidArgumentException &e)
00255     {
00256       JSK_NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00257       reference_cloud_list_ = tmp_reference_cloud_list;
00258       return false;
00259     }
00260     reference_cloud_list_ = tmp_reference_cloud_list;
00261     return true;
00262   }
00263 
00264   
00265   void ICPRegistration::alignWithBox(
00266       const sensor_msgs::PointCloud2::ConstPtr& msg,
00267       const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
00268   {
00269     boost::mutex::scoped_lock lock(mutex_);
00270     if (reference_cloud_list_.size() == 0) {
00271       JSK_NODELET_FATAL("no reference is specified");
00272       jsk_recognition_msgs::ICPResult result;
00273       result.name = std::string("NONE");
00274       result.score = DBL_MAX;
00275       result.header = box_msg->header;
00276       result.pose = box_msg->pose;
00277       pub_icp_result.publish(result);
00278       return;
00279     }
00280     try
00281     {
00282       Eigen::Affine3f offset;
00283       pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
00284       transformPointcloudInBoundingBox<PointT>(
00285         *box_msg, *msg,
00286         *output, offset,
00287         *tf_listener_);
00288       Eigen::Affine3f inversed_offset = offset.inverse();
00289       jsk_recognition_msgs::ICPResult result = alignPointcloudWithReferences(output, inversed_offset, msg->header);
00290       pub_icp_result.publish(result);
00291     }
00292     catch (tf2::ConnectivityException &e)
00293     {
00294       JSK_NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00295     }
00296     catch (tf2::InvalidArgumentException &e)
00297     {
00298       JSK_NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00299     }
00300   }
00301 
00302   void ICPRegistration::align(const sensor_msgs::PointCloud2::ConstPtr& msg)
00303   {
00304     boost::mutex::scoped_lock lock(mutex_);
00305     if (reference_cloud_list_.size() == 0) {
00306       JSK_NODELET_FATAL("no reference is specified");
00307       return;
00308     }
00309     
00310     pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00311     pcl::fromROSMsg(*msg, *cloud);
00312     Eigen::Affine3f offset = Eigen::Affine3f::Identity();
00313     // remove nan
00314     pcl::PointCloud<PointT>::Ptr non_nan_cloud (new pcl::PointCloud<PointT>);
00315     for (size_t i = 0; i < cloud->points.size(); i++) {
00316       PointT p = cloud->points[i];
00317       if (!isnan(p.x) && !isnan(p.y) && !isnan(p.z)) {
00318         non_nan_cloud->points.push_back(p);
00319       }
00320     }
00321     jsk_recognition_msgs::ICPResult result = alignPointcloudWithReferences(non_nan_cloud, offset, msg->header);
00322     pub_icp_result.publish(result);
00323   }
00324   
00325   void ICPRegistration::align(const sensor_msgs::PointCloud2::ConstPtr& msg,
00326                               const sensor_msgs::PointCloud2::ConstPtr& reference_msg)
00327   {
00328     {
00329       boost::mutex::scoped_lock lock(mutex_);
00330       reference_cloud_list_.resize(0);
00331       pcl::PointCloud<PointT>::Ptr reference_cloud (new pcl::PointCloud<PointT>);
00332       pcl::fromROSMsg(*reference_msg, *reference_cloud);
00333       // remove nan
00334       pcl::PointCloud<PointT>::Ptr non_nan_reference_cloud (new pcl::PointCloud<PointT>);
00335       for (size_t i = 0; i < reference_cloud->points.size(); i++) {
00336         PointT p = reference_cloud->points[i];
00337         if (!isnan(p.x) && !isnan(p.y) && !isnan(p.z)) {
00338           non_nan_reference_cloud->points.push_back(p);
00339         }
00340       }
00341       reference_cloud_list_.push_back(non_nan_reference_cloud);
00342     }
00343     align(msg);
00344   }
00345 
00346   jsk_recognition_msgs::ICPResult ICPRegistration::alignPointcloudWithReferences(
00347     pcl::PointCloud<PointT>::Ptr& cloud,
00348     const Eigen::Affine3f& offset,
00349     const std_msgs::Header& header)
00350   {
00351     double min_score = DBL_MAX;
00352     size_t max_index = 0;
00353     pcl::PointCloud<PointT>::Ptr best_transformed_cloud;
00354     pcl::PointCloud<PointT>::Ptr best_reference;
00355     Eigen::Affine3d best_transform_result;
00356     Eigen::Affine3f best_offset_result;
00357     jsk_recognition_msgs::ICPResult result;
00358     for (size_t i = 0; i < reference_cloud_list_.size(); i++) {
00359       Eigen::Affine3f offset_result;
00360       pcl::PointCloud<PointT>::Ptr transformed_cloud(new pcl::PointCloud<PointT>);
00361       Eigen::Affine3d transform_result;
00362       double score = scorePointcloudAlignment(
00363         cloud,
00364         reference_cloud_list_[i],
00365         offset,
00366         offset_result,
00367         transformed_cloud,
00368         transform_result);
00369       if (score < min_score) {
00370         max_index = i;
00371         min_score = score;
00372         best_transform_result = transform_result;
00373         best_transformed_cloud = transformed_cloud;
00374         best_reference = reference_cloud_list_[i];
00375         best_offset_result = offset_result;
00376       }
00377     }
00378     
00379     JSK_NODELET_INFO("best score is: %f", min_score);
00380     if (pub_result_cloud_.getNumSubscribers() > 0) {
00381       sensor_msgs::PointCloud2 ros_final;
00382       pcl::toROSMsg(*best_transformed_cloud, ros_final);
00383       ros_final.header = header;
00384       pub_result_cloud_.publish(ros_final);
00385     }
00386     geometry_msgs::PoseStamped ros_result_pose;
00387     ros_result_pose.header = header;
00388     tf::poseEigenToMsg(best_transform_result, ros_result_pose.pose);
00389     pub_result_pose_.publish(ros_result_pose);
00390     publishDebugCloud(pub_debug_source_cloud_, *best_reference);
00391     publishDebugCloud(pub_debug_target_cloud_, *cloud);
00392     pcl::PointCloud<PointT>::Ptr transformed_cloud_for_debug_result
00393       (new pcl::PointCloud<PointT>);
00394     pcl::transformPointCloud(
00395       *best_transformed_cloud, *transformed_cloud_for_debug_result,
00396       best_offset_result.inverse());
00397     publishDebugCloud(pub_debug_result_cloud_,
00398                       *transformed_cloud_for_debug_result);
00399     result.header = ros_result_pose.header;
00400     result.pose = ros_result_pose.pose;
00401     result.score = min_score;
00402     std::stringstream ss;
00403     ss << max_index;
00404     result.name = ss.str();
00405     return result;
00406   }
00407 
00408   void ICPRegistration::cameraInfoCallback(
00409     const sensor_msgs::CameraInfo::ConstPtr& msg)
00410   {
00411     boost::mutex::scoped_lock lock(mutex_);
00412     camera_info_msg_ = msg;
00413   }
00414 
00415   double ICPRegistration::alignPointcloud(
00416     pcl::PointCloud<PointT>::Ptr& cloud,
00417     pcl::PointCloud<PointT>::Ptr& reference,
00418     const Eigen::Affine3f& offset,
00419     pcl::PointCloud<PointT>::Ptr& output_cloud,
00420     Eigen::Affine3d& output_transform)
00421   {
00422     if (algorithm_ == 0 || algorithm_ == 1) {
00423       return alignPointcloudWithICP(cloud, reference, offset, output_cloud, output_transform);
00424     }
00425     else {
00426       return alignPointcloudWithNDT(cloud, reference, offset, output_cloud, output_transform);
00427     }
00428   }
00429 
00430   
00431   double ICPRegistration::alignPointcloudWithNDT(
00432     pcl::PointCloud<PointT>::Ptr& cloud,
00433     pcl::PointCloud<PointT>::Ptr& reference,
00434     const Eigen::Affine3f& offset,
00435     pcl::PointCloud<PointT>::Ptr& output_cloud,
00436     Eigen::Affine3d& output_transform)
00437   {
00438     pcl::NormalDistributionsTransform<PointT, PointT> ndt;
00439     if (reference->points.empty ()) {
00440       JSK_NODELET_ERROR("Input Reference Cloud is empty!");
00441       return DBL_MAX;
00442     }
00443     ndt.setInputSource(reference);
00444     if (cloud->points.empty ()) {
00445       JSK_NODELET_ERROR("Input Target Cloud is empty!");
00446       return DBL_MAX;
00447     }
00448     ndt.setInputTarget(cloud);
00449     pcl::PointCloud<PointT> final;
00450     ndt.align(final);
00451     pcl::transformPointCloud(final, *output_cloud, offset);
00452     Eigen::Matrix4f transformation = ndt.getFinalTransformation ();
00453     Eigen::Matrix4d transformation_d;
00454     convertMatrix4<Eigen::Matrix4f, Eigen::Matrix4d>(
00455       transformation, transformation_d);
00456     Eigen::Affine3d offsetd;
00457     convertEigenAffine3(offset, offsetd);
00458     output_transform = offsetd * Eigen::Affine3d(transformation_d);
00459     return ndt.getFitnessScore();
00460   }
00461   
00462   double ICPRegistration::alignPointcloudWithICP(
00463     pcl::PointCloud<PointT>::Ptr& cloud,
00464     pcl::PointCloud<PointT>::Ptr& reference,
00465     const Eigen::Affine3f& offset,
00466     pcl::PointCloud<PointT>::Ptr& output_cloud,
00467     Eigen::Affine3d& output_transform)
00468   {
00469     pcl::IterativeClosestPoint<PointT, PointT> icp;
00470     if (use_normal_) {
00471       pcl::IterativeClosestPointWithNormals<PointT, PointT> icp_with_normal;
00472       icp = icp_with_normal;
00473     }
00474     // icp.setInputSource(cloud);
00475     // icp.setInputTarget(reference_cloud_);
00476     if (algorithm_ == 1) {
00477       pcl::GeneralizedIterativeClosestPoint<PointT, PointT> gicp;
00478       gicp.setRotationEpsilon(rotation_epsilon_);
00479       gicp.setCorrespondenceRandomness(correspondence_randomness_);
00480       gicp.setMaximumOptimizerIterations(maximum_optimizer_iterations_);
00481       icp = gicp;
00482     }
00483     if (correspondence_algorithm_ == 1) { // Projective
00484       if (!camera_info_msg_) {
00485         JSK_NODELET_ERROR("no camera info is available yet");
00486         return DBL_MAX;
00487       }
00488       image_geometry::PinholeCameraModel model;
00489       bool model_success_p = model.fromCameraInfo(camera_info_msg_);
00490       if (!model_success_p) {
00491         JSK_NODELET_ERROR("failed to create camera model");
00492         return DBL_MAX;
00493       }
00494       pcl::registration::CorrespondenceEstimationOrganizedProjection<PointT, PointT, float>::Ptr
00495         corr_projection (new pcl::registration::CorrespondenceEstimationOrganizedProjection<PointT, PointT, float>);
00496       corr_projection->setFocalLengths(model.fx(), model.fy());
00497       corr_projection->setCameraCenters(model.cx(), model.cy());
00498       icp.setCorrespondenceEstimation(corr_projection);
00499     }
00500     
00501     if (reference->points.empty ()) {
00502       JSK_NODELET_ERROR("Input Reference Cloud is empty!");
00503       return DBL_MAX;
00504     }
00505     icp.setInputSource(reference);
00506     if (cloud->points.empty ()) {
00507       JSK_NODELET_ERROR("Input Target Cloud is empty!");
00508       return DBL_MAX;
00509     }
00510     icp.setInputTarget(cloud);
00511     icp.setMaxCorrespondenceDistance (correspondence_distance_);
00512     icp.setMaximumIterations (max_iteration_);
00513     icp.setTransformationEpsilon (transform_epsilon_);
00514     icp.setEuclideanFitnessEpsilon (euclidean_fittness_epsilon_);
00515     icp.setRANSACIterations(ransac_iterations_);
00516     icp.setRANSACOutlierRejectionThreshold(ransac_outlier_threshold_);
00517     pcl::PointCloud<PointT> final;
00518     icp.align(final);
00519     pcl::transformPointCloud(final, *output_cloud, offset);
00520     // JSK_NODELET_INFO_STREAM("ICP converged: " << icp.hasConverged());
00521     // JSK_NODELET_INFO_STREAM("ICP score: " << icp.getFitnessScore());
00522     Eigen::Matrix4f transformation = icp.getFinalTransformation ();
00523     Eigen::Matrix4d transformation_d;
00524     convertMatrix4<Eigen::Matrix4f, Eigen::Matrix4d>(
00525       transformation, transformation_d);
00526     Eigen::Affine3d offsetd;
00527     convertEigenAffine3(offset, offsetd);
00528     output_transform = offsetd * Eigen::Affine3d(transformation_d);
00529     return icp.getFitnessScore();
00530   }
00531 
00532   // compute ICP and return score
00533   double ICPRegistration::scorePointcloudAlignment(
00534     pcl::PointCloud<PointT>::Ptr& cloud,
00535     pcl::PointCloud<PointT>::Ptr& reference,
00536     const Eigen::Affine3f& offset,
00537     Eigen::Affine3f& offset_result,
00538     pcl::PointCloud<PointT>::Ptr transformed_cloud,
00539     Eigen::Affine3d& transform_result)
00540   {
00541     pcl::PointCloud<PointT>::Ptr transformed_cloud_for_debug_result
00542       (new pcl::PointCloud<PointT>);
00543     double score = alignPointcloud(cloud, reference, offset,
00544                                    transformed_cloud, transform_result);
00545     pcl::transformPointCloud(
00546       *transformed_cloud, *transformed_cloud_for_debug_result,
00547       offset.inverse());
00548     offset_result = offset;
00549     if (use_flipped_initial_pose_) {
00550       pcl::PointCloud<PointT>::Ptr flipped_transformed_cloud
00551         (new pcl::PointCloud<PointT>);
00552       Eigen::Affine3d flipped_transform_result;
00553       Eigen::Affine3f flipped_offset
00554       = offset * Eigen::AngleAxisf(M_PI, Eigen::Vector3f(0, 0, 1));
00555       pcl::PointCloud<PointT>::Ptr flipped_cloud (new pcl::PointCloud<PointT>);
00556       pcl::transformPointCloud(
00557         *cloud, *flipped_cloud,
00558         Eigen::Affine3f(Eigen::AngleAxisf(M_PI, Eigen::Vector3f(0, 0, 1))));
00559       double flipped_score
00560         = alignPointcloud(flipped_cloud, reference, flipped_offset,
00561                           flipped_transformed_cloud,
00562                           flipped_transform_result);
00563       JSK_NODELET_INFO("flipped score: %f", flipped_score);
00564       if (flipped_score < score) {
00565         score = flipped_score;
00566         transformed_cloud = flipped_transformed_cloud;
00567         transform_result = flipped_transform_result;
00568         pcl::transformPointCloud(
00569           *transformed_cloud, *transformed_cloud_for_debug_result,
00570           flipped_offset.inverse());
00571         offset_result = flipped_offset;
00572       }
00573     }
00574     return score;
00575   }
00576 
00577   void ICPRegistration::referenceCallback(
00578     const sensor_msgs::PointCloud2::ConstPtr& msg)
00579   {
00580     boost::mutex::scoped_lock lock(mutex_);
00581     reference_cloud_list_.resize(0);
00582     pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00583     pcl::fromROSMsg(*msg, *cloud);
00584     pcl::PointCloud<PointT>::Ptr non_nan_cloud (new pcl::PointCloud<PointT>);
00585     for (size_t i = 0; i < cloud->points.size(); i++) {
00586       PointT p = cloud->points[i];
00587       if (!isnan(p.x) && !isnan(p.y) && !isnan(p.z)) {
00588         non_nan_cloud->points.push_back(p);
00589       }
00590     }
00591     reference_cloud_list_.push_back(non_nan_cloud);
00592   }
00593 
00594   void ICPRegistration::referenceArrayCallback(
00595     const jsk_recognition_msgs::PointsArray::ConstPtr& msg)
00596   {
00597     boost::mutex::scoped_lock lock(mutex_);
00598     reference_cloud_list_.resize(0);
00599     for (size_t i = 0; i < msg->cloud_list.size(); i++) {
00600       pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00601       pcl::fromROSMsg(msg->cloud_list[i], *cloud);
00602       reference_cloud_list_.push_back(cloud);
00603     }
00604   }
00605   
00606   void ICPRegistration::referenceAddCallback(
00607     const sensor_msgs::PointCloud2::ConstPtr& msg)
00608   {
00609     boost::mutex::scoped_lock lock(mutex_);
00610     //reference_cloud_list_.resize(0); //not 0
00611     pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00612     pcl::fromROSMsg(*msg, *cloud);
00613     reference_cloud_list_.push_back(cloud);
00614     JSK_ROS_INFO("reference_num: %zd", reference_cloud_list_.size()-1);
00615   }  
00616 }
00617 
00618 #include <pluginlib/class_list_macros.h>
00619 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::ICPRegistration, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:47