libxr  1.0
Want to be the best embedded framework
Loading...
Searching...
No Matches
transform.hpp
1#pragma once
2
3#ifndef LIBXR_NO_EIGEN
4
5#include <Eigen/Core>
6#include <Eigen/Dense>
7#include <cmath>
8
9namespace LibXR
10{
11
12using DefaultScalar = LIBXR_DEFAULT_SCALAR;
13
14template <typename Scalar = DefaultScalar>
15class Position;
16template <typename Scalar = DefaultScalar>
17class Axis;
18template <typename Scalar = DefaultScalar>
19class RotationMatrix;
20template <typename Scalar = DefaultScalar>
21class EulerAngle;
22template <typename Scalar = DefaultScalar>
23class Quaternion;
24
37template <typename Scalar>
38class Position : public Eigen::Matrix<Scalar, 3, 1>
39{
40 public:
45 Position() : Eigen::Matrix<Scalar, 3, 1>(0, 0, 0) {}
46
54 Position(Scalar x, Scalar y, Scalar z) : Eigen::Matrix<Scalar, 3, 1>(x, y, z) {}
55
60 Position(const Eigen::Matrix<Scalar, 3, 1> &p) : Eigen::Matrix<Scalar, 3, 1>(p) {}
61
66 Position(const Position &p) : Eigen::Matrix<Scalar, 3, 1>(p) {}
67
74 template <typename T, std::enable_if_t<std::is_same<T, Scalar>::value ||
75 std::is_same<T, float>::value ||
76 std::is_same<T, double>::value,
77 int> = 0>
78 Position(const T (&data)[3]) : Eigen::Matrix<Scalar, 3, 1>(data)
79 {
80 }
81
88 Position &operator=(const Eigen::Matrix<Scalar, 3, 1> &p)
89 {
90 this->data()[0] = p[0];
91 this->data()[1] = p[1];
92 this->data()[2] = p[2];
93 return *this;
94 }
95
103 {
104 if (this != &p)
105 {
106 this->data()[0] = p[0];
107 this->data()[1] = p[1];
108 this->data()[2] = p[2];
109 }
110
111 return *this;
112 }
113
120 template <
121 typename Rotation,
122 std::enable_if_t<std::is_same<Rotation, RotationMatrix<Scalar>>::value ||
123 std::is_same<Rotation, Eigen::Matrix<Scalar, 3, 3>>::value ||
124 std::is_same<Rotation, Quaternion<Scalar>>::value ||
125 std::is_same<Rotation, Eigen::Quaternion<Scalar>>::value,
126 int> = 0>
127 Eigen::Matrix<Scalar, 3, 1> operator*(const Rotation &R) const
128 {
129 return R * (*this);
130 }
131
139 template <
140 typename Rotation,
141 std::enable_if_t<std::is_same<Rotation, RotationMatrix<Scalar>>::value ||
142 std::is_same<Rotation, Eigen::Matrix<Scalar, 3, 3>>::value ||
143 std::is_same<Rotation, Quaternion<Scalar>>::value ||
144 std::is_same<Rotation, Eigen::Quaternion<Scalar>>::value,
145 int> = 0>
146 const Position &operator*=(const Rotation &R)
147 {
148 *this = R * (*this);
149 return *this;
150 }
151
157 Eigen::Matrix<Scalar, 3, 1> operator/(const RotationMatrix<Scalar> &R) const
158 {
159 return (-R) * (*this);
160 }
161
169 {
170 *this = (-q) * (*this);
171 return *this;
172 }
173
180 const Position &operator/=(const Eigen::Matrix<Scalar, 3, 3> &R)
181 {
182 *this = R.transpose() * Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(this->data_);
183 return *this;
184 }
185
192 const Position &operator/=(const Eigen::Quaternion<Scalar> &q)
193 {
194 *this = q.conjugate() * Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(this->data_);
195 return *this;
196 }
197
203 const Position &operator*=(Scalar s)
204 {
205 *this = s * (*this);
206 return *this;
207 }
208
214 const Position &operator/=(Scalar s)
215 {
216 (*this)[0] /= s;
217 (*this)[1] /= s;
218 (*this)[2] /= s;
219 return *this;
220 }
221
228 Eigen::Quaternion<Scalar> operator/(const Position<> &p)
229 {
230 return Eigen::Quaternion<Scalar>::FromTwoVectors(p, *this);
231 }
232};
233
246template <typename Scalar>
247class Axis : public Eigen::Matrix<Scalar, 3, 1>
248{
249 public:
254 Axis() : Eigen::Matrix<Scalar, 3, 1>(0, 0, 0) {}
255
264 Axis(Scalar x, Scalar y, Scalar z) : Eigen::Matrix<Scalar, 3, 1>(x, y, z) {}
265
272 Axis(const Axis &p) : Eigen::Matrix<Scalar, 3, 1>(p) {}
273
280 static Axis X() { return Axis(1., 0., 0.); }
281
288 static Axis Y() { return Axis(0., 1., 0.); }
289
296 static Axis Z() { return Axis(0., 0., 1.); }
297
312 Axis<Scalar> &operator=(const Eigen::Matrix<Scalar, 3, 1> &p)
313 {
314 this->data()[0] = p[0];
315 this->data()[1] = p[1];
316 this->data()[2] = p[2];
317 return *this;
318 }
319
332 {
333 if (this != &p)
334 {
335 this->data()[0] = p[0];
336 this->data()[1] = p[1];
337 this->data()[2] = p[2];
338 }
339 return *this;
340 }
341};
342
348template <typename Scalar>
350{
351 public:
352 Scalar data_[3];
353
356 EulerAngle() : data_{0, 0, 0} {}
357
365 EulerAngle(Scalar roll, Scalar pitch, Scalar yaw) : data_{roll, pitch, yaw} {}
366
372 EulerAngle(const Eigen::Matrix<Scalar, 3, 1> &p) : data_{p.x(), p.y(), p.z()} {}
373
378 EulerAngle(const EulerAngle &p) : data_{p.data_[0], p.data_[1], p.data_[2]} {}
379
380 Scalar &Roll() noexcept { return data_[0]; }
381 const Scalar &Roll() const noexcept { return data_[0]; }
382 Scalar &Pitch() noexcept { return data_[1]; }
383 const Scalar &Pitch() const noexcept { return data_[1]; }
384 Scalar &Yaw() noexcept { return data_[2]; }
385 const Scalar &Yaw() const noexcept { return data_[2]; }
386
394 template <typename T, std::enable_if_t<std::is_same<T, Scalar>::value ||
395 std::is_same<T, float>::value ||
396 std::is_same<T, double>::value,
397 int> = 0>
398 EulerAngle(const T (&data)[3]) : data_{data[0], data[1], data[2]}
399 {
400 }
401
403 operator Eigen::Matrix<Scalar, 3, 1>() const
404 {
405 return Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(data_);
406 }
407
409 Scalar operator()(int i) const { return data_[i]; }
410
413 EulerAngle &operator=(const Eigen::Matrix<Scalar, 3, 1> &p)
414 {
415 data_[0] = p(0);
416 data_[1] = p(1);
417 data_[2] = p(2);
418 return *this;
419 }
420
424 {
425 if (this != &p)
426 {
427 data_[0] = p.data_[0];
428 data_[1] = p.data_[1];
429 data_[2] = p.data_[2];
430 }
431 return *this;
432 }
433
436 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrix() const { return ToRotationMatrixZYX(); }
437
438 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixZYX() const
439 {
440 Scalar ca = std::cos(Yaw()), cb = std::cos(Pitch()), cc = std::cos(Roll());
441 Scalar sa = std::sin(Yaw()), sb = std::sin(Pitch()), sc = std::sin(Roll());
442
443 return (Eigen::Matrix<Scalar, 3, 3>() << ca * cb, ca * sb * sc - cc * sa,
444 sa * sc + ca * cc * sb, cb * sa, ca * cc + sa * sb * sc,
445 cc * sa * sb - ca * sc, -sb, cb * sc, cb * cc)
446 .finished();
447 }
448
449 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixZXY() const
450 {
451 Scalar ca = std::cos(Yaw()), cb = std::cos(Roll()), cc = std::cos(Pitch());
452 Scalar sa = std::sin(Yaw()), sb = std::sin(Roll()), sc = std::sin(Pitch());
453
454 return (Eigen::Matrix<Scalar, 3, 3>() << ca * cc - sa * sb * sc, -cb * sa,
455 ca * sc + cc * sa * sb, cc * sa + ca * sb * sc, ca * cb,
456 sa * sc - ca * cc * sb, -cb * sc, sb, cb * cc)
457 .finished();
458 }
459
460 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixYXZ() const
461 {
462 Scalar ca = std::cos(Pitch()), cb = std::cos(Roll()), cc = std::cos(Yaw());
463 Scalar sa = std::sin(Pitch()), sb = std::sin(Roll()), sc = std::sin(Yaw());
464
465 return (Eigen::Matrix<Scalar, 3, 3>() << ca * cc + sa * sb * sc,
466 cc * sa * sb - ca * sc, cb * sa, cb * sc, cb * cc, -sb,
467 ca * sb * sc - cc * sa, sa * sc + ca * cc * sb, ca * cb)
468 .finished();
469 }
470
471 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixYZX() const
472 {
473 Scalar ca = std::cos(Pitch()), cb = std::cos(Yaw()), cc = std::cos(Roll());
474 Scalar sa = std::sin(Pitch()), sb = std::sin(Yaw()), sc = std::sin(Roll());
475
476 return (Eigen::Matrix<Scalar, 3, 3>() << ca * cb, sa * sc - ca * cc * sb,
477 cc * sa + ca * sb * sc, sb, cb * cc, -cb * sc, -cb * sa,
478 ca * sc + cc * sa * sb, ca * cc - sa * sb * sc)
479 .finished();
480 }
481
482 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixXYZ() const
483 {
484 Scalar ca = std::cos(Roll()), cb = std::cos(Pitch()), cc = std::cos(Yaw());
485 Scalar sa = std::sin(Roll()), sb = std::sin(Pitch()), sc = std::sin(Yaw());
486
487 return (Eigen::Matrix<Scalar, 3, 3>() << cb * cc, -cb * sc, sb,
488 ca * sc + cc * sa * sb, ca * cc - sa * sb * sc, -cb * sa,
489 sa * sc - ca * cc * sb, cc * sa + ca * sb * sc, ca * cb)
490 .finished();
491 }
492
493 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixXZY() const
494 {
495 Scalar ca = std::cos(Roll()), cb = std::cos(Yaw()), cc = std::cos(Pitch());
496 Scalar sa = std::sin(Roll()), sb = std::sin(Yaw()), sc = std::sin(Pitch());
497
498 return (Eigen::Matrix<Scalar, 3, 3>() << cb * cc, -sb, cb * sc,
499 sa * sc + ca * cc * sb, ca * cb, ca * sb * sc - cc * sa,
500 cc * sa * sb - ca * sc, cb * sa, ca * cc + sa * sb * sc)
501 .finished();
502 }
503
504 Eigen::Quaternion<Scalar> ToQuaternion() const { return ToQuaternionZYX(); }
505
506#if 0
507 Eigen::Quaternion<Scalar> ToQuaternionXYZ() const {
508 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
509 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
510 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
511 return rollAngle * pitchAngle * yawAngle;
512 }
513
514 Eigen::Quaternion<Scalar> ToQuaternionXZY() const {
515 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
516 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
517 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
518 return rollAngle * yawAngle * pitchAngle;
519 }
520
521 Eigen::Quaternion<Scalar> ToQuaternionYXZ() const {
522 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
523 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
524 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
525 return pitchAngle * rollAngle * yawAngle;
526 }
527
528 Eigen::Quaternion<Scalar> ToQuaternionYZX() const {
529 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
530 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
531 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
532 return pitchAngle * yawAngle * rollAngle;
533 }
534
535 Eigen::Quaternion<Scalar> ToQuaternionZXY() const {
536 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
537 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
538 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
539 return yawAngle * rollAngle * pitchAngle;
540 }
541
542 Eigen::Quaternion<Scalar> ToQuaternionZYX() const {
543 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
544 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
545 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
546 return yawAngle * pitchAngle * rollAngle;
547 }
548#endif
549
552 Eigen::Quaternion<Scalar> ToQuaternionXYZ() const
553 {
554 return Eigen::Quaternion<Scalar>(ToRotationMatrixXYZ());
555 }
556
557 Eigen::Quaternion<Scalar> ToQuaternionXZY() const
558 {
559 return Eigen::Quaternion<Scalar>(ToRotationMatrixXZY());
560 }
561
562 Eigen::Quaternion<Scalar> ToQuaternionYXZ() const
563 {
564 return Eigen::Quaternion<Scalar>(ToRotationMatrixYXZ());
565 }
566
567 Eigen::Quaternion<Scalar> ToQuaternionYZX() const
568 {
569 return Eigen::Quaternion<Scalar>(ToRotationMatrixYZX());
570 }
571
572 Eigen::Quaternion<Scalar> ToQuaternionZXY() const
573 {
574 return Eigen::Quaternion<Scalar>(ToRotationMatrixZXY());
575 }
576
577 Eigen::Quaternion<Scalar> ToQuaternionZYX() const
578 {
579 return Eigen::Quaternion<Scalar>(ToRotationMatrixZYX());
580 }
581};
582
597template <typename Scalar>
598class RotationMatrix : public Eigen::Matrix<Scalar, 3, 3>
599{
600 public:
605 RotationMatrix() : Eigen::Matrix<Scalar, 3, 3>()
606 {
607 (*this) << 1, 0, 0, 0, 1, 0, 0, 0, 1;
608 }
609
616 RotationMatrix(Scalar r00, Scalar r01, Scalar r02, Scalar r10, Scalar r11, Scalar r12,
617 Scalar r20, Scalar r21, Scalar r22)
618 : Eigen::Matrix<Scalar, 3, 3>()
619 {
620 (*this) << r00, r01, r02, r10, r11, r12, r20, r21, r22;
621 }
622
629 RotationMatrix(const Eigen::Matrix<Scalar, 3, 3> &R) : Eigen::Matrix<Scalar, 3, 3>{R} {}
630
637 RotationMatrix(const Eigen::Quaternion<Scalar> &q)
638 : Eigen::Matrix<Scalar, 3, 3>{q.ToRotationMatrix()}
639 {
640 }
641
649
650 template <typename T, std::enable_if_t<std::is_same<T, Scalar>::value ||
651 std::is_same<T, float>::value ||
652 std::is_same<T, double>::value,
653 int> = 0>
654 RotationMatrix(const T (&data)[9]) : Eigen::Matrix<Scalar, 3, 3>()
655 {
656 (*this) << data[0], data[1], data[2], data[3], data[4], data[5], data[6], data[7],
657 data[8];
658 }
659
660 template <typename T, std::enable_if_t<std::is_same<T, Scalar>::value ||
661 std::is_same<T, float>::value ||
662 std::is_same<T, double>::value,
663 int> = 0>
664 RotationMatrix(const T (&data)[3][3]) : Eigen::Matrix<Scalar, 3, 3>()
665 {
666 (*this) << data[0][0], data[0][1], data[0][2], data[1][0], data[1][1], data[1][2],
667 data[2][0], data[2][1], data[2][2];
668 }
669
676 Eigen::Matrix<Scalar, 3, 3> operator-() const { return this->transpose(); }
677
688 {
689 if (this != &R)
690 {
691 this->data()[0] = R.data()[0];
692 this->data()[1] = R.data()[1];
693 this->data()[2] = R.data()[2];
694 this->data()[3] = R.data()[3];
695 this->data()[4] = R.data()[4];
696 this->data()[5] = R.data()[5];
697 this->data()[6] = R.data()[6];
698 this->data()[7] = R.data()[7];
699 this->data()[8] = R.data()[8];
700 }
701 return *this;
702 }
703
704 RotationMatrix &operator=(const Eigen::Matrix<Scalar, 3, 3> &R)
705 {
706 this->data()[0] = R.data()[0];
707 this->data()[1] = R.data()[1];
708 this->data()[2] = R.data()[2];
709 this->data()[3] = R.data()[3];
710 this->data()[4] = R.data()[4];
711 this->data()[5] = R.data()[5];
712 this->data()[6] = R.data()[6];
713 this->data()[7] = R.data()[7];
714 this->data()[8] = R.data()[8];
715 return *this;
716 }
717
718 RotationMatrix &operator=(const Eigen::Quaternion<Scalar> &q)
719 {
720 *this = q.ToRotationMatrix();
721 return *this;
722 }
723
724 RotationMatrix &operator=(const Quaternion<Scalar> &q)
725 {
726 *this = q.ToRotationMatrix();
727 return *this;
728 }
729
730 Position<Scalar> operator*(const Position<Scalar> &p) const
731 {
732 return Position<Scalar>((*this) * Eigen::Matrix<Scalar, 3, 1>(p));
733 }
734
742 Eigen::Matrix<Scalar, 3, 1> operator*(const Eigen::Matrix<Scalar, 3, 1> &p) const
743 {
744 return static_cast<Eigen::Matrix<Scalar, 3, 3>>(*this) * p;
745 }
746
755 {
756 const Eigen::Matrix<Scalar, 3, 3> &a =
757 static_cast<const Eigen::Matrix<Scalar, 3, 3> &>(*this);
758 const Eigen::Matrix<Scalar, 3, 3> &b =
759 static_cast<const Eigen::Matrix<Scalar, 3, 3> &>(rhs);
760 return RotationMatrix(a * b);
761 }
762
773 Eigen::Matrix<Scalar, 3, 1> ToEulerAngle() const { return ToEulerAngleZYX(); }
774
775 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZYX() const
776 {
777 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
778
779 Scalar roll = std::atan2(r(2, 1), r(2, 2));
780 Scalar yaw = std::atan2(r(1, 0), r(0, 0));
781 Scalar pitch = std::asin(-r(2, 0));
782
783 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
784 }
785
786 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXZY() const
787 {
788 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
789
790 Scalar roll = std::atan2(r(2, 1), r(1, 1));
791 Scalar yaw = std::asin(-r(0, 1));
792 Scalar pitch = std::atan2(r(0, 2), r(0, 0));
793
794 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
795 }
796
797 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYZX() const
798 {
799 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
800
801 Scalar pitch = std::atan2(-r(2, 0), r(0, 0));
802 Scalar yaw = std::asin(r(1, 0));
803 Scalar roll = std::atan2(-r(1, 2), r(1, 1));
804
805 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
806 }
807
808 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYXZ() const
809 {
810 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
811
812 Scalar pitch = std::atan2(r(0, 2), r(2, 2));
813 Scalar roll = std::asin(-r(1, 2));
814 Scalar yaw = std::atan2(r(1, 0), r(1, 1));
815
816 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
817 }
818
819 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZXY() const
820 {
821 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
822
823 Scalar roll = std::asin(r(2, 1));
824 Scalar yaw = std::atan2(r(1, 1), -r(0, 1));
825 Scalar pitch = std::atan2(-r(2, 0), r(2, 2));
826
827 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
828 }
829
830 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXYZ() const
831 {
832 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
833
834 Scalar yaw = std::atan2(-r(0, 1), r(0, 0));
835 Scalar pitch = std::asin(r(0, 2));
836 Scalar roll = std::atan2(-r(1, 2), r(2, 2));
837
838 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
839 }
840};
841
855template <typename Scalar>
856class Quaternion : public Eigen::Quaternion<Scalar>
857{
858 public:
863 Quaternion() : Eigen::Quaternion<Scalar>(1, 0, 0, 0) {}
864
872 Quaternion(Scalar w, Scalar x, Scalar y, Scalar z)
873 : Eigen::Quaternion<Scalar>(w, x, y, z)
874 {
875 }
876
881 Quaternion(const Eigen::Quaternion<Scalar> &q) : Eigen::Quaternion<Scalar>(q) {}
882
888 : Eigen::Quaternion<Scalar>(
889 Eigen::Quaternion<Scalar>(static_cast<Eigen::Matrix<Scalar, 3, 3>>(R)))
890 {
891 }
892
898 Quaternion(const Eigen::Matrix<Scalar, 3, 3> R)
899 : Eigen::Quaternion<Scalar>(
900 Eigen::Quaternion<Scalar>(static_cast<Eigen::Matrix<Scalar, 3, 3>>(R)))
901 {
902 }
903
908 template <typename T, std::enable_if_t<std::is_same<T, Scalar>::value ||
909 std::is_same<T, float>::value ||
910 std::is_same<T, double>::value,
911 int> = 0>
912 Quaternion(const T (&data)[4]) : Eigen::Quaternion<Scalar>(data)
913 {
914 }
915
921 Scalar operator()(int i) const
922 {
923 switch (i)
924 {
925 case 3:
926 return this->w();
927 case 0:
928 return this->x();
929 case 1:
930 return this->y();
931 case 2:
932 return this->z();
933 default:
934 return 0;
935 }
936 }
937
943 Quaternion &operator=(const Eigen::Quaternion<Scalar> &q)
944 {
945 *this = Quaternion(q);
946 return *this;
947 }
948
953 Quaternion operator-() const { return Quaternion((*this).conjugate()); }
954
961 {
962 return Quaternion(this->w() + q.w(), this->x() + q.x(), this->y() + q.y(),
963 this->z() + q.z());
964 }
965
966 Quaternion operator+(const Eigen::Quaternion<Scalar> &q) const
967 {
968 return Quaternion(this->w() + q.w(), this->x() + q.x(), this->y() + q.y(),
969 this->z() + q.z());
970 }
971
972 Quaternion operator-(const Quaternion &q) const
973 {
974 return Quaternion(this->w() - q.w(), this->x() - q.x(), this->y() - q.y(),
975 this->z() - q.z());
976 }
977
978 Quaternion operator-(const Eigen::Quaternion<Scalar> &q) const
979 {
980 return Quaternion(this->w() - q.w(), this->x() - q.x(), this->y() - q.y(),
981 this->z() - q.z());
982 }
983
990 {
991 return Eigen::Quaternion<Scalar>(*this) * Eigen::Quaternion<Scalar>(q);
992 }
993
994 Quaternion operator*(const Eigen::Quaternion<Scalar> &q) const
995 {
996 return Eigen::Quaternion<Scalar>(*this) * q;
997 }
998
1005 Quaternion operator/(const Quaternion &q) const { return (*this) * (-q); }
1006
1007 Quaternion operator/(const Eigen::Quaternion<Scalar> &q) const
1008 {
1009 return (*this) * (-q);
1010 }
1011
1012 template <typename Q,
1013 std::enable_if_t<std::is_same<Q, Quaternion>::value ||
1014 std::is_same<Q, Eigen::Quaternion<Scalar>>::value,
1015 int> = 0>
1016 const Quaternion &operator+=(const Q &q)
1017 {
1018 *this = *this + q;
1019 return *this;
1020 }
1021
1022 template <typename Q,
1023 std::enable_if_t<std::is_same<Q, Quaternion>::value ||
1024 std::is_same<Q, Eigen::Quaternion<Scalar>>::value,
1025 int> = 0>
1026 const Quaternion &operator-=(const Q &q)
1027 {
1028 *this = *this - q;
1029 return *this;
1030 }
1031
1038 {
1039 return Eigen::Quaternion<Scalar>(*this) * Eigen::Matrix<Scalar, 3, 1>(p);
1040 }
1041
1053 Eigen::Matrix<Scalar, 3, 1> ToEulerAngle() const { return ToEulerAngleZYX(); }
1054
1055 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYZX() const
1056 {
1057 Scalar roll = std::atan2(2 * this->w() * this->x() - 2 * this->y() * this->z(),
1058 1 - 2 * (this->x() * this->x() + this->z() * this->z()));
1059 Scalar pitch = std::atan2(2 * this->w() * this->y() - 2 * this->x() * this->z(),
1060 1 - 2 * (this->y() * this->y() + this->z() * this->z()));
1061 Scalar yaw = std::asin(2 * (this->w() * this->z() + this->x() * this->y()));
1062 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1063 }
1064
1065 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZYX() const
1066 {
1067 Scalar yaw = std::atan2(2 * (this->w() * this->z() + this->x() * this->y()),
1068 1 - 2 * (this->z() * this->z() + this->y() * this->y()));
1069 Scalar pitch = std::asin(2 * (this->w() * this->y() - this->x() * this->z()));
1070 Scalar roll = std::atan2(2 * (this->w() * this->x() + this->y() * this->z()),
1071 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1072 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1073 }
1074
1075 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYXZ() const
1076 {
1077 Scalar roll = std::asin(2 * (this->w() * this->x() - this->y() * this->z()));
1078 Scalar yaw = std::atan2(2 * (this->w() * this->z() + this->x() * this->y()),
1079 1 - 2 * (this->z() * this->z() + this->x() * this->x()));
1080 Scalar pitch = std::atan2(2 * (this->x() * this->z() + this->w() * this->y()),
1081 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1082 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1083 }
1084
1085 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZXY() const
1086 {
1087 Scalar pitch = std::atan2(-2 * (this->x() * this->z() - this->w() * this->y()),
1088 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1089 Scalar roll = std::asin(2 * (this->w() * this->x() + this->y() * this->z()));
1090 Scalar yaw = std::atan2(-2 * (this->x() * this->y() - this->w() * this->z()),
1091 1 - 2 * (this->z() * this->z() + this->x() * this->x()));
1092 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1093 }
1094
1095 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXZY() const
1096 {
1097 Scalar pitch = std::atan2(2 * (this->w() * this->y() + this->x() * this->z()),
1098 1 - 2 * (this->z() * this->z() + this->y() * this->y()));
1099 Scalar yaw = std::asin(2 * (this->w() * this->z() - this->x() * this->y()));
1100 Scalar roll = std::atan2(2 * (this->w() * this->x() + this->y() * this->z()),
1101 1 - 2 * (this->z() * this->z() + this->x() * this->x()));
1102 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1103 }
1104
1105 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXYZ() const
1106 {
1107 Scalar yaw = std::atan2(-2 * (this->x() * this->y() - this->w() * this->z()),
1108 1 - 2 * (this->z() * this->z() + this->y() * this->y()));
1109 Scalar pitch = std::asin(2 * (this->w() * this->y() + this->x() * this->z()));
1110 Scalar roll = std::atan2(-2 * (this->y() * this->z() - this->w() * this->x()),
1111 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1112 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1113 }
1114
1125 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrix() const
1126 {
1127 return Eigen::Matrix<Scalar, 3, 3>(*this);
1128 }
1129};
1130
1137template <typename Scalar = DefaultScalar>
1139{
1140 public:
1145
1148 Transform() = default;
1149
1160
1168 {
1169 rotation = q;
1170 return *this;
1171 }
1172
1179 Transform &operator=(const Eigen::AngleAxis<Scalar> &a)
1180 {
1181 rotation = a;
1182 return *this;
1183 }
1184
1192 {
1193 translation = p;
1194 return *this;
1195 }
1196
1204 {
1205 return Transform(Eigen::Quaternion<Scalar>(rotation * t.rotation),
1206 Eigen::Matrix<Scalar, 3, 1>(translation + rotation * t.translation));
1207 }
1208
1216 {
1218 }
1219};
1220
1221} // namespace LibXR
1222
1223#endif
三维坐标轴类,继承自 Eigen::Matrix<Scalar, 3, 1>。 A 3D axis class, inheriting from Eigen::Matrix<Scalar,...
static Axis X()
返回 X 轴单位向量 (1,0,0)。 Returns the unit vector along the X-axis (1,0,0).
Axis< Scalar > & operator=(const Eigen::Matrix< Scalar, 3, 1 > &p)
赋值运算符重载,将 Eigen::Matrix<Scalar, 3, 1> 赋值给 Axis 对象。 Overloaded assignment operator to assign an Eigen:...
static Axis Z()
返回 Z 轴单位向量 (0,0,1)。 Returns the unit vector along the Z-axis (0,0,1).
Axis()
默认构造函数,将向量初始化为 (0,0,0)。 Default constructor initializing the vector to (0,0,0).
static Axis Y()
返回 Y 轴单位向量 (0,1,0)。 Returns the unit vector along the Y-axis (0,1,0).
Axis(Scalar x, Scalar y, Scalar z)
通过 (x, y, z) 坐标值构造轴向量。 Constructs an axis vector using (x, y, z) coordinates.
Axis< Scalar > & operator=(const Axis &p)
赋值运算符重载,将另一个 Axis 对象赋值给当前对象。 Overloaded assignment operator to assign another Axis object to this obj...
Axis(const Axis &p)
拷贝构造函数,复制另一个 Axis 对象。 Copy constructor to duplicate another Axis object.
表示欧拉角的类,用于描述3D旋转。Class representing Euler angles for 3D rotation.
Eigen::Matrix< Scalar, 3, 3 > ToRotationMatrix() const
转换为旋转矩阵,默认使用 ZYX 顺序。Converts to a rotation matrix using the ZYX order by default.
EulerAngle & operator=(const Eigen::Matrix< Scalar, 3, 1 > &p)
赋值运算符,从 Eigen 3D 向量赋值。Assignment operator from an Eigen 3D vector.
Scalar data_[3]
存储欧拉角的数组。Array storing Euler angles.
EulerAngle(const Eigen::Matrix< Scalar, 3, 1 > &p)
通过 Eigen 3D 向量构造欧拉角对象。Constructs an Euler angle object using an Eigen 3D vector.
EulerAngle()
默认构造函数,初始化所有角度为零。Default constructor initializing all angles to zero.
Eigen::Quaternion< Scalar > ToQuaternionXYZ() const
转换为四元数,默认使用 ZYX 顺序。Converts to a quaternion using the ZYX order by default.
EulerAngle & operator=(const EulerAngle &p)
赋值运算符,从另一个 EulerAngle 赋值。Assignment operator from another EulerAngle.
EulerAngle(Scalar roll, Scalar pitch, Scalar yaw)
使用指定角度构造欧拉角对象。Constructs an Euler angle object with given angles.
EulerAngle(const T(&data)[3])
通过 3 元素数组构造欧拉角对象。Constructs an Euler angle object using a 3-element array.
Scalar operator()(int i) const
获取欧拉角的某个分量。Retrieves a specific Euler angle component.
EulerAngle(const EulerAngle &p)
拷贝构造函数。Copy constructor.
三维空间中的位置向量 / 3D position vector
Definition transform.hpp:39
const Position & operator/=(const Eigen::Quaternion< Scalar > &q)
逆四元数变换并更新当前向量 / Apply inverse quaternion transformation and update the current vector
const Position & operator*=(Scalar s)
按标量缩放当前向量 / Scale the current vector by a scalar
Position()
默认构造函数,初始化为 (0,0,0) / Default constructor initializing to (0,0,0)
Definition transform.hpp:45
Position & operator=(const Position &p)
赋值运算符,将 Eigen 向量赋值给 Position / Assignment operator to assign an Eigen vector to Position
Eigen::Matrix< Scalar, 3, 1 > operator*(const Rotation &R) const
赋值运算符,将另一个 Position 赋值给当前对象 / Assignment operator to assign another Position to this object
Position(Scalar x, Scalar y, Scalar z)
构造函数,指定 x, y, z 坐标 / Constructor specifying x, y, z coordinates
Definition transform.hpp:54
const Position & operator/=(Scalar s)
按标量除法缩放当前向量 / Scale the current vector by dividing with a scalar
Position(const T(&data)[3])
乘以旋转矩阵 / Multiply by a rotation matrix
Definition transform.hpp:78
Eigen::Quaternion< Scalar > operator/(const Position<> &p)
计算从另一个 Position 到当前 Position 的旋转四元数 / Compute the quaternion rotation from another Position to the cu...
const Position & operator/=(const Eigen::Matrix< Scalar, 3, 3 > &R)
逆旋转矩阵变换并更新当前向量 / Apply inverse rotation matrix transformation and update the current vector
Position(const Position &p)
复制构造函数 / Copy constructor
Definition transform.hpp:66
Position(const Eigen::Matrix< Scalar, 3, 1 > &p)
复制构造函数 / Copy constructor
Definition transform.hpp:60
const Position & operator/=(const Quaternion< Scalar > &q)
逆四元数旋转并更新当前向量 / Apply inverse quaternion rotation and update the current vector
const Position & operator*=(const Rotation &R)
旋转并更新当前向量 / Rotate and update the current vector
Position & operator=(const Eigen::Matrix< Scalar, 3, 1 > &p)
赋值运算符,将 Eigen 向量赋值给 Position / Assignment operator to assign an Eigen vector to Position
Definition transform.hpp:88
Eigen::Matrix< Scalar, 3, 1 > operator/(const RotationMatrix< Scalar > &R) const
旋转矩阵的逆变换 / Inverse transformation using a rotation matrix
四元数表示与运算,继承自 Eigen::Quaternion / Quaternion representation and operations, inheriting from Eigen::Qua...
Eigen::Matrix< Scalar, 3, 1 > ToEulerAngle() const
获取四元数的欧拉角表示(默认使用 ZYX 旋转顺序) Get the Euler angles representation of the quaternion (default ZYX order)
Quaternion(const Eigen::Quaternion< Scalar > &q)
复制构造函数 / Copy constructor
Quaternion operator-() const
取共轭四元数 / Get the conjugate quaternion
Quaternion operator+(const Quaternion &q) const
四元数加法 / Quaternion addition
Scalar operator()(int i) const
获取四元数的分量 / Retrieve a specific component of the quaternion
Quaternion(const RotationMatrix< Scalar > &R)
通过旋转矩阵构造四元数 / Construct a quaternion from a rotation matrix
Quaternion operator*(const Quaternion &q) const
四元数乘法 / Quaternion multiplication
Quaternion(Scalar w, Scalar x, Scalar y, Scalar z)
通过四个分量初始化四元数 / Construct a quaternion using four components
Quaternion(const Eigen::Matrix< Scalar, 3, 3 > R)
通过 3x3 旋转矩阵构造四元数 / Construct a quaternion from a 3x3 rotation matrix
Quaternion()
默认构造函数,初始化为单位四元数 / Default constructor initializing to an identity quaternion
Quaternion operator/(const Quaternion &q) const
四元数除法(即左乘其共轭) / Quaternion division (multiplication by its conjugate)
Quaternion(const T(&data)[4])
通过四维数组初始化四元数 / Construct a quaternion from a 4-element array
Quaternion & operator=(const Eigen::Quaternion< Scalar > &q)
赋值运算符 / Assignment operator
Position< Scalar > operator*(const Position< Scalar > &p) const
旋转三维向量 / Rotate a 3D vector
Eigen::Matrix< Scalar, 3, 3 > ToRotationMatrix() const
将四元数转换为 3x3 旋转矩阵 / Convert the quaternion to a 3x3 rotation matrix
旋转矩阵类,继承自 Eigen::Matrix<Scalar, 3, 3>。 Rotation matrix class, inheriting from Eigen::Matrix<Scalar,...
RotationMatrix(const Eigen::Quaternion< Scalar > &q)
通过 Eigen 四元数构造旋转矩阵。 Constructs a rotation matrix from an Eigen quaternion.
RotationMatrix(Scalar r00, Scalar r01, Scalar r02, Scalar r10, Scalar r11, Scalar r12, Scalar r20, Scalar r21, Scalar r22)
通过 9 个矩阵元素的值构造旋转矩阵。 Constructs a rotation matrix using 9 matrix elements.
Eigen::Matrix< Scalar, 3, 1 > operator*(const Eigen::Matrix< Scalar, 3, 1 > &p) const
计算旋转矩阵与三维向量的乘积。 Computes the product of the rotation matrix and a 3D vector.
RotationMatrix operator*(const RotationMatrix &rhs) const
计算两个旋转矩阵的乘积。 Computes the product of two rotation matrices.
RotationMatrix & operator=(const RotationMatrix &R)
赋值运算符,将 RotationMatrix 赋值给当前对象。 Overloaded assignment operator to assign a RotationMatrix to the curr...
Eigen::Matrix< Scalar, 3, 1 > ToEulerAngle() const
将旋转矩阵转换为欧拉角(默认使用 ZYX 顺序)。 Converts the rotation matrix to Euler angles (default ZYX order).
RotationMatrix()
默认构造函数,初始化单位旋转矩阵。 Default constructor initializing an identity rotation matrix.
Eigen::Matrix< Scalar, 3, 3 > operator-() const
计算旋转矩阵的转置(逆矩阵)。 Computes the transpose (inverse) of the rotation matrix.
RotationMatrix(const Quaternion< Scalar > &q)
通过 Quaternion 四元数构造旋转矩阵。 Constructs a rotation matrix from a Quaternion object.
RotationMatrix(const Eigen::Matrix< Scalar, 3, 3 > &R)
通过 Eigen 3x3 矩阵构造旋转矩阵。 Constructs a rotation matrix from an Eigen 3x3 matrix.
表示三维空间中的刚体变换,包括旋转和位移。Represents rigid body transformations in 3D space, including rotation and transl...
Transform operator+(const Transform &t) const
计算当前变换与另一个变换的组合。Computes the composition of the current transformation with another transformation.
Transform & operator=(const Position< Scalar > &p)
赋值运算符,将平移部分设置为给定的位移。Assignment operator setting the translation component to the given position.
Transform & operator=(const Eigen::AngleAxis< Scalar > &a)
赋值运算符,将旋转部分设置为给定的旋转轴-角度表示。Assignment operator setting the rotation component using an axis-angle repr...
Transform()=default
默认构造函数,创建单位变换。Default constructor creating an identity transformation.
Quaternion< Scalar > rotation
Transform operator-(const Transform &t) const
计算当前变换与另一个变换的相对变换。Computes the relative transformation between the current transformation and another...
Position< Scalar > translation
Transform & operator=(const Quaternion< Scalar > &q)
赋值运算符,将旋转部分设置为给定的四元数。Assignment operator setting the rotation component to the given quaternion.
Transform(const Quaternion< Scalar > &rotation, const Position< Scalar > &translation)
使用给定的旋转和位移构造变换。Constructs a transformation with the given rotation and translation.
LibXR 命名空间