rigid-body-kinematics.hpp File Reference

Implements integrators for the kinematics, in terms or rotations and translations. More...

#include <Eigen/SVD>
#include <state-observation/api.h>
#include <state-observation/tools/definitions.hpp>
#include <state-observation/tools/miscellaneous-algorithms.hpp>
#include <state-observation/tools/probability-law-simulation.hpp>
#include <state-observation/tools/rigid-body-kinematics.hxx>
Include dependency graph for rigid-body-kinematics.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  stateObservation::kine::indexes< rotationType >
 
struct  stateObservation::kine::indexes< rotationVector >
 
struct  stateObservation::kine::indexes< quaternion >
 
class  stateObservation::kine::Orientation
 
class  stateObservation::kine::internal::KinematicsInternal< T >
 
struct  stateObservation::kine::internal::KinematicsInternal< T >::Flags
 
struct  stateObservation::kine::Kinematics
 Class facilitating the manipulation of the kinematics of a frame within another and the associated operations. More...
 
struct  stateObservation::kine::LocalKinematics
 Class facilitating the manipulation of the local kinematics of a frame within another and the associated operations. More...
 

Namespaces

 stateObservation
 
 stateObservation::kine
 
 stateObservation::kine::internal
 

Enumerations

enum  stateObservation::kine::rotationType { stateObservation::kine::matrix = 0, stateObservation::kine::rotationVector = 1, stateObservation::kine::quaternion = 2, stateObservation::kine::angleaxis = 3 }
 

Functions

void stateObservation::kine::integrateKinematics (Vector3 &position, const Vector3 &velocity, double dt)
 
void stateObservation::kine::integrateKinematics (Vector3 &position, Vector3 &velocity, const Vector3 &acceleration, double dt)
 
void stateObservation::kine::integrateKinematics (Matrix3 &orientation, const Vector3 &rotationVelocity, double dt)
 
void stateObservation::kine::integrateKinematics (Matrix3 &orientation, Vector3 &rotationVelocity, const Vector3 &rotationAcceleration, double dt)
 
void stateObservation::kine::integrateKinematics (Quaternion &orientation, const Vector3 &rotationVelocity, double dt)
 
void stateObservation::kine::integrateKinematics (Quaternion &orientation, Vector3 &rotationVelocity, const Vector3 &rotationAcceleration, double dt)
 
void stateObservation::kine::integrateKinematics (Vector3 &position, Vector3 &velocity, const Vector3 &acceleration, Matrix3 &orientation, Vector3 &rotationVelocity, const Vector3 &rotationAcceleration, double dt)
 
void stateObservation::kine::integrateKinematics (Vector3 &position, Vector3 &velocity, const Vector3 &acceleration, Quaternion &orientation, Vector3 &rotationVelocity, const Vector3 &rotationAcceleration, double dt)
 
void stateObservation::kine::integrateKinematics (Vector3 &position, const Vector3 &velocity, Matrix3 &orientation, const Vector3 &rotationVelocity, double dt)
 integrates the postition/orientation given the velocities More...
 
void stateObservation::kine::integrateKinematics (Vector3 &position, const Vector3 &velocity, Quaternion &orientation, const Vector3 &rotationVelocity, double dt)
 integrates the postition/orientation given the velocities More...
 
Vector stateObservation::kine::regulateRotationVector (const Vector3 &v)
 
AngleAxis stateObservation::kine::rotationVectorToAngleAxis (const Vector3 &v)
 Transforms the rotation vector into angle axis. More...
 
Matrix3 stateObservation::kine::rotationVectorToRotationMatrix (const Vector3 &v)
 Transforms the rotation vector into rotation matrix. More...
 
Quaternion stateObservation::kine::rotationVectorToQuaternion (const Vector3 &v)
 Transforms the rotation vector into quaternion. More...
 
Vector3 stateObservation::kine::rotationMatrixToRotationVector (const Matrix3 &R)
 Transforms the rotation matrix into rotation vector. More...
 
Vector3 stateObservation::kine::quaternionToRotationVector (const Quaternion &q)
 Tranbsform a quaternion into rotation vector. More...
 
Vector3 stateObservation::kine::quaternionToRotationVector (const Vector4 &v)
 Transforms a quaternion into rotation vector. More...
 
double stateObservation::kine::scalarComponent (const Quaternion &q)
 scalar component of a quaternion More...
 
Vector3 stateObservation::kine::vectorComponent (const Quaternion &q)
 vector part of the quaternion More...
 
Vector3 stateObservation::kine::rotationMatrixToRollPitchYaw (const Matrix3 &R, Vector3 &v)
 
Vector3 stateObservation::kine::rotationMatrixToRollPitchYaw (const Matrix3 &R)
 
Matrix3 stateObservation::kine::rollPitchYawToRotationMatrix (double roll, double pitch, double yaw)
 
Matrix3 stateObservation::kine::rollPitchYawToRotationMatrix (const Vector3 &rpy)
 
Quaternion stateObservation::kine::rollPitchYawToQuaternion (double roll, double pitch, double yaw)
 
Quaternion stateObservation::kine::rollPitchYawToQuaternion (const Vector3 &rpy)
 
Matrix3 stateObservation::kine::orthogonalizeRotationMatrix (const Matrix3 &M)
 Projects the Matrix to so(3) More...
 
Matrix3 stateObservation::kine::skewSymmetric (const Vector3 &v, Matrix3 &R)
 transform a 3d vector into a skew symmetric 3x3 matrix More...
 
Matrix3 stateObservation::kine::skewSymmetric (const Vector3 &v)
 transform a 3d vector into a skew symmetric 3x3 matrix More...
 
Matrix3 stateObservation::kine::skewSymmetric2 (const Vector3 &v, Matrix3 &R)
 transform a 3d vector into a squared skew symmetric 3x3 matrix More...
 
Matrix3 stateObservation::kine::skewSymmetric2 (const Vector3 &v)
 transform a 3d vector into a squared skew symmetric 3x3 matrix More...
 
Vector6 stateObservation::kine::homogeneousMatrixToVector6 (const Matrix4 &M)
 transforms a homogeneous matrix into 6d vector (position theta mu) More...
 
Matrix4 stateObservation::kine::vector6ToHomogeneousMatrix (const Vector6 &v)
 transforms a 6d vector (position theta mu) into a homogeneous matrix More...
 
Matrix3 stateObservation::kine::twoVectorsToRotationMatrix (const Vector3 &v1, const Vector3 Rv1)
 Builds the smallest angle matrix allowing to get from a NORMALIZED vector v1 to its imahe Rv1 This is based on Rodrigues formula. More...
 
bool stateObservation::kine::isPureYaw (const Matrix3 &R)
 checks if this matrix is a pure yaw matrix or not More...
 
Vector3 stateObservation::kine::getInvariantHorizontalVector (const Matrix3 &R)
 Gets a vector that remains horizontal with this rotation. This vector is NOT normalized. More...
 
Vector3 stateObservation::kine::getInvariantOrthogonalVector (const Matrix3 &Rhat, const Vector3 &Rtez)
 Gets a vector \(v\) that is orthogonal to \(e_z\) and such that \(\hat{R}^T e_z\) is orthogonal to the tilt \(R^T e_z\). This vector is NOT normalized. More...
 
Matrix3 stateObservation::kine::mergeTiltWithYaw (const Vector3 &Rtez, const Matrix3 &R2, const Vector3 &v=Vector3::UnitX()) noexcept(false)
 Merge the roll and pitch from the tilt (R^T e_z) with the yaw from a rotation matrix (minimizes the deviation of the v vector) More...
 
Matrix3 stateObservation::kine::mergeRoll1Pitch1WithYaw2 (const Matrix3 &R1, const Matrix3 &R2, const Vector3 &v=Vector3::UnitX())
 Merge the roll and pitch with the yaw from a rotation matrix (minimizes the deviation of the v vector) More...
 
Matrix3 stateObservation::kine::mergeTiltWithYawAxisAgnostic (const Vector3 &Rtez, const Matrix3 &R2)
 Merge the roll and pitch from the tilt (R^T e_z) with the yaw from a rotation matrix (minimizes the deviation of the v vector) More...
 
Matrix3 stateObservation::kine::mergeRoll1Pitch1WithYaw2AxisAgnostic (const Matrix3 &R1, const Matrix3 &R2)
 Merge the roll and pitch with the yaw from a rotation matrix with optimal reference vector. More...
 
double stateObservation::kine::rotationMatrixToAngle (const Matrix3 &rotation, const Vector3 &axis, const Vector3 &v)
 take 3x3 matrix represeting a rotation and gives the angle that vector v turns around the axis with this rotation More...
 
double stateObservation::kine::rotationMatrixToYaw (const Matrix3 &rotation, const Vector2 &v)
 take 3x3 matrix represeting a rotation and gives the angle that vector v turns around the upward vertical axis with this rotation More...
 
double stateObservation::kine::rotationMatrixToYaw (const Matrix3 &rotation)
 take 3x3 matrix represeting a rotation and gives the yaw angle from roll pitch yaw representation More...
 
double stateObservation::kine::rotationMatrixToYawAxisAgnostic (const Matrix3 &rotation)
 take 3x3 matrix represeting a rotation and gives a corresponding angle around upward vertical axis More...
 
Quaternion stateObservation::kine::zeroRotationQuaternion ()
 Get the Identity Quaternion. More...
 
Quaternion stateObservation::kine::randomRotationQuaternion ()
 Get a uniformly random Quaternion. More...
 
double stateObservation::kine::randomAngle ()
 get a randomAngle between -pi and pu More...
 
bool stateObservation::kine::isRotationMatrix (const Matrix3 &, double precision=2 *cst::epsilon1)
 Checks if it is a rotation matrix (right-hand orthonormal) or not. More...
 
void stateObservation::kine::fixedPointRotationToTranslation (const Matrix3 &R, const Vector3 &rotationVelocity, const Vector3 &rotationAcceleration, const Vector3 &fixedPoint, Vector3 &outputTranslation, Vector3 &outputLinearVelocity, Vector3 &outputLinearAcceleration)
 transforms a rotation into translation given a constraint of a fixed point More...
 
Vector3 stateObservation::kine::derivateRotationFD (const Quaternion &q1, const Quaternion &q2, double dt)
 derivates a quaternion using finite difference to get a angular velocity vector More...
 
Vector3 stateObservation::kine::derivateRotationFD (const Vector3 &o1, const Vector3 &o2, double dt)
 derivates a rotation vector using finite difference to get a angular velocity vector More...
 
Vector6 stateObservation::kine::derivateHomogeneousMatrixFD (const Matrix4 &m1, const Matrix4 &m2, double dt)
 
Vector6 stateObservation::kine::derivatePoseThetaUFD (const Vector6 &v1, const Vector6 &v2, double dt)
 
void stateObservation::kine::derivateRotationMultiplicative (const Vector3 &deltaR, Matrix3 &dRdR, Matrix3 &dRddeltaR)
 
Matrix3 stateObservation::kine::derivateRtvMultiplicative (const Matrix3 &R, const Vector3 &v)
 
IndexedVectorArray stateObservation::kine::reconstructStateTrajectory (const IndexedVectorArray &positionOrientation, double dt)
 
Vector stateObservation::kine::invertState (const Vector &state)
 
Matrix4 stateObservation::kine::invertHomoMatrix (const Matrix4 &m)
 
std::ostream & operator<< (std::ostream &os, const stateObservation::kine::Kinematics &k)
 
std::ostream & operator<< (std::ostream &os, const stateObservation::kine::LocalKinematics &k)
 

Variables

constexpr double stateObservation::kine::quatNormTol = 1e-6
 relative tolereance to the square of quaternion norm. More...
 

Detailed Description

Implements integrators for the kinematics, in terms or rotations and translations.

Author
Mehdi Benallegue
Date
2013

Function Documentation

◆ operator<<() [1/2]

std::ostream& operator<< ( std::ostream &  os,
const stateObservation::kine::Kinematics k 
)
inline

◆ operator<<() [2/2]

std::ostream& operator<< ( std::ostream &  os,
const stateObservation::kine::LocalKinematics k 
)
inline