incremental_model_registration_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
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 #define BOOST_PARAMETER_MAX_ARITY 7
00036 
00037 #include <sstream>
00038 #include "jsk_pcl_ros/incremental_model_registration.h"
00039 #include "jsk_pcl_ros/pcl_conversion_util.h"
00040 #include <pcl/common/transforms.h>
00041 #include <pcl/filters/extract_indices.h>
00042 #include <jsk_pcl_ros/ICPAlign.h>
00043 
00044 namespace jsk_pcl_ros
00045 {
00046   CapturedSamplePointCloud::CapturedSamplePointCloud()
00047   {
00048 
00049   }
00050 
00051   CapturedSamplePointCloud::CapturedSamplePointCloud(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
00052                          const Eigen::Affine3f& pose):
00053     original_cloud_(cloud), original_pose_(pose),
00054     refined_cloud_(new pcl::PointCloud<pcl::PointXYZRGB>)
00055   {
00056     
00057   }
00058 
00059   pcl::PointCloud<pcl::PointXYZRGB>::Ptr
00060   CapturedSamplePointCloud::getOriginalPointCloud()
00061   {
00062     return original_cloud_;
00063   }
00064 
00065   Eigen::Affine3f CapturedSamplePointCloud::getOriginalPose()
00066   {
00067     return original_pose_;
00068   }
00069 
00070   pcl::PointCloud<pcl::PointXYZRGB>::Ptr
00071   CapturedSamplePointCloud::getRefinedPointCloud()
00072   {
00073     return refined_cloud_;
00074   }
00075 
00076   Eigen::Affine3f CapturedSamplePointCloud::getRefinedPose()
00077   {
00078     return refined_pose_;
00079   }
00080 
00081   void CapturedSamplePointCloud::setRefinedPointCloud(
00082     pcl::PointCloud<pcl::PointXYZRGB> cloud)
00083   {
00084     *refined_cloud_ = cloud;   // copying
00085   }
00086 
00087   void CapturedSamplePointCloud::setRefinedPose(
00088     Eigen::Affine3f pose)
00089   {
00090     refined_pose_ = Eigen::Affine3f(pose);
00091   }
00092   
00093   void IncrementalModelRegistration::onInit()
00094   {
00095     DiagnosticNodelet::onInit();
00096     pnh_->param("frame_id", frame_id_,
00097                 std::string("multisense/left_camera_optical_frame"));
00098     start_registration_srv_
00099       = pnh_->advertiseService(
00100         "start_registration", &IncrementalModelRegistration::startRegistration,
00101         this);
00102     pub_cloud_non_registered_
00103       = pnh_->advertise<sensor_msgs::PointCloud2>("output/non_registered", 1);
00104     pub_registered_
00105       = pnh_->advertise<sensor_msgs::PointCloud2>("output/registered", 1);
00106     sub_cloud_.subscribe(*pnh_, "input", 1);
00107     sub_indices_.subscribe(*pnh_, "input/indices", 1);
00108     sub_pose_.subscribe(*pnh_, "input/pose", 1);
00109     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00110     sync_->connectInput(sub_cloud_, sub_indices_, sub_pose_);
00111     sync_->registerCallback(boost::bind(
00112                               &IncrementalModelRegistration::newsampleCallback,
00113                               this, _1, _2, _3));
00114   }
00115 
00116   void IncrementalModelRegistration::transformPointCloudRepsectedToPose(
00117     pcl::PointCloud<pcl::PointXYZRGB>::Ptr input,
00118     pcl::PointCloud<pcl::PointXYZRGB>::Ptr output,
00119     const geometry_msgs::PoseStamped::ConstPtr& pose_msg)
00120   {
00121     Eigen::Affine3f posef;
00122     tf::poseMsgToEigen(pose_msg->pose, posef);
00123     Eigen::Affine3f transform = posef.inverse();
00124     
00125     pcl::transformPointCloud<pcl::PointXYZRGB>(
00126       *input, *output, transform);
00127   }
00128   
00129   void IncrementalModelRegistration::newsampleCallback(
00130     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00131     const pcl_msgs::PointIndices::ConstPtr& indices_msg,
00132     const geometry_msgs::PoseStamped::ConstPtr& pose_msg)
00133   {
00134     boost::mutex::scoped_lock lock(mutex_);
00135     pcl::PointCloud<pcl::PointXYZRGB>::Ptr
00136       cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
00137     pcl::PointCloud<pcl::PointXYZRGB>::Ptr
00138       filtered_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
00139     pcl::fromROSMsg(*cloud_msg, *cloud);
00140     pcl::PointCloud<pcl::PointXYZRGB>::Ptr
00141       transformed_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
00142     pcl::PointIndices::Ptr
00143       indices (new pcl::PointIndices);
00144     indices->indices = indices_msg->indices;
00145     pcl::ExtractIndices<pcl::PointXYZRGB> ex;
00146     ex.setInputCloud(cloud);
00147     ex.setIndices(indices);
00148     ex.filter(*filtered_cloud);
00149     transformPointCloudRepsectedToPose(
00150       filtered_cloud, transformed_cloud, pose_msg);
00151     Eigen::Affine3f initial_pose;
00152     if (samples_.size() == 0) {
00153       // first pointcloud, it will be the `origin`
00154       tf::poseMsgToEigen(pose_msg->pose, origin_);
00155       initial_pose = origin_;
00156     }
00157     else {
00158       // compute transformation from origin_
00159       Eigen::Affine3f offset;
00160       tf::poseMsgToEigen(pose_msg->pose, offset);
00161       initial_pose = origin_.inverse() * offset;
00162     }
00163     CapturedSamplePointCloud::Ptr sample (new CapturedSamplePointCloud(transformed_cloud, initial_pose));
00164     samples_.push_back(sample);
00165     
00166     all_cloud_ = all_cloud_ + *transformed_cloud;
00167     sensor_msgs::PointCloud2 ros_all_cloud;
00168     pcl::toROSMsg(all_cloud_, ros_all_cloud);
00169     ros_all_cloud.header = cloud_msg->header;
00170     pub_cloud_non_registered_.publish(ros_all_cloud);
00171   }
00172 
00173   void IncrementalModelRegistration::callICP(
00174     pcl::PointCloud<pcl::PointXYZRGB>::Ptr reference,
00175     pcl::PointCloud<pcl::PointXYZRGB>::Ptr target,
00176     Eigen::Affine3f& output_transform)
00177   {
00178     ros::ServiceClient icp
00179       = pnh_->serviceClient<jsk_pcl_ros::ICPAlign>("icp_service");
00180     sensor_msgs::PointCloud2 reference_ros, target_ros;
00181     pcl::toROSMsg(*reference, reference_ros);
00182     pcl::toROSMsg(*target, target_ros);
00183     ros::Time now = ros::Time::now();
00184     reference_ros.header.stamp = target_ros.header.stamp = now;
00185     reference_ros.header.frame_id = target_ros.header.frame_id = "map";
00186     ICPAlign srv;
00187     srv.request.reference_cloud = reference_ros;
00188     srv.request.target_cloud = target_ros;
00189     icp.call(srv);
00190     tf::poseMsgToEigen(srv.response.result.pose,
00191                             output_transform);
00192   }
00193   
00194   bool IncrementalModelRegistration::startRegistration(
00195     std_srvs::Empty::Request& req,
00196     std_srvs::Empty::Response& res)
00197   {
00198     if (samples_.size() <= 1) {
00199       JSK_ROS_ERROR("no enough samples");
00200       return false;
00201     }
00202     JSK_ROS_INFO("Starting registration %lu samples", samples_.size());
00203     // setup initial
00204     CapturedSamplePointCloud::Ptr initial_sample = samples_[0];
00205     initial_sample->setRefinedPointCloud(
00206       *(initial_sample->getOriginalPointCloud()));
00207     initial_sample->setRefinedPose(initial_sample->getOriginalPose());
00208     for (size_t i = 0; i < samples_.size() - 1; i++) {
00209       CapturedSamplePointCloud::Ptr from_sample = samples_[i];
00210       CapturedSamplePointCloud::Ptr to_sample = samples_[i+1];
00211       pcl::PointCloud<pcl::PointXYZRGB>::Ptr reference_cloud
00212         = from_sample->getRefinedPointCloud();
00213       pcl::PointCloud<pcl::PointXYZRGB>::Ptr target_cloud
00214         = to_sample->getOriginalPointCloud();
00215       Eigen::Affine3f transform;
00216       callICP(reference_cloud, target_cloud, transform);
00217       to_sample->setRefinedPose(to_sample->getOriginalPose() * transform);
00218       // transform pointcloud
00219       pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_cloud
00220         (new pcl::PointCloud<pcl::PointXYZRGB>);
00221       pcl::transformPointCloud<pcl::PointXYZRGB>(
00222         *target_cloud, *transformed_cloud, transform);
00223       to_sample->setRefinedPointCloud(*transformed_cloud);
00224     }
00225     pcl::PointCloud<pcl::PointXYZRGB>::Ptr registered_cloud
00226       (new pcl::PointCloud<pcl::PointXYZRGB>);
00227     pcl::PointCloud<pcl::PointXYZRGB>::Ptr non_registered_cloud
00228       (new pcl::PointCloud<pcl::PointXYZRGB>);
00229     for (size_t i = 0; i < samples_.size(); i++) {
00230       *registered_cloud = *(samples_[i]->getRefinedPointCloud()) + *registered_cloud;
00231       *non_registered_cloud = *(samples_[i]->getOriginalPointCloud()) + *non_registered_cloud;
00232     }
00233     sensor_msgs::PointCloud2 registered_ros_cloud, nonregistered_ros_cloud;
00234     pcl::toROSMsg(*registered_cloud, registered_ros_cloud);
00235     registered_ros_cloud.header.stamp = ros::Time::now();
00236     registered_ros_cloud.header.frame_id = frame_id_;
00237     pub_registered_.publish(registered_ros_cloud);
00238     pcl::toROSMsg(*non_registered_cloud, nonregistered_ros_cloud);
00239     nonregistered_ros_cloud.header.stamp = ros::Time::now();
00240     nonregistered_ros_cloud.header.frame_id = frame_id_;
00241     pub_cloud_non_registered_.publish(nonregistered_ros_cloud);
00242   }
00243   
00244 }
00245 
00246 #include <pluginlib/class_list_macros.h>
00247 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::IncrementalModelRegistration, nodelet::Nodelet);


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