elch.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id$
00037  *
00038  */
00039 
00040 #include <pcl/io/pcd_io.h>
00041 #include <pcl/point_types.h>
00042 #include <pcl/common/transforms.h>
00043 #include <pcl/registration/icp.h>
00044 #include <pcl/registration/elch.h>
00045 
00046 #include <iostream>
00047 #include <string>
00048 
00049 #include <vector>
00050 
00051 typedef pcl::PointXYZ PointType;
00052 typedef pcl::PointCloud<PointType> Cloud;
00053 typedef Cloud::ConstPtr CloudConstPtr;
00054 typedef Cloud::Ptr CloudPtr;
00055 typedef std::pair<std::string, CloudPtr> CloudPair;
00056 typedef std::vector<CloudPair> CloudVector;
00057 
00058 bool
00059 loopDetection (int end, const CloudVector &clouds, double dist, int &first, int &last)
00060 {
00061   static double min_dist = -1;
00062   int state = 0;
00063 
00064   for (int i = end-1; i > 0; i--)
00065   {
00066     Eigen::Vector4f cstart, cend;
00067     //TODO use pose of scan
00068     pcl::compute3DCentroid (*(clouds[i].second), cstart);
00069     pcl::compute3DCentroid (*(clouds[end].second), cend);
00070     Eigen::Vector4f diff = cend - cstart;
00071 
00072     double norm = diff.norm ();
00073 
00074     //std::cout << "distance between " << i << " and " << end << " is " << norm << " state is " << state << std::endl;
00075 
00076     if (state == 0 && norm > dist)
00077     {
00078       state = 1;
00079       //std::cout << "state 1" << std::endl;
00080     }
00081     if (state > 0 && norm < dist)
00082     {
00083       state = 2;
00084       //std::cout << "loop detected between scan " << i << " (" << clouds[i].first << ") and scan " << end << " (" << clouds[end].first << ")" << std::endl;
00085       if (min_dist < 0 || norm < min_dist)
00086       {
00087         min_dist = norm;
00088         first = i;
00089         last = end;
00090       }
00091     }
00092   }
00093   //std::cout << "min_dist: " << min_dist << " state: " << state << " first: " << first << " end: " << end << std::endl;
00094   if (min_dist > 0 && (state < 2 || end == int (clouds.size ()) - 1)) //TODO
00095   {
00096     min_dist = -1;
00097     return true;
00098   }
00099   return false;
00100 }
00101 
00102 int
00103 main (int argc, char **argv)
00104 {
00105   pcl::registration::ELCH<PointType> elch;
00106   pcl::IterativeClosestPoint<PointType, PointType>::Ptr icp (new pcl::IterativeClosestPoint<PointType, PointType>);
00107   icp->setMaximumIterations (100);
00108   icp->setMaxCorrespondenceDistance (0.1);
00109   icp->setRANSACOutlierRejectionThreshold (0.1);
00110   elch.setReg (icp);
00111 
00112   CloudVector clouds;
00113   for (int i = 1; i < argc; i++)
00114   {
00115     CloudPtr pc (new Cloud);
00116     pcl::io::loadPCDFile (argv[i], *pc);
00117     clouds.push_back (CloudPair (argv[i], pc));
00118     std::cout << "loading file: " << argv[i] << " size: " << pc->size () << std::endl;
00119     elch.addPointCloud (clouds[i-1].second);
00120   }
00121 
00122   int first = 0, last = 0;
00123 
00124   for (size_t i = 0; i < clouds.size (); i++)
00125   {
00126 
00127     if (loopDetection (int (i), clouds, 3.0, first, last))
00128     {
00129       std::cout << "Loop between " << first << " (" << clouds[first].first << ") and " << last << " (" << clouds[last].first << ")" << std::endl;
00130       elch.setLoopStart (first);
00131       elch.setLoopEnd (last);
00132       elch.compute ();
00133     }
00134   }
00135 
00136   for (size_t i = 0; i < clouds.size (); i++)
00137   {
00138     std::string result_filename (clouds[i].first);
00139     result_filename = result_filename.substr (result_filename.rfind ("/") + 1);
00140     pcl::io::savePCDFileBinary (result_filename.c_str (), *(clouds[i].second));
00141     std::cout << "saving result to " << result_filename << std::endl;
00142   }
00143 
00144   return 0;
00145 }


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:14:49