TransformationsImpl.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 "TransformationsImpl.h"
37 #include "Functions.h"
38 
39 #include <iostream>
40 
41 using namespace PointMatcherSupport;
42 
45  runtime_error(reason)
46 {}
47 
49 template<typename T>
51  const DataPoints& input,
52  const TransformationParameters& parameters) const
53 {
54  assert(input.features.rows() == parameters.rows());
55  assert(parameters.rows() == parameters.cols());
56 
57  const unsigned int nbRows = parameters.rows()-1;
58  const unsigned int nbCols = parameters.cols()-1;
59 
60  const TransformationParameters R(parameters.topLeftCorner(nbRows, nbCols));
61 
62  if(this->checkParameters(parameters) == false)
63  throw TransformationError("RigidTransformation: Error, rotation matrix is not orthogonal.");
64 
65  //DataPoints transformedCloud(input.featureLabels, input.descriptorLabels, input.timeLabels, input.features.cols());
66  DataPoints transformedCloud = input;
67 
68  // Apply the transformation to features
69  transformedCloud.features = parameters * input.features;
70 
71  // Apply the transformation to descriptors
72  int row(0);
73  const int descCols(input.descriptors.cols());
74  for (size_t i = 0; i < input.descriptorLabels.size(); ++i)
75  {
76  const int span(input.descriptorLabels[i].span);
77  const std::string& name(input.descriptorLabels[i].text);
78  const BOOST_AUTO(inputDesc, input.descriptors.block(row, 0, span, descCols));
79  BOOST_AUTO(outputDesc, transformedCloud.descriptors.block(row, 0, span, descCols));
80  if (name == "normals" || name == "observationDirections")
81  outputDesc = R * inputDesc;
82 
83  row += span;
84  }
85 
86  return transformedCloud;
87 }
88 
90 template<typename T>
92 {
93  //FIXME: FP - should we put that as function argument?
94  const T epsilon = 0.001;
95  const unsigned int nbRows = parameters.rows()-1;
96  const unsigned int nbCols = parameters.cols()-1;
97 
98  const TransformationParameters R(parameters.topLeftCorner(nbRows, nbCols));
99 
100  if(anyabs(1 - R.determinant()) > epsilon)
101  return false;
102  else
103  return true;
104 
105 }
106 
108 template<typename T>
110 {
111  TransformationParameters ortho = parameters;
112  if(ortho.cols() == 4)
113  {
114  //const Eigen::Matrix<T, 3, 1> col0 = parameters.block(0, 0, 3, 1).normalized();
115  const Eigen::Matrix<T, 3, 1> col1 = parameters.block(0, 1, 3, 1).normalized();
116  const Eigen::Matrix<T, 3, 1> col2 = parameters.block(0, 2, 3, 1).normalized();
117 
118  const Eigen::Matrix<T, 3, 1> newCol0 = col1.cross(col2);
119  const Eigen::Matrix<T, 3, 1> newCol1 = col2.cross(newCol0);
120  const Eigen::Matrix<T, 3, 1> newCol2 = col2;
121 
122  ortho.block(0, 0, 3, 1) = newCol0;
123  ortho.block(0, 1, 3, 1) = newCol1;
124  ortho.block(0, 2, 3, 1) = newCol2;
125  }
126  else if(ortho.cols() == 3)
127  {
128  const T epsilon = 0.001;
129 
130  // R = [ a b]
131  // [-b a]
132  if(anyabs(parameters(0,0) - parameters(1,1)) > epsilon || anyabs(parameters(1,0) + parameters(0,1)) > epsilon)
133  {
134  throw TransformationError("RigidTransformation: Error, only proper rigid transformations are supported.");
135  }
136 
137  // mean of a and b
138  T a = (parameters(0,0) + parameters(1,1))/2;
139  T b = (-parameters(1,0) + parameters(0,1))/2;
140  T sum = sqrt(pow(a,2) + pow(b,2));
141 
142  a = a/sum;
143  b = b/sum;
144 
145  ortho(0,0) = a; ortho(0,1) = b;
146  ortho(1,0) = -b; ortho(1,1) = a;
147  }
148 
149 
150  return ortho;
151 }
152 
155 
157 template<typename T>
159  const DataPoints& input,
160  const TransformationParameters& parameters) const
161 {
162  assert(input.features.rows() == parameters.rows());
163  assert(parameters.rows() == parameters.cols());
164 
165  const unsigned int nbRows = parameters.rows()-1;
166  const unsigned int nbCols = parameters.cols()-1;
167 
168  const TransformationParameters R(parameters.topLeftCorner(nbRows, nbCols));
169 
170  if(this->checkParameters(parameters) == false)
171  throw TransformationError("SimilarityTransformation: Error, invalid similarity transform.");
172 
173  //DataPoints transformedCloud(input.featureLabels, input.descriptorLabels, input.timeLabels, input.features.cols());
174  DataPoints transformedCloud = input;
175 
176  // Apply the transformation to features
177  transformedCloud.features = parameters * input.features;
178 
179  // Apply the transformation to descriptors
180  int row(0);
181  const int descCols(input.descriptors.cols());
182  for (size_t i = 0; i < input.descriptorLabels.size(); ++i)
183  {
184  const int span(input.descriptorLabels[i].span);
185  const std::string& name(input.descriptorLabels[i].text);
186  const BOOST_AUTO(inputDesc, input.descriptors.block(row, 0, span, descCols));
187  BOOST_AUTO(outputDesc, transformedCloud.descriptors.block(row, 0, span, descCols));
188  if (name == "normals" || name == "observationDirections")
189  outputDesc = R * inputDesc;
190 
191  row += span;
192  }
193 
194  return transformedCloud;
195 }
196 
198 template<typename T>
200 {
201  //FIXME: FP - should we put that as function argument?
202  return true;
203 }
204 
206 template<typename T>
208 {
209  return parameters;
210 }
211 
214 
215 template<typename T>
217  const TransformationParameters& parameters) const {
218  assert(input.features.rows() == parameters.rows());
219  assert(parameters.rows() == parameters.cols());
220 
221  if(this->checkParameters(parameters) == false)
222  throw PointMatcherSupport::TransformationError("PureTranslation: Error, left part not identity.");
223 
224  //DataPoints transformedCloud(input.featureLabels, input.descriptorLabels, input.features.cols());
225  DataPoints transformedCloud = input;
226 
227  // Apply the transformation to features
228  transformedCloud.features = parameters * input.features;
229 
230  return transformedCloud;
231 }
232 
233 template<typename T>
235  const TransformationParameters& parameters) const {
236  const int rows = parameters.rows();
237  const int cols = parameters.cols();
238 
239  // make a copy of the parameters to perform corrections on
240  TransformationParameters correctedParameters(parameters);
241 
242  // set the top left block to the identity matrix
243  correctedParameters.block(0,0,rows-1,cols-1).setIdentity();
244 
245  // fix the bottom row
246  correctedParameters.block(rows-1,0,1,cols-1).setZero();
247  correctedParameters(rows-1,cols-1) = 1;
248 
249  return correctedParameters;
250 }
251 
252 template<typename T>
254  const TransformationParameters& parameters) const {
255  const int rows = parameters.rows();
256  const int cols = parameters.cols();
257 
258  // make a copy of parameters to perform the check
259  TransformationParameters parameters_(parameters);
260 
261  // set the translation components of the transformation matrix to 0
262  parameters_.block(0,cols-1,rows-1,1).setZero();
263 
264  // If we have the identity matrix, than this is indeed a pure translation
265  if (parameters_.isApprox(TransformationParameters::Identity(rows,cols)))
266  return true;
267  else
268  return false;
269 }
270 
TransformationsImpl::PureTranslation::correctParameters
virtual TransformationParameters correctParameters(const TransformationParameters &parameters) const
Definition: TransformationsImpl.cpp:234
PointMatcher::DataPoints::descriptorLabels
Labels descriptorLabels
labels of descriptors
Definition: PointMatcher.h:334
epsilon
double epsilon
TransformationsImpl::RigidTransformation::compute
virtual DataPoints compute(const DataPoints &input, const TransformationParameters &parameters) const
RigidTransformation.
Definition: TransformationsImpl.cpp:50
TransformationsImpl::PureTranslation::compute
virtual DataPoints compute(const DataPoints &input, const TransformationParameters &parameters) const
Definition: TransformationsImpl.cpp:216
TransformationsImpl::SimilarityTransformation::compute
virtual DataPoints compute(const DataPoints &input, const TransformationParameters &parameters) const
SimilarityTransformation.
Definition: TransformationsImpl.cpp:158
PointMatcherSupport::TransformationError::TransformationError
TransformationError(const std::string &reason)
return an exception when a transformation has invalid parameters
Definition: TransformationsImpl.cpp:44
PointMatcher::DataPoints
A point cloud.
Definition: PointMatcher.h:207
testing::internal::string
::std::string string
Definition: gtest.h:1979
TransformationsImpl::PureTranslation
Definition: TransformationsImpl.h:79
TransformationsImpl::SimilarityTransformation
Definition: TransformationsImpl.h:67
PointMatcher::DataPoints::descriptors
Matrix descriptors
descriptors of points in the cloud, might be empty
Definition: PointMatcher.h:333
TransformationsImpl::SimilarityTransformation::correctParameters
virtual TransformationParameters correctParameters(const TransformationParameters &parameters) const
Nothing to correct for a similarity transform.
Definition: TransformationsImpl.cpp:207
TransformationsImpl::RigidTransformation::checkParameters
virtual bool checkParameters(const TransformationParameters &parameters) const
Ensure orthogonality of the rotation matrix.
Definition: TransformationsImpl.cpp:91
TransformationsImpl::TransformationParameters
PointMatcher< T >::TransformationParameters TransformationParameters
Definition: TransformationsImpl.h:51
TransformationsImpl::RigidTransformation
Definition: TransformationsImpl.h:54
PointMatcher::DataPoints::features
Matrix features
features of points in the cloud
Definition: PointMatcher.h:331
TransformationsImpl.h
TransformationsImpl::RigidTransformation::correctParameters
virtual TransformationParameters correctParameters(const TransformationParameters &parameters) const
Force orthogonality of the rotation matrix.
Definition: TransformationsImpl.cpp:109
TransformationsImpl::SimilarityTransformation::checkParameters
virtual bool checkParameters(const TransformationParameters &parameters) const
Nothing to check for a similarity transform.
Definition: TransformationsImpl.cpp:199
PointMatcherSupport::anyabs
static T anyabs(const T &v)
Definition: Functions.h:44
Functions.h
PointMatcherSupport
Functions and classes that are not dependant on scalar type are defined in this namespace.
Definition: Bibliography.cpp:45
PointMatcherSupport::TransformationError
An expection thrown when a transformation has invalid parameters.
Definition: PointMatcher.h:89
PointMatcherSupport::pow
constexpr T pow(const T base, const std::size_t exponent)
Definition: utils.h:47
PointMatcher::TransformationParameters
Matrix TransformationParameters
A matrix holding the parameters a transformation.
Definition: PointMatcher.h:182
TransformationsImpl::PureTranslation::checkParameters
virtual bool checkParameters(const TransformationParameters &parameters) const
Definition: TransformationsImpl.cpp:253


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:04