compute_overlap.cpp
Go to the documentation of this file.
00001 // kate: replace-tabs off; indent-width 4; indent-mode normal
00002 // vim: ts=4:sw=4:noexpandtab
00003 /*
00004 
00005 Copyright (c) 2010--2012,
00006 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
00007 You can contact the authors at <f dot pomerleau at gmail dot com> and
00008 <stephane at magnenat dot net>
00009 
00010 All rights reserved.
00011 
00012 Redistribution and use in source and binary forms, with or without
00013 modification, are permitted provided that the following conditions are met:
00014     * Redistributions of source code must retain the above copyright
00015       notice, this list of conditions and the following disclaimer.
00016     * Redistributions in binary form must reproduce the above copyright
00017       notice, this list of conditions and the following disclaimer in the
00018       documentation and/or other materials provided with the distribution.
00019     * Neither the name of the <organization> nor the
00020       names of its contributors may be used to endorse or promote products
00021       derived from this software without specific prior written permission.
00022 
00023 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00024 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00025 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00026 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
00027 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00028 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00030 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00031 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00032 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00033 
00034 */
00035 
00036 #include "pointmatcher/PointMatcher.h"
00037 #include "pointmatcher/IO.h"
00038 #include <cassert>
00039 #include <iostream>
00040 #include <iomanip>
00041 #include <fstream>
00042 #include <boost/format.hpp>
00043 #include <boost/filesystem/path.hpp>
00044 #include <boost/filesystem/operations.hpp>
00045 #include <boost/lexical_cast.hpp>
00046 
00047 using namespace std;
00048 using namespace PointMatcherSupport;
00049 
00050 void validateArgs(int argc, char *argv[]);
00051 void setupArgs(int argc, char *argv[], unsigned int& startId, unsigned int& endId, string& extension);
00052 
00057 int main(int argc, char *argv[])
00058 {
00059         validateArgs(argc, argv);
00060 
00061         typedef PointMatcher<float> PM;
00062         typedef PointMatcherIO<float> PMIO;
00063         typedef PM::Matrix Matrix;
00064         typedef PM::TransformationParameters TP;
00065         typedef PM::DataPoints DP;
00066         typedef PM::Matches Matches;
00067 
00068         // Process arguments
00069         PMIO::FileInfoVector list(argv[1]);
00070         bool debugMode = false;
00071         if (argc == 4)
00072                 debugMode = true;
00073         
00074         if(debugMode)
00075                 setLogger(PM::get().LoggerRegistrar.create("FileLogger"));
00076 
00077         // Prepare transformation chain for maps
00078         std::shared_ptr<PM::Transformation> rigidTransform;
00079         rigidTransform = PM::get().TransformationRegistrar.create("RigidTransformation");
00080         
00081         PM::Transformations transformations;
00082         transformations.push_back(rigidTransform);
00083 
00084         DP reading, reference;
00085         TP Tread = TP::Identity(4,4);
00086         DP mapCloud;
00087         TP Tref = TP::Identity(4,4);
00088 
00089         unsigned startingI = 0;
00090         unsigned listSizeI = list.size();
00091         unsigned listSizeJ = list.size();
00092         if(debugMode)
00093         {
00094                 startingI = boost::lexical_cast<unsigned>(argv[2]);
00095                 listSizeI = startingI + 1;
00096         }
00097 
00098         PM::Matrix overlapResults = PM::Matrix::Ones(listSizeJ, listSizeI);
00099 
00100         for(unsigned i = startingI; i < listSizeI; i++)
00101         {
00102                 unsigned startingJ = i+1;
00103                 if(debugMode)
00104                 {
00105                         startingJ = boost::lexical_cast<unsigned>(argv[3]);
00106                         listSizeJ = startingJ + 1;
00107                 }
00108                 for(unsigned j = startingJ; j < listSizeJ; j++)
00109                 {
00110                         // Load point clouds
00111                         reading = DP::load(list[i].readingFileName);
00112                         reference = DP::load(list[j].readingFileName);
00113 
00114                         cout << "Point cloud loaded" << endl;
00115 
00116                         // Load transformation matrices
00117                         if(list[i].groundTruthTransformation.rows() != 0)
00118                         {
00119                                 Tread = list[i].groundTruthTransformation;
00120                                 Tref = list[j].groundTruthTransformation;
00121                         }
00122                         else
00123                         {
00124                                 cout << "ERROR: fields gTXX (i.e., ground truth matrix) is required" << endl;
00125                                 abort();
00126                         }
00127 
00128                         // Move point cloud in global frame
00129                         transformations.apply(reading, Tread);
00130                         transformations.apply(reference, Tref);
00131 
00132                         // Preprare filters
00133                         std::shared_ptr<PM::DataPointsFilter> subSample =
00134                                 PM::get().DataPointsFilterRegistrar.create(
00135                                         "RandomSamplingDataPointsFilter", 
00136                                         {{"prob", "0.5"}}
00137                                 );
00138 
00139                         std::shared_ptr<PM::DataPointsFilter> maxDensity =
00140                                 PM::get().DataPointsFilterRegistrar.create(
00141                                         "MaxDensityDataPointsFilter"
00142                                 );
00143                         
00144                         /*std::shared_ptr<PM::DataPointsFilter> cutInHalf;
00145                         cutInHalf = PM::get().DataPointsFilterRegistrar.create(
00146                                 "MinDistDataPointsFilter", PM::Parameters({
00147                                         {"dim", "1"},
00148                                         {"minDist", "0"}
00149                                 }));*/
00150 
00151                         std::shared_ptr<PM::DataPointsFilter> computeDensity =
00152                                 PM::get().DataPointsFilterRegistrar.create(
00153                                         "SurfaceNormalDataPointsFilter",
00154                                         {
00155                                                 {"knn", "20"},
00156                                                 {"keepDensities", "1"}
00157                                         }
00158                                 );
00159 
00160                         reading = subSample->filter(reading);
00161                         reading = computeDensity->filter(reading);
00162                         reading = maxDensity->filter(reading);
00163                         //reading = cutInHalf->filter(reading);
00164                         const Matrix inliersRead = Matrix::Zero(1, reading.features.cols());
00165                         reading.addDescriptor("inliers", inliersRead);
00166 
00167                         reference = subSample->filter(reference);
00168                         reference = computeDensity->filter(reference);
00169                         reference = maxDensity->filter(reference);
00170                         const Matrix inliersRef = Matrix::Zero(1, reference.features.cols());
00171                         reference.addDescriptor("inliers", inliersRef);
00172 
00173                         //TODO: reverse self and target
00174                         DP self = reading;
00175                         DP target = reference;
00176 
00177                         for(int l = 0; l < 2; l++)
00178                         {
00179                                 const int selfPtsCount = self.features.cols();
00180                                 const int targetPtsCount = target.features.cols();
00181 
00182                                 // Build kd-tree
00183                                 int knn = 20;
00184                                 int knnAll = 50;
00185                                 std::shared_ptr<PM::Matcher> matcherSelf =
00186                                         PM::get().MatcherRegistrar.create(
00187                                                 "KDTreeMatcher",
00188                                                 {{"knn", toParam(knn)}}
00189                                         );
00190 
00191                                 std::shared_ptr<PM::Matcher> matcherTarget =
00192                                         PM::get().MatcherRegistrar.create(
00193                                                 "KDTreeVarDistMatcher",
00194                                                 {
00195                                                         {"knn", toParam(knnAll)},
00196                                                         {"maxDistField", "maxSearchDist"}
00197                                                 }
00198                                         );
00199 
00200                                 matcherSelf->init(self);
00201                                 matcherTarget->init(target);
00202 
00203                                 Matches selfMatches(knn, selfPtsCount);
00204                                 selfMatches = matcherSelf->findClosests(self);
00205 
00206                                 const Matrix maxSearchDist = selfMatches.dists.colwise().maxCoeff().cwiseSqrt();
00207                                 self.addDescriptor("maxSearchDist", maxSearchDist);
00208 
00209                                 Matches targetMatches(knnAll, targetPtsCount);
00210                                 targetMatches = matcherTarget->findClosests(self);
00211 
00212                                 BOOST_AUTO(inlierSelf, self.getDescriptorViewByName("inliers"));
00213                                 BOOST_AUTO(inlierTarget, target.getDescriptorViewByName("inliers"));
00214                                 for(int i = 0; i < selfPtsCount; i++)
00215                                 {
00216                                         for(int k = 0; k < knnAll; k++)
00217                                         {
00218                                                 if (targetMatches.dists(k, i) != Matches::InvalidDist)
00219                                                 {
00220                                                         inlierSelf(0,i) = 1.0;
00221                                                         inlierTarget(0,targetMatches.ids(k, i)) = 1.0;
00222                                                 }
00223                                         }
00224                                 }
00225                                 
00226                                 // Swap point clouds
00227                                 PM::swapDataPoints(self, target);
00228                         }
00229                         
00230                         const BOOST_AUTO(finalInlierSelf, self.getDescriptorViewByName("inliers"));
00231                         const BOOST_AUTO(finalInlierTarget, target.getDescriptorViewByName("inliers"));
00232                         const double selfRatio = (finalInlierSelf.array() > 0).count()/(double)finalInlierSelf.cols();
00233                         const double targetRatio = (finalInlierTarget.array() > 0).count()/(double)finalInlierTarget.cols();
00234                         
00235                         cout << i << " -> " << j << ": " << selfRatio << endl;
00236                         cout << j << " -> " << i << ": " << targetRatio << endl;
00237                         
00238                         if(debugMode)
00239                         {
00240                                 self.save("scan_i.vtk");
00241                                 target.save("scan_j.vtk");
00242                         }
00243                         else
00244                         {
00245                                 overlapResults(j,i) = selfRatio;
00246                                 overlapResults(i,j) = targetRatio;
00247                         }
00248                 }
00249         }
00250 
00251 
00252         // write results in a file
00253         std::fstream outFile;
00254         outFile.open("overlapResults.csv", fstream::out);
00255         for(int x=0; x < overlapResults.rows(); x++)
00256         {
00257                 for(int y=0; y < overlapResults.cols(); y++)
00258                 {
00259                         outFile << overlapResults(x, y) << ", ";
00260                 }
00261 
00262                 outFile << endl;
00263         }
00264 
00265         outFile.close();
00266 
00267         return 0;
00268 }
00269 
00270 void validateArgs(int argc, char *argv[])
00271 {
00272         if (!(argc == 2 || argc == 4))
00273         {
00274                 cerr << endl;
00275                 cerr << " ERROR in command line" << endl << endl; 
00276                 cerr << " Usage: " << argv[0] << " listOfFiles.csv <i j>" << endl;
00277                 cerr << " Note: 'i' and 'j' are optional arguments. If used, only compute the overlap for those 2 point cloud ids and dump VTK files for visual inspection." << endl;
00278                 cerr << endl;
00279                 cerr << " Example: " << endl;
00280                 cerr << "    $ " << argv[0] << " ../example/data/carCloudList.csv" << endl;
00281                 cerr << endl;
00282                 abort();
00283         }
00284 }
00285 
00286 
00287 


libpointmatcher
Author(s):
autogenerated on Thu Jun 20 2019 19:51:29