Drake
Rotation Class Reference

A 3-dimensional rotation. More...

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

Public Member Functions

 Rotation ()
 Default constructor, creating an identity Rotation. More...
 
const Quaternion< double > & quat () const
 Provides a quaternion representation of the rotation. More...
 
void set_quat (const Quaternion< double > &quaternion)
 Sets value from a Quaternion quaternion (which will be normalized). More...
 
Matrix3< doublematrix () const
 Provides a rotation matrix representation of the rotation. More...
 
Vector3< doublerpy () 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...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 Rotation (const Rotation &)=default
 
Rotationoperator= (const Rotation &)=default
 
 Rotation (Rotation &&)=default
 
Rotationoperator= (Rotation &&)=default
 

Static Public Member Functions

static Rotation FromQuat (const Quaternion< double > &quaternion)
 Constructs a Rotation from a quaternion quaternion (which will be normalized). More...
 
static Rotation FromRpy (const Vector3< double > &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...
 

Detailed Description

A 3-dimensional rotation.

Constructor & Destructor Documentation

Rotation ( const Rotation )
default
Rotation ( Rotation &&  )
default
Rotation ( )
inline

Default constructor, creating an identity Rotation.

Member Function Documentation

static Rotation FromQuat ( const Quaternion< double > &  quaternion)
inlinestatic

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

static Rotation FromRpy ( const Vector3< double > &  rpy)
inlinestatic

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

Here is the call graph for this function:

Here is the caller graph for this function:

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

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

Matrix3<double> matrix ( ) const
inline

Provides a rotation matrix representation of the rotation.

Here is the caller graph for this function:

Rotation& operator= ( Rotation &&  )
default
Rotation& operator= ( const Rotation )
default
double pitch ( ) const
inline

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

Here is the caller graph for this function:

const Quaternion<double>& quat ( ) const
inline

Provides a quaternion representation of the rotation.

double roll ( ) const
inline

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

Here is the caller graph for this function:

Vector3<double> rpy ( ) const
inline

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

Here is the call graph for this function:

void set_quat ( const Quaternion< double > &  quaternion)
inline

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

double yaw ( ) const
inline

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

Here is the call graph for this function:

Here is the caller graph for this function:


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