libxr 1.0
Want to be the best embedded framework
Loading...
Searching...
No Matches
transform.hpp
1#pragma once
2
3#include <Eigen/Core>
4#include <Eigen/Dense>
5#include <cmath>
6
7namespace LibXR
8{
9
10using DefaultScalar = LIBXR_DEFAULT_SCALAR;
11
12template <typename Scalar = DefaultScalar>
13class Position;
14template <typename Scalar = DefaultScalar>
15class Axis;
16template <typename Scalar = DefaultScalar>
17class RotationMatrix;
18template <typename Scalar = DefaultScalar>
19class EulerAngle;
20template <typename Scalar = DefaultScalar>
21class Quaternion;
22
35template <typename Scalar>
36class Position : public Eigen::Matrix<Scalar, 3, 1>
37{
38 public:
43 Position() : Eigen::Matrix<Scalar, 3, 1>(0, 0, 0) {}
44
52 Position(Scalar x, Scalar y, Scalar z) : Eigen::Matrix<Scalar, 3, 1>(x, y, z) {}
53
58 Position(const Eigen::Matrix<Scalar, 3, 1> &p) : Eigen::Matrix<Scalar, 3, 1>(p) {}
59
64 Position(const Position &p) : Eigen::Matrix<Scalar, 3, 1>(p) {}
65
73 std::is_same<T, float>::value ||
74 std::is_same<T, double>::value,
75 int> = 0>
76 Position(const T (&data)[3]) : Eigen::Matrix<Scalar, 3, 1>(data)
77 {
78 }
79
86 Position &operator=(const Eigen::Matrix<Scalar, 3, 1> &p)
87 {
88 memcpy(this->data(), p.data(), 3 * sizeof(Scalar));
89 return *this;
90 }
91
99 {
100 if (this != &p)
101 {
102 memcpy(this->data(), p.data(), 3 * sizeof(Scalar));
103 }
104
105 return *this;
106 }
107
114 template <
115 typename Rotation,
116 std::enable_if_t<std::is_same<Rotation, RotationMatrix<Scalar>>::value ||
117 std::is_same<Rotation, Eigen::Matrix<Scalar, 3, 3>>::value ||
118 std::is_same<Rotation, Quaternion<Scalar>>::value ||
119 std::is_same<Rotation, Eigen::Quaternion<Scalar>>::value,
120 int> = 0>
121 Eigen::Matrix<Scalar, 3, 1> operator*(const Rotation &R)
122 {
123 return R * (*this);
124 }
125
133 template <
134 typename Rotation,
135 std::enable_if_t<std::is_same<Rotation, RotationMatrix<Scalar>>::value ||
136 std::is_same<Rotation, Eigen::Matrix<Scalar, 3, 3>>::value ||
137 std::is_same<Rotation, Quaternion<Scalar>>::value ||
138 std::is_same<Rotation, Eigen::Quaternion<Scalar>>::value,
139 int> = 0>
141 {
142 *this = R * (*this);
143 return *this;
144 }
145
151 Eigen::Matrix<Scalar, 3, 1> operator/(const RotationMatrix<Scalar> &R)
152 {
153 return (-R) * (*this);
154 }
155
163 {
164 *this = (-q) * (*this);
165 return *this;
166 }
167
174 const Position &operator/=(const Eigen::Matrix<Scalar, 3, 3> &R)
175 {
176 *this = R.transpose() * Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(this->data_);
177 return *this;
178 }
179
186 const Position &operator/=(const Eigen::Quaternion<Scalar> &q)
187 {
188 *this = q.conjugate() * Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(this->data_);
189 return *this;
190 }
191
198 {
199 *this = s * (*this);
200 return *this;
201 }
202
209 {
210 (*this)[0] /= s;
211 (*this)[1] /= s;
212 (*this)[2] /= s;
213 return *this;
214 }
215
222 Eigen::Quaternion<Scalar> operator/(const Position<> &p)
223 {
224 return Eigen::Quaternion<Scalar>::FromTwoVectors(p, *this);
225 }
226};
227
240template <typename Scalar>
241class Axis : public Eigen::Matrix<Scalar, 3, 1>
242{
243 public:
248 Axis() : Eigen::Matrix<Scalar, 3, 1>(0, 0, 0) {}
249
258 Axis(Scalar x, Scalar y, Scalar z) : Eigen::Matrix<Scalar, 3, 1>(x, y, z) {}
259
266 Axis(const Axis &p) : Eigen::Matrix<Scalar, 3, 1>(p) {}
267
274 static Axis X() { return Axis(1., 0., 0.); }
275
282 static Axis Y() { return Axis(0., 1., 0.); }
283
290 static Axis Z() { return Axis(0., 0., 1.); }
291
306 Axis<Scalar> &operator=(const Eigen::Matrix<Scalar, 3, 1> &p)
307 {
308 memcpy(this->data(), p.data(), 3 * sizeof(Scalar));
309 return *this;
310 }
311
324 {
325 if (this != &p)
326 {
327 memcpy(this->data(), p.data(), 3 * sizeof(Scalar));
328 }
329 return *this;
330 }
331};
332
338template <typename Scalar>
340{
341 public:
343
346 EulerAngle() : data_{0, 0, 0} {}
347
356
362 EulerAngle(const Eigen::Matrix<Scalar, 3, 1> &p) : data_{p.x(), p.y(), p.z()} {}
363
368 EulerAngle(const EulerAngle &p) : data_{p.data_[0], p.data_[1], p.data_[2]} {}
369
370 const Scalar &Roll() const { return data_[0]; }
371 const Scalar &Pitch() const { return data_[1]; }
372 const Scalar &Yaw() const { return data_[2]; }
373
382 std::is_same<T, float>::value ||
383 std::is_same<T, double>::value,
384 int> = 0>
385 EulerAngle(const T (&data)[3]) : data_{data[0], data[1], data[2]}
386 {
387 }
388
390 operator Eigen::Matrix<Scalar, 3, 1>() const
391 {
392 return Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(data_);
393 }
394
396 Scalar operator()(int i) const { return data_[i]; }
397
400 EulerAngle &operator=(const Eigen::Matrix<Scalar, 3, 1> &p)
401 {
402 data_[0] = p(0);
403 data_[1] = p(1);
404 data_[2] = p(2);
405 return *this;
406 }
407
411 {
412 if (this != &p)
413 {
414 memcpy(data_, p.data_, 3 * sizeof(Scalar));
415 }
416 return *this;
417 }
418
421 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrix() const { return ToRotationMatrixZYX(); }
422
423 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixZYX() const
424 {
425 Scalar ca = std::cos(Yaw()), cb = std::cos(Pitch()), cc = std::cos(Roll());
426 Scalar sa = std::sin(Yaw()), sb = std::sin(Pitch()), sc = std::sin(Roll());
427
428 return (Eigen::Matrix<Scalar, 3, 3>() << ca * cb, ca * sb * sc - cc * sa,
429 sa * sc + ca * cc * sb, cb * sa, ca * cc + sa * sb * sc,
430 cc * sa * sb - ca * sc, -sb, cb * sc, cb * cc)
431 .finished();
432 }
433
434 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixZXY() const
435 {
436 Scalar ca = std::cos(Yaw()), cb = std::cos(Roll()), cc = std::cos(Pitch());
437 Scalar sa = std::sin(Yaw()), sb = std::sin(Roll()), sc = std::sin(Pitch());
438
439 return (Eigen::Matrix<Scalar, 3, 3>() << ca * cc - sa * sb * sc, -cb * sa,
440 ca * sc + cc * sa * sb, cc * sa + ca * sb * sc, ca * cb,
441 sa * sc - ca * cc * sb, -cb * sc, sb, cb * cc)
442 .finished();
443 }
444
445 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixYXZ() const
446 {
447 Scalar ca = std::cos(Pitch()), cb = std::cos(Roll()), cc = std::cos(Yaw());
448 Scalar sa = std::sin(Pitch()), sb = std::sin(Roll()), sc = std::sin(Yaw());
449
450 return (Eigen::Matrix<Scalar, 3, 3>() << ca * cc + sa * sb * sc,
451 cc * sa * sb - ca * sc, cb * sa, cb * sc, cb * cc, -sb,
452 ca * sb * sc - cc * sa, sa * sc + ca * cc * sb, ca * cb)
453 .finished();
454 }
455
456 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixYZX() const
457 {
458 Scalar ca = std::cos(Pitch()), cb = std::cos(Yaw()), cc = std::cos(Roll());
459 Scalar sa = std::sin(Pitch()), sb = std::sin(Yaw()), sc = std::sin(Roll());
460
461 return (Eigen::Matrix<Scalar, 3, 3>() << ca * cb, sa * sc - ca * cc * sb,
462 cc * sa + ca * sb * sc, sb, cb * cc, -cb * sc, -cb * sa,
463 ca * sc + cc * sa * sb, ca * cc - sa * sb * sc)
464 .finished();
465 }
466
467 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixXYZ() const
468 {
469 Scalar ca = std::cos(Roll()), cb = std::cos(Pitch()), cc = std::cos(Yaw());
470 Scalar sa = std::sin(Roll()), sb = std::sin(Pitch()), sc = std::sin(Yaw());
471
472 return (Eigen::Matrix<Scalar, 3, 3>() << cb * cc, -cb * sc, sb,
473 ca * sc + cc * sa * sb, ca * cc - sa * sb * sc, -cb * sa,
474 sa * sc - ca * cc * sb, cc * sa + ca * sb * sc, ca * cb)
475 .finished();
476 }
477
478 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixXZY() const
479 {
480 Scalar ca = std::cos(Roll()), cb = std::cos(Yaw()), cc = std::cos(Pitch());
481 Scalar sa = std::sin(Roll()), sb = std::sin(Yaw()), sc = std::sin(Pitch());
482
483 return (Eigen::Matrix<Scalar, 3, 3>() << cb * cc, -sb, cb * sc,
484 sa * sc + ca * cc * sb, ca * cb, ca * sb * sc - cc * sa,
485 cc * sa * sb - ca * sc, cb * sa, ca * cc + sa * sb * sc)
486 .finished();
487 }
488
489 Eigen::Quaternion<Scalar> ToQuaternion() const { return ToQuaternionZYX(); }
490
491#if 0
492 Eigen::Quaternion<Scalar> ToQuaternionXYZ() const {
493 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
494 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
495 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
496 return rollAngle * pitchAngle * yawAngle;
497 }
498
499 Eigen::Quaternion<Scalar> ToQuaternionXZY() const {
500 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
501 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
502 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
503 return rollAngle * yawAngle * pitchAngle;
504 }
505
506 Eigen::Quaternion<Scalar> ToQuaternionYXZ() const {
507 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
508 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
509 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
510 return pitchAngle * rollAngle * yawAngle;
511 }
512
513 Eigen::Quaternion<Scalar> ToQuaternionYZX() const {
514 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
515 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
516 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
517 return pitchAngle * yawAngle * rollAngle;
518 }
519
520 Eigen::Quaternion<Scalar> ToQuaternionZXY() const {
521 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
522 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
523 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
524 return yawAngle * rollAngle * pitchAngle;
525 }
526
527 Eigen::Quaternion<Scalar> ToQuaternionZYX() const {
528 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
529 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
530 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
531 return yawAngle * pitchAngle * rollAngle;
532 }
533#endif
534
537 Eigen::Quaternion<Scalar> ToQuaternionXYZ() const
538 {
539 return Eigen::Quaternion<Scalar>(ToRotationMatrixXYZ());
540 }
541
542 Eigen::Quaternion<Scalar> ToQuaternionXZY() const
543 {
544 return Eigen::Quaternion<Scalar>(ToRotationMatrixXZY());
545 }
546
547 Eigen::Quaternion<Scalar> ToQuaternionYXZ() const
548 {
549 return Eigen::Quaternion<Scalar>(ToRotationMatrixYXZ());
550 }
551
552 Eigen::Quaternion<Scalar> ToQuaternionYZX() const
553 {
554 return Eigen::Quaternion<Scalar>(ToRotationMatrixYZX());
555 }
556
557 Eigen::Quaternion<Scalar> ToQuaternionZXY() const
558 {
559 return Eigen::Quaternion<Scalar>(ToRotationMatrixZXY());
560 }
561
562 Eigen::Quaternion<Scalar> ToQuaternionZYX() const
563 {
564 return Eigen::Quaternion<Scalar>(ToRotationMatrixZYX());
565 }
566};
567
582template <typename Scalar>
583class RotationMatrix : public Eigen::Matrix<Scalar, 3, 3>
584{
585 public:
590 RotationMatrix() : Eigen::Matrix<Scalar, 3, 3>()
591 {
592 (*this) << 1, 0, 0, 0, 1, 0, 0, 0, 1;
593 }
594
603 : Eigen::Matrix<Scalar, 3, 3>()
604 {
605 (*this) << r00, r01, r02, r10, r11, r12, r20, r21, r22;
606 }
607
614 RotationMatrix(const Eigen::Matrix<Scalar, 3, 3> &R) : Eigen::Matrix<Scalar, 3, 3>{R} {}
615
622 RotationMatrix(const Eigen::Quaternion<Scalar> &q)
623 : Eigen::Matrix<Scalar, 3, 3>{q.toRotationMatrix()}
624 {
625 }
626
633 RotationMatrix(const Quaternion<Scalar> &q) { *this = q.ToRotationMatrix(); }
634
636 std::is_same<T, float>::value ||
637 std::is_same<T, double>::value,
638 int> = 0>
639 RotationMatrix(const T (&data)[9]) : Eigen::Matrix<Scalar, 3, 3>()
640 {
641 (*this) << data[0], data[1], data[2], data[3], data[4], data[5], data[6], data[7],
642 data[8];
643 }
644
646 std::is_same<T, float>::value ||
647 std::is_same<T, double>::value,
648 int> = 0>
649 RotationMatrix(const T (&data)[3][3]) : Eigen::Matrix<Scalar, 3, 3>()
650 {
651 (*this) << data[0][0], data[0][1], data[0][2], data[1][0], data[1][1], data[1][2],
652 data[2][0], data[2][1], data[2][2];
653 }
654
661 Eigen::Matrix<Scalar, 3, 3> operator-() const { return this->transpose(); }
662
673 {
674 if (this != &R)
675 {
676 memcpy(this->data(), R.data(), 9 * sizeof(Scalar));
677 }
678 return *this;
679 }
680
681 RotationMatrix &operator=(const Eigen::Matrix<Scalar, 3, 3> &R)
682 {
683 memcpy(this->data(), R.data(), 9 * sizeof(Scalar));
684 return *this;
685 }
686
687 RotationMatrix &operator=(const Eigen::Quaternion<Scalar> &q)
688 {
689 *this = q.ToRotationMatrix();
690 return *this;
691 }
692
694 {
695 *this = q.ToRotationMatrix();
696 return *this;
697 }
698
699 Position<Scalar> operator*(const Position<Scalar> &p) const
700 {
701 return Position<Scalar>((*this) * Eigen::Matrix<Scalar, 3, 1>(p));
702 }
703
711 Eigen::Matrix<Scalar, 3, 1> operator*(const Eigen::Matrix<Scalar, 3, 1> &p) const
712 {
713 return static_cast<Eigen::Matrix<Scalar, 3, 3>>(*this) * p;
714 }
715
726 Eigen::Matrix<Scalar, 3, 1> ToEulerAngle() const { return ToEulerAngleZYX(); }
727
728 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZYX() const
729 {
730 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
731
732 Scalar roll = std::atan2(r(2, 1), r(2, 2));
733 Scalar yaw = std::atan2(r(1, 0), r(0, 0));
734 Scalar pitch = std::asin(-r(2, 0));
735
736 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
737 }
738
739 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXZY() const
740 {
741 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
742
743 Scalar roll = std::atan2(r(2, 1), r(1, 1));
744 Scalar yaw = std::asin(-r(0, 1));
745 Scalar pitch = std::atan2(r(0, 2), r(0, 0));
746
747 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
748 }
749
750 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYZX() const
751 {
752 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
753
754 Scalar pitch = std::atan2(-r(2, 0), r(0, 0));
755 Scalar yaw = std::asin(r(1, 0));
756 Scalar roll = std::atan2(-r(1, 2), r(1, 1));
757
758 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
759 }
760
761 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYXZ() const
762 {
763 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
764
765 Scalar pitch = std::atan2(r(0, 2), r(2, 2));
766 Scalar roll = std::asin(-r(1, 2));
767 Scalar yaw = std::atan2(r(1, 0), r(1, 1));
768
769 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
770 }
771
772 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZXY() const
773 {
774 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
775
776 Scalar roll = std::asin(r(2, 1));
777 Scalar yaw = std::atan2(r(1, 1), -r(0, 1));
778 Scalar pitch = std::atan2(-r(2, 0), r(2, 2));
779
780 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
781 }
782
783 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXYZ() const
784 {
785 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
786
787 Scalar yaw = std::atan2(-r(0, 1), r(0, 0));
788 Scalar pitch = std::asin(r(0, 2));
789 Scalar roll = std::atan2(-r(1, 2), r(2, 2));
790
791 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
792 }
793};
794
808template <typename Scalar>
809class Quaternion : public Eigen::Quaternion<Scalar>
810{
811 public:
816 Quaternion() : Eigen::Quaternion<Scalar>(1, 0, 0, 0) {}
817
826 : Eigen::Quaternion<Scalar>(w, x, y, z)
827 {
828 }
829
834 Quaternion(const Eigen::Quaternion<Scalar> &q) : Eigen::Quaternion<Scalar>(q) {}
835
841 : Eigen::Quaternion<Scalar>(
842 Eigen::Quaternion<Scalar>(static_cast<Eigen::Matrix<Scalar, 3, 3>>(R)))
843 {
844 }
845
851 Quaternion(const Eigen::Matrix<Scalar, 3, 3> R)
852 : Eigen::Quaternion<Scalar>(
853 Eigen::Quaternion<Scalar>(static_cast<Eigen::Matrix<Scalar, 3, 3>>(R)))
854 {
855 }
856
862 std::is_same<T, float>::value ||
863 std::is_same<T, double>::value,
864 int> = 0>
865 Quaternion(const T (&data)[4]) : Eigen::Quaternion<Scalar>(data)
866 {
867 }
868
874 Scalar operator()(int i) const
875 {
876 switch (i)
877 {
878 case 3:
879 return this->w();
880 case 0:
881 return this->x();
882 case 1:
883 return this->y();
884 case 2:
885 return this->z();
886 default:
887 return 0;
888 }
889 }
890
896 Quaternion &operator=(const Eigen::Quaternion<Scalar> &q)
897 {
898 *this = Quaternion(q);
899 return *this;
900 }
901
906 Quaternion operator-() const { return Quaternion((*this).conjugate()); }
907
914 {
915 return Quaternion(this->w() + q.w(), this->x() + q.x(), this->y() + q.y(),
916 this->z() + q.z());
917 }
918
919 Quaternion operator+(const Eigen::Quaternion<Scalar> &q) const
920 {
921 return Quaternion(this->w() + q.w(), this->x() + q.x(), this->y() + q.y(),
922 this->z() + q.z());
923 }
924
925 Quaternion operator-(const Quaternion &q) const
926 {
927 return Quaternion(this->w() - q.w(), this->x() - q.x(), this->y() - q.y(),
928 this->z() - q.z());
929 }
930
931 Quaternion operator-(const Eigen::Quaternion<Scalar> &q) const
932 {
933 return Quaternion(this->w() - q.w(), this->x() - q.x(), this->y() - q.y(),
934 this->z() - q.z());
935 }
936
943 {
944 return Eigen::Quaternion<Scalar>(*this) * Eigen::Quaternion<Scalar>(q);
945 }
946
947 Quaternion operator*(const Eigen::Quaternion<Scalar> &q) const
948 {
949 return Eigen::Quaternion<Scalar>(*this) * q;
950 }
951
958 Quaternion operator/(const Quaternion &q) const { return (*this) * (-q); }
959
960 Quaternion operator/(const Eigen::Quaternion<Scalar> &q) const
961 {
962 return (*this) * (-q);
963 }
964
965 template <typename Q,
966 std::enable_if_t<std::is_same<Q, Quaternion>::value ||
967 std::is_same<Q, Eigen::Quaternion<Scalar>>::value,
968 int> = 0>
969 const Quaternion &operator+=(const Q &q)
970 {
971 *this = *this + q;
972 return *this;
973 }
974
975 template <typename Q,
976 std::enable_if_t<std::is_same<Q, Quaternion>::value ||
977 std::is_same<Q, Eigen::Quaternion<Scalar>>::value,
978 int> = 0>
979 const Quaternion &operator-=(const Q &q)
980 {
981 *this = *this - q;
982 return *this;
983 }
984
991 {
992 return Eigen::Quaternion<Scalar>(*this) * Eigen::Matrix<Scalar, 3, 1>(p);
993 }
994
1006 Eigen::Matrix<Scalar, 3, 1> ToEulerAngle() const { return ToEulerAngleZYX(); }
1007
1008 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYZX() const
1009 {
1010 Scalar roll = std::atan2(2 * this->w() * this->x() - 2 * this->y() * this->z(),
1011 1 - 2 * (this->x() * this->x() + this->z() * this->z()));
1012 Scalar pitch = std::atan2(2 * this->w() * this->y() - 2 * this->x() * this->z(),
1013 1 - 2 * (this->y() * this->y() + this->z() * this->z()));
1014 Scalar yaw = std::asin(2 * (this->w() * this->z() + this->x() * this->y()));
1015 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1016 }
1017
1018 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZYX() const
1019 {
1020 Scalar yaw = std::atan2(2 * (this->w() * this->z() + this->x() * this->y()),
1021 1 - 2 * (this->z() * this->z() + this->y() * this->y()));
1022 Scalar pitch = std::asin(2 * (this->w() * this->y() - this->x() * this->z()));
1023 Scalar roll = std::atan2(2 * (this->w() * this->x() + this->y() * this->z()),
1024 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1025 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1026 }
1027
1028 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYXZ() const
1029 {
1030 Scalar roll = std::asin(2 * (this->w() * this->x() - this->y() * this->z()));
1031 Scalar yaw = std::atan2(2 * (this->w() * this->z() + this->x() * this->y()),
1032 1 - 2 * (this->z() * this->z() + this->x() * this->x()));
1033 Scalar pitch = std::atan2(2 * (this->x() * this->z() + this->w() * this->y()),
1034 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1035 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1036 }
1037
1038 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZXY() const
1039 {
1040 Scalar pitch = std::atan2(-2 * (this->x() * this->z() - this->w() * this->y()),
1041 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1042 Scalar roll = std::asin(2 * (this->w() * this->x() + this->y() * this->z()));
1043 Scalar yaw = std::atan2(-2 * (this->x() * this->y() - this->w() * this->z()),
1044 1 - 2 * (this->z() * this->z() + this->x() * this->x()));
1045 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1046 }
1047
1048 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXZY() const
1049 {
1050 Scalar pitch = std::atan2(2 * (this->w() * this->y() + this->x() * this->z()),
1051 1 - 2 * (this->z() * this->z() + this->y() * this->y()));
1052 Scalar yaw = std::asin(2 * (this->w() * this->z() - this->x() * this->y()));
1053 Scalar roll = std::atan2(2 * (this->w() * this->x() + this->y() * this->z()),
1054 1 - 2 * (this->z() * this->z() + this->x() * this->x()));
1055 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1056 }
1057
1058 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXYZ() const
1059 {
1060 Scalar yaw = std::atan2(-2 * (this->x() * this->y() - this->w() * this->z()),
1061 1 - 2 * (this->z() * this->z() + this->y() * this->y()));
1062 Scalar pitch = std::asin(2 * (this->w() * this->y() + this->x() * this->z()));
1063 Scalar roll = std::atan2(-2 * (this->y() * this->z() - this->w() * this->x()),
1064 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1065 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1066 }
1067
1078 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrix() const
1079 {
1080 return Eigen::Matrix<Scalar, 3, 3>(*this);
1081 }
1082};
1083
1090template <typename Scalar = DefaultScalar>
1092{
1093 public:
1098
1101 Transform() = default;
1102
1113
1121 {
1122 rotation = q;
1123 return *this;
1124 }
1125
1132 Transform &operator=(const Eigen::AngleAxis<Scalar> &a)
1133 {
1134 rotation = a;
1135 return *this;
1136 }
1137
1145 {
1146 translation = p;
1147 return *this;
1148 }
1149
1157 {
1158 return Transform(Eigen::Quaternion<Scalar>(rotation * t.rotation),
1159 Eigen::Matrix<Scalar, 3, 1>(translation + rotation * t.translation));
1160 }
1161
1169 {
1170 return Transform(rotation / t.rotation, translation - t.translation);
1171 }
1172};
1173
1174} // namespace LibXR
三维坐标轴类,继承自 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:37
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:43
Position & operator=(const Position &p)
赋值运算符,将 Eigen 向量赋值给 Position / Assignment operator to assign an Eigen vector to Position
Definition transform.hpp:98
Eigen::Matrix< Scalar, 3, 1 > operator/(const RotationMatrix< Scalar > &R)
旋转矩阵的逆变换 / Inverse transformation using a rotation matrix
Eigen::Matrix< Scalar, 3, 1 > operator*(const Rotation &R)
赋值运算符,将另一个 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:52
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:76
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:64
Position(const Eigen::Matrix< Scalar, 3, 1 > &p)
复制构造函数 / Copy constructor
Definition transform.hpp:58
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:86
四元数表示与运算,继承自 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 &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 Color Control Library / LibXR终端颜色控制库
constexpr auto min(T1 a, T2 b) -> typename std::common_type< T1, T2 >::type
计算两个数的最小值