12using DefaultScalar = LIBXR_DEFAULT_SCALAR;
14template <
typename Scalar = DefaultScalar>
16template <
typename Scalar = DefaultScalar>
18template <
typename Scalar = DefaultScalar>
20template <
typename Scalar = DefaultScalar>
22template <
typename Scalar = DefaultScalar>
37template <
typename Scalar>
38class Position :
public Eigen::Matrix<Scalar, 3, 1>
45 Position() : Eigen::Matrix<Scalar, 3, 1>(0, 0, 0) {}
54 Position(Scalar x, Scalar y, Scalar z) : Eigen::Matrix<Scalar, 3, 1>(x, y, z) {}
60 Position(
const Eigen::Matrix<Scalar, 3, 1> &p) : Eigen::Matrix<Scalar, 3, 1>(p) {}
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,
78 Position(
const T (&data)[3]) : Eigen::Matrix<Scalar, 3, 1>(data)
90 this->data()[0] = p[0];
91 this->data()[1] = p[1];
92 this->data()[2] = p[2];
106 this->data()[0] = p[0];
107 this->data()[1] = p[1];
108 this->data()[2] = p[2];
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,
127 Eigen::Matrix<Scalar, 3, 1>
operator*(
const Rotation &R)
const
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,
159 return (-R) * (*this);
170 *
this = (-q) * (*
this);
182 *
this = R.transpose() * Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(this->data_);
194 *
this = q.conjugate() * Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(this->data_);
230 return Eigen::Quaternion<Scalar>::FromTwoVectors(p, *
this);
246template <
typename Scalar>
247class Axis :
public Eigen::Matrix<Scalar, 3, 1>
254 Axis() : Eigen::Matrix<Scalar, 3, 1>(0, 0, 0) {}
264 Axis(Scalar x, Scalar y, Scalar z) : Eigen::Matrix<Scalar, 3, 1>(x, y, z) {}
272 Axis(
const Axis &p) : Eigen::Matrix<Scalar, 3, 1>(p) {}
314 this->data()[0] = p[0];
315 this->data()[1] = p[1];
316 this->data()[2] = p[2];
335 this->data()[0] = p[0];
336 this->data()[1] = p[1];
337 this->data()[2] = p[2];
348template <
typename Scalar>
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]; }
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,
403 operator Eigen::Matrix<Scalar, 3, 1>()
const
405 return Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(
data_);
438 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixZYX()
const
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());
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)
449 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixZXY()
const
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());
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)
460 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixYXZ()
const
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());
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)
471 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixYZX()
const
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());
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)
482 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixXYZ()
const
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());
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)
493 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixXZY()
const
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());
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)
504 Eigen::Quaternion<Scalar> ToQuaternion()
const {
return ToQuaternionZYX(); }
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;
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;
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;
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;
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;
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;
554 return Eigen::Quaternion<Scalar>(ToRotationMatrixXYZ());
557 Eigen::Quaternion<Scalar> ToQuaternionXZY()
const
559 return Eigen::Quaternion<Scalar>(ToRotationMatrixXZY());
562 Eigen::Quaternion<Scalar> ToQuaternionYXZ()
const
564 return Eigen::Quaternion<Scalar>(ToRotationMatrixYXZ());
567 Eigen::Quaternion<Scalar> ToQuaternionYZX()
const
569 return Eigen::Quaternion<Scalar>(ToRotationMatrixYZX());
572 Eigen::Quaternion<Scalar> ToQuaternionZXY()
const
574 return Eigen::Quaternion<Scalar>(ToRotationMatrixZXY());
577 Eigen::Quaternion<Scalar> ToQuaternionZYX()
const
579 return Eigen::Quaternion<Scalar>(ToRotationMatrixZYX());
597template <
typename Scalar>
607 (*this) << 1, 0, 0, 0, 1, 0, 0, 0, 1;
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>()
620 (*this) << r00, r01, r02, r10, r11, r12, r20, r21, r22;
629 RotationMatrix(
const Eigen::Matrix<Scalar, 3, 3> &R) : Eigen::Matrix<Scalar, 3, 3>{R} {}
638 : Eigen::Matrix<Scalar, 3, 3>{q.ToRotationMatrix()}
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,
654 RotationMatrix(
const T (&data)[9]) : Eigen::Matrix<Scalar, 3, 3>()
656 (*this) << data[0], data[1], data[2], data[3], data[4], data[5], data[6], data[7],
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,
664 RotationMatrix(
const T (&data)[3][3]) : Eigen::Matrix<Scalar, 3, 3>()
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];
676 Eigen::Matrix<Scalar, 3, 3>
operator-()
const {
return this->transpose(); }
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];
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];
720 *
this = q.ToRotationMatrix();
726 *
this = q.ToRotationMatrix();
730 Position<Scalar> operator*(
const Position<Scalar> &p)
const
732 return Position<Scalar>((*
this) * Eigen::Matrix<Scalar, 3, 1>(p));
742 Eigen::Matrix<Scalar, 3, 1>
operator*(
const Eigen::Matrix<Scalar, 3, 1> &p)
const
744 return static_cast<Eigen::Matrix<Scalar, 3, 3>
>(*this) * p;
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);
773 Eigen::Matrix<Scalar, 3, 1>
ToEulerAngle()
const {
return ToEulerAngleZYX(); }
775 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZYX()
const
777 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
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));
783 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
786 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXZY()
const
788 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
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));
794 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
797 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYZX()
const
799 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
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));
805 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
808 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYXZ()
const
810 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
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));
816 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
819 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZXY()
const
821 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
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));
827 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
830 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXYZ()
const
832 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
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));
838 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
855template <
typename Scalar>
889 Eigen::
Quaternion<Scalar>(static_cast<Eigen::Matrix<Scalar, 3, 3>>(R)))
900 Eigen::
Quaternion<Scalar>(static_cast<Eigen::Matrix<Scalar, 3, 3>>(R)))
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,
962 return Quaternion(this->w() + q.w(), this->x() + q.x(), this->y() + q.y(),
968 return Quaternion(this->w() + q.w(), this->x() + q.x(), this->y() + q.y(),
974 return Quaternion(this->w() - q.w(), this->x() - q.x(), this->y() - q.y(),
980 return Quaternion(this->w() - q.w(), this->x() - q.x(), this->y() - q.y(),
991 return Eigen::Quaternion<Scalar>(*
this) * Eigen::Quaternion<Scalar>(q);
996 return Eigen::Quaternion<Scalar>(*
this) * q;
1009 return (*
this) * (-q);
1012 template <
typename Q,
1013 std::enable_if_t<std::is_same<Q, Quaternion>::value ||
1014 std::is_same<Q, Eigen::Quaternion<Scalar>>::value,
1022 template <
typename Q,
1023 std::enable_if_t<std::is_same<Q, Quaternion>::value ||
1024 std::is_same<Q, Eigen::Quaternion<Scalar>>::value,
1039 return Eigen::Quaternion<Scalar>(*
this) * Eigen::Matrix<Scalar, 3, 1>(p);
1053 Eigen::Matrix<Scalar, 3, 1>
ToEulerAngle()
const {
return ToEulerAngleZYX(); }
1055 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYZX()
const
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);
1065 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZYX()
const
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);
1075 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYXZ()
const
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);
1085 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZXY()
const
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);
1095 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXZY()
const
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);
1105 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXYZ()
const
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);
1127 return Eigen::Matrix<Scalar, 3, 3>(*
this);
1137template <
typename Scalar = DefaultScalar>
三维坐标轴类,继承自 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
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)
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
const Position & operator/=(Scalar s)
按标量除法缩放当前向量 / Scale the current vector by dividing with a scalar
Position(const T(&data)[3])
乘以旋转矩阵 / Multiply by a rotation matrix
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
Position(const Eigen::Matrix< Scalar, 3, 1 > &p)
复制构造函数 / Copy constructor
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
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.