TransformUtils.hpp
Go to the documentation of this file.
1 #ifndef __TRANSFORM_UTILS__
2 #define __TRANSFORM_UTILS__
3 
39 #include "lvr2/io/Model.hpp"
41 
42 #include <Eigen/Dense>
43 
44 namespace lvr2
45 {
46 
54 template<typename T>
55 void getPoseFromMatrix(BaseVector<T>& position, BaseVector<T>& angles, const Transform<T>& mat);
56 
65 template<typename T>
66 Transform<T> transformRegistration(const Transform<T>& transform, const Transform<T>& registration);
67 
71 template<typename T>
72 Transform<T> buildTransformation(T* alignxf);
73 
91 template<typename T>
92 void transformAndReducePointCloud(ModelPtr model, int modulo,
93  const T& sx, const T& sy, const T& sz,
94  const unsigned char& xPos,
95  const unsigned char& yPos,
96  const unsigned char& zPos);
97 
108 template<typename T>
109 void transformAndReducePointCloud(ModelPtr& model, int modulo, const CoordinateTransform<T>& c);
110 
117 template<typename T>
118 void transformPointCloud(ModelPtr model, const Transform<T>& transformation);
119 
128 template<typename T>
129 Transform<T> transformFrame(const Transform<T>& frame, const CoordinateTransform<T>& ct);
130 
140 template<typename T>
141 Transform<T> inverseTransform(const Transform<T>& transform);
142 
150 template<typename T>
151 Transform<T> poseToMatrix(const Vector3<T>& position, const Vector3<T>& rotation);
152 
160 template<typename T>
161 void matrixToPose(const Transform<T>& mat, Vector3<T>& position, Vector3<T>& rotation);
162 
171 template <typename T>
173 {
174  Transform<T> ret;
175 
176  ret(0) = in(5);
177  ret(1) = -in(9);
178  ret(2) = -in(1);
179  ret(3) = -in(13);
180  ret(4) = -in(6);
181  ret(5) = in(10);
182  ret(6) = in(2);
183  ret(7) = in(14);
184  ret(8) = -in(4);
185  ret(9) = in(8);
186  ret(10) = in(0);
187  ret(11) = in(12);
188  ret(12) = -100*in(7);
189  ret(13) = 100*in(11);
190  ret(14) = 100*in(3);
191  ret(15) = in(15);
192 
193  return ret;
194 }
195 
204 template <typename T>
206 {
207  Transform<T> ret;
208 
209  ret(0) = in(10);
210  ret(1) = -in(2);
211  ret(2) = in(6);
212  ret(3) = in(14)/100.0;
213  ret(4) = -in(8);
214  ret(5) = in(0);
215  ret(6) = -in(4);
216  ret(7) = -in(12)/100.0;
217  ret(8) = in(9);
218  ret(9) = -in(1);
219  ret(10) = in(5);
220  ret(11) = in(13)/100.0;
221  ret(12) = in(11);
222  ret(13) = -in(3);
223  ret(14) = in(7);
224  ret(15) = in(15);
225 
226  return ret;
227 }
228 
229 template <typename T>
231 {
232  return Vector3<T>(
233  in.coeff(2) / static_cast<T>(100.0),
234  - in.coeff(0) / static_cast<T>(100.0),
235  in.coeff(1) / static_cast<T>(100.0)
236  );
237 }
238 
240 // Change Coodinate Systems
242 
244 // 1) CS -> LVR
246 
272 template <typename T>
274 {
275  return Vector3<T>(
276  in.coeff(2) / static_cast<T>(100.0),
277  - in.coeff(0) / static_cast<T>(100.0),
278  in.coeff(1) / static_cast<T>(100.0)
279  );
280 }
281 
282 template<typename T>
284 {
285  Rotation<T> ret;
286 
287  // use coeff functions to access elements without range check
288  // should be faster?
289 
290  // OLD CODE: why transpose?
291  // ret.coeffRef(0, 0) = in.coeff(2, 2);
292  // ret.coeffRef(0, 1) = -in.coeff(0, 2);
293  // ret.coeffRef(0, 2) = in.coeff(1, 2);
294  // ret.coeffRef(1, 0) = -in.coeff(2, 0);
295  // ret.coeffRef(1, 1) = in.coeff(0, 0);
296  // ret.coeffRef(1, 2) = -in.coeff(1, 0);
297  // ret.coeffRef(2, 0) = in.coeff(2, 1);
298  // ret.coeffRef(2, 1) = -in.coeff(0, 1);
299  // ret.coeffRef(2, 2) = in.coeff(1, 1);
300 
301  ret.coeffRef(0, 0) = in.coeff(2, 2);
302  ret.coeffRef(1, 0) = -in.coeff(0, 2);
303  ret.coeffRef(2, 0) = in.coeff(1, 2);
304  ret.coeffRef(0, 1) = -in.coeff(2, 0);
305  ret.coeffRef(1, 1) = in.coeff(0, 0);
306  ret.coeffRef(2, 1) = -in.coeff(1, 0);
307  ret.coeffRef(0, 2) = in.coeff(2, 1);
308  ret.coeffRef(1, 2) = -in.coeff(0, 1);
309  ret.coeffRef(2, 2) = in.coeff(1, 1);
310 
311  return ret;
312 }
313 
314 template <typename T>
316 {
317  Transform<T> ret;
318 
319  // Rotation
320  const Rotation<T> R = in.template block<3,3>(0,0);
321  ret.template block<3,3>(0,0) = slam6dToLvr(R);
322 
323  // Translation
324  ret.coeffRef(0, 3) = in.coeff(2, 3)/static_cast<T>(100.0);
325  ret.coeffRef(1, 3) = -in.coeff(0, 3)/static_cast<T>(100.0);
326  ret.coeffRef(2, 3) = in.coeff(1, 3)/static_cast<T>(100.0);
327  ret.coeffRef(3, 0) = in.coeff(3, 2)/static_cast<T>(100.0);
328  ret.coeffRef(3, 1) = -in.coeff(3, 0)/static_cast<T>(100.0);
329  ret.coeffRef(3, 2) = in.coeff(3, 1)/static_cast<T>(100.0);
330  ret.coeffRef(3, 3) = in.coeff(3, 3);
331 
332  return ret;
333 }
334 
363 template <typename T>
365 {
366  return Vector3<T>(
367  in.coeff(2),
368  -in.coeff(0),
369  -in.coeff(1)
370  );
371 }
372 
373 template <typename T>
375 {
376  Rotation<T> ret;
377 
378  ret.coeffRef(0,0) = in.coeff(2,2);
379  ret.coeffRef(0,1) = -in.coeff(2,0);
380  ret.coeffRef(0,2) = -in.coeff(2,1);
381  ret.coeffRef(1,0) = -in.coeff(0,2);
382  ret.coeffRef(1,1) = in.coeff(0,0);
383  ret.coeffRef(1,2) = in.coeff(0,1);
384  ret.coeffRef(2,0) = -in.coeff(1,2);
385  ret.coeffRef(2,1) = in.coeff(1,0);
386  ret.coeffRef(2,2) = in.coeff(1,1);
387 
388  return ret;
389 }
390 
391 template <typename T>
393 {
394  Transform<T> ret;
395 
396  const Rotation<T> R = in.template block<3,3>(0,0);
397  ret.template block<3,3>(0,0) = openCvToLvr(R);
398 
399  ret.coeffRef(0,3) = in.coeff(2,3);
400  ret.coeffRef(1,3) = -in.coeff(0,3);
401  ret.coeffRef(2,3) = -in.coeff(1,3);
402 
403  ret.coeffRef(3,0) = in.coeff(3,2);
404  ret.coeffRef(3,1) = -in.coeff(3,0);
405  ret.coeffRef(3,2) = -in.coeff(3,1);
406 
407  ret.coeffRef(3,3) = in.coeff(3,3);
408 
409  return ret;
410 }
411 
412 
414 // 2) Lvr -> CS
416 
417 
418 
443 template <typename T>
445 {
446  return Vector3<T>(
447  -in.coeff(1) * static_cast<T>(100.0),
448  in.coeff(2) * static_cast<T>(100.0),
449  in.coeff(0) * static_cast<T>(100.0)
450  );
451 }
452 
453 template<typename T>
455 {
456  Rotation<T> ret;
457 
458  // use coeff functions to access elements without range check
459  // should be faster?
460 
461  // OLD CODE: why transpose?
462  // ret.coeffRef(0, 0) = in.coeff(1, 1); // in.coeff(1, 1)
463  // ret.coeffRef(0, 1) = -in.coeff(2, 1); // in.coeff(1, 2)
464  // ret.coeffRef(0, 2) = -in.coeff(0, 1); // in.coeff(1, 0)
465  // ret.coeffRef(1, 0) = -in.coeff(1, 2);
466  // ret.coeffRef(1, 1) = in.coeff(2, 2);
467  // ret.coeffRef(1, 2) = in.coeff(0, 2);
468  // ret.coeffRef(2, 0) = -in.coeff(1, 0);
469  // ret.coeffRef(2, 1) = in.coeff(2, 0);
470  // ret.coeffRef(2, 2) = in.coeff(0, 0);
471 
472  ret.coeffRef(0, 0) = in.coeff(1, 1); // in.coeff(1, 1)
473  ret.coeffRef(1, 0) = -in.coeff(2, 1); // in.coeff(1, 2)
474  ret.coeffRef(2, 0) = -in.coeff(0, 1); // in.coeff(1, 0)
475  ret.coeffRef(0, 1) = -in.coeff(1, 2);
476  ret.coeffRef(1, 1) = in.coeff(2, 2);
477  ret.coeffRef(2, 1) = in.coeff(0, 2);
478  ret.coeffRef(0, 2) = -in.coeff(1, 0);
479  ret.coeffRef(1, 2) = in.coeff(2, 0);
480  ret.coeffRef(2, 2) = in.coeff(0, 0);
481 
482  return ret;
483 }
484 
485 template <typename T>
487 {
488  Transform<T> ret;
489 
490  // Rotation
491  const Rotation<T> R = in.template block<3,3>(0,0);
492  ret.template block<3,3>(0,0) = lvrToSlam6d(R);
493 
494  // Translation
495  ret.coeffRef(0, 3) = -static_cast<T>(100.0) * in.coeff(1, 3);
496  ret.coeffRef(1, 3) = static_cast<T>(100.0) * in.coeff(2, 3);
497  ret.coeffRef(2, 3) = static_cast<T>(100.0) * in.coeff(0, 3);
498  ret.coeffRef(3, 0) = -static_cast<T>(100.0) * in.coeff(3, 1);
499  ret.coeffRef(3, 1) = static_cast<T>(100.0) * in.coeff(3, 2);
500  ret.coeffRef(3, 2) = static_cast<T>(100.0) * in.coeff(3, 0);
501 
502  ret.coeffRef(3, 3) = in.coeff(3, 3);
503 
504  return ret;
505 }
506 
507 
508 
537 template <typename T>
539 {
540  return Vector3<T>(
541  -in.coeff(1),
542  -in.coeff(2),
543  in.coeff(0)
544  );
545 }
546 
547 template <typename T>
549 {
550  Rotation<T> ret;
551 
552  ret.coeffRef(0,0) = in.coeff(1,1);
553  ret.coeffRef(0,1) = in.coeff(1,2);
554  ret.coeffRef(0,2) = -in.coeff(1,0);
555  ret.coeffRef(1,0) = in.coeff(2,1);
556  ret.coeffRef(1,1) = in.coeff(2,2);
557  ret.coeffRef(1,2) = -in.coeff(2,0);
558  ret.coeffRef(2,0) = -in.coeff(0,1);
559  ret.coeffRef(2,1) = -in.coeff(0,2);
560  ret.coeffRef(2,2) = in.coeff(0,0);
561 
562  return ret;
563 }
564 
565 template <typename T>
567 {
568  Transform<T> ret;
569 
570  const Rotation<T> R = in.template block<3,3>(0,0);
571  ret.template block<3,3>(0,0) = lvrToOpenCv(R);
572 
573  ret.coeffRef(0,3) = -in.coeff(1,3);
574  ret.coeffRef(1,3) = -in.coeff(2,3);
575  ret.coeffRef(2,3) = in.coeff(0,3);
576 
577  ret.coeffRef(3,0) = -in.coeff(3,1);
578  ret.coeffRef(3,1) = -in.coeff(3,2);
579  ret.coeffRef(3,2) = in.coeff(3,0);
580 
581  ret.coeffRef(3,3) = in.coeff(3,3);
582 
583  return ret;
584 }
585 
586 template<typename T>
588 {
589  T *m = mat.data();
590  if (pose != 0)
591  {
592  float _trX, _trY;
593  if (m[0] > 0.0)
594  {
595  pose[4] = asin(m[8]);
596  }
597  else
598  {
599  pose[4] = (float)M_PI - asin(m[8]);
600  }
601  // rPosTheta[1] = asin( m[8]); // Calculate Y-axis angle
602 
603  float C = cos(pose[4]);
604  if (fabs(C) > 0.005)
605  { // Gimball lock?
606  _trX = m[10] / C; // No, so get X-axis angle
607  _trY = -m[9] / C;
608  pose[3] = atan2(_trY, _trX);
609  _trX = m[0] / C; // Get Z-axis angle
610  _trY = -m[4] / C;
611  pose[5] = atan2(_trY, _trX);
612  }
613  else
614  { // Gimball lock has occurred
615  pose[3] = 0.0; // Set X-axis angle to zero
616  _trX = m[5]; //1 // And calculate Z-axis angle
617  _trY = m[1]; //2
618  pose[5] = atan2(_trY, _trX);
619  }
620 
621  // cout << pose[3] << " " << pose[4] << " " << pose[5] << endl;
622 
623  pose[0] = m[12];
624  pose[1] = m[13];
625  pose[2] = m[14];
626  }
627 }
628 
629 template<typename T>
630 void eigenToEuler(Transform<T>& mat, T* pose)
631 {
632  T *m = mat.data();
633  if (pose != 0)
634  {
635  float _trX, _trY;
636  if (m[0] > 0.0)
637  {
638  pose[4] = asin(m[8]);
639  }
640  else
641  {
642  pose[4] = (float)M_PI - asin(m[8]);
643  }
644  // rPosTheta[1] = asin( m[8]); // Calculate Y-axis angle
645 
646  float C = cos(pose[4]);
647  if (fabs(C) > 0.005)
648  { // Gimball lock?
649  _trX = m[10] / C; // No, so get X-axis angle
650  _trY = -m[9] / C;
651  pose[3] = atan2(_trY, _trX);
652  _trX = m[0] / C; // Get Z-axis angle
653  _trY = -m[4] / C;
654  pose[5] = atan2(_trY, _trX);
655  }
656  else
657  { // Gimball lock has occurred
658  pose[3] = 0.0; // Set X-axis angle to zero
659  _trX = m[5]; //1 // And calculate Z-axis angle
660  _trY = m[1]; //2
661  pose[5] = atan2(_trY, _trX);
662  }
663 
664  // cout << pose[3] << " " << pose[4] << " " << pose[5] << endl;
665 
666  pose[0] = m[12];
667  pose[1] = m[13];
668  pose[2] = m[14];
669  }
670 }
671 
672 
673 
674 } // namespace lvr2
675 
676 #include "TransformUtils.tcc"
677 
678 #endif
lvr2::slam6dToRieglTransform
static Transform< T > slam6dToRieglTransform(const Transform< T > &in)
Converts a transformation matrix that is used in slam6d coordinate system into a transformation matri...
Definition: TransformUtils.hpp:205
lvr2::transformRegistration
Transform< T > transformRegistration(const Transform< T > &transform, const Transform< T > &registration)
Transforms a registration matrix according to the given transformation matrix, i.e....
lvr2::inverseTransform
Transform< T > inverseTransform(const Transform< T > &transform)
Computes the inverse transformation from the given transformation matrix, which means if transform en...
transform
Definition: src/tools/lvr2_transform/Options.cpp:44
lvr2::extrinsicsToEuler
void extrinsicsToEuler(Extrinsics< T > mat, T *pose)
Definition: TransformUtils.hpp:587
lvr2::buildTransformation
Transform< T > buildTransformation(T *alignxf)
Transforms an slam6d transformation matrix into an Eigen 4x4 matrix.
lvr2::Rotation
Eigen::Matrix< T, 3, 3 > Rotation
General 3x3 rotation matrix.
Definition: MatrixTypes.hpp:75
CoordinateTransform.hpp
lvr2::getPoseFromMatrix
void getPoseFromMatrix(BaseVector< T > &position, BaseVector< T > &angles, const Transform< T > &mat)
Computes a Euler representation from the given transformation matrix.
M_PI
#define M_PI
Definition: Matrix4.hpp:52
lvr2::rieglToSLAM6DTransform
static Transform< T > rieglToSLAM6DTransform(const Transform< T > &in)
Converts a transformation matrix that is used in riegl coordinate system into a transformation matrix...
Definition: TransformUtils.hpp:172
lvr2::Transform
Eigen::Matrix< T, 4, 4 > Transform
General 4x4 transformation matrix (4x4)
Definition: MatrixTypes.hpp:65
lvr2::lvrToSlam6d
static Vector3< T > lvrToSlam6d(const Vector3< T > &in)
Lvr to Slam6D coordinate change: Point.
Definition: TransformUtils.hpp:444
lvr2::Extrinsics
Eigen::Matrix< T, 4, 4 > Extrinsics
4x4 extrinsic calibration
Definition: MatrixTypes.hpp:85
MatrixTypes.hpp
lvr2::Vector3
Eigen::Matrix< T, 3, 1 > Vector3
Eigen 3D vector.
Definition: MatrixTypes.hpp:115
lvr2::slam6DToRieglPoint
static Vector3< T > slam6DToRieglPoint(const Vector3< T > &in)
Definition: TransformUtils.hpp:230
Model.hpp
lvr2::eigenToEuler
void eigenToEuler(Transform< T > &mat, T *pose)
Definition: TransformUtils.hpp:630
lvr2::transformAndReducePointCloud
void transformAndReducePointCloud(ModelPtr model, int modulo, const T &sx, const T &sy, const T &sz, const unsigned char &xPos, const unsigned char &yPos, const unsigned char &zPos)
Transforms (scale and switch coordinates) and reduces a model containing point cloud data using a mod...
lvr2
Definition: BaseBufferManipulators.hpp:39
lvr2::ModelPtr
std::shared_ptr< Model > ModelPtr
Definition: Model.hpp:80
lvr2::openCvToLvr
static Vector3< T > openCvToLvr(const Vector3< T > &in)
OpenCV to Lvr coordinate change: Point.
Definition: TransformUtils.hpp:364
lvr2::slam6dToLvr
static Vector3< T > slam6dToLvr(const Vector3< T > &in)
Slam6D to LVR coordinate change: Point.
Definition: TransformUtils.hpp:273
lvr2::matrixToPose
void matrixToPose(const Transform< T > &mat, Vector3< T > &position, Vector3< T > &rotation)
Extracts the Pose from a Matrix.
lvr2::transformPointCloud
void transformPointCloud(ModelPtr model, const Transform< T > &transformation)
Transforms a model containing a point cloud according to the given transformation (usually from a ....
lvr2::transformFrame
Transform< T > transformFrame(const Transform< T > &frame, const CoordinateTransform< T > &ct)
Transforms the given source frame according to the given coordinate transform struct.
lvr2::poseToMatrix
Transform< T > poseToMatrix(const Vector3< T > &position, const Vector3< T > &rotation)
Converts a Pose to a Matrix.
lvr2::lvrToOpenCv
static Vector3< T > lvrToOpenCv(const Vector3< T > &in)
Lvr to OpenCV coordinate change: Point.
Definition: TransformUtils.hpp:538


lvr2
Author(s): Thomas Wiemann , Sebastian Pütz , Alexander Mock , Lars Kiesow , Lukas Kalbertodt , Tristan Igelbrink , Johan M. von Behren , Dominik Feldschnieders , Alexander Löhr
autogenerated on Wed Mar 2 2022 00:37:25