compute_overlap.cpp
Go to the documentation of this file.
1 // kate: replace-tabs off; indent-width 4; indent-mode normal
2 // vim: ts=4:sw=4:noexpandtab
3 /*
4 
5 Copyright (c) 2010--2012,
6 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
7 You can contact the authors at <f dot pomerleau at gmail dot com> and
8 <stephane at magnenat dot net>
9 
10 All rights reserved.
11 
12 Redistribution and use in source and binary forms, with or without
13 modification, are permitted provided that the following conditions are met:
14  * Redistributions of source code must retain the above copyright
15  notice, this list of conditions and the following disclaimer.
16  * Redistributions in binary form must reproduce the above copyright
17  notice, this list of conditions and the following disclaimer in the
18  documentation and/or other materials provided with the distribution.
19  * Neither the name of the <organization> nor the
20  names of its contributors may be used to endorse or promote products
21  derived from this software without specific prior written permission.
22 
23 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
24 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
25 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
26 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
27 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
28 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
30 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
31 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
32 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
33 
34 */
35 
37 #include "pointmatcher/IO.h"
38 #include <cassert>
39 #include <iostream>
40 #include <fstream>
41 #include <boost/lexical_cast.hpp>
42 
43 using namespace std;
44 using namespace PointMatcherSupport;
45 
46 void validateArgs(int argc, char *argv[]);
47 void setupArgs(int argc, char *argv[], unsigned int& startId, unsigned int& endId, string& extension);
48 
53 int main(int argc, char *argv[])
54 {
55  validateArgs(argc, argv);
56 
57  typedef PointMatcher<float> PM;
59  typedef PM::Matrix Matrix;
61  typedef PM::DataPoints DP;
62  typedef PM::Matches Matches;
63 
64  // Process arguments
65  PMIO::FileInfoVector list(argv[1]);
66  bool debugMode = false;
67  if (argc == 4)
68  debugMode = true;
69 
70  if(debugMode)
71  setLogger(PM::get().LoggerRegistrar.create("FileLogger"));
72 
73  // Prepare transformation chain for maps
74  std::shared_ptr<PM::Transformation> rigidTransform;
75  rigidTransform = PM::get().TransformationRegistrar.create("RigidTransformation");
76 
78  transformations.push_back(rigidTransform);
79 
81  TP Tread = TP::Identity(4,4);
82  DP mapCloud;
83  TP Tref = TP::Identity(4,4);
84 
85  unsigned startingI = 0;
86  unsigned listSizeI = list.size();
87  unsigned listSizeJ = list.size();
88  if(debugMode)
89  {
90  startingI = boost::lexical_cast<unsigned>(argv[2]);
91  listSizeI = startingI + 1;
92  }
93 
94  PM::Matrix overlapResults = PM::Matrix::Ones(listSizeJ, listSizeI);
95 
96  for(unsigned i = startingI; i < listSizeI; i++)
97  {
98  unsigned startingJ = i+1;
99  if(debugMode)
100  {
101  startingJ = boost::lexical_cast<unsigned>(argv[3]);
102  listSizeJ = startingJ + 1;
103  }
104  for(unsigned j = startingJ; j < listSizeJ; j++)
105  {
106  // Load point clouds
107  reading = DP::load(list[i].readingFileName);
108  reference = DP::load(list[j].readingFileName);
109 
110  cout << "Point cloud loaded" << endl;
111 
112  // Load transformation matrices
113  if(list[i].groundTruthTransformation.rows() != 0)
114  {
115  Tread = list[i].groundTruthTransformation;
116  Tref = list[j].groundTruthTransformation;
117  }
118  else
119  {
120  cout << "ERROR: fields gTXX (i.e., ground truth matrix) is required" << endl;
121  abort();
122  }
123 
124  // Move point cloud in global frame
125  transformations.apply(reading, Tread);
127 
128  // Preprare filters
129  std::shared_ptr<PM::DataPointsFilter> subSample =
130  PM::get().DataPointsFilterRegistrar.create(
131  "RandomSamplingDataPointsFilter",
132  {{"prob", "0.5"}}
133  );
134 
135  std::shared_ptr<PM::DataPointsFilter> maxDensity =
136  PM::get().DataPointsFilterRegistrar.create(
137  "MaxDensityDataPointsFilter"
138  );
139 
140  /*std::shared_ptr<PM::DataPointsFilter> cutInHalf;
141  cutInHalf = PM::get().DataPointsFilterRegistrar.create(
142  "MinDistDataPointsFilter", PM::Parameters({
143  {"dim", "1"},
144  {"minDist", "0"}
145  }));*/
146 
147  std::shared_ptr<PM::DataPointsFilter> computeDensity =
148  PM::get().DataPointsFilterRegistrar.create(
149  "SurfaceNormalDataPointsFilter",
150  {
151  {"knn", "20"},
152  {"keepDensities", "1"}
153  }
154  );
155 
156  reading = subSample->filter(reading);
157  reading = computeDensity->filter(reading);
158  reading = maxDensity->filter(reading);
159  //reading = cutInHalf->filter(reading);
160  const Matrix inliersRead = Matrix::Zero(1, reading.features.cols());
161  reading.addDescriptor("inliers", inliersRead);
162 
163  reference = subSample->filter(reference);
165  reference = maxDensity->filter(reference);
166  const Matrix inliersRef = Matrix::Zero(1, reference.features.cols());
167  reference.addDescriptor("inliers", inliersRef);
168 
169  //TODO: reverse self and target
170  DP self = reading;
171  DP target = reference;
172 
173  for(int l = 0; l < 2; l++)
174  {
175  const int selfPtsCount = self.features.cols();
176  const int targetPtsCount = target.features.cols();
177 
178  // Build kd-tree
179  int knn = 20;
180  int knnAll = 50;
181  std::shared_ptr<PM::Matcher> matcherSelf =
182  PM::get().MatcherRegistrar.create(
183  "KDTreeMatcher",
184  {{"knn", toParam(knn)}}
185  );
186 
187  std::shared_ptr<PM::Matcher> matcherTarget =
188  PM::get().MatcherRegistrar.create(
189  "KDTreeVarDistMatcher",
190  {
191  {"knn", toParam(knnAll)},
192  {"maxDistField", "maxSearchDist"}
193  }
194  );
195 
196  matcherSelf->init(self);
197  matcherTarget->init(target);
198 
199  Matches selfMatches(knn, selfPtsCount);
200  selfMatches = matcherSelf->findClosests(self);
201 
202  const Matrix maxSearchDist = selfMatches.dists.colwise().maxCoeff().cwiseSqrt();
203  self.addDescriptor("maxSearchDist", maxSearchDist);
204 
205  Matches targetMatches(knnAll, targetPtsCount);
206  targetMatches = matcherTarget->findClosests(self);
207 
208  BOOST_AUTO(inlierSelf, self.getDescriptorViewByName("inliers"));
209  BOOST_AUTO(inlierTarget, target.getDescriptorViewByName("inliers"));
210  for(int i = 0; i < selfPtsCount; i++)
211  {
212  for(int k = 0; k < knnAll; k++)
213  {
214  if (targetMatches.dists(k, i) != Matches::InvalidDist)
215  {
216  inlierSelf(0,i) = 1.0;
217  inlierTarget(0,targetMatches.ids(k, i)) = 1.0;
218  }
219  }
220  }
221 
222  // Swap point clouds
223  PM::swapDataPoints(self, target);
224  }
225 
226  const BOOST_AUTO(finalInlierSelf, self.getDescriptorViewByName("inliers"));
227  const BOOST_AUTO(finalInlierTarget, target.getDescriptorViewByName("inliers"));
228  const double selfRatio = (finalInlierSelf.array() > 0).count()/(double)finalInlierSelf.cols();
229  const double targetRatio = (finalInlierTarget.array() > 0).count()/(double)finalInlierTarget.cols();
230 
231  cout << i << " -> " << j << ": " << selfRatio << endl;
232  cout << j << " -> " << i << ": " << targetRatio << endl;
233 
234  if(debugMode)
235  {
236  self.save("scan_i.vtk");
237  target.save("scan_j.vtk");
238  }
239  else
240  {
241  overlapResults(j,i) = selfRatio;
242  overlapResults(i,j) = targetRatio;
243  }
244  }
245  }
246 
247 
248  // write results in a file
249  std::fstream outFile;
250  outFile.open("overlapResults.csv", fstream::out);
251  for(int x=0; x < overlapResults.rows(); x++)
252  {
253  for(int y=0; y < overlapResults.cols(); y++)
254  {
255  outFile << overlapResults(x, y) << ", ";
256  }
257 
258  outFile << endl;
259  }
260 
261  outFile.close();
262 
263  return 0;
264 }
265 
266 void validateArgs(int argc, char *argv[])
267 {
268  if (!(argc == 2 || argc == 4))
269  {
270  cerr << endl;
271  cerr << " ERROR in command line" << endl << endl;
272  cerr << " Usage: " << argv[0] << " listOfFiles.csv <i j>" << endl;
273  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;
274  cerr << endl;
275  cerr << " Example: " << endl;
276  cerr << " $ " << argv[0] << " ../example/data/carCloudList.csv" << endl;
277  cerr << endl;
278  abort();
279  }
280 }
281 
282 
283 
Transformations
PM::Transformations Transformations
Definition: pypoint_matcher_helper.h:21
PointMatcherIO
IO Functions and classes that are dependant on scalar type are defined in this templatized class.
Definition: IO.h:43
compute_overlap.reference
reference
Definition: compute_overlap.py:71
PointMatcherSupport::toParam
std::string toParam(const S &value)
Return the string value using lexical_cast.
Definition: Parametrizable.h:123
compute_overlap.transformations
transformations
Definition: compute_overlap.py:45
compute_overlap.knn
int knn
Definition: compute_overlap.py:128
Matches
PM::Matches Matches
Definition: pypoint_matcher_helper.h:19
DataPoints
PM::DataPoints DataPoints
Definition: pypoint_matcher_helper.h:16
Matrix
PM::Matrix Matrix
Definition: pypoint_matcher_helper.h:59
PointMatcher< float >
PointMatcherSupport::setLogger
void setLogger(std::shared_ptr< Logger > newLogger)
Set a new logger, protected by a mutex.
Definition: Logger.cpp:98
PointMatcher::DataPoints
A point cloud.
Definition: PointMatcher.h:207
x
x
PMIO
PointMatcherIO< float > PMIO
Definition: eval_solution.cpp:62
compute_overlap.Tref
Tref
Definition: compute_overlap.py:49
compute_overlap.target
target
Definition: compute_overlap.py:121
PointMatcher< float >::Matrix
Eigen::Matrix< float, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
Definition: PointMatcher.h:169
validateArgs
void validateArgs(int argc, char *argv[])
Definition: compute_overlap.cpp:266
PointMatcherSupport::Registrar::create
std::shared_ptr< Interface > create(const std::string &name, const Parametrizable::Parameters &params=Parametrizable::Parameters()) const
Create an instance.
Definition: Registrar.h:161
PointMatcherIO::FileInfoVector
A vector of file info, to be used in batch processing.
Definition: IO.h:245
PointMatcher< float >::swapDataPoints
static void swapDataPoints(DataPoints &a, DataPoints &b)
Exchange in place point clouds a and b, with no data copy.
Definition: pointmatcher/DataPoints.cpp:1023
setupArgs
void setupArgs(int argc, char *argv[], unsigned int &startId, unsigned int &endId, string &extension)
std
TP
PM::TransformationParameters TP
Definition: eval_solution.cpp:63
PointMatcherSupport::computeDensity
T computeDensity(const typename PointMatcher< T >::Matrix &NN)
Definition: utils.h:104
compute_overlap.Tread
Tread
Definition: compute_overlap.py:48
PointMatcher< float >::get
static const PointMatcher & get()
Return instances.
Definition: Registry.cpp:147
PointMatcherSupport
Functions and classes that are not dependant on scalar type are defined in this namespace.
Definition: Bibliography.cpp:45
DP
PM::DataPoints DP
Definition: convert.cpp:45
PM
PointMatcher< float > PM
Definition: eval_solution.cpp:61
main
int main(int argc, char *argv[])
Definition: compute_overlap.cpp:53
PointMatcher::DataPoints::load
static DataPoints load(const std::string &fileName)
Load a point cloud from a file, determine format from extension.
Definition: pointmatcher/IO.cpp:353
PointMatcher.h
public interface
IO.h
compute_overlap.reading
reading
Definition: compute_overlap.py:70
PointMatcherSupport::Registrar
A factor for subclasses of Interface.
Definition: Registrar.h:59
PointMatcher< float >::TransformationParameters
Matrix TransformationParameters
A matrix holding the parameters a transformation.
Definition: PointMatcher.h:182


libpointmatcher
Author(s):
autogenerated on Sun Dec 22 2024 03:21:52