12template <
typename Scalar = DefaultScalar>
14template <
typename Scalar = DefaultScalar>
16template <
typename Scalar = DefaultScalar>
18template <
typename Scalar = DefaultScalar>
20template <
typename Scalar = DefaultScalar>
35template <
typename Scalar>
36class Position :
public Eigen::Matrix<Scalar, 3, 1>
58 Position(
const Eigen::Matrix<Scalar, 3, 1> &p) : Eigen::Matrix<
Scalar, 3, 1>(p) {}
73 std::is_same<T, float>::value ||
74 std::is_same<T, double>::value,
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,
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,
153 return (-
R) * (*this);
164 *
this = (-
q) * (*
this);
176 *
this =
R.transpose() * Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(this->data_);
188 *
this =
q.conjugate() * Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(this->data_);
224 return Eigen::Quaternion<Scalar>::FromTwoVectors(p, *
this);
240template <
typename Scalar>
241class Axis :
public Eigen::Matrix<Scalar, 3, 1>
338template <
typename Scalar>
382 std::is_same<T, float>::value ||
383 std::is_same<T, double>::value,
390 operator Eigen::Matrix<Scalar, 3, 1>()
const
392 return Eigen::Map<const Eigen::Matrix<Scalar, 3, 1>>(
data_);
423 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixZYX()
const
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());
428 return (Eigen::Matrix<Scalar, 3, 3>() <<
ca * cb,
ca *
sb *
sc -
cc *
sa,
434 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixZXY()
const
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());
439 return (Eigen::Matrix<Scalar, 3, 3>() <<
ca *
cc -
sa *
sb *
sc, -cb *
sa,
445 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixYXZ()
const
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());
450 return (Eigen::Matrix<Scalar, 3, 3>() <<
ca *
cc +
sa *
sb *
sc,
456 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixYZX()
const
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());
461 return (Eigen::Matrix<Scalar, 3, 3>() <<
ca * cb,
sa *
sc -
ca *
cc *
sb,
467 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixXYZ()
const
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());
472 return (Eigen::Matrix<Scalar, 3, 3>() << cb *
cc, -cb *
sc,
sb,
478 Eigen::Matrix<Scalar, 3, 3> ToRotationMatrixXZY()
const
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());
483 return (Eigen::Matrix<Scalar, 3, 3>() << cb *
cc, -
sb, cb *
sc,
489 Eigen::Quaternion<Scalar> ToQuaternion()
const {
return ToQuaternionZYX(); }
493 Eigen::AngleAxisd
rollAngle(Roll(), Eigen::Vector3d::UnitX());
494 Eigen::AngleAxisd
pitchAngle(Pitch(), Eigen::Vector3d::UnitY());
495 Eigen::AngleAxisd
yawAngle(Yaw(), Eigen::Vector3d::UnitZ());
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());
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());
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());
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());
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());
539 return Eigen::Quaternion<Scalar>(ToRotationMatrixXYZ());
542 Eigen::Quaternion<Scalar> ToQuaternionXZY()
const
544 return Eigen::Quaternion<Scalar>(ToRotationMatrixXZY());
547 Eigen::Quaternion<Scalar> ToQuaternionYXZ()
const
549 return Eigen::Quaternion<Scalar>(ToRotationMatrixYXZ());
552 Eigen::Quaternion<Scalar> ToQuaternionYZX()
const
554 return Eigen::Quaternion<Scalar>(ToRotationMatrixYZX());
557 Eigen::Quaternion<Scalar> ToQuaternionZXY()
const
559 return Eigen::Quaternion<Scalar>(ToRotationMatrixZXY());
562 Eigen::Quaternion<Scalar> ToQuaternionZYX()
const
564 return Eigen::Quaternion<Scalar>(ToRotationMatrixZYX());
582template <
typename Scalar>
592 (*this) << 1, 0, 0, 0, 1, 0, 0, 0, 1;
603 : Eigen::Matrix<
Scalar, 3, 3>()
623 : Eigen::Matrix<
Scalar, 3, 3>{
q.toRotationMatrix()}
636 std::is_same<T, float>::value ||
637 std::is_same<T, double>::value,
641 (*this) << data[0], data[1], data[2], data[3], data[4], data[5], data[6], data[7],
646 std::is_same<T, float>::value ||
647 std::is_same<T, double>::value,
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];
689 *
this =
q.ToRotationMatrix();
695 *
this =
q.ToRotationMatrix();
711 Eigen::Matrix<Scalar, 3, 1>
operator*(
const Eigen::Matrix<Scalar, 3, 1> &p)
const
713 return static_cast<Eigen::Matrix<Scalar, 3, 3>
>(*this) * p;
726 Eigen::Matrix<Scalar, 3, 1>
ToEulerAngle()
const {
return ToEulerAngleZYX(); }
728 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZYX()
const
730 const Eigen::Matrix<Scalar, 3, 3> &
r = (*this);
739 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXZY()
const
741 const Eigen::Matrix<Scalar, 3, 3> &
r = (*this);
750 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYZX()
const
752 const Eigen::Matrix<Scalar, 3, 3> &
r = (*this);
761 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYXZ()
const
763 const Eigen::Matrix<Scalar, 3, 3> &
r = (*this);
772 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZXY()
const
774 const Eigen::Matrix<Scalar, 3, 3> &
r = (*this);
783 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXYZ()
const
785 const Eigen::Matrix<Scalar, 3, 3> &
r = (*this);
808template <
typename Scalar>
862 std::is_same<T, float>::value ||
863 std::is_same<T, double>::value,
944 return Eigen::Quaternion<Scalar>(*
this) * Eigen::Quaternion<Scalar>(
q);
949 return Eigen::Quaternion<Scalar>(*
this) *
q;
962 return (*
this) * (-
q);
965 template <
typename Q,
966 std::enable_if_t<std::is_same<Q, Quaternion>::value ||
967 std::is_same<Q, Eigen::Quaternion<Scalar>>
::value,
975 template <
typename Q,
976 std::enable_if_t<std::is_same<Q, Quaternion>::value ||
977 std::is_same<Q, Eigen::Quaternion<Scalar>>
::value,
992 return Eigen::Quaternion<Scalar>(*
this) * Eigen::Matrix<Scalar, 3, 1>(p);
1006 Eigen::Matrix<Scalar, 3, 1>
ToEulerAngle()
const {
return ToEulerAngleZYX(); }
1008 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYZX()
const
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()));
1018 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZYX()
const
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()));
1028 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleYXZ()
const
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()));
1038 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleZXY()
const
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()));
1048 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXZY()
const
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()));
1058 Eigen::Matrix<Scalar, 3, 1> ToEulerAngleXYZ()
const
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()));
1080 return Eigen::Matrix<Scalar, 3, 3>(*
this);
1090template <
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 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
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::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.
LibXR Color Control Library / LibXR终端颜色控制库
constexpr auto min(T1 a, T2 b) -> typename std::common_type< T1, T2 >::type
计算两个数的最小值