Apollo 10.0
自动驾驶开放平台
apollo::common::math::EulerAnglesZXY< T > 模板类 参考

Any orientation of a rigid body on a 3-D space can be achieved by composing three rotations about the axes of an orthogonal coordinate system. 更多...

#include <euler_angles_zxy.h>

apollo::common::math::EulerAnglesZXY< T > 的协作图:

Public 成员函数

 EulerAnglesZXY ()
 Constructs an identity rotation.
 
 EulerAnglesZXY (T yaw)
 Constructs a rotation using only yaw (i.e., around the z-axis).
 
 EulerAnglesZXY (T roll, T pitch, T yaw)
 Constructs a rotation using arbitrary roll, pitch, and yaw.
 
 EulerAnglesZXY (T qw, T qx, T qy, T qz)
 Constructs a rotation using components of a quaternion.
 
 EulerAnglesZXY (const Eigen::Quaternion< T > &q)
 Constructs a rotation from quaternion.
 
roll () const
 Getter for roll_
 
pitch () const
 Getter for pitch_
 
yaw () const
 Getter for yaw_
 
void Normalize ()
 Normalizes roll_, pitch_, and yaw_ to [-PI, PI).
 
bool IsValid ()
 Verifies the validity of the specified rotation.
 
Eigen::Quaternion< T > ToQuaternion () const
 Converts to a quaternion with a non-negative scalar part
 

详细描述

template<typename T>
class apollo::common::math::EulerAnglesZXY< T >

Any orientation of a rigid body on a 3-D space can be achieved by composing three rotations about the axes of an orthogonal coordinate system.

These rotations are said to be extrinsic if the axes are assumed to be motionless, and intrinsic otherwise. Here, we use an intrinsic referential, which is relative to the car's orientation. Our vehicle reference frame follows NovAtel's convention: Right/Forward/Up (RFU) respectively for the axes x/y/z. In particular, we describe the orientation of the car by three angles: 1) the pitch, in (-pi/2, pi/2), corresponds to a rotation around the x-axis; 2) the roll, in [-pi, pi), corresponds to a rotation around the y-axis; 3) the yaw, in [-pi, pi), corresponds to a rotation around the z-axis. The pitch is zero when the car is level and positive when the nose is up. The roll is zero when the car is level and positive when the left part is up. The yaw is zero when the car is facing North, and positive when facing West. In turn, in the world frame, the x/y/z axes point to East/North/Up (ENU). These angles represent the rotation from the world to the vehicle frames.

Implements a class of Euler angles (actually, Tait-Bryan angles), with intrinsic sequence ZXY.

参数
TNumber type: double or float

在文件 euler_angles_zxy.h66 行定义.

构造及析构函数说明

◆ EulerAnglesZXY() [1/5]

template<typename T >
apollo::common::math::EulerAnglesZXY< T >::EulerAnglesZXY ( )
inline

Constructs an identity rotation.

在文件 euler_angles_zxy.h71 行定义.

71: roll_(0), pitch_(0), yaw_(0) {}

◆ EulerAnglesZXY() [2/5]

template<typename T >
apollo::common::math::EulerAnglesZXY< T >::EulerAnglesZXY ( yaw)
inlineexplicit

Constructs a rotation using only yaw (i.e., around the z-axis).

参数
yawThe yaw of the car

在文件 euler_angles_zxy.h78 行定义.

78: roll_(0), pitch_(0), yaw_(yaw) {}

◆ EulerAnglesZXY() [3/5]

template<typename T >
apollo::common::math::EulerAnglesZXY< T >::EulerAnglesZXY ( roll,
pitch,
yaw 
)
inline

Constructs a rotation using arbitrary roll, pitch, and yaw.

参数
rollThe roll of the car
pitchThe pitch of the car
yawThe yaw of the car

在文件 euler_angles_zxy.h87 行定义.

88 : roll_(roll), pitch_(pitch), yaw_(yaw) {}

◆ EulerAnglesZXY() [4/5]

template<typename T >
apollo::common::math::EulerAnglesZXY< T >::EulerAnglesZXY ( qw,
qx,
qy,
qz 
)
inline

Constructs a rotation using components of a quaternion.

参数
qwQuaternion w-coordinate
qxQuaternion x-coordinate
qyQuaternion y-coordinate
qzQuaternion z-coordinate

在文件 euler_angles_zxy.h98 行定义.

99 : roll_(std::atan2(static_cast<T>(2.0) * (qw * qy - qx * qz),
100 static_cast<T>(2.0) * (Square<T>(qw) + Square<T>(qz)) -
101 static_cast<T>(1.0))),
102 pitch_(std::asin(static_cast<T>(2.0) * (qw * qx + qy * qz))),
103 yaw_(std::atan2(static_cast<T>(2.0) * (qw * qz - qx * qy),
104 static_cast<T>(2.0) * (Square<T>(qw) + Square<T>(qy)) -
105 static_cast<T>(1.0))) {}

◆ EulerAnglesZXY() [5/5]

template<typename T >
apollo::common::math::EulerAnglesZXY< T >::EulerAnglesZXY ( const Eigen::Quaternion< T > &  q)
inlineexplicit

Constructs a rotation from quaternion.

参数
qQuaternion

在文件 euler_angles_zxy.h111 行定义.

112 : EulerAnglesZXY(q.w(), q.x(), q.y(), q.z()) {}
EulerAnglesZXY()
Constructs an identity rotation.

成员函数说明

◆ IsValid()

template<typename T >
bool apollo::common::math::EulerAnglesZXY< T >::IsValid ( )
inline

Verifies the validity of the specified rotation.

返回
True iff -PI/2 < pitch < PI/2

在文件 euler_angles_zxy.h145 行定义.

145 {
146 Normalize();
147 return pitch_ < M_PI_2 && pitch_ > -M_PI_2;
148 }
void Normalize()
Normalizes roll_, pitch_, and yaw_ to [-PI, PI).

◆ Normalize()

template<typename T >
void apollo::common::math::EulerAnglesZXY< T >::Normalize ( )
inline

Normalizes roll_, pitch_, and yaw_ to [-PI, PI).

在文件 euler_angles_zxy.h135 行定义.

135 {
136 roll_ = NormalizeAngle(roll_);
137 pitch_ = NormalizeAngle(pitch_);
138 yaw_ = NormalizeAngle(yaw_);
139 }
double NormalizeAngle(const double angle)
Normalize angle to [-PI, PI).
Definition math_utils.cc:53

◆ pitch()

template<typename T >
T apollo::common::math::EulerAnglesZXY< T >::pitch ( ) const
inline

Getter for pitch_

返回
The pitch of the car

在文件 euler_angles_zxy.h124 行定义.

124{ return pitch_; }

◆ roll()

template<typename T >
T apollo::common::math::EulerAnglesZXY< T >::roll ( ) const
inline

Getter for roll_

返回
The roll of the car

在文件 euler_angles_zxy.h118 行定义.

118{ return roll_; }

◆ ToQuaternion()

template<typename T >
Eigen::Quaternion< T > apollo::common::math::EulerAnglesZXY< T >::ToQuaternion ( ) const
inline

Converts to a quaternion with a non-negative scalar part

返回
Quaternion encoding this rotation.

在文件 euler_angles_zxy.h154 行定义.

154 {
155 T coeff = static_cast<T>(0.5);
156 T r = roll_ * coeff;
157 T p = pitch_ * coeff;
158 T y = yaw_ * coeff;
159
160 T sr = std::sin(r);
161 T sp = std::sin(p);
162 T sy = std::sin(y);
163
164 T cr = std::cos(r);
165 T cp = std::cos(p);
166 T cy = std::cos(y);
167
168 T qw = cr * cp * cy - sr * sp * sy;
169 T qx = cr * sp * cy - sr * cp * sy;
170 T qy = cr * sp * sy + sr * cp * cy;
171 T qz = cr * cp * sy + sr * sp * cy;
172 if (qw < 0.0) {
173 return {-qw, -qx, -qy, -qz};
174 }
175 return {qw, qx, qy, qz};
176 }

◆ yaw()

template<typename T >
T apollo::common::math::EulerAnglesZXY< T >::yaw ( ) const
inline

Getter for yaw_

返回
The yaw of the car

在文件 euler_angles_zxy.h130 行定义.

130{ return yaw_; }

该类的文档由以下文件生成: