00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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
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
00078 PM::Transformation* transformPoints;
00079 transformPoints = PM::get().TransformationRegistrar.create("TransformFeatures");
00080
00081 PM::Transformation* transformNormals;
00082 transformNormals = PM::get().TransformationRegistrar.create("TransformNormals");
00083
00084 PM::Transformations transformations;
00085 transformations.push_back(transformPoints);
00086 transformations.push_back(transformNormals);
00087
00088 DP reading, reference;
00089 TP Tread = TP::Identity(4,4);
00090 DP mapCloud;
00091 TP Tref = TP::Identity(4,4);
00092
00093
00094
00095
00096
00097 unsigned startingI = 0;
00098
00099
00100 unsigned listSizeI = 3;
00101 unsigned listSizeJ = 3;
00102 if(debugMode)
00103 {
00104 startingI = boost::lexical_cast<unsigned>(argv[2]);
00105 listSizeI = startingI + 1;
00106 }
00107
00108 PM::Matrix overlapResults = PM::Matrix::Ones(listSizeJ, listSizeI);
00109
00110 for(unsigned i = startingI; i < listSizeI; i++)
00111 {
00112 unsigned startingJ = i+1;
00113 if(debugMode)
00114 {
00115 startingJ = boost::lexical_cast<unsigned>(argv[3]);
00116 listSizeJ = startingJ + 1;
00117 }
00118 for(unsigned j = startingJ; j < listSizeJ; j++)
00119 {
00120
00121 reading = DP::load(list[i].readingFileName);
00122 reference = DP::load(list[j].readingFileName);
00123
00124 cout << "Point cloud loaded" << endl;
00125
00126
00127 if(list[i].groundTruthTransformation.rows() != 0)
00128 {
00129 Tread = list[i].groundTruthTransformation;
00130 Tref = list[j].groundTruthTransformation;
00131 }
00132 else
00133 {
00134 cout << "ERROR: fields gTXX (ground truth) is required" << endl;
00135 abort();
00136 }
00137
00138
00139 transformations.apply(reading, Tread);
00140 transformations.apply(reference, Tref);
00141
00142
00143 PM::DataPointsFilter* subSample(
00144 PM::get().DataPointsFilterRegistrar.create(
00145 "RandomSamplingDataPointsFilter",
00146 map_list_of
00147 ("prob", "0.5")
00148 )
00149 );
00150
00151 PM::DataPointsFilter* maxDensity(
00152 PM::get().DataPointsFilterRegistrar.create(
00153 "MaxDensityDataPointsFilter"
00154 )
00155 );
00156
00157
00158
00159
00160
00161
00162
00163
00164 PM::DataPointsFilter* computeDensity(
00165 PM::get().DataPointsFilterRegistrar.create(
00166 "SurfaceNormalDataPointsFilter",
00167 map_list_of
00168 ("knn", "20")
00169 ("keepDensities", "1")
00170 )
00171 );
00172
00173 reading = subSample->filter(reading);
00174 reading = computeDensity->filter(reading);
00175 reading = maxDensity->filter(reading);
00176
00177 const Matrix inliersRead = Matrix::Zero(1, reading.features.cols());
00178 reading.addDescriptor("inliers", inliersRead);
00179
00180 reference = subSample->filter(reference);
00181 reference = computeDensity->filter(reference);
00182 reference = maxDensity->filter(reference);
00183 const Matrix inliersRef = Matrix::Zero(1, reference.features.cols());
00184 reference.addDescriptor("inliers", inliersRef);
00185
00186
00187 DP self = reading;
00188 DP target = reference;
00189
00190 for(int l = 0; l < 2; l++)
00191 {
00192 const int selfPtsCount = self.features.cols();
00193 const int targetPtsCount = target.features.cols();
00194
00195
00196 int knn = 20;
00197 int knnAll = 50;
00198 PM::Matcher* matcherSelf(
00199 PM::get().MatcherRegistrar.create(
00200 "KDTreeMatcher",
00201 map_list_of
00202 ("knn", toParam(knn))
00203 )
00204 );
00205
00206 PM::Matcher* matcherTarget(
00207 PM::get().MatcherRegistrar.create(
00208 "KDTreeVarDistMatcher",
00209 map_list_of
00210 ("knn", toParam(knnAll))
00211 ("maxDistField", "maxSearchDist")
00212 )
00213 );
00214
00215 matcherSelf->init(self);
00216 matcherTarget->init(target);
00217
00218 Matches selfMatches(knn, selfPtsCount);
00219 selfMatches = matcherSelf->findClosests(self);
00220
00221 const Matrix maxSearchDist = selfMatches.dists.colwise().maxCoeff().cwiseSqrt();
00222 self.addDescriptor("maxSearchDist", maxSearchDist);
00223
00224 Matches targetMatches(knnAll, targetPtsCount);
00225 targetMatches = matcherTarget->findClosests(self);
00226
00227 BOOST_AUTO(inlierSelf, self.getDescriptorViewByName("inliers"));
00228 BOOST_AUTO(inlierTarget, target.getDescriptorViewByName("inliers"));
00229 for(int i = 0; i < selfPtsCount; i++)
00230 {
00231 for(int k = 0; k < knnAll; k++)
00232 {
00233 if (targetMatches.dists(k, i) != numeric_limits<float>::infinity())
00234 {
00235 inlierSelf(0,i) = 1.0;
00236 inlierTarget(0,targetMatches.ids(k, i)) = 1.0;
00237 }
00238 }
00239 }
00240
00241
00242 PM::swapDataPoints(self, target);
00243 }
00244
00245 const BOOST_AUTO(finalInlierSelf, self.getDescriptorViewByName("inliers"));
00246 const BOOST_AUTO(finalInlierTarget, target.getDescriptorViewByName("inliers"));
00247 const double selfRatio = (finalInlierSelf.array() > 0).count()/(double)finalInlierSelf.cols();
00248 const double targetRatio = (finalInlierTarget.array() > 0).count()/(double)finalInlierTarget.cols();
00249
00250 cout << i << " -> " << j << ": " << selfRatio << endl;
00251 cout << j << " -> " << i << ": " << targetRatio << endl;
00252
00253 if(debugMode)
00254 {
00255 self.save("scan_i.vtk");
00256 target.save("scan_j.vtk");
00257 }
00258 else
00259 {
00260 overlapResults(j,i) = selfRatio;
00261 overlapResults(i,j) = targetRatio;
00262 }
00263 }
00264 }
00265
00266
00267
00268 std::fstream outFile;
00269 outFile.open("overlapResults.csv", fstream::out);
00270 for(int x=0; x < overlapResults.rows(); x++)
00271 {
00272 for(int y=0; y < overlapResults.cols(); y++)
00273 {
00274 outFile << overlapResults(x, y) << ", ";
00275 }
00276
00277 outFile << endl;
00278 }
00279
00280 outFile.close();
00281
00282 return 0;
00283 }
00284
00285 void validateArgs(int argc, char *argv[])
00286 {
00287 if (!(argc == 2 || argc == 4))
00288 {
00289 cerr << "\nError in command line, usage " << argv[0] << " listOfFiles.csv <i j>" << endl;
00290 cerr << "\ni 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;
00291 abort();
00292 }
00293 }
00294
00295
00296