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.
更多...
|
| 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.
|
|
T | roll () const |
| Getter for roll_
|
|
T | pitch () const |
| Getter for pitch_
|
|
T | 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.
- 参数
-
T | Number type: double or float |
在文件 euler_angles_zxy.h 第 66 行定义.