build_map.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 <filesystem>
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 vector<string> loadYamlFile(string listFileName);
49 
57 int main(int argc, char *argv[])
58 {
59  validateArgs(argc, argv);
60 
61  typedef PointMatcher<float> PM;
64  typedef PM::DataPoints DP;
65 
66  // Process arguments
67  PMIO::FileInfoVector list(argv[1]);
68  const unsigned totalPointCount = boost::lexical_cast<unsigned>(argv[2]);
69  string outputFileName(argv[3]);
70 
71 
72  setLogger(PM::get().LoggerRegistrar.create("FileLogger"));
73 
74  PM::DataPoints mapCloud;
75 
76  PM::DataPoints lastCloud, newCloud;
77  TP T = TP::Identity(4,4);
78 
79  // Define transformation chain
80  std::shared_ptr<PM::Transformation> transformation;
81  transformation = PM::get().REG(Transformation).create("RigidTransformation");
82 
83  // This filter will remove a sphere of 1 m radius. Easy way to remove the sensor self-scanning.
84  std::shared_ptr<PM::DataPointsFilter> removeScanner =
85  PM::get().DataPointsFilterRegistrar.create(
86  "MinDistDataPointsFilter",
87  {{"minDist", "1.0"}}
88  );
89 
90  // This filter will randomly remove 35% of the points.
91  std::shared_ptr<PM::DataPointsFilter> randSubsample =
92  PM::get().DataPointsFilterRegistrar.create(
93  "RandomSamplingDataPointsFilter",
94  {{"prob", toParam(0.65)}}
95  );
96 
97  // For a complete description of filter, see
98  // https://github.com/norlab-ulaval/libpointmatcher/blob/master/doc/Datafilters.md
99  std::shared_ptr<PM::DataPointsFilter> normalFilter =
100  PM::get().DataPointsFilterRegistrar.create(
101  "SurfaceNormalDataPointsFilter",
102  {
103  {"knn", toParam(10)},
104  {"epsilon", toParam(5)},
105  {"keepNormals",toParam(1)},
106  {"keepDensities",toParam(0)}
107  }
108  );
109 
110  std::shared_ptr<PM::DataPointsFilter> densityFilter =
111  PM::get().DataPointsFilterRegistrar.create(
112  "SurfaceNormalDataPointsFilter",
113  {
114  {"knn", "10"},
115  {"epsilon", "5"},
116  {"keepDensities","1"},
117  {"keepNormals","0"}
118  }
119  );
120 
121  std::shared_ptr<PM::DataPointsFilter> observationDirectionFilter =
122  PM::get().DataPointsFilterRegistrar.create(
123  "ObservationDirectionDataPointsFilter"
124  );
125 
126  std::shared_ptr<PM::DataPointsFilter> orientNormalFilter =
127  PM::get().DataPointsFilterRegistrar.create(
128  "OrientNormalsDataPointsFilter",
129  {{"towardCenter", "1"}}
130  );
131 
132  std::shared_ptr<PM::DataPointsFilter> uniformSubsample =
133  PM::get().DataPointsFilterRegistrar.create(
134  "MaxDensityDataPointsFilter",
135  {{"maxDensity", toParam(30)}}
136  );
137 
138  std::shared_ptr<PM::DataPointsFilter> shadowFilter =
139  PM::get().DataPointsFilterRegistrar.create(
140  "ShadowDataPointsFilter"
141  );
142 
143  for(unsigned i=0; i < list.size(); i++)
144  {
145  cout << endl << "-----------------------------" << endl;
146  cout << "Loading " << list[i].readingFileName;
147  newCloud = DP::load(list[i].readingFileName);
148 
149  cout << " found " << newCloud.getNbPoints() << " points. " << endl;
150 
151 
152  if(list[i].groundTruthTransformation.rows() != 0)
153  T = list[i].groundTruthTransformation;
154  else
155  {
156  cout << "ERROR: the field gTXX (ground truth) is required" << endl;
157  abort();
158  }
159 
161 
162  // Remove the scanner
163  newCloud = removeScanner->filter(newCloud);
164 
165 
166  // Accelerate the process and dissolve lines
167  newCloud = randSubsample->filter(newCloud);
168 
169  // Build filter to remove shadow points and down-sample
170  newCloud = normalFilter->filter(newCloud);
171  newCloud = observationDirectionFilter->filter(newCloud);
172  newCloud = orientNormalFilter->filter(newCloud);
173  newCloud = shadowFilter->filter(newCloud);
174 
175  // Transforme pointCloud
176  cout << "Transformation matrix: " << endl << T << endl;
177  newCloud = transformation->compute(newCloud, T);
178 
179  if(i==0)
180  {
181  mapCloud = newCloud;
182  }
183  else
184  {
185  mapCloud.concatenate(newCloud);
186 
187  // Control point cloud size
188  double probToKeep = totalPointCount/(double)mapCloud.features.cols();
189  if(probToKeep < 1)
190  {
191 
192  mapCloud = densityFilter->filter(mapCloud);
193  mapCloud = uniformSubsample->filter(mapCloud);
194 
195  probToKeep = totalPointCount/(double)mapCloud.features.cols();
196 
197  if(probToKeep < 1)
198  {
199  cout << "Randomly keep " << probToKeep*100 << "\% points" << endl;
200  randSubsample = PM::get().DataPointsFilterRegistrar.create(
201  "RandomSamplingDataPointsFilter",
202  {{"prob", toParam(probToKeep)}}
203  );
204  mapCloud = randSubsample->filter(mapCloud);
205  }
206  }
207  }
208 
209  stringstream outputFileNameIter;
210  outputFileNameIter << std::filesystem::path(outputFileName).stem().c_str() << "_" << i << ".vtk";
211 
212  mapCloud.save(outputFileNameIter.str());
213  }
214 
215  mapCloud = densityFilter->filter(mapCloud);
216  mapCloud = uniformSubsample->filter(mapCloud);
217 
218  mapCloud = densityFilter->filter(mapCloud);
219 
220  cout << endl ;
221  cout << "-----------------------------" << endl;
222  cout << "-----------------------------" << endl;
223  cout << "Final number of points in the map: " << mapCloud.getNbPoints() << endl;
224  mapCloud.save(outputFileName);
225  cout << endl ;
226 
227  return 0;
228 }
229 
230 void validateArgs(int argc, char *argv[])
231 {
232  if (!(argc == 4))
233  {
234  cerr << endl;
235  cerr << "Error in command line, usage " << argv[0] << " listOfFiles.csv maxPoint outputFileName.{vtk,csv,ply}" << endl;
236  cerr << endl;
237  cerr << " example using file from example/data: " << endl;
238  cerr << " " << argv[0] << " carCloudList.csv 30000 test.vtk" << endl;
239  cerr << endl;
240  cerr << "Note: the file listOfFiles.csv need to include a serialize transformation matrix. For example:" << endl;
241  cerr << " fileName1.vtk, T00, T01, T02, T03, T10, T11, T12, T13, T20, T21, T22, T23, T30, T31, T32" << endl;
242  cerr << endl;
243  cerr << "Where Txy would be a 4x4 transformation matrix:" << endl;
244  cerr << " [T00 T01 T02 T03] " << endl;
245  cerr << " [T10 T11 T12 T13] " << endl;
246  cerr << " [T20 T21 T22 T23] " << endl;
247  cerr << " [T30 T31 T32 T33] (i.e., 0,0,0,1)" << endl;
248  cerr << endl;
249  cerr << "For more data visit:" << endl;
250  cerr << " http://projects.asl.ethz.ch/datasets/doku.php?id=laserregistration:laserregistration" << endl;
251  cerr << endl;
252 
253  abort();
254  }
255 }
256 
257 
258 
PointMatcherIO
IO Functions and classes that are dependant on scalar type are defined in this templatized class.
Definition: IO.h:43
PointMatcher< float >::Parameters
Parametrizable::Parameters Parameters
alias
Definition: PointMatcher.h:186
PointMatcherSupport::toParam
std::string toParam(const S &value)
Return the string value using lexical_cast.
Definition: Parametrizable.h:123
build_map.T
T
Definition: build_map.py:34
DataPoints
PM::DataPoints DataPoints
Definition: pypoint_matcher_helper.h:16
PointMatcher< float >
PointMatcherSupport::setLogger
void setLogger(std::shared_ptr< Logger > newLogger)
Set a new logger, protected by a mutex.
Definition: Logger.cpp:98
PointMatcher::Transformation
A function that transforms points and their descriptors given a transformation matrix.
Definition: PointMatcher.h:404
loadYamlFile
vector< string > loadYamlFile(string listFileName)
align_sequence.params
params
Definition: align_sequence.py:13
PMIO
PointMatcherIO< float > PMIO
Definition: eval_solution.cpp:62
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
validateArgs
void validateArgs(int argc, char *argv[])
Definition: build_map.cpp:230
setupArgs
void setupArgs(int argc, char *argv[], unsigned int &startId, unsigned int &endId, string &extension)
main
int main(int argc, char *argv[])
Definition: build_map.cpp:57
std
TP
PM::TransformationParameters TP
Definition: eval_solution.cpp:63
build_map.transformation
transformation
Definition: build_map.py:37
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
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
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