54 assert(input.
features.rows() == parameters.rows());
55 assert(parameters.rows() == parameters.cols());
57 const unsigned int nbRows = parameters.rows()-1;
58 const unsigned int nbCols = parameters.cols()-1;
62 if(this->checkParameters(parameters) ==
false)
63 throw TransformationError(
"RigidTransformation: Error, rotation matrix is not orthogonal.");
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;
86 return transformedCloud;
95 const unsigned int nbRows = parameters.rows()-1;
96 const unsigned int nbCols = parameters.cols()-1;
100 if(
anyabs(1 - R.determinant()) > epsilon)
112 if(ortho.cols() == 4)
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();
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;
122 ortho.block(0, 0, 3, 1) = newCol0;
123 ortho.block(0, 1, 3, 1) = newCol1;
124 ortho.block(0, 2, 3, 1) = newCol2;
126 else if(ortho.cols() == 3)
132 if(
anyabs(parameters(0,0) - parameters(1,1)) > epsilon ||
anyabs(parameters(1,0) + parameters(0,1)) > epsilon)
134 throw TransformationError(
"RigidTransformation: Error, only proper rigid transformations are supported.");
138 T a = (parameters(0,0) + parameters(1,1))/2;
139 T b = (-parameters(1,0) + parameters(0,1))/2;
145 ortho(0,0) = a; ortho(0,1) = b;
146 ortho(1,0) = -b; ortho(1,1) = a;
162 assert(input.
features.rows() == parameters.rows());
163 assert(parameters.rows() == parameters.cols());
165 const unsigned int nbRows = parameters.rows()-1;
166 const unsigned int nbCols = parameters.cols()-1;
170 if(this->checkParameters(parameters) ==
false)
171 throw TransformationError(
"SimilarityTransformation: Error, invalid similarity transform.");
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;
194 return transformedCloud;
218 assert(input.
features.rows() == parameters.rows());
219 assert(parameters.rows() == parameters.cols());
221 if(this->checkParameters(parameters) ==
false)
230 return transformedCloud;
236 const int rows = parameters.rows();
237 const int cols = parameters.cols();
243 correctedParameters.block(0,0,rows-1,cols-1).setIdentity();
246 correctedParameters.block(rows-1,0,1,cols-1).setZero();
247 correctedParameters(rows-1,cols-1) = 1;
249 return correctedParameters;
255 const int rows = parameters.rows();
256 const int cols = parameters.cols();
262 parameters_.block(0,cols-1,rows-1,1).setZero();
265 if (parameters_.isApprox(TransformationParameters::Identity(rows,cols)))
constexpr T pow(const T base, const std::size_t exponent)
Matrix descriptors
descriptors of points in the cloud, might be empty
Functions and classes that are not dependant on scalar type are defined in this namespace.
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
Matrix features
features of points in the cloud
Matrix TransformationParameters
A matrix holding the parameters a transformation.
static T anyabs(const T &v)
Labels descriptorLabels
labels of descriptors