robotoc
robotoc - efficient ROBOT Optimal Control solvers
Loading...
Searching...
No Matches
robotoc::rotation Namespace Reference

Enumerations

enum class  ProjectionAxis { X , Y , Z }
 Projection axis of the rotation. More...
 

Functions

template<typename VectorType >
Eigen::Matrix3d RotationMatrixFromQuaternion (const Eigen::MatrixBase< VectorType > &quat_xyzw)
 Convert quaternion vector (x, y, z, w) to a Rotation matrix. More...
 
template<typename VectorType >
Eigen::Matrix3d RotationMatrixFromNormalVector (const Eigen::MatrixBase< VectorType > &normal_vector)
 Convert a normal vector to its surface Rotation matrix. More...
 
template<typename MatrixType >
Eigen::Vector4d QuaternionFromRotationMatrix (const Eigen::MatrixBase< MatrixType > &R)
 Convert a rotation matrix to a quaternion vector (x, y, z, w). More...
 
template<typename VectorType >
Eigen::Vector4d QuaternionFromNormalVector (const Eigen::MatrixBase< VectorType > &normal_vector)
 Convert a normal vector to its surface quaternion (x, y, z, w). More...
 
void ProjectRotationMatrix (Eigen::Matrix3d &R, const ProjectionAxis axis)
 Projects a rotation matrix onto a specified axis. More...
 

Enumeration Type Documentation

◆ ProjectionAxis

Projection axis of the rotation.

Enumerator

Function Documentation

◆ ProjectRotationMatrix()

void robotoc::rotation::ProjectRotationMatrix ( Eigen::Matrix3d &  R,
const ProjectionAxis  axis 
)
inline

Projects a rotation matrix onto a specified axis.

Parameters
[in,out]RRotation matrix.
[in]axisAxis of the projection.

◆ QuaternionFromNormalVector()

template<typename VectorType >
Eigen::Vector4d robotoc::rotation::QuaternionFromNormalVector ( const Eigen::MatrixBase< VectorType > &  normal_vector)
inline

Convert a normal vector to its surface quaternion (x, y, z, w).

Parameters
[in]normal_vectorNormal vector.
Returns
Quaternion vector (x, y, z, w).

◆ QuaternionFromRotationMatrix()

template<typename MatrixType >
Eigen::Vector4d robotoc::rotation::QuaternionFromRotationMatrix ( const Eigen::MatrixBase< MatrixType > &  R)
inline

Convert a rotation matrix to a quaternion vector (x, y, z, w).

Parameters
[in]Rrotation matrix.
Returns
Quaternion vector (x, y, z, w).

◆ RotationMatrixFromNormalVector()

template<typename VectorType >
Eigen::Matrix3d robotoc::rotation::RotationMatrixFromNormalVector ( const Eigen::MatrixBase< VectorType > &  normal_vector)
inline

Convert a normal vector to its surface Rotation matrix.

Parameters
[in]normal_vectorNormal vector.
Returns
Rotation matrixo of the surface.

◆ RotationMatrixFromQuaternion()

template<typename VectorType >
Eigen::Matrix3d robotoc::rotation::RotationMatrixFromQuaternion ( const Eigen::MatrixBase< VectorType > &  quat_xyzw)
inline

Convert quaternion vector (x, y, z, w) to a Rotation matrix.

Parameters
[in]quat_xyzwQuaternion vector (x, y, z, w).
Returns
Rotation matrix.