ErrorMinimizer.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 
36 #include "PointMatcher.h"
37 #include "PointMatcherPrivate.h"
38 
40 // ErrorElements
42 
44 template<typename T>
48  weights(OutlierWeights()),
49  matches(Matches()),
50  nbRejectedMatches(-1),
51  nbRejectedPoints(-1),
52  pointUsedRatio(-1.0),
53  weightedPointUsedRatio(-1.0)
54 {
55 }
56 
58 template<typename T>
59 PointMatcher<T>::ErrorMinimizer::ErrorElements::ErrorElements(const DataPoints& requestedPts, const DataPoints& sourcePts, const OutlierWeights& outlierWeights, const Matches& matches)
60 {
61  typedef typename Matches::Ids Ids;
62  typedef typename Matches::Dists Dists;
63 
64  assert(matches.ids.rows() > 0);
65  assert(matches.ids.cols() > 0);
66  assert(matches.ids.cols() == requestedPts.features.cols()); //nbpts
67  assert(outlierWeights.rows() == matches.ids.rows()); // knn
68 
69  const int knn = outlierWeights.rows();
70  const int dimFeat = requestedPts.features.rows();
71  const int dimReqDesc = requestedPts.descriptors.rows();
72  const int dimReqTime = requestedPts.times.rows();
73 
74  // Count points with no weights
75  const int pointsCount = (outlierWeights.array() != 0.0).count();
76  if (pointsCount == 0)
77  throw ConvergenceError("ErrorMnimizer: no point to minimize");
78 
79  Matrix keptFeat(dimFeat, pointsCount);
80 
81  Matrix keptDesc;
82  if(dimReqDesc > 0)
83  keptDesc = Matrix(dimReqDesc, pointsCount);
84 
85  Int64Matrix keptTime;
86  if(dimReqTime > 0)
87  keptTime = Int64Matrix(dimReqTime, pointsCount);
88 
89  Matches keptMatches (Dists(1,pointsCount), Ids(1, pointsCount));
90  OutlierWeights keptWeights(1, pointsCount);
91 
92  int j = 0;
93  int rejectedMatchCount = 0;
94  int rejectedPointCount = 0;
95  bool matchExist = false;
96  this->weightedPointUsedRatio = 0;
97 
98  for (int i = 0; i < requestedPts.features.cols(); ++i) //nb pts
99  {
100  matchExist = false;
101  for(int k = 0; k < knn; k++) // knn
102  {
103  const auto matchDist = matches.dists(k, i);
104  if (matchDist == Matches::InvalidDist){
105  continue;
106  }
107 
108  if (outlierWeights(k,i) != 0.0)
109  {
110  if(dimReqDesc > 0)
111  keptDesc.col(j) = requestedPts.descriptors.col(i);
112 
113  if(dimReqTime > 0)
114  keptTime.col(j) = requestedPts.times.col(i);
115 
116 
117  keptFeat.col(j) = requestedPts.features.col(i);
118  keptMatches.ids(0, j) = matches.ids(k, i);
119  keptMatches.dists(0, j) = matchDist;
120  keptWeights(0,j) = outlierWeights(k,i);
121  ++j;
122  this->weightedPointUsedRatio += outlierWeights(k,i);
123  matchExist = true;
124  }
125  else
126  {
127  rejectedMatchCount++;
128  }
129  }
130 
131  if(matchExist == false)
132  {
133  rejectedPointCount++;
134  }
135  }
136 
137  assert(j == pointsCount);
138 
139  this->pointUsedRatio = T(j)/T(knn*requestedPts.features.cols());
140  this->weightedPointUsedRatio /= T(knn*requestedPts.features.cols());
141 
142  assert(dimFeat == sourcePts.features.rows());
143  const int dimSourDesc = sourcePts.descriptors.rows();
144  const int dimSourTime = sourcePts.times.rows();
145 
146  Matrix associatedFeat(dimFeat, pointsCount);
147 
148  Matrix associatedDesc;
149  if(dimSourDesc > 0)
150  associatedDesc = Matrix(dimSourDesc, pointsCount);
151 
152  Int64Matrix associatedTime;
153  if(dimSourTime> 0)
154  associatedTime = Int64Matrix(dimSourTime, pointsCount);
155 
156  // Fetch matched points
157  for (int i = 0; i < pointsCount; ++i)
158  {
159  const int refIndex(keptMatches.ids(i));
160  associatedFeat.col(i) = sourcePts.features.block(0, refIndex, dimFeat, 1);
161 
162  if(dimSourDesc > 0)
163  associatedDesc.col(i) = sourcePts.descriptors.block(0, refIndex, dimSourDesc, 1);
164 
165  if(dimSourTime> 0)
166  associatedTime.col(i) = sourcePts.times.block(0, refIndex, dimSourTime, 1);
167 
168  }
169 
170  // Copy final data to structure
171  this->reading = DataPoints(
172  keptFeat,
173  requestedPts.featureLabels,
174  keptDesc,
175  requestedPts.descriptorLabels,
176  keptTime,
177  requestedPts.timeLabels
178  );
179 
180  this->reference = DataPoints(
181  associatedFeat,
182  sourcePts.featureLabels,
183  associatedDesc,
184  sourcePts.descriptorLabels,
185  associatedTime,
186  sourcePts.timeLabels
187  );
188 
189  this->weights = keptWeights;
190  this->matches = keptMatches;
191  this->nbRejectedMatches = rejectedMatchCount;
192  this->nbRejectedPoints = rejectedPointCount;
193 }
194 
195 
197 // ErrorMinimizer
199 
201 template<typename T>
203 {}
204 
206 template<typename T>
208  Parametrizable(className,paramsDoc,params)
209 {}
210 
212 template<typename T>
214 {}
215 
217 template<typename T>
218 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ErrorMinimizer::compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const OutlierWeights& outlierWeights, const Matches& matches)
219 {
220 
221  // generates pairs of matching points
222  typename ErrorMinimizer::ErrorElements matchedPoints(filteredReading, filteredReference, outlierWeights, matches);
223 
224  // calls specific instantiation for a given ErrorMinimizer
225  TransformationParameters transform = this->compute(matchedPoints);
226 
227  // saves paired points for future introspection
228  this->lastErrorElements = matchedPoints;
229 
230  // returns transforme parameters
231  return transform;
232 }
233 
235 template<typename T>
237 {
238  return lastErrorElements.pointUsedRatio;
239 }
240 
242 template<typename T>
244 {
245  //Warning: the use of the variable lastErrorElements is not standardized yet.
246  return lastErrorElements;
247 }
248 
250 template<typename T>
252 {
253  return lastErrorElements.weightedPointUsedRatio;
254 }
255 
257 template<typename T>
259 {
260  LOG_WARNING_STREAM("ErrorMinimizer - warning, no specific method to compute overlap was provided for the ErrorMinimizer used.");
261  return lastErrorElements.weightedPointUsedRatio;
262 }
263 
265 template<typename T>
267 {
268  LOG_WARNING_STREAM("ErrorMinimizer - warning, no specific method to compute covariance was provided for the ErrorMinimizer used.");
269  return Matrix::Zero(6,6);
270 }
271 
273 template<typename T>
274 T PointMatcher<T>::ErrorMinimizer::getResidualError(const DataPoints& filteredReading, const DataPoints& filteredReference, const OutlierWeights& outlierWeights, const Matches& matches) const
275 {
276  LOG_WARNING_STREAM("ErrorMinimizer - warning, no specific method to compute residual was provided for the ErrorMinimizer used.");
277  return std::numeric_limits<T>::max();
278 }
279 
281 template<typename T>
283 {
284  //Note: A = [x, y, z, 1] and B = [x, y, z] for convenience
285 
286  // Expecting matched points
287  assert(A.cols() == B.cols());
288 
289  // Expecting homogenous coord X eucl. coord
290  assert(A.rows() -1 == B.rows());
291 
292  // Expecting homogenous coordinates
293  assert(A.rows() == 4 || A.rows() == 3);
294 
295  const unsigned int x = 0;
296  const unsigned int y = 1;
297  const unsigned int z = 2;
298 
299  Matrix cross;
300  if(A.rows() == 4)
301  {
302  cross = Matrix(B.rows(), B.cols());
303 
304  cross.row(x) = A.row(y).array() * B.row(z).array() - A.row(z).array() * B.row(y).array();
305  cross.row(y) = A.row(z).array() * B.row(x).array() - A.row(x).array() * B.row(z).array();
306  cross.row(z) = A.row(x).array() * B.row(y).array() - A.row(y).array() * B.row(x).array();
307  }
308  else
309  {
310  //pseudo-cross product for 2D vectors
311  cross = Vector(B.cols());
312  cross = A.row(x).array() * B.row(y).array() - A.row(y).array() * B.row(x).array();
313  }
314  return cross;
315 }
316 
317 
318 
319 
compute_overlap.reference
reference
Definition: compute_overlap.py:71
PointMatcher::ErrorMinimizer::ErrorElements::nbRejectedPoints
int nbRejectedPoints
number of points with all matches set to zero weights
Definition: PointMatcher.h:540
PointMatcher::Matches::Dists
Matrix Dists
Squared distances to closest points, dense matrix of ScalarType.
Definition: PointMatcher.h:373
PointMatcher::Matches::dists
Dists dists
squared distances to closest points
Definition: PointMatcher.h:384
PointMatcher::DataPoints::descriptorLabels
Labels descriptorLabels
labels of descriptors
Definition: PointMatcher.h:334
compute_overlap.knn
int knn
Definition: compute_overlap.py:128
PointMatcher::ErrorMinimizer::getCovariance
virtual Matrix getCovariance() const
If not redefined by child class, return zero matrix.
Definition: ErrorMinimizer.cpp:266
PointMatcher::Matches::ids
Ids ids
identifiers of closest points
Definition: PointMatcher.h:385
PointMatcher::OutlierWeights
Matrix OutlierWeights
Weights of the associations between the points in Matches and the points in the reference.
Definition: PointMatcher.h:397
PointMatcher::ErrorMinimizer::getErrorElements
ErrorElements getErrorElements() const
Return the last the ErrorElements structure that was used for error minimization.
Definition: ErrorMinimizer.cpp:243
build_map.T
T
Definition: build_map.py:34
DataPoints
PM::DataPoints DataPoints
Definition: pypoint_matcher_helper.h:16
PointMatcher::ErrorMinimizer::ErrorElements::pointUsedRatio
T pointUsedRatio
the ratio of how many points were used for error minimization
Definition: PointMatcher.h:541
PointMatcher::ErrorMinimizer::crossProduct
static Matrix crossProduct(const Matrix &A, const Matrix &B)
Helper funtion doing the cross product in 3D and a pseudo cross product in 2D.
Definition: ErrorMinimizer.cpp:282
PointMatcher
Functions and classes that are dependant on scalar type are defined in this templatized class.
Definition: PointMatcher.h:130
PointMatcherPrivate.h
PointMatcher::ConvergenceError
Point matcher did not converge.
Definition: PointMatcher.h:148
PointMatcher::ErrorMinimizer::ErrorElements::ErrorElements
ErrorElements()
Constructor without data.
Definition: ErrorMinimizer.cpp:45
PointMatcher::DataPoints
A point cloud.
Definition: PointMatcher.h:207
x
x
PointMatcher::ErrorMinimizer::getPointUsedRatio
T getPointUsedRatio() const
Return the ratio of how many points were used for error minimization.
Definition: ErrorMinimizer.cpp:236
PointMatcher::ErrorMinimizer::getResidualError
virtual T getResidualError(const DataPoints &filteredReading, const DataPoints &filteredReference, const OutlierWeights &outlierWeights, const Matches &matches) const
If not redefined by child class, return max value for T.
Definition: ErrorMinimizer.cpp:274
PointMatcher::ErrorMinimizer::getOverlap
virtual T getOverlap() const
If not redefined by child class, return the ratio of how many points were used (with weight) for erro...
Definition: ErrorMinimizer.cpp:258
testing::internal::string
::std::string string
Definition: gtest.h:1979
PointMatcher::DataPoints::timeLabels
Labels timeLabels
labels of times.
Definition: PointMatcher.h:336
PointMatcher::ErrorMinimizer::getWeightedPointUsedRatio
T getWeightedPointUsedRatio() const
Return the ratio of how many points were used (with weight) for error minimization.
Definition: ErrorMinimizer.cpp:251
PointMatcher::Int64Matrix
Eigen::Matrix< std::int64_t, Eigen::Dynamic, Eigen::Dynamic > Int64Matrix
A dense signed 64-bits matrix.
Definition: PointMatcher.h:173
PointMatcher::ErrorMinimizer::ErrorMinimizer
ErrorMinimizer()
Construct without parameter.
Definition: ErrorMinimizer.cpp:202
PointMatcher::ErrorMinimizer::ErrorElements
A structure holding data ready for minimization. The data are "normalized", for instance there are no...
Definition: PointMatcher.h:533
PointMatcherSupport::Parametrizable::ParametersDoc
std::vector< ParameterDoc > ParametersDoc
The documentation of all parameters.
Definition: Parametrizable.h:187
align_sequence.params
params
Definition: align_sequence.py:13
PointMatcher::DataPoints::featureLabels
Labels featureLabels
labels of features
Definition: PointMatcher.h:332
PointMatcher::ErrorMinimizer::ErrorElements::matches
Matches matches
associations
Definition: PointMatcher.h:538
PointMatcher::ErrorMinimizer::ErrorElements::weightedPointUsedRatio
T weightedPointUsedRatio
the ratio of how many points were used (with weight) for error minimization
Definition: PointMatcher.h:542
PointMatcher::DataPoints::descriptors
Matrix descriptors
descriptors of points in the cloud, might be empty
Definition: PointMatcher.h:333
icp_advance_api.matches
matches
Definition: icp_advance_api.py:114
PointMatcher::Matrix
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
Definition: PointMatcher.h:169
PointMatcher::ErrorMinimizer::ErrorElements::reading
DataPoints reading
reading point cloud
Definition: PointMatcher.h:535
PointMatcher::Matches::Ids
IntMatrix Ids
Identifiers of closest points, dense matrix of integers.
Definition: PointMatcher.h:374
LOG_WARNING_STREAM
#define LOG_WARNING_STREAM(args)
Definition: PointMatcherPrivate.h:68
PointMatcher::DataPoints::features
Matrix features
features of points in the cloud
Definition: PointMatcher.h:331
PointMatcher::ErrorMinimizer::ErrorElements::reference
DataPoints reference
reference point cloud
Definition: PointMatcher.h:536
PointMatcher::Vector
Eigen::Matrix< T, Eigen::Dynamic, 1 > Vector
A vector over ScalarType.
Definition: PointMatcher.h:161
PointMatcher::Matches
Result of the data-association step (Matcher::findClosests), before outlier rejection.
Definition: PointMatcher.h:371
PointMatcher::DataPoints::times
Int64Matrix times
time associated to each points, might be empty
Definition: PointMatcher.h:335
PointMatcherSupport::Parametrizable
The superclass of classes that are constructed using generic parameters. This class provides the para...
Definition: Parametrizable.h:141
PointMatcher::ErrorMinimizer::ErrorElements::weights
OutlierWeights weights
weights for every association
Definition: PointMatcher.h:537
PointMatcher::ErrorMinimizer::ErrorElements::nbRejectedMatches
int nbRejectedMatches
number of matches with zero weights
Definition: PointMatcher.h:539
PointMatcher::ErrorMinimizer::~ErrorMinimizer
virtual ~ErrorMinimizer()
virtual destructor
Definition: ErrorMinimizer.cpp:213
PointMatcher::ErrorMinimizer
An error minimizer will compute a transformation matrix such as to minimize the error between the rea...
Definition: PointMatcher.h:530
PointMatcher.h
public interface
PointMatcherSupport::Parametrizable::className
const std::string className
name of the class
Definition: Parametrizable.h:202
PointMatcherSupport::Parametrizable::Parameters
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
Definition: Parametrizable.h:199
PointMatcher::ErrorMinimizer::compute
virtual TransformationParameters compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const OutlierWeights &outlierWeights, const Matches &matches)
Find the transformation that minimizes the error.
Definition: ErrorMinimizer.cpp:218
compute_overlap.reading
reading
Definition: compute_overlap.py:70
PointMatcher::TransformationParameters
Matrix TransformationParameters
A matrix holding the parameters a transformation.
Definition: PointMatcher.h:182
PointMatcher::Matches::InvalidDist
static constexpr T InvalidDist
In case of too few matches the ids are filled with InvalidId.
Definition: PointMatcher.h:378


libpointmatcher
Author(s):
autogenerated on Mon Jan 1 2024 03:24:42