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 >:
Collaboration diagram for LibXR::Quaternion< Scalar >:

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< Scalaroperator* (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 809 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 816 of file transform.hpp.

816: 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 825 of file transform.hpp.

826 : Eigen::Quaternion<Scalar>(w, x, y, z)
827 {
828 }
constexpr auto min(T1 a, T2 b) -> typename std::common_type< T1, T2 >::type
计算两个数的最小值

◆ 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 834 of file transform.hpp.

834: 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 840 of file transform.hpp.

841 : Eigen::Quaternion<Scalar>(
842 Eigen::Quaternion<Scalar>(static_cast<Eigen::Matrix<Scalar, 3, 3>>(R)))
843 {
844 }

◆ 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 851 of file transform.hpp.

852 : Eigen::Quaternion<Scalar>(
853 Eigen::Quaternion<Scalar>(static_cast<Eigen::Matrix<Scalar, 3, 3>>(R)))
854 {
855 }

◆ 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 865 of file transform.hpp.

865 : Eigen::Quaternion<Scalar>(data)
866 {
867 }

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 874 of file transform.hpp.

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 }

◆ operator*() [1/3]

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

Definition at line 947 of file transform.hpp.

948 {
949 return Eigen::Quaternion<Scalar>(*this) * q;
950 }

◆ operator*() [2/3]

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

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

Definition at line 990 of file transform.hpp.

991 {
992 return Eigen::Quaternion<Scalar>(*this) * Eigen::Matrix<Scalar, 3, 1>(p);
993 }

◆ operator*() [3/3]

四元数乘法 / Quaternion multiplication

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

Definition at line 942 of file transform.hpp.

943 {
944 return Eigen::Quaternion<Scalar>(*this) * Eigen::Quaternion<Scalar>(q);
945 }

◆ operator+() [1/2]

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

Definition at line 919 of file transform.hpp.

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

◆ operator+() [2/2]

四元数加法 / Quaternion addition

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

Definition at line 913 of file transform.hpp.

914 {
915 return Quaternion(this->w() + q.w(), this->x() + q.x(), this->y() + q.y(),
916 this->z() + q.z());
917 }

◆ 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 969 of file transform.hpp.

970 {
971 *this = *this + q;
972 return *this;
973 }

◆ operator-() [1/3]

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

取共轭四元数 / Get the conjugate quaternion

Returns
共轭四元数 / Conjugated quaternion

Definition at line 906 of file transform.hpp.

906{ 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 931 of file transform.hpp.

932 {
933 return Quaternion(this->w() - q.w(), this->x() - q.x(), this->y() - q.y(),
934 this->z() - q.z());
935 }

◆ operator-() [3/3]

Definition at line 925 of file transform.hpp.

926 {
927 return Quaternion(this->w() - q.w(), this->x() - q.x(), this->y() - q.y(),
928 this->z() - q.z());
929 }

◆ 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 979 of file transform.hpp.

980 {
981 *this = *this - q;
982 return *this;
983 }

◆ operator/() [1/2]

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

Definition at line 960 of file transform.hpp.

961 {
962 return (*this) * (-q);
963 }

◆ operator/() [2/2]

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

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

Definition at line 958 of file transform.hpp.

958{ 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 896 of file transform.hpp.

897 {
898 *this = Quaternion(q);
899 return *this;
900 }

◆ 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 1006 of file transform.hpp.

1006{ return ToEulerAngleZYX(); }

◆ ToEulerAngleXYZ()

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

Definition at line 1058 of file transform.hpp.

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 }

◆ ToEulerAngleXZY()

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

Definition at line 1048 of file transform.hpp.

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 }

◆ ToEulerAngleYXZ()

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

Definition at line 1028 of file transform.hpp.

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 }

◆ ToEulerAngleYZX()

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

Definition at line 1008 of file transform.hpp.

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 }

◆ ToEulerAngleZXY()

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

Definition at line 1038 of file transform.hpp.

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 }

◆ ToEulerAngleZYX()

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

Definition at line 1018 of file transform.hpp.

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 }

◆ 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 1078 of file transform.hpp.

1079 {
1080 return Eigen::Matrix<Scalar, 3, 3>(*this);
1081 }

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