libxr  1.0
Want to be the best embedded framework
Loading...
Searching...
No Matches
LibXR::Quaternion< Scalar > Class Template Reference

四元数表示与运算,继承自 Eigen::Quaternion / Quaternion representation and operations, inheriting from Eigen::Quaternion More...

#include <transform.hpp>

Inheritance diagram for LibXR::Quaternion< Scalar >:
[legend]
Collaboration diagram for LibXR::Quaternion< Scalar >:
[legend]

Public Member Functions

 Quaternion ()
 默认构造函数,初始化为单位四元数 / Default constructor initializing to an identity quaternion
 
 Quaternion (Scalar w, Scalar x, Scalar y, Scalar z)
 通过四个分量初始化四元数 / Construct a quaternion using four components
 
 Quaternion (const Eigen::Quaternion< Scalar > &q)
 复制构造函数 / Copy constructor
 
 Quaternion (const RotationMatrix< Scalar > &R)
 通过旋转矩阵构造四元数 / Construct a quaternion from a rotation matrix
 
 Quaternion (const Eigen::Matrix< Scalar, 3, 3 > R)
 通过 3x3 旋转矩阵构造四元数 / Construct a quaternion from a 3x3 rotation matrix
 
template<typename T , std::enable_if_t< std::is_same< T, Scalar >::value||std::is_same< T, float >::value||std::is_same< T, double >::value, int > = 0>
 Quaternion (const T(&data)[4])
 通过四维数组初始化四元数 / Construct a quaternion from a 4-element array
 
Scalar operator() (int i) const
 获取四元数的分量 / Retrieve a specific component of the quaternion
 
Quaternionoperator= (const Eigen::Quaternion< Scalar > &q)
 赋值运算符 / Assignment operator
 
Quaternion operator- () const
 取共轭四元数 / Get the conjugate quaternion
 
Quaternion operator+ (const Quaternion &q) const
 四元数加法 / Quaternion addition
 
Quaternion operator+ (const Eigen::Quaternion< Scalar > &q) const
 
Quaternion operator- (const Quaternion &q) const
 
Quaternion operator- (const Eigen::Quaternion< Scalar > &q) const
 
Quaternion operator* (const Quaternion &q) const
 四元数乘法 / Quaternion multiplication
 
Quaternion operator* (const Eigen::Quaternion< Scalar > &q) const
 
Quaternion operator/ (const Quaternion &q) const
 四元数除法(即左乘其共轭) / Quaternion division (multiplication by its conjugate)
 
Quaternion operator/ (const Eigen::Quaternion< Scalar > &q) const
 
template<typename Q , std::enable_if_t< std::is_same< Q, Quaternion >::value||std::is_same< Q, Eigen::Quaternion< Scalar > >::value, int > = 0>
const Quaternionoperator+= (const Q &q)
 
template<typename Q , std::enable_if_t< std::is_same< Q, Quaternion >::value||std::is_same< Q, Eigen::Quaternion< Scalar > >::value, int > = 0>
const Quaternionoperator-= (const Q &q)
 
Position< Scalar > operator* (const Position< Scalar > &p) const
 旋转三维向量 / Rotate a 3D vector
 
Eigen::Matrix< Scalar, 3, 1 > ToEulerAngle () const
 获取四元数的欧拉角表示(默认使用 ZYX 旋转顺序) Get the Euler angles representation of the quaternion (default ZYX order)
 
Eigen::Matrix< Scalar, 3, 1 > ToEulerAngleYZX () const
 
Eigen::Matrix< Scalar, 3, 1 > ToEulerAngleZYX () const
 
Eigen::Matrix< Scalar, 3, 1 > ToEulerAngleYXZ () const
 
Eigen::Matrix< Scalar, 3, 1 > ToEulerAngleZXY () const
 
Eigen::Matrix< Scalar, 3, 1 > ToEulerAngleXZY () const
 
Eigen::Matrix< Scalar, 3, 1 > ToEulerAngleXYZ () const
 
Eigen::Matrix< Scalar, 3, 3 > ToRotationMatrix () const
 将四元数转换为 3x3 旋转矩阵 / Convert the quaternion to a 3x3 rotation matrix
 

Detailed Description

template<typename Scalar>
class LibXR::Quaternion< Scalar >

四元数表示与运算,继承自 Eigen::Quaternion / Quaternion representation and operations, inheriting from Eigen::Quaternion

该类提供了对四元数的基本运算,如加法、减法、乘法、除法,以及与旋转矩阵和欧拉角的转换等。 This class provides fundamental quaternion operations, such as addition, subtraction, multiplication, and division, along with conversions to rotation matrices and Euler angles.

Template Parameters
Scalar数值类型(默认使用 DefaultScalar) / Numeric type (default: DefaultScalar)

Definition at line 856 of file transform.hpp.

Constructor & Destructor Documentation

◆ Quaternion() [1/6]

template<typename Scalar >
LibXR::Quaternion< Scalar >::Quaternion ( )
inline

默认构造函数,初始化为单位四元数 / Default constructor initializing to an identity quaternion

Definition at line 863 of file transform.hpp.

863: Eigen::Quaternion<Scalar>(1, 0, 0, 0) {}

◆ Quaternion() [2/6]

template<typename Scalar >
LibXR::Quaternion< Scalar >::Quaternion ( Scalar w,
Scalar x,
Scalar y,
Scalar z )
inline

通过四个分量初始化四元数 / Construct a quaternion using four components

Parameters
w实部 / Real part
xi 分量 / i component
yj 分量 / j component
zk 分量 / k component

Definition at line 872 of file transform.hpp.

873 : Eigen::Quaternion<Scalar>(w, x, y, z)
874 {
875 }

◆ Quaternion() [3/6]

template<typename Scalar >
LibXR::Quaternion< Scalar >::Quaternion ( const Eigen::Quaternion< Scalar > & q)
inline

复制构造函数 / Copy constructor

Parameters
q另一个 Eigen::Quaternion 四元数 / Another Eigen::Quaternion

Definition at line 881 of file transform.hpp.

881: Eigen::Quaternion<Scalar>(q) {}

◆ Quaternion() [4/6]

template<typename Scalar >
LibXR::Quaternion< Scalar >::Quaternion ( const RotationMatrix< Scalar > & R)
inline

通过旋转矩阵构造四元数 / Construct a quaternion from a rotation matrix

Parameters
R旋转矩阵 / Rotation matrix

Definition at line 887 of file transform.hpp.

888 : Eigen::Quaternion<Scalar>(
889 Eigen::Quaternion<Scalar>(static_cast<Eigen::Matrix<Scalar, 3, 3>>(R)))
890 {
891 }

◆ Quaternion() [5/6]

template<typename Scalar >
LibXR::Quaternion< Scalar >::Quaternion ( const Eigen::Matrix< Scalar, 3, 3 > R)
inline

通过 3x3 旋转矩阵构造四元数 / Construct a quaternion from a 3x3 rotation matrix

Parameters
R旋转矩阵 / Rotation matrix

Definition at line 898 of file transform.hpp.

899 : Eigen::Quaternion<Scalar>(
900 Eigen::Quaternion<Scalar>(static_cast<Eigen::Matrix<Scalar, 3, 3>>(R)))
901 {
902 }

◆ Quaternion() [6/6]

template<typename Scalar >
template<typename T , std::enable_if_t< std::is_same< T, Scalar >::value||std::is_same< T, float >::value||std::is_same< T, double >::value, int > = 0>
LibXR::Quaternion< Scalar >::Quaternion ( const T(&) data[4])
inline

通过四维数组初始化四元数 / Construct a quaternion from a 4-element array

Parameters
data4 维数组,表示 (w, x, y, z) / A 4-element array representing (w, x, y, z)

Definition at line 912 of file transform.hpp.

913 : Eigen::Quaternion<Scalar>(
914 static_cast<Scalar>(data[0]), static_cast<Scalar>(data[1]),
915 static_cast<Scalar>(data[2]), static_cast<Scalar>(data[3]))
916 {
917 }

Member Function Documentation

◆ operator()()

template<typename Scalar >
Scalar LibXR::Quaternion< Scalar >::operator() ( int i) const
inline

获取四元数的分量 / Retrieve a specific component of the quaternion

Parameters
i分量索引 (0: x, 1: y, 2: z, 3: w) / Component index (0: x, 1: y, 2: z, 3: w)
Returns
该分量的值 / Value of the component

Definition at line 924 of file transform.hpp.

925 {
926 switch (i)
927 {
928 case 3:
929 return this->w();
930 case 0:
931 return this->x();
932 case 1:
933 return this->y();
934 case 2:
935 return this->z();
936 default:
937 return 0;
938 }
939 }

◆ operator*() [1/3]

template<typename Scalar >
Quaternion LibXR::Quaternion< Scalar >::operator* ( const Eigen::Quaternion< Scalar > & q) const
inline

Definition at line 997 of file transform.hpp.

998 {
999 return Eigen::Quaternion<Scalar>(*this) * q;
1000 }

◆ operator*() [2/3]

template<typename Scalar >
Position< Scalar > LibXR::Quaternion< Scalar >::operator* ( const Position< Scalar > & p) const
inline

旋转三维向量 / Rotate a 3D vector

Parameters
p需要旋转的 Position 向量 / Position vector to be rotated
Returns
旋转后的 Position 向量 / Rotated Position vector

Definition at line 1040 of file transform.hpp.

1041 {
1042 return Eigen::Quaternion<Scalar>(*this) * Eigen::Matrix<Scalar, 3, 1>(p);
1043 }

◆ operator*() [3/3]

template<typename Scalar >
Quaternion LibXR::Quaternion< Scalar >::operator* ( const Quaternion< Scalar > & q) const
inline

四元数乘法 / Quaternion multiplication

Parameters
q另一个四元数 / Another quaternion
Returns
计算后的四元数 / Computed quaternion

Definition at line 992 of file transform.hpp.

993 {
994 return Eigen::Quaternion<Scalar>(*this) * Eigen::Quaternion<Scalar>(q);
995 }

◆ operator+() [1/2]

template<typename Scalar >
Quaternion LibXR::Quaternion< Scalar >::operator+ ( const Eigen::Quaternion< Scalar > & q) const
inline

Definition at line 969 of file transform.hpp.

970 {
971 return Quaternion(this->w() + q.w(), this->x() + q.x(), this->y() + q.y(),
972 this->z() + q.z());
973 }
Quaternion()
默认构造函数,初始化为单位四元数 / Default constructor initializing to an identity quaternion

◆ operator+() [2/2]

template<typename Scalar >
Quaternion LibXR::Quaternion< Scalar >::operator+ ( const Quaternion< Scalar > & q) const
inline

四元数加法 / Quaternion addition

Parameters
q另一个四元数 / Another quaternion
Returns
计算后的四元数 / Computed quaternion

Definition at line 963 of file transform.hpp.

964 {
965 return Quaternion(this->w() + q.w(), this->x() + q.x(), this->y() + q.y(),
966 this->z() + q.z());
967 }

◆ operator+=()

template<typename Scalar >
template<typename Q , std::enable_if_t< std::is_same< Q, Quaternion >::value||std::is_same< Q, Eigen::Quaternion< Scalar > >::value, int > = 0>
const Quaternion & LibXR::Quaternion< Scalar >::operator+= ( const Q & q)
inline

Definition at line 1019 of file transform.hpp.

1020 {
1021 *this = *this + q;
1022 return *this;
1023 }

◆ operator-() [1/3]

template<typename Scalar >
Quaternion LibXR::Quaternion< Scalar >::operator- ( ) const
inline

取共轭四元数 / Get the conjugate quaternion

Returns
共轭四元数 / Conjugated quaternion

Definition at line 956 of file transform.hpp.

956{ return Quaternion((*this).conjugate()); }

◆ operator-() [2/3]

template<typename Scalar >
Quaternion LibXR::Quaternion< Scalar >::operator- ( const Eigen::Quaternion< Scalar > & q) const
inline

Definition at line 981 of file transform.hpp.

982 {
983 return Quaternion(this->w() - q.w(), this->x() - q.x(), this->y() - q.y(),
984 this->z() - q.z());
985 }

◆ operator-() [3/3]

template<typename Scalar >
Quaternion LibXR::Quaternion< Scalar >::operator- ( const Quaternion< Scalar > & q) const
inline

Definition at line 975 of file transform.hpp.

976 {
977 return Quaternion(this->w() - q.w(), this->x() - q.x(), this->y() - q.y(),
978 this->z() - q.z());
979 }

◆ operator-=()

template<typename Scalar >
template<typename Q , std::enable_if_t< std::is_same< Q, Quaternion >::value||std::is_same< Q, Eigen::Quaternion< Scalar > >::value, int > = 0>
const Quaternion & LibXR::Quaternion< Scalar >::operator-= ( const Q & q)
inline

Definition at line 1029 of file transform.hpp.

1030 {
1031 *this = *this - q;
1032 return *this;
1033 }

◆ operator/() [1/2]

template<typename Scalar >
Quaternion LibXR::Quaternion< Scalar >::operator/ ( const Eigen::Quaternion< Scalar > & q) const
inline

Definition at line 1010 of file transform.hpp.

1011 {
1012 return Eigen::Quaternion<Scalar>(*this) * q.conjugate();
1013 }

◆ operator/() [2/2]

template<typename Scalar >
Quaternion LibXR::Quaternion< Scalar >::operator/ ( const Quaternion< Scalar > & q) const
inline

四元数除法(即左乘其共轭) / Quaternion division (multiplication by its conjugate)

Parameters
q另一个四元数 / Another quaternion
Returns
计算后的四元数 / Computed quaternion

Definition at line 1008 of file transform.hpp.

1008{ return (*this) * (-q); }

◆ operator=()

template<typename Scalar >
Quaternion & LibXR::Quaternion< Scalar >::operator= ( const Eigen::Quaternion< Scalar > & q)
inline

赋值运算符 / Assignment operator

Parameters
q另一个四元数 / Another quaternion
Returns
赋值后的 Quaternion / Assigned Quaternion

Definition at line 946 of file transform.hpp.

947 {
948 *this = Quaternion(q);
949 return *this;
950 }

◆ ToEulerAngle()

template<typename Scalar >
Eigen::Matrix< Scalar, 3, 1 > LibXR::Quaternion< Scalar >::ToEulerAngle ( ) const
inline

获取四元数的欧拉角表示(默认使用 ZYX 旋转顺序) Get the Euler angles representation of the quaternion (default ZYX order)

该方法将四元数转换为欧拉角,表示旋转顺序为 ZYX(即先绕 Z 轴旋转,再绕 Y 轴,最后绕 X 轴)。 This method converts the quaternion into Euler angles using the ZYX rotation order (first rotate around the Z-axis, then Y-axis, and finally the X-axis).

Returns
计算得到的欧拉角向量 (roll, pitch, yaw) / Computed Euler angles vector (roll, pitch, yaw)

Definition at line 1056 of file transform.hpp.

1056{ return ToEulerAngleZYX(); }

◆ ToEulerAngleXYZ()

template<typename Scalar >
Eigen::Matrix< Scalar, 3, 1 > LibXR::Quaternion< Scalar >::ToEulerAngleXYZ ( ) const
inline

Definition at line 1108 of file transform.hpp.

1109 {
1110 Scalar yaw = std::atan2(-2 * (this->x() * this->y() - this->w() * this->z()),
1111 1 - 2 * (this->z() * this->z() + this->y() * this->y()));
1112 Scalar pitch = std::asin(2 * (this->w() * this->y() + this->x() * this->z()));
1113 Scalar roll = std::atan2(-2 * (this->y() * this->z() - this->w() * this->x()),
1114 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1115 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1116 }

◆ ToEulerAngleXZY()

template<typename Scalar >
Eigen::Matrix< Scalar, 3, 1 > LibXR::Quaternion< Scalar >::ToEulerAngleXZY ( ) const
inline

Definition at line 1098 of file transform.hpp.

1099 {
1100 Scalar pitch = std::atan2(2 * (this->w() * this->y() + this->x() * this->z()),
1101 1 - 2 * (this->z() * this->z() + this->y() * this->y()));
1102 Scalar yaw = std::asin(2 * (this->w() * this->z() - this->x() * this->y()));
1103 Scalar roll = std::atan2(2 * (this->w() * this->x() + this->y() * this->z()),
1104 1 - 2 * (this->z() * this->z() + this->x() * this->x()));
1105 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1106 }

◆ ToEulerAngleYXZ()

template<typename Scalar >
Eigen::Matrix< Scalar, 3, 1 > LibXR::Quaternion< Scalar >::ToEulerAngleYXZ ( ) const
inline

Definition at line 1078 of file transform.hpp.

1079 {
1080 Scalar roll = std::asin(2 * (this->w() * this->x() - this->y() * this->z()));
1081 Scalar yaw = std::atan2(2 * (this->w() * this->z() + this->x() * this->y()),
1082 1 - 2 * (this->z() * this->z() + this->x() * this->x()));
1083 Scalar pitch = std::atan2(2 * (this->x() * this->z() + this->w() * this->y()),
1084 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1085 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1086 }

◆ ToEulerAngleYZX()

template<typename Scalar >
Eigen::Matrix< Scalar, 3, 1 > LibXR::Quaternion< Scalar >::ToEulerAngleYZX ( ) const
inline

Definition at line 1058 of file transform.hpp.

1059 {
1060 Scalar roll = std::atan2(2 * this->w() * this->x() - 2 * this->y() * this->z(),
1061 1 - 2 * (this->x() * this->x() + this->z() * this->z()));
1062 Scalar pitch = std::atan2(2 * this->w() * this->y() - 2 * this->x() * this->z(),
1063 1 - 2 * (this->y() * this->y() + this->z() * this->z()));
1064 Scalar yaw = std::asin(2 * (this->w() * this->z() + this->x() * this->y()));
1065 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1066 }

◆ ToEulerAngleZXY()

template<typename Scalar >
Eigen::Matrix< Scalar, 3, 1 > LibXR::Quaternion< Scalar >::ToEulerAngleZXY ( ) const
inline

Definition at line 1088 of file transform.hpp.

1089 {
1090 Scalar pitch = std::atan2(-2 * (this->x() * this->z() - this->w() * this->y()),
1091 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1092 Scalar roll = std::asin(2 * (this->w() * this->x() + this->y() * this->z()));
1093 Scalar yaw = std::atan2(-2 * (this->x() * this->y() - this->w() * this->z()),
1094 1 - 2 * (this->z() * this->z() + this->x() * this->x()));
1095 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1096 }

◆ ToEulerAngleZYX()

template<typename Scalar >
Eigen::Matrix< Scalar, 3, 1 > LibXR::Quaternion< Scalar >::ToEulerAngleZYX ( ) const
inline

Definition at line 1068 of file transform.hpp.

1069 {
1070 Scalar yaw = std::atan2(2 * (this->w() * this->z() + this->x() * this->y()),
1071 1 - 2 * (this->z() * this->z() + this->y() * this->y()));
1072 Scalar pitch = std::asin(2 * (this->w() * this->y() - this->x() * this->z()));
1073 Scalar roll = std::atan2(2 * (this->w() * this->x() + this->y() * this->z()),
1074 1 - 2 * (this->y() * this->y() + this->x() * this->x()));
1075 return Eigen::Matrix<Scalar, 3, 1>(roll, pitch, yaw);
1076 }

◆ ToRotationMatrix()

template<typename Scalar >
Eigen::Matrix< Scalar, 3, 3 > LibXR::Quaternion< Scalar >::ToRotationMatrix ( ) const
inline

将四元数转换为 3x3 旋转矩阵 / Convert the quaternion to a 3x3 rotation matrix

该方法使用四元数生成等效的 3x3 旋转矩阵,矩阵可用于坐标变换、姿态计算等。 This method generates an equivalent 3x3 rotation matrix from the quaternion. The resulting matrix can be used for coordinate transformations, attitude calculations, etc.

Returns
计算得到的 3x3 旋转矩阵 / Computed 3x3 rotation matrix

Definition at line 1128 of file transform.hpp.

1129 {
1130 return Eigen::Matrix<Scalar, 3, 3>(*this);
1131 }

The documentation for this class was generated from the following file: