Class inertialsim::geometry::CoordinateRotation¶
ClassList > inertialsim > geometry > CoordinateRotation
3-dimensional coordinate frame rotations (passive convention). More...
#include <coordinate_rotation.h>
Inherits the following classes: inertialsim::geometry::RotationBase
Public Types inherited from inertialsim::geometry::RotationBase¶
See inertialsim::geometry::RotationBase
| Type | Name |
|---|---|
| typedef MatrixLieGroup< Derived, 3, 3 > | Base |
Public Types inherited from inertialsim::geometry::MatrixLieGroup¶
See inertialsim::geometry::MatrixLieGroup
| Type | Name |
|---|---|
| typedef Eigen::Matrix< Scalar, AlgebraDimension, Eigen::Dynamic > | AlgebraArray Matrix of algebra elements (rows = axes, cols = samples). |
| typedef Eigen::Matrix< Scalar, AlgebraDimension, 1 > | AlgebraElement Algebra element type (vector). |
| typedef std::vector< GroupElement > | GroupArray Array of group elements. |
| typedef Eigen::Matrix< Scalar, GroupDimension, GroupDimension > | GroupElement Group element type (square matrix). |
| typedef Eigen::Matrix< Scalar, AlgebraDimension, AlgebraDimension > | JacobianMatrix Jacobian matrix (algebra to algebra). |
| typedef std::vector< JacobianMatrix > | JacobianMatrixArray Array of Jacobian matrices. |
Public Functions¶
| Type | Name |
|---|---|
| AxisAngle | AsAxisAngle () const Return axis and angle representation (passive). |
| EulerAngles | AsEuler (const std::string & sequence) const Return Euler angle representation (intrinsic). |
| RotationVector | AsRotationVector () const Return rotation vector representation (passive). |
Public Functions inherited from inertialsim::geometry::RotationBase¶
See inertialsim::geometry::RotationBase
| Type | Name |
|---|---|
| AxisAngle | AsAxisAngle () const Return axis and angle representation. |
| EulerAngles | AsEuler (const std::string & sequence) const Return the Euler angle representation. |
| const RotationMatrixArray & | AsMatrix () const Return the rotation matrix representation. |
| Quaternion | AsQuaternion () const Return the quaternion representation. |
| RotationVector | AsRotationVector () const Return the rotation vector representation. |
| RotationVector | Error (const RotationBase< OtherDerived > & reference) const Calculate error compared to a reference rotation. |
| int | num_rotations () const Number of rotations stored. |
Public Functions inherited from inertialsim::geometry::MatrixLieGroup¶
See inertialsim::geometry::MatrixLieGroup
| Type | Name |
|---|---|
| Vector3D | Apply (const Vector3D & vectors) const Apply the group action to an array of vectors. |
| Derived | Interpolate (const Timestamps & interp_time, Interpolator method=Interpolator::LINEAR) const Interpolate at given times. |
| Derived | Inverse () const Invert an instance. |
| Derived | Slice (int start, int end) const Get a slice of elements. |
| AlgebraArray | TimeDerivative (int order=1, int accuracy=4, const std::string & side="right") const Compute time derivative using finite differences. |
| int | num_elements () const Number of elements stored in the instance. |
| Derived | operator* (const Derived & rhs) const Composition operator on the matrix group. Supports broadcasting: if either lhs or rhs has size 1, it will be broadcast against all elements of the other operand. Derived classes may implement more efficient methods. |
| Derived | operator[] (int index) const Get a single element by index. |
| const std::optional< Timestamps > & | time () const Time array (or nullopt if not set). |
| virtual | ~MatrixLieGroup () = default |
Public Static Functions¶
| Type | Name |
|---|---|
| CoordinateRotation | FromAxisAngle (const Vector3D & axis, const Scalar1D & angle, const std::optional< Timestamps > & time=std::nullopt) Construct from axis and angle (passive). |
| CoordinateRotation | FromEuler (const EulerAngles & euler, const std::string & sequence, const std::optional< Timestamps > & time=std::nullopt) Construct from Euler angles (intrinsic convention). |
| CoordinateRotation | FromRotationVector (const RotationVector & rotation_vectors, const std::optional< Timestamps > & time=std::nullopt) Construct from rotation vectors (passive). |
| JacobianMatrixArray | JacobianImpl (const AlgebraArray & rotation_vectors, const std::string & side, bool inverse) Jacobian of SO(3) exponential map (passive convention). |
Public Static Functions inherited from inertialsim::geometry::RotationBase¶
See inertialsim::geometry::RotationBase
| Type | Name |
|---|---|
| RotationMatrixArray | DoubleIntegralFactor (const RotationVector & rotation_vectors) Double integral factor. |
| Derived | FromAxisAngle (const Vector3D & axis, const Scalar1D & angle, const std::optional< Timestamps > & time=std::nullopt) Construct a Rotation from an axis and angle. |
| Derived | FromEuler (const EulerAngles & euler, const std::string & sequence, const std::optional< Timestamps > & time=std::nullopt) Construct a Rotation from a sequence of Euler angles. |
| Derived | FromMatrix (const RotationMatrixArray & matrices, const std::optional< Timestamps > & time=std::nullopt, bool orthonormalize=false) Construct a Rotation from rotation matrices. |
| Derived | FromQuaternion (const Quaternion & quaternions, const std::optional< Timestamps > & time=std::nullopt, bool scalar_last=false) Construct a Rotation from quaternions. |
| Derived | FromRotationVector (const RotationVector & rotation_vectors, const std::optional< Timestamps > & time=std::nullopt) Construct a Rotation from rotation vectors. |
| RotationMatrixArray | IntegralFactor (const RotationVector & rotation_vectors) First integral factor. |
Public Static Functions inherited from inertialsim::geometry::MatrixLieGroup¶
See inertialsim::geometry::MatrixLieGroup
| Type | Name |
|---|---|
| Derived | Compose (const std::vector< Derived > & instances) Compose a sequence of instances (first to last). |
| Derived | FromIdentity (int num_elements=1) Create identity elements. |
| Derived | FromRandom (int num_elements=1, std::optional< Eigen::numext::uint64_t > seed=std::nullopt) Create random elements. |
Protected Functions inherited from inertialsim::geometry::RotationBase¶
See inertialsim::geometry::RotationBase
| Type | Name |
|---|---|
| Vector3D | ApplyImpl (const Vector3D & vectors) const Apply rotation to vectors. |
| AlgebraArray | AsAlgebraImpl () const Return algebra representation. |
| GroupArray | AsGroupImpl () const Return as group elements (for CRTP interface). |
| Derived | InverseImpl () const Return the inverse rotation. |
| RotationBase () Default constructor. |
|
| RotationBase (const RotationMatrixArray & matrices, const std::optional< Timestamps > & time=std::nullopt) Construct from rotation matrices. |
|
| int | num_elements_impl () const Number of rotations stored. |
Protected Functions inherited from inertialsim::geometry::MatrixLieGroup¶
See inertialsim::geometry::MatrixLieGroup
| Type | Name |
|---|---|
| AlgebraArray | AsAlgebra () const Get the algebra elements. |
| GroupArray | AsGroup () const Get the group elements. |
| Derived | CubicHermiteInterpolate (const Timestamps & time) const Cubic Hermite spline interpolation. |
| Derived | LinearInterpolate (const Timestamps & time) const Linear interpolation implementation. |
| MatrixLieGroup (const std::optional< Timestamps > & time=std::nullopt) Constructor. |
|
| Derived & | derived () CRTP helper to access derived class. |
| const Derived & | derived () const |
| int | num_times () const |
Protected Static Functions inherited from inertialsim::geometry::RotationBase¶
See inertialsim::geometry::RotationBase
| Type | Name |
|---|---|
| GroupElement | ExpImpl (const AlgebraElement & rotation_vector) Exponential map: rotation vector to rotation matrix. |
| Derived | FromAlgebraImpl (const AlgebraArray & rotation_vectors, const std::optional< Timestamps > & time=std::nullopt) Construct from algebra elements (for CRTP interface). |
| Derived | FromGroupImpl (const GroupArray & elements, const std::optional< Timestamps > & time) Construct from group elements (for CRTP interface). |
| Derived | FromIdentityImpl (int num_elements) Construct identity rotations. |
| Derived | FromRandomImpl (int num_rotations, std::optional< uint64_t > seed=std::nullopt) Construct uniformly distributed random rotations. |
| JacobianMatrixArray | JacobianImpl (const AlgebraArray & rotation_vectors, const std::string & side, bool inverse) Jacobian of SO(3) exponential map. |
| AlgebraElement | LogImpl (const GroupElement & matrix) Logarithm map: rotation matrix to rotation vector. |
Protected Static Functions inherited from inertialsim::geometry::MatrixLieGroup¶
See inertialsim::geometry::MatrixLieGroup
| Type | Name |
|---|---|
| GroupElement | Exp (const AlgebraElement & vector) Exponential map from algebra to group. |
| Derived | FromAlgebra (const AlgebraArray & elements, const std::optional< Timestamps > & time) Create instance from algebra elements. |
| Derived | FromGroup (const GroupArray & elements, const std::optional< Timestamps > & time) Create instance from group elements. |
| JacobianMatrixArray | Jacobian (const AlgebraArray & algebra, const std::string & side="left", bool inverse=false) Calculate the Jacobian given algebra elements. |
| AlgebraElement | Log (const GroupElement & element) Logarithm map from group to algebra. |
Detailed Description¶
CoordinateRotation is a subclass of RotationBase that uses the passive convention. Passive rotations act to transform vector components between coordinate systems. The passive convention is the standard for describing orientation in inertial navigation and aerospace applications.
Coordinate rotations are also commonly known as direction cosine matrices (DCM) or coordinate transformation matrices.
** **
In the passive convention (used by this class), rotations act to transform the components of physical vectors to different coordinate systems. This contrasts with the active convention used by the Rotation class, where rotations act to rotate an object relative to a fixed coordinate system.
A passive coordinate rotation matrix is the transpose of the equivalent active rotation matrix: \(C_{i}^{b} = R_{i \rightarrow b}^{T}\)
Some references use the terminology alibi (active) and alias (passive). Reference [02], Reference [05], and Reference [11] discuss active vs. passive transforms in greater detail.
See also: Rotation for active rotations.
See also: CoordinateTransform for combined rotation and translation transforms.
Public Functions Documentation¶
function AsAxisAngle¶
Return axis and angle representation (passive).
Returns:
Tuple of axes (3xN) and angles (N).
function AsEuler¶
Return Euler angle representation (intrinsic).
inline EulerAngles inertialsim::geometry::CoordinateRotation::AsEuler (
const std::string & sequence
) const
Parameters:
sequenceRotation sequence (e.g., "XYZ").
Returns:
Euler angles (3xN matrix).
function AsRotationVector¶
Return rotation vector representation (passive).
Returns:
Rotation vectors (3xN matrix).
Public Static Functions Documentation¶
function FromAxisAngle¶
Construct from axis and angle (passive).
static inline CoordinateRotation inertialsim::geometry::CoordinateRotation::FromAxisAngle (
const Vector3D & axis,
const Scalar1D & angle,
const std::optional< Timestamps > & time=std::nullopt
)
Parameters:
axisUnit axes of rotation (3xN matrix).angleAngles of rotation (N vector).timeOptional time array.
Returns:
CoordinateRotation instance.
function FromEuler¶
Construct from Euler angles (intrinsic convention).
static inline CoordinateRotation inertialsim::geometry::CoordinateRotation::FromEuler (
const EulerAngles & euler,
const std::string & sequence,
const std::optional< Timestamps > & time=std::nullopt
)
Parameters:
eulerEuler angles (3xN matrix).sequenceRotation sequence (e.g., "XYZ").timeOptional time array.
Returns:
CoordinateRotation instance.
function FromRotationVector¶
Construct from rotation vectors (passive).
static inline CoordinateRotation inertialsim::geometry::CoordinateRotation::FromRotationVector (
const RotationVector & rotation_vectors,
const std::optional< Timestamps > & time=std::nullopt
)
Parameters:
rotation_vectorsRotation vectors (3xN matrix).timeOptional time array.
Returns:
CoordinateRotation instance.
function JacobianImpl¶
Jacobian of SO(3) exponential map (passive convention).
static inline JacobianMatrixArray inertialsim::geometry::CoordinateRotation::JacobianImpl (
const AlgebraArray & rotation_vectors,
const std::string & side,
bool inverse
)
Returns the transposed Jacobian due to the passive convention.
Parameters:
rotation_vectorsRotation vectors (3xN).side"left" or "right" to specify which Jacobian.inverseIf true, return inverse Jacobian.
Returns:
Vector of 3x3 Jacobian matrices.
The documentation for this class was generated from the following file cpp/include/inertialsim/geometry/coordinate_rotation.h