registration_visualizer.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: registration_visualizer.hpp 2011-07-15 00:18:54Z georgeLisca $
00035  *
00036  */
00037 
00039 template<typename PointSource, typename PointTarget> void
00040   pcl::RegistrationVisualizer<PointSource, PointTarget>::startDisplay ()
00041   {
00042     // Create and start the rendering thread. This will open the display window.
00043     viewer_thread_ = boost::thread (&pcl::RegistrationVisualizer<PointSource, PointTarget>::runDisplay, this);
00044   }
00045 
00047 template<typename PointSource, typename PointTarget> void
00048   pcl::RegistrationVisualizer<PointSource, PointTarget>::stopDisplay ()
00049   {
00050     // Stop the rendering thread. This will kill the display window.
00051     viewer_thread_.~thread ();
00052   }
00053 
00055 template<typename PointSource, typename PointTarget> void
00056   pcl::RegistrationVisualizer<PointSource, PointTarget>::runDisplay ()
00057   {
00058     // Open 3D viewer
00059     viewer_
00060         = boost::shared_ptr<pcl::visualization::PCLVisualizer> (new pcl::visualization::PCLVisualizer ("3D Viewer"));
00061     viewer_->initCameraParameters ();
00062 
00063     // Create the handlers for the three point clouds buffers: cloud_source_, cloud_target_ and cloud_intermediate_
00064     pcl::visualization::PointCloudColorHandlerCustom<PointSource> cloud_source_handler_ (cloud_source_.makeShared (),
00065                                                                                          255, 0, 0);
00066     pcl::visualization::PointCloudColorHandlerCustom<PointTarget> cloud_target_handler_ (cloud_target_.makeShared (),
00067                                                                                          0, 0, 255);
00068     pcl::visualization::PointCloudColorHandlerCustom<PointSource> cloud_intermediate_handler_ (cloud_intermediate_.makeShared (),
00069                                                                                                255, 255, 0);
00070 
00071     // Create the view port for displaying initial source and target point clouds
00072     int v1 (0);
00073     viewer_->createViewPort (0.0, 0.0, 0.5, 1.0, v1);
00074     viewer_->setBackgroundColor (0, 0, 0, v1);
00075     viewer_->addText ("Initial position of source and target point clouds", 10, 50, "title v1", v1);
00076     viewer_->addText ("Blue -> target", 10, 30, 0.0, 0.0, 1.0, "legend target v1", v1);
00077     viewer_->addText ("Red  -> source", 10, 10, 1.0, 0.0, 0.0, "legend source v1", v1);
00078     //
00079     viewer_->addPointCloud<PointSource> (cloud_source_.makeShared (), cloud_source_handler_, "cloud source v1", v1);
00080     viewer_->addPointCloud<PointTarget> (cloud_target_.makeShared (), cloud_target_handler_, "cloud target v1", v1);
00081 
00082     // Create the view port for displaying the registration process of source to target point cloud
00083     int v2 (0);
00084     viewer_->createViewPort (0.5, 0.0, 1.0, 1.0, v2);
00085     viewer_->setBackgroundColor (0.1, 0.1, 0.1, v2);
00086     std::string registration_port_title_ = "Registration using "+registration_method_name_;
00087     viewer_->addText (registration_port_title_, 10, 90, "title v2", v2);
00088 
00089     viewer_->addText ("Yellow -> intermediate", 10, 50, 1.0, 1.0, 0.0, "legend intermediate v2", v2);
00090     viewer_->addText ("Blue   -> target", 10, 30, 0.0, 0.0, 1.0, "legend target v2", v2);
00091     viewer_->addText ("Red    -> source", 10, 10, 1.0, 0.0, 0.0, "legend source v2", v1);
00092 
00093 //    viewer_->addPointCloud<PointSource> (cloud_source_.makeShared (), cloud_source_handler_, "cloud source v2", v2);
00094     viewer_->addPointCloud<PointTarget> (cloud_target_.makeShared (), cloud_target_handler_, "cloud target v2", v2);
00095     viewer_->addPointCloud<PointSource> (cloud_intermediate_.makeShared (), cloud_intermediate_handler_,
00096                                          "cloud intermediate v2", v2);
00097 
00098     // Used to remove all old correspondences
00099     size_t  correspondeces_old_size = 0;
00100 
00101     // Add coordinate system to both ports
00102     viewer_->addCoordinateSystem (1.0);
00103 
00104     // The root name of correspondence lines
00105     std::string line_root_ = "line";
00106 
00107     // Visualization loop
00108     while (!viewer_->wasStopped ())
00109     {
00110       // Lock access to visualizer buffers
00111       visualizer_updating_mutex_.lock ();
00112 
00113       // Updating intermediate point cloud
00114       // Remove old point cloud
00115       viewer_->removePointCloud ("cloud intermediate v2", v2);
00116 
00117       // Add the new point cloud
00118       viewer_->addPointCloud<pcl::PointXYZ> (cloud_intermediate_.makeShared (), cloud_intermediate_handler_,
00119                                              "cloud intermediate v2", v2);
00120 
00121       // Updating the correspondece lines
00122 
00123       std::string line_name_;
00124       // Remove the old correspondeces
00125       for (size_t correspondence_id = 0; correspondence_id < correspondeces_old_size; ++correspondence_id)
00126       {
00127         // Generate the line name
00128         line_name_ = getIndexedName (line_root_, correspondence_id);
00129 
00130         // Remove the current line according to it's name
00131         viewer_->removeShape (line_name_, v2);
00132       }
00133 
00134       // Display the new correspondences lines
00135       size_t correspondences_new_size = cloud_intermediate_indices_.size ();
00136 
00137 
00138       std::stringstream stream_;
00139       stream_ << "Random -> correspondences " << correspondences_new_size;
00140       viewer_->removeShape ("correspondences_size", 0);
00141       viewer_->addText (stream_.str(), 10, 70, 0.0, 1.0, 0.0, "correspondences_size", v2);
00142 
00143       // Display entire set of correspondece lines if no maximum displayed correspondences is set
00144       if( ( 0 < maximum_displayed_correspondences_ ) &&
00145           (maximum_displayed_correspondences_ < correspondences_new_size) )
00146         correspondences_new_size = maximum_displayed_correspondences_;
00147 
00148       // Actualize correspondeces_old_size
00149       correspondeces_old_size = correspondences_new_size;
00150 
00151       // Update new correspondence lines
00152       for (size_t correspondence_id = 0; correspondence_id < correspondences_new_size; ++correspondence_id)
00153       {
00154         // Generate random color for current correspondence line
00155         double random_red   = 255 * rand () / (RAND_MAX + 1.0);
00156         double random_green = 255 * rand () / (RAND_MAX + 1.0);
00157         double random_blue  = 255 * rand () / (RAND_MAX + 1.0);
00158 
00159         // Generate the name for current line
00160         line_name_ = getIndexedName (line_root_, correspondence_id);
00161 
00162         // Add the new correspondence line.
00163         viewer_->addLine (cloud_intermediate_[cloud_intermediate_indices_[correspondence_id]],
00164                           cloud_target_[cloud_target_indices_[correspondence_id]],
00165                           random_red, random_green, random_blue,
00166                           line_name_, v2);
00167       }
00168 
00169       // Unlock access to visualizer buffers
00170       visualizer_updating_mutex_.unlock ();
00171 
00172       // Render visualizer updated buffers
00173       viewer_->spinOnce (100);
00174       boost::this_thread::sleep (boost::posix_time::microseconds (100000));
00175 
00176     }
00177   }
00178 
00180 template<typename PointSource, typename PointTarget> void
00181   pcl::RegistrationVisualizer<PointSource, PointTarget>::updateIntermediateCloud (
00182       const pcl::PointCloud<PointSource> &cloud_src,
00183       const std::vector<int> &indices_src,
00184       const pcl::PointCloud<PointTarget> &cloud_tgt,
00185       const std::vector<int> &indices_tgt)
00186   {
00187     // Lock local buffers
00188     visualizer_updating_mutex_.lock ();
00189 
00190     // Update source and target point clouds if this is the first callback
00191     // Here we are sure that source and target point clouds are initialized
00192     if (!first_update_flag_)
00193     {
00194       first_update_flag_ = true;
00195 
00196       this->cloud_source_ = cloud_src;
00197       this->cloud_target_ = cloud_tgt;
00198 
00199       this->cloud_intermediate_ = cloud_src;
00200     }
00201 
00202     // Copy the intermediate point cloud and it's associates indices
00203     cloud_intermediate_ = cloud_src;
00204     cloud_intermediate_indices_ = indices_src;
00205 
00206     // Copy the intermediate indices associate to the target point cloud
00207     cloud_target_indices_ = indices_tgt;
00208 
00209     // Unlock local buffers
00210     visualizer_updating_mutex_.unlock ();
00211   }


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:38