rbd Namespace Reference

Namespaces

 ik
 
 parsers
 

Classes

struct  Block
 
class  Body
 
class  CentroidalMomentumMatrix
 
class  CoMJacobian
 
class  CoMJacobianDummy
 
class  ConfigConverter
 
class  Coriolis
 
class  ForwardDynamics
 
class  IDIM
 
class  InverseDynamics
 
class  InverseKinematics
 
class  InverseStatics
 
class  Jacobian
 
class  Joint
 
class  MultiBody
 
struct  MultiBodyConfig
 
class  MultiBodyGraph
 

Typedefs

using Blocks = std::vector< Block >
 

Functions

std::ostream & operator<< (std::ostream &out, const Body &b)
 
RBDYN_DLLAPI Eigen::Vector3d computeCoM (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI Eigen::Vector3d computeCoMVelocity (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI Eigen::Vector3d computeCoMAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI Eigen::Vector3d sComputeCoM (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI Eigen::Vector3d sComputeCoMVelocity (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI Eigen::Vector3d sComputeCoMAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DEPRECATED RBDYN_DLLAPI void eulerJointIntegration (Joint::Type type, const std::vector< double > &alpha, const std::vector< double > &alphaD, double step, std::vector< double > &q)
 Old name for. More...
 
RBDYN_DEPRECATED RBDYN_DLLAPI void eulerIntegration (const MultiBody &mb, MultiBodyConfig &mbc, double step)
 Old name for. More...
 
RBDYN_DEPRECATED RBDYN_DLLAPI void sEulerIntegration (const MultiBody &mb, MultiBodyConfig &mbc, double step)
 Old name for. More...
 
RBDYN_DLLAPI void forwardAcceleration (const MultiBody &mb, MultiBodyConfig &mbc, const sva::MotionVecd &A_0=sva::MotionVecd(Eigen::Vector6d::Zero()))
 
RBDYN_DLLAPI void sForwardAcceleration (const MultiBody &mb, MultiBodyConfig &mbc, const sva::MotionVecd &A_0=sva::MotionVecd(Eigen::Vector6d::Zero()))
 
RBDYN_DLLAPI void forwardKinematics (const MultiBody &mb, MultiBodyConfig &mbc)
 
RBDYN_DLLAPI void sForwardKinematics (const MultiBody &mb, MultiBodyConfig &mbc)
 
RBDYN_DLLAPI void forwardVelocity (const MultiBody &mb, MultiBodyConfig &mbc)
 
RBDYN_DLLAPI void sForwardVelocity (const MultiBody &mb, MultiBodyConfig &mbc)
 
RBDYN_DLLAPI Eigen::Matrix< double, 6, 10 > IMPhi (const sva::MotionVecd &mv)
 Return the IMPhi matrix that compute I*m = IMPhi(m)*phi_i. More...
 
RBDYN_DLLAPI Eigen::Matrix< double, 10, 1 > inertiaToVector (const sva::RBInertiad &rbi)
 
RBDYN_DLLAPI sva::RBInertiad vectorToInertia (const Eigen::Matrix< double, 10, 1 > &vec)
 Convert a phi vector into a RBInertiad. More...
 
RBDYN_DLLAPI sva::RBInertiad sVectorToInertia (const Eigen::VectorXd &vec)
 
RBDYN_DLLAPI Eigen::VectorXd multiBodyToInertialVector (const rbd::MultiBody &mb)
 
template<typename T >
Eigen::Matrix3< T > QuatToE (const std::vector< T > &q)
 
std::ostream & operator<< (std::ostream &out, const Joint &b)
 
RBDYN_DLLAPI sva::ForceVecd computeCentroidalMomentum (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com)
 
RBDYN_DLLAPI sva::ForceVecd computeCentroidalMomentumDot (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com, const Eigen::Vector3d &comDot)
 Compute the time derivative of centroidal momentum at the CoM frame. More...
 
RBDYN_DLLAPI sva::ForceVecd sComputeCentroidalMomentum (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com)
 
RBDYN_DLLAPI sva::ForceVecd sComputeCentroidalMomentumDot (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com, const Eigen::Vector3d &comDot)
 
RBDYN_DLLAPI void paramToVector (const std::vector< std::vector< double >> &v, Eigen::Ref< Eigen::VectorXd > e)
 
RBDYN_DLLAPI void sParamToVector (const std::vector< std::vector< double >> &v, Eigen::Ref< Eigen::VectorXd > e)
 
RBDYN_DLLAPI Eigen::VectorXd paramToVector (const MultiBody &mb, const std::vector< std::vector< double >> &v)
 
RBDYN_DLLAPI Eigen::VectorXd sParamToVector (const MultiBody &mb, const std::vector< std::vector< double >> &v)
 
RBDYN_DLLAPI Eigen::VectorXd dofToVector (const MultiBody &mb, const std::vector< std::vector< double >> &v)
 
RBDYN_DLLAPI Eigen::VectorXd sDofToVector (const MultiBody &mb, const std::vector< std::vector< double >> &v)
 
RBDYN_DLLAPI void vectorToParam (const Eigen::Ref< const Eigen::VectorXd > &e, std::vector< std::vector< double >> &v)
 
RBDYN_DLLAPI void sVectorToParam (const Eigen::Ref< const Eigen::VectorXd > &e, std::vector< std::vector< double >> &v)
 
RBDYN_DLLAPI std::vector< std::vector< double > > vectorToParam (const MultiBody &mb, const Eigen::VectorXd &e)
 
RBDYN_DLLAPI std::vector< std::vector< double > > sVectorToParam (const MultiBody &mb, const Eigen::VectorXd &e)
 
RBDYN_DLLAPI std::vector< std::vector< double > > vectorToDof (const MultiBody &mb, const Eigen::VectorXd &e)
 
RBDYN_DLLAPI std::vector< std::vector< double > > sVectorToDof (const MultiBody &mb, const Eigen::VectorXd &e)
 
template<typename T >
void checkMatchBodiesVector (const MultiBody &mb, const std::vector< T > &vec, const std::string &name)
 
template<typename T >
void checkMatchJointsVector (const MultiBody &mb, const std::vector< T > &vec, const std::string &name)
 
RBDYN_DLLAPI void checkMatchBodyPos (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI void checkMatchParentToSon (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI void checkMatchBodyVel (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI void checkMatchBodyAcc (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI void checkMatchJointConf (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI void checkMatchJointVelocity (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI void checkMatchJointTorque (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI void checkMatchMotionSubspace (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI void checkMatchQ (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI void checkMatchAlpha (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI void checkMatchAlphaD (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI void checkMatchForce (const MultiBody &mb, const MultiBodyConfig &mbc)
 
RBDYN_DLLAPI std::pair< Eigen::Quaterniond, bool > SO3Integration (const Eigen::Quaterniond &qi, const Eigen::Vector3d &wi, const Eigen::Vector3d &wD, double step, double relEps=1e-12, double absEps=std::numeric_limits< double >::epsilon(), bool breakOnWarning=false)
 
RBDYN_DLLAPI void jointIntegration (Joint::Type type, const std::vector< double > &alpha, const std::vector< double > &alphaD, double step, std::vector< double > &q, double prec=1e-10)
 
RBDYN_DLLAPI void integration (const MultiBody &mb, MultiBodyConfig &mbc, double step, double prec=1e-10)
 
RBDYN_DLLAPI void sIntegration (const MultiBody &mb, MultiBodyConfig &mbc, double step, double prec=1e-10)
 safe version of More...
 
RBDYN_DLLAPI void imagePointJacobian (const Eigen::Vector2d &point2d, const double depthEstimate, Eigen::Matrix< double, 2, 6 > &jac)
 
RBDYN_DLLAPI void imagePointJacobian (const Eigen::Vector3d &point3d, Eigen::Matrix< double, 2, 6 > &jac)
 
RBDYN_DLLAPI void imagePointJacobianDot (const Eigen::Vector2d &imagePoint, const Eigen::Vector2d &imagePointSpeed, const double depth, const double depthDot, Eigen::Matrix< double, 2, 6 > &jac)
 
RBDYN_DLLAPI void poseJacobian (const Eigen::Matrix3d &rotation, Eigen::Matrix< double, 6, 6 > &jac)
 
RBDYN_DLLAPI void depthDotJacobian (const Eigen::Vector2d &imagePointSpeed, const double depthEstimate, Eigen::Matrix< double, 1, 6 > &jac)
 
RBDYN_DLLAPI void getAngleAxis (const Eigen::Matrix3d &rotation, double &rot_angle, Eigen::Vector3d &rot_axis)
 
RBDYN_DLLAPI void getSkewSym (const Eigen::Vector3d &vector, Eigen::Matrix3d &matrix)
 
RBDYN_DLLAPI Eigen::Vector3d computeCentroidalZMP (MultiBodyConfig &mbc, Eigen::Vector3d &com, Eigen::Vector3d &comA, double altitude)
 
Eigen::Vector3d computeCentroidalZMPNoGravity (Eigen::Vector3d &com, Eigen::Vector3d &comA, double altitude)
 Compute the ZMP in the world frame considering that gravity is taken into account in the CoM acceleration. More...
 
Eigen::Vector3d computeCentroidalZMPComplete (MultiBodyConfig &mbc, Eigen::Vector3d &com, Eigen::Vector3d &comA, double altitude, sva::ForceVecd wr_external, double mass)
 Compute the ZMP considering the external wrench applied on the robot the gravity should also be already in the CoM acceleration. More...
 

Typedef Documentation

◆ Blocks

typedef std::vector< Block > rbd::Blocks

Function Documentation

◆ checkMatchAlpha()

RBDYN_DLLAPI void rbd::checkMatchAlpha ( const MultiBody mb,
const MultiBodyConfig mbc 
)
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.alpha.

◆ checkMatchAlphaD()

RBDYN_DLLAPI void rbd::checkMatchAlphaD ( const MultiBody mb,
const MultiBodyConfig mbc 
)
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.alphaD.

◆ checkMatchBodiesVector()

template<typename T >
void rbd::checkMatchBodiesVector ( const MultiBody mb,
const std::vector< T > &  vec,
const std::string &  name 
)
Exceptions
std::domain_errorIf there is a mismatch between mb.nrBodies and vec.size()

◆ checkMatchBodyAcc()

RBDYN_DLLAPI void rbd::checkMatchBodyAcc ( const MultiBody mb,
const MultiBodyConfig mbc 
)
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.bodyAccB.

◆ checkMatchBodyPos()

RBDYN_DLLAPI void rbd::checkMatchBodyPos ( const MultiBody mb,
const MultiBodyConfig mbc 
)
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.bodyPosW.

◆ checkMatchBodyVel()

RBDYN_DLLAPI void rbd::checkMatchBodyVel ( const MultiBody mb,
const MultiBodyConfig mbc 
)
Exceptions
std::domain_errorIf there is a mismatch between mb and (mbc.bodyVelW, mbc.bodyVelB).

◆ checkMatchForce()

RBDYN_DLLAPI void rbd::checkMatchForce ( const MultiBody mb,
const MultiBodyConfig mbc 
)
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.force.

◆ checkMatchJointConf()

RBDYN_DLLAPI void rbd::checkMatchJointConf ( const MultiBody mb,
const MultiBodyConfig mbc 
)
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.jointConfig.

◆ checkMatchJointsVector()

template<typename T >
void rbd::checkMatchJointsVector ( const MultiBody mb,
const std::vector< T > &  vec,
const std::string &  name 
)
Exceptions
std::domain_errorIf there is a mismatch between mb.nrJoints and vec.size()

◆ checkMatchJointTorque()

RBDYN_DLLAPI void rbd::checkMatchJointTorque ( const MultiBody mb,
const MultiBodyConfig mbc 
)
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.jointTorque.

◆ checkMatchJointVelocity()

RBDYN_DLLAPI void rbd::checkMatchJointVelocity ( const MultiBody mb,
const MultiBodyConfig mbc 
)
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.jointVelocity.

◆ checkMatchMotionSubspace()

RBDYN_DLLAPI void rbd::checkMatchMotionSubspace ( const MultiBody mb,
const MultiBodyConfig mbc 
)
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.motionSubspace.

◆ checkMatchParentToSon()

RBDYN_DLLAPI void rbd::checkMatchParentToSon ( const MultiBody mb,
const MultiBodyConfig mbc 
)
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.parentToSon.

◆ checkMatchQ()

RBDYN_DLLAPI void rbd::checkMatchQ ( const MultiBody mb,
const MultiBodyConfig mbc 
)
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.q.

◆ computeCentroidalMomentum()

RBDYN_DLLAPI sva::ForceVecd rbd::computeCentroidalMomentum ( const MultiBody mb,
const MultiBodyConfig mbc,
const Eigen::Vector3d &  com 
)

Compute the centroidal momentum at the CoM frame as describe in [Orin and Gosawami 2008].

Parameters
mbMultiBody used has model.
mbcUse bodyPosW, bodyVelB.
comCoM position.
Returns
centroidal momentum at the CoM frame.

◆ computeCentroidalMomentumDot()

RBDYN_DLLAPI sva::ForceVecd rbd::computeCentroidalMomentumDot ( const MultiBody mb,
const MultiBodyConfig mbc,
const Eigen::Vector3d &  com,
const Eigen::Vector3d &  comDot 
)

Compute the time derivative of centroidal momentum at the CoM frame.

Parameters
mbMultiBody used has model.
mbcUse bodyPosW, bodyVelB, bodyAccB.
comCoM position.
comDotCoM velocity.
Returns
Derivative of the centroidal momentum at the CoM frame.

◆ computeCentroidalZMP()

RBDYN_DLLAPI Eigen::Vector3d rbd::computeCentroidalZMP ( MultiBodyConfig mbc,
Eigen::Vector3d &  com,
Eigen::Vector3d &  comA,
double  altitude 
)

Compute the ZMP in the world frame as in Kajita's book on humanoid robots chap. 3 p.38

Parameters
mbcUse gravity
comCoM position in world frame
comACoM acceleration in world frame, this must be computed without the gravity term
altitudeDouble representing the surface's altitude in world frame
Returns
ZMP

◆ computeCentroidalZMPComplete()

Eigen::Vector3d rbd::computeCentroidalZMPComplete ( MultiBodyConfig mbc,
Eigen::Vector3d &  com,
Eigen::Vector3d &  comA,
double  altitude,
sva::ForceVecd  wr_external,
double  mass 
)

Compute the ZMP considering the external wrench applied on the robot the gravity should also be already in the CoM acceleration.

Parameters
mbcused for the gravity
comCoM position in world frame
comACoM acceleration in world frame, this must be computed with the gravity term
altitudeDouble representing the surface's altitude in world frame
wr_externalExternal wrench acting on the CoM
massMass of the robot
Returns
ZMP

◆ computeCentroidalZMPNoGravity()

Eigen::Vector3d rbd::computeCentroidalZMPNoGravity ( Eigen::Vector3d &  com,
Eigen::Vector3d &  comA,
double  altitude 
)

Compute the ZMP in the world frame considering that gravity is taken into account in the CoM acceleration.

Parameters
comCoM position in world frame
comACoM acceleration in world frame, this must be computed with the gravity term
altitudeDouble representing the surface's altitude in world frame
Returns
ZMP

◆ computeCoM()

RBDYN_DLLAPI Eigen::Vector3d rbd::computeCoM ( const MultiBody mb,
const MultiBodyConfig mbc 
)

Compute the Center of Mass (CoM) position of a multibody.

Parameters
mbMultiBody used has model.
mbcUse bodyPosW.
Returns
CoM position in world frame.

◆ computeCoMAcceleration()

RBDYN_DLLAPI Eigen::Vector3d rbd::computeCoMAcceleration ( const MultiBody mb,
const MultiBodyConfig mbc 
)

Compute the Center of Mass (CoM) acceleration of a multibody.

Parameters
mbMultiBody used has model.
mbcUse bodyPosW, bodyVelW, bodyVelB, and bodyAccB.
Returns
CoM velocity in world frame.

◆ computeCoMVelocity()

RBDYN_DLLAPI Eigen::Vector3d rbd::computeCoMVelocity ( const MultiBody mb,
const MultiBodyConfig mbc 
)

Compute the Center of Mass (CoM) velocity of a multibody.

Parameters
mbMultiBody used has model.
mbcUse bodyPosW and bodyVelB.
Returns
CoM velocity in world frame.

◆ depthDotJacobian()

RBDYN_DLLAPI void rbd::depthDotJacobian ( const Eigen::Vector2d &  imagePointSpeed,
const double  depthEstimate,
Eigen::Matrix< double, 1, 6 > &  jac 
)

Compute the interaction matrix of the depth derivative

Parameters
imagePointSpeedis the normalized 2D coordinate speed
depthEstimateis the estimate of the current depth
jacis the output Jacobian

◆ dofToVector()

RBDYN_DLLAPI Eigen::VectorXd rbd::dofToVector ( const MultiBody mb,
const std::vector< std::vector< double >> &  v 
)

Convert dof vector to Eigen Vector.

Parameters
mbMultiBody used has model.
vdof vector.
Returns
dof converted in eigen vector.

◆ eulerIntegration()

RBDYN_DEPRECATED RBDYN_DLLAPI void rbd::eulerIntegration ( const MultiBody mb,
MultiBodyConfig mbc,
double  step 
)

Old name for.

See also
integration

◆ eulerJointIntegration()

RBDYN_DEPRECATED RBDYN_DLLAPI void rbd::eulerJointIntegration ( Joint::Type  type,
const std::vector< double > &  alpha,
const std::vector< double > &  alphaD,
double  step,
std::vector< double > &  q 
)

Old name for.

See also
jointIntegration

◆ forwardAcceleration()

RBDYN_DLLAPI void rbd::forwardAcceleration ( const MultiBody mb,
MultiBodyConfig mbc,
const sva::MotionVecd &  A_0 = sva::MotionVecd(Eigen::Vector6d::Zero()) 
)

Compute the forward acceleration of a MultiBody.

Parameters
mbMultiBody used has model.
mbcUse alphaD generalized acceleration vector, jointVelocity, parentToSon and bodyVelB. Fill bodyAccB.
A_0initial acceleration in world coordinate.

◆ forwardKinematics()

RBDYN_DLLAPI void rbd::forwardKinematics ( const MultiBody mb,
MultiBodyConfig mbc 
)

Compute the forward kinematic of a MultiBody.

Parameters
mbMultiBody used has model.
mbcUse q generalized position vector. Fill bodyPosW, jointConfig, motionSubspace and parentToSon.

◆ forwardVelocity()

RBDYN_DLLAPI void rbd::forwardVelocity ( const MultiBody mb,
MultiBodyConfig mbc 
)

Compute the forward velocity of a MultiBody.

Parameters
mbMultiBody used has model.
mbcUse alpha generalized velocity vector, bodyPosW, jointConfig and parentToSon. Fill jointVelocity, bodyVelW and bodyVelB.

◆ getAngleAxis()

RBDYN_DLLAPI void rbd::getAngleAxis ( const Eigen::Matrix3d &  rotation,
double &  rot_angle,
Eigen::Vector3d &  rot_axis 
)

Compute the angle and axis of an angle-axis rotation representation given a rotation matrix

Parameters
rotationmatrix as input
rot_angleas output angle
rot_axisas output axis

◆ getSkewSym()

RBDYN_DLLAPI void rbd::getSkewSym ( const Eigen::Vector3d &  vector,
Eigen::Matrix3d &  matrix 
)

Obtain the skew-symmetric (or anti-symmetric) matrix of a vector

Parameters
vectoras input
matrixas output

◆ imagePointJacobian() [1/2]

RBDYN_DLLAPI void rbd::imagePointJacobian ( const Eigen::Vector2d &  point2d,
const double  depthEstimate,
Eigen::Matrix< double, 2, 6 > &  jac 
)

Compute the interaction matrix of an image point

Parameters
point2dnormalized image coordinates (x,y) = (X/Z, Y/Z)
depthEstimatean estimate of the point depth Z
jacis the output Jacobian

◆ imagePointJacobian() [2/2]

RBDYN_DLLAPI void rbd::imagePointJacobian ( const Eigen::Vector3d &  point3d,
Eigen::Matrix< double, 2, 6 > &  jac 
)

Compute the interaction matrix of an image point

Parameters
point3dmetric location of the point relative to the camera frame
jacis the output Jacobian

◆ imagePointJacobianDot()

RBDYN_DLLAPI void rbd::imagePointJacobianDot ( const Eigen::Vector2d &  imagePoint,
const Eigen::Vector2d &  imagePointSpeed,
const double  depth,
const double  depthDot,
Eigen::Matrix< double, 2, 6 > &  jac 
)

Compute the interaction matrix derivative of an image point

Parameters
imagePointis the normalized 2D point
imagePointSpeedis the speed of the normalized 2D point
depthis the depth estimate
depthDotis the derivative of the depth estimate
jacis the output Jacobian

◆ IMPhi()

RBDYN_DLLAPI Eigen::Matrix<double, 6, 10> rbd::IMPhi ( const sva::MotionVecd &  mv)

Return the IMPhi matrix that compute I*m = IMPhi(m)*phi_i.

◆ inertiaToVector()

RBDYN_DLLAPI Eigen::Matrix<double, 10, 1> rbd::inertiaToVector ( const sva::RBInertiad &  rbi)

Convert a RBInertiad into a phi vector. We define the inertial parameters of a body i as the 10d vector phi_i = [m, h, I] = [m, hx, hy, hz, Ixx, Ixy, Ixz, Iyy, Iyz, Yzz]

◆ integration()

RBDYN_DLLAPI void rbd::integration ( const MultiBody mb,
MultiBodyConfig mbc,
double  step,
double  prec = 1e-10 
)

Use numerical or Euler methods (depending on joints) to compute the joint configurations and velocities after a step with constant joint accelerations.

Parameters
mbMultiBody used has model.
mbcUse alphaD, alpha and q. Fill alpha and q.
stepIntegration step.
precAbsolute precision used by numerical integrators.

◆ jointIntegration()

RBDYN_DLLAPI void rbd::jointIntegration ( Joint::Type  type,
const std::vector< double > &  alpha,
const std::vector< double > &  alphaD,
double  step,
std::vector< double > &  q,
double  prec = 1e-10 
)

Integrate joint configuration.

Parameters
typeJoint type.
alphaJoint velocity vector.
alphaDJoint acceleration vector.
stepIntegration step.
qJoint configuration vector.
precAbsolute precision used by numerical integrators.

◆ multiBodyToInertialVector()

RBDYN_DLLAPI Eigen::VectorXd rbd::multiBodyToInertialVector ( const rbd::MultiBody mb)

Apply inertiaToVector to all MultiBody Body and concatenate it into one vector Phi = [phi_0, ..., phi_N]

◆ operator<<() [1/2]

std::ostream& rbd::operator<< ( std::ostream &  out,
const Body b 
)
inline

◆ operator<<() [2/2]

std::ostream& rbd::operator<< ( std::ostream &  out,
const Joint b 
)
inline

◆ paramToVector() [1/2]

RBDYN_DLLAPI Eigen::VectorXd rbd::paramToVector ( const MultiBody mb,
const std::vector< std::vector< double >> &  v 
)

Convert parameter vector to Eigen Vector.

Parameters
mbMultiBody used has model.
vParameter vector.
Returns
Parameter converted in eigen vector.

◆ paramToVector() [2/2]

RBDYN_DLLAPI void rbd::paramToVector ( const std::vector< std::vector< double >> &  v,
Eigen::Ref< Eigen::VectorXd >  e 
)

Convert parameter vector to Eigen Vector.

Parameters
vParameter vector.
eOutput Eigen vector (must be of the good size).

◆ poseJacobian()

RBDYN_DLLAPI void rbd::poseJacobian ( const Eigen::Matrix3d &  rotation,
Eigen::Matrix< double, 6, 6 > &  jac 
)

Compute the interaction matrix of a pose

Parameters
rotationmatrix
jacis the output Jacobian
rot_angle_thresholdis the minimum angle of an axis angle representation where the angle is considered as zero

◆ QuatToE()

template<typename T >
Eigen::Matrix3< T > rbd::QuatToE ( const std::vector< T > &  q)
inline

Utility function to compute a rotation matrix from the parameter vector.

Parameters
qparameter vector with a least 4 values (treated as wxyz).
Returns
Rotation matrix in successor frame.

◆ sComputeCentroidalMomentum()

RBDYN_DLLAPI sva::ForceVecd rbd::sComputeCentroidalMomentum ( const MultiBody mb,
const MultiBodyConfig mbc,
const Eigen::Vector3d &  com 
)

Safe version.

See also
computeCentroidalMomentum.
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.

◆ sComputeCentroidalMomentumDot()

RBDYN_DLLAPI sva::ForceVecd rbd::sComputeCentroidalMomentumDot ( const MultiBody mb,
const MultiBodyConfig mbc,
const Eigen::Vector3d &  com,
const Eigen::Vector3d &  comDot 
)

Safe version.

See also
computeCentroidalMomentumDot.
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.

◆ sComputeCoM()

RBDYN_DLLAPI Eigen::Vector3d rbd::sComputeCoM ( const MultiBody mb,
const MultiBodyConfig mbc 
)

Safe version.

See also
computeCoM.
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.

◆ sComputeCoMAcceleration()

RBDYN_DLLAPI Eigen::Vector3d rbd::sComputeCoMAcceleration ( const MultiBody mb,
const MultiBodyConfig mbc 
)

Safe version.

See also
computeCoMAcceleration.
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.

◆ sComputeCoMVelocity()

RBDYN_DLLAPI Eigen::Vector3d rbd::sComputeCoMVelocity ( const MultiBody mb,
const MultiBodyConfig mbc 
)

Safe version.

See also
computeCoMVelocity.
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.

◆ sDofToVector()

RBDYN_DLLAPI Eigen::VectorXd rbd::sDofToVector ( const MultiBody mb,
const std::vector< std::vector< double >> &  v 
)

Safe version of

See also
paramToDof.
Exceptions
std::out_of_rangeif dof and Eigen vector mismatch.

◆ sEulerIntegration()

RBDYN_DEPRECATED RBDYN_DLLAPI void rbd::sEulerIntegration ( const MultiBody mb,
MultiBodyConfig mbc,
double  step 
)

Old name for.

See also
sIntegration

◆ sForwardAcceleration()

RBDYN_DLLAPI void rbd::sForwardAcceleration ( const MultiBody mb,
MultiBodyConfig mbc,
const sva::MotionVecd &  A_0 = sva::MotionVecd(Eigen::Vector6d::Zero()) 
)

Safe version.

See also
forwardAcceleration.
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.

◆ sForwardKinematics()

RBDYN_DLLAPI void rbd::sForwardKinematics ( const MultiBody mb,
MultiBodyConfig mbc 
)

Safe version.

See also
forwardKinematics.
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.

◆ sForwardVelocity()

RBDYN_DLLAPI void rbd::sForwardVelocity ( const MultiBody mb,
MultiBodyConfig mbc 
)

Safe version.

See also
forwardVelocity.
Exceptions
std::domain_errorIf there is a mismatch between mb and mbc.

◆ sIntegration()

RBDYN_DLLAPI void rbd::sIntegration ( const MultiBody mb,
MultiBodyConfig mbc,
double  step,
double  prec = 1e-10 
)

safe version of

See also
integration.

◆ SO3Integration()

RBDYN_DLLAPI std::pair<Eigen::Quaterniond, bool> rbd::SO3Integration ( const Eigen::Quaterniond &  qi,
const Eigen::Vector3d &  wi,
const Eigen::Vector3d &  wD,
double  step,
double  relEps = 1e-12,
double  absEps = std::numeric_limits< double >::epsilon(),
bool  breakOnWarning = false 
)

Integrate a constant rotation acceleration.

Parameters
qiInitial orientation.
wiInitial rotation speed.
wDConstant acceleration.
stepIntegration step.
relEpsStopping criterion for the underlying Magnus expansion, relatively to the norm of its first term.
absEpsAbsolute precision required on the underlying Magnus expansion.
breakOnWarningIf true, computation is stopped right after the underlying Magnus expansion when it returns a warning, and qi is returned, otherwise perform the full computation.

◆ sParamToVector() [1/2]

RBDYN_DLLAPI Eigen::VectorXd rbd::sParamToVector ( const MultiBody mb,
const std::vector< std::vector< double >> &  v 
)

Safe version of

See also
paramToVector.
Exceptions
std::out_of_rangeif param and Eigen vector mismatch.

◆ sParamToVector() [2/2]

RBDYN_DLLAPI void rbd::sParamToVector ( const std::vector< std::vector< double >> &  v,
Eigen::Ref< Eigen::VectorXd >  e 
)

Safe version of

See also
paramToVector.
Exceptions
std::out_of_rangeif param and Eigen vector mismatch.

◆ sVectorToDof()

RBDYN_DLLAPI std::vector<std::vector<double> > rbd::sVectorToDof ( const MultiBody mb,
const Eigen::VectorXd &  e 
)

Safe version of

See also
vectorToDof.
Exceptions
std::out_of_rangeif dof and Eigen vector mismatch.

◆ sVectorToInertia()

RBDYN_DLLAPI sva::RBInertiad rbd::sVectorToInertia ( const Eigen::VectorXd &  vec)

Safe version of

See also
vectorToInertia.
Exceptions
std::out_of_rangeif the vector don't have 10 rows.

◆ sVectorToParam() [1/2]

RBDYN_DLLAPI void rbd::sVectorToParam ( const Eigen::Ref< const Eigen::VectorXd > &  e,
std::vector< std::vector< double >> &  v 
)

Safe version of

See also
vectorToParam.
Exceptions
std::out_of_rangeif param and Eigen vector mismatch.

◆ sVectorToParam() [2/2]

RBDYN_DLLAPI std::vector<std::vector<double> > rbd::sVectorToParam ( const MultiBody mb,
const Eigen::VectorXd &  e 
)

Safe version of

See also
vectorToParam.
Exceptions
std::out_of_rangeif param and Eigen vector mismatch.

◆ vectorToDof()

RBDYN_DLLAPI std::vector<std::vector<double> > rbd::vectorToDof ( const MultiBody mb,
const Eigen::VectorXd &  e 
)

Convert dof vector to Eigen Vector.

Parameters
mbMultiBody used has model.
eEigen vector.
Returns
Eigen vector converted in parameter vector.

◆ vectorToInertia()

RBDYN_DLLAPI sva::RBInertiad rbd::vectorToInertia ( const Eigen::Matrix< double, 10, 1 > &  vec)

Convert a phi vector into a RBInertiad.

◆ vectorToParam() [1/2]

RBDYN_DLLAPI void rbd::vectorToParam ( const Eigen::Ref< const Eigen::VectorXd > &  e,
std::vector< std::vector< double >> &  v 
)

Convert parameter vector to Eigen Vector.

Parameters
eEigen vector.
vOutput parameter vector (must be of the good size).

◆ vectorToParam() [2/2]

RBDYN_DLLAPI std::vector<std::vector<double> > rbd::vectorToParam ( const MultiBody mb,
const Eigen::VectorXd &  e 
)

Convert parameter vector to Eigen Vector.

Parameters
mbMultiBody used has model.
eEigen vector.
Returns
Eigen vector converted in parameter vector.