Public Member Functions | Static Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes
towr::EulerConverter Class Reference

Converts Euler angles and derivatives to angular quantities. More...

#include <euler_converter.h>

List of all members.

Public Member Functions

Jacobian DerivOfRotVecMult (double t, const Vector3d &v, bool inverse) const
 Returns the derivative of result of the linear equation M*v.
 EulerConverter ()
 EulerConverter (const NodeSpline::Ptr &euler_angles)
 Constructs and links this object to the Euler angle values.
Vector3d GetAngularAccelerationInWorld (double t) const
 Converts Euler angles, rates and rate derivatives o angular accelerations.
Vector3d GetAngularVelocityInWorld (double t) const
 Converts Euler angles and Euler rates to angular velocities.
Jacobian GetDerivOfAngAccWrtEulerNodes (double t) const
 Jacobian of the angular acceleration with respect to the Euler nodes.
Jacobian GetDerivOfAngVelWrtEulerNodes (double t) const
 Jacobian of the angular velocity with respect to the Euler nodes.
Eigen::Quaterniond GetQuaternionBaseToWorld (double t) const
 Converts the Euler angles at time t to a Quaternion.
MatrixSXd GetRotationMatrixBaseToWorld (double t) const
 Converts the Euler angles at time t to a rotation matrix.
virtual ~EulerConverter ()

Static Public Member Functions

static Eigen::Quaterniond GetQuaternionBaseToWorld (const EulerAngles &pos)
static MatrixSXd GetRotationMatrixBaseToWorld (const EulerAngles &xyz)

Private Member Functions

JacRowMatrix GetDerivativeOfRotationMatrixWrtNodes (double t) const
 matrix of derivatives of each cell w.r.t node values.
Jacobian GetDerivMdotwrtNodes (double t, Dim3D dim) const
 Derivative of the dim row of the time derivative of M with respect to the node values.
Jacobian GetDerivMwrtNodes (double t, Dim3D dim) const
 Derivative of the dim row of matrix M with respect to the node values.
JacobianRow GetJac (double t, Dx deriv, Dim3D dim) const

Static Private Member Functions

static Vector3d GetAngularAccelerationInWorld (State euler)
static Vector3d GetAngularVelocityInWorld (const EulerAngles &pos, const EulerRates &vel)
static MatrixSXd GetM (const EulerAngles &xyz)
 Matrix that maps euler rates to angular velocities in world.
static MatrixSXd GetMdot (const EulerAngles &xyz, const EulerRates &xyz_d)
 time derivative of GetM()

Private Attributes

NodeSpline::Ptr euler_
Jacobian jac_wrt_nodes_structure_

Detailed Description

Converts Euler angles and derivatives to angular quantities.

Euler angles, their first derivatives (Euler rates) and their second derivatives fully define the angular state of an rigid body in space. This class provides equivalent formulation of these values, specifically:

Furthermore, the Euler angle spline is fully defined by a set of node values. This class also gives the derivative of the above quantities with respect to the values of these nodes.

Formulas taken from kindr: http://docs.leggedrobotics.com/kindr/cheatsheet_latest.pdf

See matlab script "matlab/euler_converter.m" for derivation.

Definition at line 62 of file euler_converter.h.


Constructor & Destructor Documentation

towr::EulerConverter::EulerConverter ( const NodeSpline::Ptr &  euler_angles)

Constructs and links this object to the Euler angle values.

Parameters:
euler_angles_splineThe Euler angle spline defined by node values.

The order of application that is assumed here is (Z,Y',X''). So in order to get the orientation of an object in space from the Euler angles, we first rotate around yaw(z) axis, then around new pitch(y) axis and finally around new roll(x) axis.

However, the 3-dimensional Euler angles must store the euler angles, rates, and rate derivatives in the order (roll, pitch, yaw): double roll = euler_angles->GetPoint(t).x(); double pitch = euler_angles->GetPoint(t).y(); double yaw = euler_angles->GetPoint(t).z();

Definition at line 38 of file euler_converter.cc.


Member Function Documentation

EulerConverter::Jacobian towr::EulerConverter::DerivOfRotVecMult ( double  t,
const Vector3d &  v,
bool  inverse 
) const

Returns the derivative of result of the linear equation M*v.

M is the rotation matrix from base to world, defined by the Euler nodes. v is any vector independent of the Euler nodes. The sensitivity of the 3-dimensional vector w.r.t the Euler node values is given.

Parameters:
ttime at which the Euler angles are evaluated.
vvector (e.g. relative position, velocity, acceleration).
inverseif true, the derivative for M^(-1)*v is evaluated.
Returns:
3 x n dimensional matrix (n = number of Euler node values).

Definition at line 224 of file euler_converter.cc.

Eigen::Vector3d towr::EulerConverter::GetAngularAccelerationInWorld ( double  t) const

Converts Euler angles, rates and rate derivatives o angular accelerations.

Parameters:
tThe current time in the euler angles spline.
Returns:
A 3-dim vector (x,y,z) of the angular accelerations in world frame.

Definition at line 73 of file euler_converter.cc.

Eigen::Vector3d towr::EulerConverter::GetAngularAccelerationInWorld ( State  euler) [static, private]
See also:
GetAngularAccelerationInWorld(t)

Definition at line 80 of file euler_converter.cc.

Eigen::Vector3d towr::EulerConverter::GetAngularVelocityInWorld ( double  t) const

Converts Euler angles and Euler rates to angular velocities.

Parameters:
tThe current time in the euler angles spline.
Returns:
A 3-dim vector (x,y,z) of the angular velocities in world frame.

Definition at line 59 of file euler_converter.cc.

Eigen::Vector3d towr::EulerConverter::GetAngularVelocityInWorld ( const EulerAngles &  pos,
const EulerRates &  vel 
) [static, private]
See also:
GetAngularVelocityInWorld(t)

Definition at line 66 of file euler_converter.cc.

EulerConverter::JacRowMatrix towr::EulerConverter::GetDerivativeOfRotationMatrixWrtNodes ( double  t) const [private]

matrix of derivatives of each cell w.r.t node values.

This 2d-array has the same dimensions as the rotation matrix M_IB, but each cell if filled with a row vector.

Definition at line 242 of file euler_converter.cc.

EulerConverter::Jacobian towr::EulerConverter::GetDerivMdotwrtNodes ( double  t,
Dim3D  dim 
) const [private]

Derivative of the dim row of the time derivative of M with respect to the node values.

Parameters:
dimWhich dimension of the angular acceleration is desired.

Definition at line 271 of file euler_converter.cc.

EulerConverter::Jacobian towr::EulerConverter::GetDerivMwrtNodes ( double  t,
Dim3D  dim 
) const [private]

Derivative of the dim row of matrix M with respect to the node values.

Parameters:
dimWhich dimension of the angular acceleration is desired.
Returns:
the Jacobian w.r.t the coefficients for each of the 3 rows of the matrix stacked on top of each other.

Definition at line 169 of file euler_converter.cc.

EulerConverter::Jacobian towr::EulerConverter::GetDerivOfAngAccWrtEulerNodes ( double  t) const

Jacobian of the angular acceleration with respect to the Euler nodes.

Parameters:
tThe current time in the Euler angles spline.
Returns:
The 3xn Jacobian Matrix of derivatives. 3: because angular acceleration has an x,y,z component n: the number of optimized nodes values defining the Euler spline.

Definition at line 105 of file euler_converter.cc.

EulerConverter::Jacobian towr::EulerConverter::GetDerivOfAngVelWrtEulerNodes ( double  t) const

Jacobian of the angular velocity with respect to the Euler nodes.

Parameters:
tThe current time in the Euler angles spline.
Returns:
The 3xn Jacobian Matrix of derivatives. 3: because angular velocity has an x,y,z component. n: the number of optimized nodes values defining the Euler spline.

Definition at line 86 of file euler_converter.cc.

EulerConverter::JacobianRow towr::EulerConverter::GetJac ( double  t,
Dx  deriv,
Dim3D  dim 
) const [private]

Definition at line 307 of file euler_converter.cc.

EulerConverter::MatrixSXd towr::EulerConverter::GetM ( const EulerAngles &  xyz) [static, private]

Matrix that maps euler rates to angular velocities in world.

Make sure euler rates are ordered roll-pitch-yaw. They are however applied in the order yaw-pitch-role to determine the angular velocities.

Definition at line 134 of file euler_converter.cc.

EulerConverter::MatrixSXd towr::EulerConverter::GetMdot ( const EulerAngles &  xyz,
const EulerRates &  xyz_d 
) [static, private]

time derivative of GetM()

Definition at line 151 of file euler_converter.cc.

Eigen::Quaterniond towr::EulerConverter::GetQuaternionBaseToWorld ( double  t) const

Converts the Euler angles at time t to a Quaternion.

Parameters:
tThe current time in the euler angles spline.
Returns:
A Quaternion the maps a vector from base to world frame.

Definition at line 45 of file euler_converter.cc.

Eigen::Quaterniond towr::EulerConverter::GetQuaternionBaseToWorld ( const EulerAngles &  pos) [static]
See also:
GetQuaternionBaseToWorld(t)

Definition at line 52 of file euler_converter.cc.

EulerConverter::MatrixSXd towr::EulerConverter::GetRotationMatrixBaseToWorld ( double  t) const

Converts the Euler angles at time t to a rotation matrix.

Parameters:
tThe current time in the euler angles spline.
Returns:
A 3x3 rotation matrix that maps a vector from base to world frame.

Definition at line 201 of file euler_converter.cc.

EulerConverter::MatrixSXd towr::EulerConverter::GetRotationMatrixBaseToWorld ( const EulerAngles &  xyz) [static]
See also:
GetRotationMatrixBaseToWorld(t)

Definition at line 208 of file euler_converter.cc.


Member Data Documentation

NodeSpline::Ptr towr::EulerConverter::euler_ [private]

Definition at line 159 of file euler_converter.h.

Definition at line 209 of file euler_converter.h.


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


towr
Author(s): Alexander W. Winkler
autogenerated on Mon Apr 15 2019 02:42:32