icp_customized.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 <cassert>
38 #include <iostream>
39 
40 using namespace std;
41 
42 void validateArgs(int argc, char *argv[], bool& isCSV);
43 
53 int main(int argc, char *argv[])
54 {
55  bool isCSV = true;
56  validateArgs(argc, argv, isCSV);
57 
58  typedef PointMatcher<float> PM;
59  typedef PM::DataPoints DP;
60 
61  // Load point clouds
62  const DP ref(DP::load(argv[1]));
63  const DP data(DP::load(argv[2]));
64 
65  // Create the default ICP algorithm
66  PM::ICP icp;
69 
70  // Uncomment for console outputs
71  setLogger(PM::get().LoggerRegistrar.create("FileLogger"));
72 
73  // Prepare reading filters
74  name = "MinDistDataPointsFilter";
75  params["minDist"] = "1.0";
76  std::shared_ptr<PM::DataPointsFilter> minDist_read =
77  PM::get().DataPointsFilterRegistrar.create(name, params);
78  params.clear();
79 
80  name = "RandomSamplingDataPointsFilter";
81  params["prob"] = "0.05";
82  std::shared_ptr<PM::DataPointsFilter> rand_read =
83  PM::get().DataPointsFilterRegistrar.create(name, params);
84  params.clear();
85 
86  // Prepare reference filters
87  name = "MinDistDataPointsFilter";
88  params["minDist"] = "1.0";
89  std::shared_ptr<PM::DataPointsFilter> minDist_ref =
90  PM::get().DataPointsFilterRegistrar.create(name, params);
91  params.clear();
92 
93  name = "RandomSamplingDataPointsFilter";
94  params["prob"] = "0.05";
95  std::shared_ptr<PM::DataPointsFilter> rand_ref =
96  PM::get().DataPointsFilterRegistrar.create(name, params);
97  params.clear();
98 
99  // Prepare matching function
100  name = "KDTreeMatcher";
101  params["knn"] = "1";
102  params["epsilon"] = "3.16";
103  std::shared_ptr<PM::Matcher> kdtree =
104  PM::get().MatcherRegistrar.create(name, params);
105  params.clear();
106 
107  // Prepare outlier filters
108  name = "TrimmedDistOutlierFilter";
109  params["ratio"] = "0.75";
110  std::shared_ptr<PM::OutlierFilter> trim =
111  PM::get().OutlierFilterRegistrar.create(name, params);
112  params.clear();
113 
114  // Prepare error minimization
115  name = "PointToPointErrorMinimizer";
116  std::shared_ptr<PM::ErrorMinimizer> pointToPoint =
117  PM::get().ErrorMinimizerRegistrar.create(name);
118 
119  // Prepare transformation checker filters
120  name = "CounterTransformationChecker";
121  params["maxIterationCount"] = "150";
122  std::shared_ptr<PM::TransformationChecker> maxIter =
123  PM::get().TransformationCheckerRegistrar.create(name, params);
124  params.clear();
125 
126  name = "DifferentialTransformationChecker";
127  params["minDiffRotErr"] = "0.001";
128  params["minDiffTransErr"] = "0.01";
129  params["smoothLength"] = "4";
130  std::shared_ptr<PM::TransformationChecker> diff =
131  PM::get().TransformationCheckerRegistrar.create(name, params);
132  params.clear();
133 
134  // Prepare inspector
135  std::shared_ptr<PM::Inspector> nullInspect =
136  PM::get().InspectorRegistrar.create("NullInspector");
137 
138 // name = "VTKFileInspector";
139 // params["dumpDataLinks"] = "1";
140 // params["dumpReading"] = "1";
141 // params["dumpReference"] = "1";
142 // std::shared_ptr<PM::Inspector> vtkInspect =
143 // PM::get().InspectorRegistrar.create(name, params);
144 // params.clear();
145 
146  // Prepare transformation
147  std::shared_ptr<PM::Transformation> rigidTrans =
148  PM::get().TransformationRegistrar.create("RigidTransformation");
149 
150  // Build ICP solution
151  icp.readingDataPointsFilters.push_back(minDist_read);
152  icp.readingDataPointsFilters.push_back(rand_read);
153 
154  icp.referenceDataPointsFilters.push_back(minDist_ref);
155  icp.referenceDataPointsFilters.push_back(rand_ref);
156 
157  icp.matcher = kdtree;
158 
159  icp.outlierFilters.push_back(trim);
160 
161  icp.errorMinimizer = pointToPoint;
162 
163  icp.transformationCheckers.push_back(maxIter);
164  icp.transformationCheckers.push_back(diff);
165 
166  // toggle to write vtk files per iteration
167  icp.inspector = nullInspect;
168  //icp.inspector = vtkInspect;
169 
170  icp.transformations.push_back(rigidTrans);
171 
172  // Compute the transformation to express data in ref
174 
175  // Transform data to express it in ref
176  DP data_out(data);
177  icp.transformations.apply(data_out, T);
178 
179  // Safe files to see the results
180  ref.save("test_ref.vtk");
181  data.save("test_data_in.vtk");
182  data_out.save("test_data_out.vtk");
183  cout << "Final transformation:" << endl << T << endl;
184 
185  return 0;
186 }
187 
188 void validateArgs(int argc, char *argv[], bool& isCSV )
189 {
190  if (argc != 3)
191  {
192  cerr << "Wrong number of arguments, usage " << argv[0] << " reference.csv reading.csv" << endl;
193  cerr << "Will create 3 vtk files for inspection: ./test_ref.vtk, ./test_data_in.vtk and ./test_data_out.vtk" << endl;
194  cerr << endl << "2D Example:" << endl;
195  cerr << " " << argv[0] << " ../../examples/data/2D_twoBoxes.csv ../../examples/data/2D_oneBox.csv" << endl;
196  cerr << endl << "3D Example:" << endl;
197  cerr << " " << argv[0] << " ../../examples/data/car_cloud400.csv ../../examples/data/car_cloud401.csv" << endl;
198  exit(1);
199  }
200 }
build_map.T
T
Definition: build_map.py:34
DataPoints
PM::DataPoints DataPoints
Definition: pypoint_matcher_helper.h:16
icp_customized.maxIter
maxIter
Definition: icp_customized.py:87
icp_customized.name
string name
Definition: icp_customized.py:45
icp_customized.rand_ref
rand_ref
Definition: icp_customized.py:63
main
int main(int argc, char *argv[])
Definition: icp_customized.cpp:53
icp_customized.trim
trim
Definition: icp_customized.py:76
PointMatcher< float >
PointMatcherSupport::setLogger
void setLogger(std::shared_ptr< Logger > newLogger)
Set a new logger, protected by a mutex.
Definition: Logger.cpp:98
align_sequence.icp
icp
Definition: align_sequence.py:40
PointMatcher::DataPoints
A point cloud.
Definition: PointMatcher.h:207
testing::internal::string
::std::string string
Definition: gtest.h:1979
align_sequence.params
params
Definition: align_sequence.py:13
icp.data
data
Definition: icp.py:50
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
icp.data_out
data_out
Definition: icp.py:93
ICP
PM::ICP ICP
Definition: pypoint_matcher_helper.h:33
icp.ref
ref
Definition: icp.py:49
icp_customized.kdtree
kdtree
Definition: icp_customized.py:70
icp_customized.minDist_ref
minDist_ref
Definition: icp_customized.py:58
icp_customized.minDist_read
minDist_read
Definition: icp_customized.py:47
std
icp_customized.pointToPoint
pointToPoint
Definition: icp_customized.py:81
icp_customized.diff
diff
Definition: icp_customized.py:94
icp
Definition: icp.py:1
PointMatcher< float >::get
static const PointMatcher & get()
Return instances.
Definition: Registry.cpp:147
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
icp_customized.rand_read
rand_read
Definition: icp_customized.py:52
validateArgs
void validateArgs(int argc, char *argv[], bool &isCSV)
Definition: icp_customized.cpp:188
PointMatcherSupport::Parametrizable::Parameters
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
Definition: Parametrizable.h:199
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
icp_customized.nullInspect
nullInspect
Definition: icp_customized.py:100


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