55 inPlaceCompute(parameters, transformedCloud);
56 return transformedCloud;
65 assert(cloud.
features.rows() == parameters.rows());
66 assert(parameters.rows() == parameters.cols());
68 if(this->checkParameters(parameters) ==
false)
69 throw TransformationError(
"RigidTransformation: Error, rotation matrix is not orthogonal.");
72 cloud.
features.applyOnTheLeft(parameters);
75 const unsigned int nbRows = parameters.rows()-1;
76 const unsigned int nbCols = parameters.cols()-1;
79 int descStartingRow(0);
87 if (descName ==
"normals" || descName ==
"observationDirections")
89 cloud.
descriptors.block(descStartingRow, 0, descSpan, descCols).applyOnTheLeft(R);
91 else if (descName ==
"eigVectors")
93 int vectorSpan = std::sqrt(descSpan);
94 int vectorStartingRow = descStartingRow;
96 cloud.
descriptors.block(vectorStartingRow, 0, vectorSpan, descCols).applyOnTheLeft(R);
97 vectorStartingRow += vectorSpan;
98 cloud.
descriptors.block(vectorStartingRow, 0, vectorSpan, descCols).applyOnTheLeft(R);
102 vectorStartingRow += vectorSpan;
103 cloud.
descriptors.block(vectorStartingRow, 0, vectorSpan, descCols).applyOnTheLeft(R);
107 descStartingRow += descSpan;
116 const T epsilon = 0.001;
117 const unsigned int nbRows = parameters.rows()-1;
118 const unsigned int nbCols = parameters.cols()-1;
122 if(
anyabs(1 - R.determinant()) > epsilon)
134 if(ortho.cols() == 4)
137 const Eigen::Matrix<T, 3, 1> col1 = parameters.block(0, 1, 3, 1).normalized();
138 const Eigen::Matrix<T, 3, 1> col2 = parameters.block(0, 2, 3, 1).normalized();
140 const Eigen::Matrix<T, 3, 1> newCol0 = col1.cross(col2);
141 const Eigen::Matrix<T, 3, 1> newCol1 = col2.cross(newCol0);
142 const Eigen::Matrix<T, 3, 1> newCol2 = col2;
144 ortho.block(0, 0, 3, 1) = newCol0;
145 ortho.block(0, 1, 3, 1) = newCol1;
146 ortho.block(0, 2, 3, 1) = newCol2;
148 else if(ortho.cols() == 3)
150 const T epsilon = 0.001;
154 if(
anyabs(parameters(0,0) - parameters(1,1)) > epsilon ||
anyabs(parameters(1,0) + parameters(0,1)) > epsilon)
156 throw TransformationError(
"RigidTransformation: Error, only proper rigid transformations are supported.");
160 T a = (parameters(0,0) + parameters(1,1))/2;
161 T b = (-parameters(1,0) + parameters(0,1))/2;
162 T sum = sqrt(
pow(a,2) +
pow(b,2));
167 ortho(0,0) = a; ortho(0,1) = b;
168 ortho(1,0) = -b; ortho(1,1) = a;
185 inPlaceCompute(parameters, transformedCloud);
186 return transformedCloud;
195 assert(cloud.
features.rows() == parameters.rows());
196 assert(parameters.rows() == parameters.cols());
198 if(this->checkParameters(parameters) ==
false)
199 throw TransformationError(
"SimilarityTransformation: Error, invalid similarity transform.");
202 cloud.
features.applyOnTheLeft(parameters);
205 const unsigned int nbRows = parameters.rows() - 1;
206 const unsigned int nbCols = parameters.cols() - 1;
209 int descStartingRow(0);
217 if (descName ==
"normals" || descName ==
"observationDirections")
219 cloud.
descriptors.block(descStartingRow, 0, descSpan, descCols).applyOnTheLeft(R);
221 else if (descName ==
"eigVectors")
223 int vectorSpan = std::sqrt(descSpan);
224 int vectorStartingRow = descStartingRow;
226 cloud.
descriptors.block(vectorStartingRow, 0, vectorSpan, descCols).applyOnTheLeft(R);
227 vectorStartingRow += vectorSpan;
228 cloud.
descriptors.block(vectorStartingRow, 0, vectorSpan, descCols).applyOnTheLeft(R);
232 vectorStartingRow += vectorSpan;
233 cloud.
descriptors.block(vectorStartingRow, 0, vectorSpan, descCols).applyOnTheLeft(R);
237 descStartingRow += descSpan;
263 inPlaceCompute(parameters, transformedCloud);
264 return transformedCloud;
271 assert(cloud.
features.rows() == parameters.rows());
272 assert(parameters.rows() == parameters.cols());
274 if(this->checkParameters(parameters) ==
false)
278 cloud.
features.applyOnTheLeft(parameters);
284 const int rows = parameters.rows();
285 const int cols = parameters.cols();
291 correctedParameters.block(0,0,rows-1,cols-1).setIdentity();
294 correctedParameters.block(rows-1,0,1,cols-1).setZero();
295 correctedParameters(rows-1,cols-1) = 1;
297 return correctedParameters;
303 const int rows = parameters.rows();
304 const int cols = parameters.cols();
310 parameters_.block(0,cols-1,rows-1,1).setZero();
313 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.
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