maliput
Rotation Class Reference

Detailed Description

A 3-dimensional rotation.

#include <include/maliput/api/lane_data.h>

Public Member Functions

 Rotation ()
 Default constructor, creating an identity Rotation. More...
 
const math::Quaternionquat () const
 Provides a quaternion representation of the rotation. More...
 
void set_quat (const math::Quaternion &quaternion)
 Sets value from a math::Quaternion quaternion (which will be normalized). More...
 
math::Matrix3 matrix () const
 Provides a 3x3 rotation matrix representation of "this" rotation. More...
 
math::RollPitchYaw rpy () const
 Provides a representation of rotation as a vector of angles [roll, pitch, yaw] (in radians). More...
 
double roll () const
 Returns the roll component of the Rotation (in radians). More...
 
double pitch () const
 Returns the pitch component of the Rotation (in radians). More...
 
double yaw () const
 Returns the yaw component of the Rotation (in radians). More...
 
InertialPosition Apply (const InertialPosition &inertial_position) const
 Returns the rotated inertial_position InertialPosition in the Inertial-frame. More...
 
Rotation Reverse () const
 Returns the rotation corresponding to "going the other way instead", i.e., the orientation of (-s,-r,h). More...
 
double Distance (const Rotation &rot) const
 Let $R_1$ be this rotation description, and let rot be $R_2$, another rotation description in the Inertial-frame. More...
 

Static Public Member Functions

static Rotation FromQuat (const math::Quaternion &quaternion)
 Constructs a Rotation from a math::Quaternion quaternion (which will be normalized). More...
 
static Rotation FromRpy (const math::Vector3 &rpy)
 Constructs a Rotation from rpy, a vector of [roll, pitch, yaw], expressing a roll around X, followed by pitch around Y, followed by yaw around Z (with all angles in radians). More...
 
static Rotation FromRpy (double roll, double pitch, double yaw)
 Constructs a Rotation expressing a roll around X, followed by pitch around Y, followed by yaw around Z (with all angles in radians). More...
 

Constructor & Destructor Documentation

◆ Rotation()

Rotation ( )

Default constructor, creating an identity Rotation.

Member Function Documentation

◆ Apply()

InertialPosition Apply ( const InertialPosition inertial_position) const

Returns the rotated inertial_position InertialPosition in the Inertial-frame.

◆ Distance()

double Distance ( const Rotation rot) const

Let $R_1$ be this rotation description, and let rot be $R_2$, another rotation description in the Inertial-frame.

Let $F_W_1$ and $F_W_2$ be the versors describing the basis of the Inertial-frame. Then, let $F_R_1$ and $F_R_2$ be the rotated $F_W_1$ and $F_W_2$ by $R_1$ and $R_2$ respectively. This method returns the root square sum of each angle between versors in $F_R_1$ and $F_R_2$.

◆ FromQuat()

static Rotation FromQuat ( const math::Quaternion quaternion)
static

Constructs a Rotation from a math::Quaternion quaternion (which will be normalized).

◆ FromRpy() [1/2]

static Rotation FromRpy ( const math::Vector3 rpy)
static

Constructs a Rotation from rpy, a vector of [roll, pitch, yaw], expressing a roll around X, followed by pitch around Y, followed by yaw around Z (with all angles in radians).

◆ FromRpy() [2/2]

static Rotation FromRpy ( double  roll,
double  pitch,
double  yaw 
)
static

Constructs a Rotation expressing a roll around X, followed by pitch around Y, followed by yaw around Z (with all angles in radians).

◆ matrix()

math::Matrix3 matrix ( ) const

Provides a 3x3 rotation matrix representation of "this" rotation.

◆ pitch()

double pitch ( ) const

Returns the pitch component of the Rotation (in radians).

◆ quat()

const math::Quaternion& quat ( ) const

Provides a quaternion representation of the rotation.

◆ Reverse()

Rotation Reverse ( ) const

Returns the rotation corresponding to "going the other way instead", i.e., the orientation of (-s,-r,h).

This is equivalent to a pre-rotation by PI in the s/r plane.

◆ roll()

double roll ( ) const

Returns the roll component of the Rotation (in radians).

◆ rpy()

math::RollPitchYaw rpy ( ) const

Provides a representation of rotation as a vector of angles [roll, pitch, yaw] (in radians).

◆ set_quat()

void set_quat ( const math::Quaternion quaternion)

Sets value from a math::Quaternion quaternion (which will be normalized).

◆ yaw()

double yaw ( ) const

Returns the yaw component of the Rotation (in radians).


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