Apollo  6.0
Open source self driving car software
Public Member Functions | List of all members
apollo::common::math::EulerAnglesZXY< T > Class Template Reference

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

#include <euler_angles_zxy.h>

Collaboration diagram for apollo::common::math::EulerAnglesZXY< T >:
Collaboration graph

Public Member Functions

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

Detailed Description

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

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

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.

Parameters
TNumber type: double or float

Constructor & Destructor Documentation

◆ EulerAnglesZXY() [1/5]

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

Constructs an identity rotation.

◆ 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).

Parameters
yawThe yaw of the car

◆ 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.

Parameters
rollThe roll of the car
pitchThe pitch of the car
yawThe yaw of the car

◆ 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.

Parameters
qwQuaternion w-coordinate
qxQuaternion x-coordinate
qyQuaternion y-coordinate
qzQuaternion z-coordinate

◆ EulerAnglesZXY() [5/5]

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

Constructs a rotation from quaternion.

Parameters
qQuaternion

Member Function Documentation

◆ IsValid()

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

Verifies the validity of the specified rotation.

Returns
True iff -PI/2 < pitch < PI/2

◆ Normalize()

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

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

◆ pitch()

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

Getter for pitch_.

Returns
The pitch of the car

◆ roll()

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

Getter for roll_.

Returns
The roll of the car

◆ 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.

Returns
Quaternion encoding this rotation.

◆ yaw()

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

Getter for yaw_.

Returns
The yaw of the car

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