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 memcpy(this->data(), p.data(), 3 *
sizeof(Scalar));
104 memcpy(this->data(), p.data(), 3 *
sizeof(Scalar));
118 std::enable_if_t<std::is_same<Rotation, RotationMatrix<Scalar>>::value ||
119 std::is_same<Rotation, Eigen::Matrix<Scalar, 3, 3>>::value ||
120 std::is_same<Rotation, Quaternion<Scalar>>::value ||
121 std::is_same<Rotation, Eigen::Quaternion<Scalar>>::value,
123 Eigen::Matrix<Scalar, 3, 1>
operator*(
const Rotation &R)
const
137 std::enable_if_t<std::is_same<Rotation, RotationMatrix<Scalar>>::value ||
138 std::is_same<Rotation, Eigen::Matrix<Scalar, 3, 3>>::value ||
139 std::is_same<Rotation, Quaternion<Scalar>>::value ||
140 std::is_same<Rotation, Eigen::Quaternion<Scalar>>::value,
155 return (-R) * (*this);
166 *
this = (-q) * (*
this);
178 *
this = R.transpose() * Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(this->data_);
190 *
this = q.conjugate() * Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(this->data_);
226 return Eigen::Quaternion<Scalar>::FromTwoVectors(p, *
this);
242template <
typename Scalar>
243class Axis :
public Eigen::Matrix<Scalar, 3, 1>
250 Axis() : Eigen::Matrix<Scalar, 3, 1>(0, 0, 0) {}
260 Axis(Scalar x, Scalar y, Scalar z) : Eigen::Matrix<Scalar, 3, 1>(x, y, z) {}
268 Axis(
const Axis &p) : Eigen::Matrix<Scalar, 3, 1>(p) {}
310 memcpy(this->data(), p.data(), 3 *
sizeof(Scalar));
329 memcpy(this->data(), p.data(), 3 *
sizeof(Scalar));
340template <
typename Scalar>
372 const Scalar &Roll()
const {
return data_[0]; }
373 const Scalar &Pitch()
const {
return data_[1]; }
374 const Scalar &Yaw()
const {
return data_[2]; }
383 template <typename T, std::enable_if_t<std::is_same<T, Scalar>::value ||
384 std::is_same<T, float>::value ||
385 std::is_same<T, double>::value,
392 operator Eigen::Matrix<Scalar, 3, 1>()
const
394 return Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(
data_);
425 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixZYX()
const
427 Scalar ca = std::cos(Yaw()), cb = std::cos(Pitch()), cc = std::cos(Roll());
428 Scalar sa = std::sin(Yaw()), sb = std::sin(Pitch()), sc = std::sin(Roll());
430 return (Eigen::Matrix<Scalar, 3, 3>() << ca * cb, ca * sb * sc - cc * sa,
431 sa * sc + ca * cc * sb, cb * sa, ca * cc + sa * sb * sc,
432 cc * sa * sb - ca * sc, -sb, cb * sc, cb * cc)
436 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixZXY()
const
438 Scalar ca = std::cos(Yaw()), cb = std::cos(Roll()), cc = std::cos(Pitch());
439 Scalar sa = std::sin(Yaw()), sb = std::sin(Roll()), sc = std::sin(Pitch());
441 return (Eigen::Matrix<Scalar, 3, 3>() << ca * cc - sa * sb * sc, -cb * sa,
442 ca * sc + cc * sa * sb, cc * sa + ca * sb * sc, ca * cb,
443 sa * sc - ca * cc * sb, -cb * sc, sb, cb * cc)
447 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixYXZ()
const
449 Scalar ca = std::cos(Pitch()), cb = std::cos(Roll()), cc = std::cos(Yaw());
450 Scalar sa = std::sin(Pitch()), sb = std::sin(Roll()), sc = std::sin(Yaw());
452 return (Eigen::Matrix<Scalar, 3, 3>() << ca * cc + sa * sb * sc,
453 cc * sa * sb - ca * sc, cb * sa, cb * sc, cb * cc, -sb,
454 ca * sb * sc - cc * sa, sa * sc + ca * cc * sb, ca * cb)
458 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixYZX()
const
460 Scalar ca = std::cos(Pitch()), cb = std::cos(Yaw()), cc = std::cos(Roll());
461 Scalar sa = std::sin(Pitch()), sb = std::sin(Yaw()), sc = std::sin(Roll());
463 return (Eigen::Matrix<Scalar, 3, 3>() << ca * cb, sa * sc - ca * cc * sb,
464 cc * sa + ca * sb * sc, sb, cb * cc, -cb * sc, -cb * sa,
465 ca * sc + cc * sa * sb, ca * cc - sa * sb * sc)
469 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixXYZ()
const
471 Scalar ca = std::cos(Roll()), cb = std::cos(Pitch()), cc = std::cos(Yaw());
472 Scalar sa = std::sin(Roll()), sb = std::sin(Pitch()), sc = std::sin(Yaw());
474 return (Eigen::Matrix<Scalar, 3, 3>() << cb * cc, -cb * sc, sb,
475 ca * sc + cc * sa * sb, ca * cc - sa * sb * sc, -cb * sa,
476 sa * sc - ca * cc * sb, cc * sa + ca * sb * sc, ca * cb)
480 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixXZY()
const
482 Scalar ca = std::cos(Roll()), cb = std::cos(Yaw()), cc = std::cos(Pitch());
483 Scalar sa = std::sin(Roll()), sb = std::sin(Yaw()), sc = std::sin(Pitch());
485 return (Eigen::Matrix<Scalar, 3, 3>() << cb * cc, -sb, cb * sc,
486 sa * sc + ca * cc * sb, ca * cb, ca * sb * sc - cc * sa,
487 cc * sa * sb - ca * sc, cb * sa, ca * cc + sa * sb * sc)
491 Eigen::Quaternion<Scalar> ToQuaternion()
const {
return ToQuaternionZYX(); }
495 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
496 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
497 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
498 return rollAngle * pitchAngle * yawAngle;
501 Eigen::Quaternion<Scalar> ToQuaternionXZY()
const {
502 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
503 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
504 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
505 return rollAngle * yawAngle * pitchAngle;
508 Eigen::Quaternion<Scalar> ToQuaternionYXZ()
const {
509 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
510 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
511 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
512 return pitchAngle * rollAngle * yawAngle;
515 Eigen::Quaternion<Scalar> ToQuaternionYZX()
const {
516 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
517 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
518 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
519 return pitchAngle * yawAngle * rollAngle;
522 Eigen::Quaternion<Scalar> ToQuaternionZXY()
const {
523 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
524 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
525 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
526 return yawAngle * rollAngle * pitchAngle;
529 Eigen::Quaternion<Scalar> ToQuaternionZYX()
const {
530 Eigen::AngleAxisd yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
531 Eigen::AngleAxisd pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
532 Eigen::AngleAxisd rollAngle(Roll(), Eigen::Vector3d::UnitX());
533 return yawAngle * pitchAngle * rollAngle;
541 return Eigen::Quaternion<Scalar>(ToRotationMatrixXYZ());
544 Eigen::Quaternion<Scalar> ToQuaternionXZY()
const
546 return Eigen::Quaternion<Scalar>(ToRotationMatrixXZY());
549 Eigen::Quaternion<Scalar> ToQuaternionYXZ()
const
551 return Eigen::Quaternion<Scalar>(ToRotationMatrixYXZ());
554 Eigen::Quaternion<Scalar> ToQuaternionYZX()
const
556 return Eigen::Quaternion<Scalar>(ToRotationMatrixYZX());
559 Eigen::Quaternion<Scalar> ToQuaternionZXY()
const
561 return Eigen::Quaternion<Scalar>(ToRotationMatrixZXY());
564 Eigen::Quaternion<Scalar> ToQuaternionZYX()
const
566 return Eigen::Quaternion<Scalar>(ToRotationMatrixZYX());
584template <
typename Scalar>
594 (*this) << 1, 0, 0, 0, 1, 0, 0, 0, 1;
603 RotationMatrix(Scalar r00, Scalar r01, Scalar r02, Scalar r10, Scalar r11, Scalar r12,
604 Scalar r20, Scalar r21, Scalar r22)
605 : Eigen::Matrix<Scalar, 3, 3>()
607 (*this) << r00, r01, r02, r10, r11, r12, r20, r21, r22;
616 RotationMatrix(
const Eigen::Matrix<Scalar, 3, 3> &R) : Eigen::Matrix<Scalar, 3, 3>{R} {}
625 : Eigen::Matrix<Scalar, 3, 3>{q.ToRotationMatrix()}
637 template <typename T, std::enable_if_t<std::is_same<T, Scalar>::value ||
638 std::is_same<T, float>::value ||
639 std::is_same<T, double>::value,
641 RotationMatrix(
const T (&data)[9]) : Eigen::Matrix<Scalar, 3, 3>()
643 (*this) << data[0], data[1], data[2], data[3], data[4], data[5], data[6], data[7],
647 template <typename T, std::enable_if_t<std::is_same<T, Scalar>::value ||
648 std::is_same<T, float>::value ||
649 std::is_same<T, double>::value,
651 RotationMatrix(
const T (&data)[3][3]) : Eigen::Matrix<Scalar, 3, 3>()
653 (*this) << data[0][0], data[0][1], data[0][2], data[1][0], data[1][1], data[1][2],
654 data[2][0], data[2][1], data[2][2];
663 Eigen::Matrix<Scalar, 3, 3>
operator-()
const {
return this->transpose(); }
678 memcpy(this->data(), R.data(), 9 *
sizeof(Scalar));
685 memcpy(this->data(), R.data(), 9 *
sizeof(Scalar));
691 *
this = q.ToRotationMatrix();
697 *
this = q.ToRotationMatrix();
701 Position<Scalar> operator*(
const Position<Scalar> &p)
const
703 return Position<Scalar>((*
this) * Eigen::Matrix<Scalar, 3, 1>(p));
713 Eigen::Matrix<Scalar, 3, 1>
operator*(
const Eigen::Matrix<Scalar, 3, 1> &p)
const
715 return static_cast<Eigen::Matrix<Scalar, 3, 3>
>(*this) * p;
728 Eigen::Matrix<Scalar, 3, 1>
ToEulerAngle()
const {
return ToEulerAngleZYX(); }
730 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZYX()
const
732 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
734 Scalar roll = std::atan2(r(2, 1), r(2, 2));
735 Scalar yaw = std::atan2(r(1, 0), r(0, 0));
736 Scalar pitch = std::asin(-r(2, 0));
738 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
741 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXZY()
const
743 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
745 Scalar roll = std::atan2(r(2, 1), r(1, 1));
746 Scalar yaw = std::asin(-r(0, 1));
747 Scalar pitch = std::atan2(r(0, 2), r(0, 0));
749 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
752 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYZX()
const
754 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
756 Scalar pitch = std::atan2(-r(2, 0), r(0, 0));
757 Scalar yaw = std::asin(r(1, 0));
758 Scalar roll = std::atan2(-r(1, 2), r(1, 1));
760 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
763 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYXZ()
const
765 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
767 Scalar pitch = std::atan2(r(0, 2), r(2, 2));
768 Scalar roll = std::asin(-r(1, 2));
769 Scalar yaw = std::atan2(r(1, 0), r(1, 1));
771 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
774 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZXY()
const
776 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
778 Scalar roll = std::asin(r(2, 1));
779 Scalar yaw = std::atan2(r(1, 1), -r(0, 1));
780 Scalar pitch = std::atan2(-r(2, 0), r(2, 2));
782 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
785 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXYZ()
const
787 const Eigen::Matrix<Scalar, 3, 3> &r = (*this);
789 Scalar yaw = std::atan2(-r(0, 1), r(0, 0));
790 Scalar pitch = std::asin(r(0, 2));
791 Scalar roll = std::atan2(-r(1, 2), r(2, 2));
793 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
810template <
typename Scalar>
844 Eigen::
Quaternion<Scalar>(static_cast<Eigen::Matrix<Scalar, 3, 3>>(R)))
855 Eigen::
Quaternion<Scalar>(static_cast<Eigen::Matrix<Scalar, 3, 3>>(R)))
863 template <typename T, std::enable_if_t<std::is_same<T, Scalar>::value ||
864 std::is_same<T, float>::value ||
865 std::is_same<T, double>::value,
917 return Quaternion(this->w() + q.w(), this->x() + q.x(), this->y() + q.y(),
923 return Quaternion(this->w() + q.w(), this->x() + q.x(), this->y() + q.y(),
929 return Quaternion(this->w() - q.w(), this->x() - q.x(), this->y() - q.y(),
935 return Quaternion(this->w() - q.w(), this->x() - q.x(), this->y() - q.y(),
946 return Eigen::Quaternion<Scalar>(*
this) * Eigen::Quaternion<Scalar>(q);
951 return Eigen::Quaternion<Scalar>(*
this) * q;
964 return (*
this) * (-q);
967 template <
typename Q,
968 std::enable_if_t<std::is_same<Q, Quaternion>::value ||
969 std::is_same<Q, Eigen::Quaternion<Scalar>>::value,
977 template <
typename Q,
978 std::enable_if_t<std::is_same<Q, Quaternion>::value ||
979 std::is_same<Q, Eigen::Quaternion<Scalar>>::value,
994 return Eigen::Quaternion<Scalar>(*
this) * Eigen::Matrix<Scalar, 3, 1>(p);
1008 Eigen::Matrix<Scalar, 3, 1>
ToEulerAngle()
const {
return ToEulerAngleZYX(); }
1010 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYZX()
const
1012 Scalar roll = std::atan2(2 * this->w() * this->x() - 2 * this->y() * this->z(),
1013 1 - 2 * (this->x() * this->x() + this->z() * this->z()));
1014 Scalar pitch = std::atan2(2 * this->w() * this->y() - 2 * this->x() * this->z(),
1015 1 - 2 * (this->y() * this->y() + this->z() * this->z()));
1016 Scalar yaw = std::asin(2 * (this->w() * this->z() + this->x() * this->y()));
1017 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1020 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZYX()
const
1022 Scalar yaw = std::atan2(2 * (this->w() * this->z() + this->x() * this->y()),
1023 1 - 2 * (this->z() * this->z() + this->y() * this->y()));
1024 Scalar pitch = std::asin(2 * (this->w() * this->y() - this->x() * this->z()));
1025 Scalar roll = std::atan2(2 * (this->w() * this->x() + this->y() * this->z()),
1026 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1027 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1030 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYXZ()
const
1032 Scalar roll = std::asin(2 * (this->w() * this->x() - this->y() * this->z()));
1033 Scalar yaw = std::atan2(2 * (this->w() * this->z() + this->x() * this->y()),
1034 1 - 2 * (this->z() * this->z() + this->x() * this->x()));
1035 Scalar pitch = std::atan2(2 * (this->x() * this->z() + this->w() * this->y()),
1036 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1037 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1040 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZXY()
const
1042 Scalar pitch = std::atan2(-2 * (this->x() * this->z() - this->w() * this->y()),
1043 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1044 Scalar roll = std::asin(2 * (this->w() * this->x() + this->y() * this->z()));
1045 Scalar yaw = std::atan2(-2 * (this->x() * this->y() - this->w() * this->z()),
1046 1 - 2 * (this->z() * this->z() + this->x() * this->x()));
1047 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1050 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXZY()
const
1052 Scalar pitch = std::atan2(2 * (this->w() * this->y() + this->x() * this->z()),
1053 1 - 2 * (this->z() * this->z() + this->y() * this->y()));
1054 Scalar yaw = std::asin(2 * (this->w() * this->z() - this->x() * this->y()));
1055 Scalar roll = std::atan2(2 * (this->w() * this->x() + this->y() * this->z()),
1056 1 - 2 * (this->z() * this->z() + this->x() * this->x()));
1057 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1060 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXYZ()
const
1062 Scalar yaw = std::atan2(-2 * (this->x() * this->y() - this->w() * this->z()),
1063 1 - 2 * (this->z() * this->z() + this->y() * this->y()));
1064 Scalar pitch = std::asin(2 * (this->w() * this->y() + this->x() * this->z()));
1065 Scalar roll = std::atan2(-2 * (this->y() * this->z() - this->w() * this->x()),
1066 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1067 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1082 return Eigen::Matrix<Scalar, 3, 3>(*
this);
1092template <
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 &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.