Cheetah Software  1.0
orientation_tools.h File Reference

Utility functions for 3D rotations. More...

#include "Math/MathUtilities.h"
#include "cppTypes.h"
#include <eigen3/Eigen/Dense>
#include <cmath>
#include <iostream>
#include <type_traits>
+ Include dependency graph for orientation_tools.h:
+ This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 ori
 

Enumerations

enum  ori::CoordinateAxis { ori::CoordinateAxis::X, ori::CoordinateAxis::Y, ori::CoordinateAxis::Z }
 

Functions

template<typename T >
ori::rad2deg (T rad)
 
template<typename T >
ori::deg2rad (T deg)
 
template<typename T >
Mat3< T > ori::coordinateRotation (CoordinateAxis axis, T theta)
 
template<typename T >
Mat3< typename T::Scalar > ori::rpyToRotMat (const Eigen::MatrixBase< T > &v)
 
template<typename T >
Mat3< typename T::Scalar > ori::vectorToSkewMat (const Eigen::MatrixBase< T > &v)
 
template<typename T >
Vec3< typename T::Scalar > ori::matToSkewVec (const Eigen::MatrixBase< T > &m)
 
template<typename T >
Quat< typename T::Scalar > ori::rotationMatrixToQuaternion (const Eigen::MatrixBase< T > &r1)
 
template<typename T >
Mat3< typename T::Scalar > ori::quaternionToRotationMatrix (const Eigen::MatrixBase< T > &q)
 
template<typename T >
Vec3< typename T::Scalar > ori::quatToRPY (const Eigen::MatrixBase< T > &q)
 
template<typename T >
Quat< typename T::Scalar > ori::rpyToQuat (const Eigen::MatrixBase< T > &rpy)
 
template<typename T >
Vec3< typename T::Scalar > ori::quatToso3 (const Eigen::MatrixBase< T > &q)
 
template<typename T >
Vec3< typename T::Scalar > ori::rotationMatrixToRPY (const Eigen::MatrixBase< T > &R)
 
template<typename T , typename T2 >
Quat< typename T::Scalar > ori::quatDerivative (const Eigen::MatrixBase< T > &q, const Eigen::MatrixBase< T2 > &omega)
 
template<typename T >
Quat< typename T::Scalar > ori::quatProduct (const Eigen::MatrixBase< T > &q1, const Eigen::MatrixBase< T > &q2)
 
template<typename T , typename T2 , typename T3 >
Quat< typename T::Scalar > ori::integrateQuat (const Eigen::MatrixBase< T > &quat, const Eigen::MatrixBase< T2 > &omega, T3 dt)
 
template<typename T , typename T2 , typename T3 >
Quat< typename T::Scalar > ori::integrateQuatImplicit (const Eigen::MatrixBase< T > &quat, const Eigen::MatrixBase< T2 > &omega, T3 dt)
 
template<typename T >
void ori::quaternionToso3 (const Quat< T > quat, Vec3< T > &so3)
 
template<typename T >
Quat< T > ori::so3ToQuat (Vec3< T > &so3)
 

Variables

static constexpr double ori::quaternionDerviativeStabilization = 0.1
 

Detailed Description

Utility functions for 3D rotations.

This file contains rotation utilities. We generally use "coordinate transformations" as opposed to the displacement transformations that are commonly found in graphics. To describe the orientation of a body, we use a rotation matrix which transforms from world to body coordinates. This is the transpose of the matrix which would rotate the body itself into the correct orientation.

This follows the convention of Roy Featherstone's excellent book, Rigid Body Dynamics Algorithms and the spatial_v2 MATLAB library that comes with it. Note that we don't use the spatial_v2 convention for quaternions!

Definition in file orientation_tools.h.