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 std::vector< Block > rbd::Blocks |
RBDYN_DLLAPI void rbd::checkMatchAlpha | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
std::domain_error | If there is a mismatch between mb and mbc.alpha. |
RBDYN_DLLAPI void rbd::checkMatchAlphaD | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
std::domain_error | If there is a mismatch between mb and mbc.alphaD. |
void rbd::checkMatchBodiesVector | ( | const MultiBody & | mb, |
const std::vector< T > & | vec, | ||
const std::string & | name | ||
) |
std::domain_error | If there is a mismatch between mb.nrBodies and vec.size() |
RBDYN_DLLAPI void rbd::checkMatchBodyAcc | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
std::domain_error | If there is a mismatch between mb and mbc.bodyAccB. |
RBDYN_DLLAPI void rbd::checkMatchBodyPos | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
std::domain_error | If there is a mismatch between mb and mbc.bodyPosW. |
RBDYN_DLLAPI void rbd::checkMatchBodyVel | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
std::domain_error | If there is a mismatch between mb and (mbc.bodyVelW, mbc.bodyVelB). |
RBDYN_DLLAPI void rbd::checkMatchForce | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
std::domain_error | If there is a mismatch between mb and mbc.force. |
RBDYN_DLLAPI void rbd::checkMatchJointConf | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
std::domain_error | If there is a mismatch between mb and mbc.jointConfig. |
void rbd::checkMatchJointsVector | ( | const MultiBody & | mb, |
const std::vector< T > & | vec, | ||
const std::string & | name | ||
) |
std::domain_error | If there is a mismatch between mb.nrJoints and vec.size() |
RBDYN_DLLAPI void rbd::checkMatchJointTorque | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
std::domain_error | If there is a mismatch between mb and mbc.jointTorque. |
RBDYN_DLLAPI void rbd::checkMatchJointVelocity | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
std::domain_error | If there is a mismatch between mb and mbc.jointVelocity. |
RBDYN_DLLAPI void rbd::checkMatchMotionSubspace | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
std::domain_error | If there is a mismatch between mb and mbc.motionSubspace. |
RBDYN_DLLAPI void rbd::checkMatchParentToSon | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
std::domain_error | If there is a mismatch between mb and mbc.parentToSon. |
RBDYN_DLLAPI void rbd::checkMatchQ | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
std::domain_error | If there is a mismatch between mb and mbc.q. |
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].
mb | MultiBody used has model. |
mbc | Use bodyPosW, bodyVelB. |
com | CoM position. |
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.
mb | MultiBody used has model. |
mbc | Use bodyPosW, bodyVelB, bodyAccB. |
com | CoM position. |
comDot | CoM velocity. |
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
mbc | Use gravity |
com | CoM position in world frame |
comA | CoM acceleration in world frame, this must be computed without the gravity term |
altitude | Double representing the surface's altitude in world frame |
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.
mbc | used for the gravity |
com | CoM position in world frame |
comA | CoM acceleration in world frame, this must be computed with the gravity term |
altitude | Double representing the surface's altitude in world frame |
wr_external | External wrench acting on the CoM |
mass | Mass of the robot |
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.
com | CoM position in world frame |
comA | CoM acceleration in world frame, this must be computed with the gravity term |
altitude | Double representing the surface's altitude in world frame |
RBDYN_DLLAPI Eigen::Vector3d rbd::computeCoM | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
Compute the Center of Mass (CoM) position of a multibody.
mb | MultiBody used has model. |
mbc | Use bodyPosW. |
RBDYN_DLLAPI Eigen::Vector3d rbd::computeCoMAcceleration | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
Compute the Center of Mass (CoM) acceleration of a multibody.
mb | MultiBody used has model. |
mbc | Use bodyPosW, bodyVelW, bodyVelB, and bodyAccB. |
RBDYN_DLLAPI Eigen::Vector3d rbd::computeCoMVelocity | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
Compute the Center of Mass (CoM) velocity of a multibody.
mb | MultiBody used has model. |
mbc | Use bodyPosW and bodyVelB. |
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
imagePointSpeed | is the normalized 2D coordinate speed |
depthEstimate | is the estimate of the current depth |
jac | is the output Jacobian |
RBDYN_DLLAPI Eigen::VectorXd rbd::dofToVector | ( | const MultiBody & | mb, |
const std::vector< std::vector< double >> & | v | ||
) |
Convert dof vector to Eigen Vector.
mb | MultiBody used has model. |
v | dof vector. |
RBDYN_DEPRECATED RBDYN_DLLAPI void rbd::eulerIntegration | ( | const MultiBody & | mb, |
MultiBodyConfig & | mbc, | ||
double | step | ||
) |
Old name for.
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.
RBDYN_DLLAPI void rbd::forwardAcceleration | ( | const MultiBody & | mb, |
MultiBodyConfig & | mbc, | ||
const sva::MotionVecd & | A_0 = sva::MotionVecd(Eigen::Vector6d::Zero()) |
||
) |
RBDYN_DLLAPI void rbd::forwardKinematics | ( | const MultiBody & | mb, |
MultiBodyConfig & | mbc | ||
) |
RBDYN_DLLAPI void rbd::forwardVelocity | ( | const MultiBody & | mb, |
MultiBodyConfig & | mbc | ||
) |
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
rotation | matrix as input |
rot_angle | as output angle |
rot_axis | as output axis |
RBDYN_DLLAPI void rbd::getSkewSym | ( | const Eigen::Vector3d & | vector, |
Eigen::Matrix3d & | matrix | ||
) |
Obtain the skew-symmetric (or anti-symmetric) matrix of a vector
vector | as input |
matrix | as output |
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
point2d | normalized image coordinates (x,y) = (X/Z, Y/Z) |
depthEstimate | an estimate of the point depth Z |
jac | is the output Jacobian |
RBDYN_DLLAPI void rbd::imagePointJacobian | ( | const Eigen::Vector3d & | point3d, |
Eigen::Matrix< double, 2, 6 > & | jac | ||
) |
Compute the interaction matrix of an image point
point3d | metric location of the point relative to the camera frame |
jac | is the output Jacobian |
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
imagePoint | is the normalized 2D point |
imagePointSpeed | is the speed of the normalized 2D point |
depth | is the depth estimate |
depthDot | is the derivative of the depth estimate |
jac | is the output Jacobian |
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.
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]
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.
mb | MultiBody used has model. |
mbc | Use alphaD, alpha and q. Fill alpha and q. |
step | Integration step. |
prec | Absolute precision used by numerical integrators. |
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 |
||
) |
RBDYN_DLLAPI Eigen::VectorXd rbd::multiBodyToInertialVector | ( | const rbd::MultiBody & | mb | ) |
|
inline |
|
inline |
RBDYN_DLLAPI Eigen::VectorXd rbd::paramToVector | ( | const MultiBody & | mb, |
const std::vector< std::vector< double >> & | v | ||
) |
Convert parameter vector to Eigen Vector.
mb | MultiBody used has model. |
v | Parameter vector. |
RBDYN_DLLAPI void rbd::paramToVector | ( | const std::vector< std::vector< double >> & | v, |
Eigen::Ref< Eigen::VectorXd > | e | ||
) |
Convert parameter vector to Eigen Vector.
v | Parameter vector. |
e | Output Eigen vector (must be of the good size). |
RBDYN_DLLAPI void rbd::poseJacobian | ( | const Eigen::Matrix3d & | rotation, |
Eigen::Matrix< double, 6, 6 > & | jac | ||
) |
Compute the interaction matrix of a pose
rotation | matrix |
jac | is the output Jacobian |
rot_angle_threshold | is the minimum angle of an axis angle representation where the angle is considered as zero |
|
inline |
Utility function to compute a rotation matrix from the parameter vector.
q | parameter vector with a least 4 values (treated as wxyz). |
RBDYN_DLLAPI sva::ForceVecd rbd::sComputeCentroidalMomentum | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc, | ||
const Eigen::Vector3d & | com | ||
) |
Safe version.
std::domain_error | If there is a mismatch between mb and mbc. |
RBDYN_DLLAPI sva::ForceVecd rbd::sComputeCentroidalMomentumDot | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc, | ||
const Eigen::Vector3d & | com, | ||
const Eigen::Vector3d & | comDot | ||
) |
Safe version.
std::domain_error | If there is a mismatch between mb and mbc. |
RBDYN_DLLAPI Eigen::Vector3d rbd::sComputeCoM | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
Safe version.
std::domain_error | If there is a mismatch between mb and mbc. |
RBDYN_DLLAPI Eigen::Vector3d rbd::sComputeCoMAcceleration | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
Safe version.
std::domain_error | If there is a mismatch between mb and mbc. |
RBDYN_DLLAPI Eigen::Vector3d rbd::sComputeCoMVelocity | ( | const MultiBody & | mb, |
const MultiBodyConfig & | mbc | ||
) |
Safe version.
std::domain_error | If there is a mismatch between mb and mbc. |
RBDYN_DLLAPI Eigen::VectorXd rbd::sDofToVector | ( | const MultiBody & | mb, |
const std::vector< std::vector< double >> & | v | ||
) |
Safe version of
std::out_of_range | if dof and Eigen vector mismatch. |
RBDYN_DEPRECATED RBDYN_DLLAPI void rbd::sEulerIntegration | ( | const MultiBody & | mb, |
MultiBodyConfig & | mbc, | ||
double | step | ||
) |
Old name for.
RBDYN_DLLAPI void rbd::sForwardAcceleration | ( | const MultiBody & | mb, |
MultiBodyConfig & | mbc, | ||
const sva::MotionVecd & | A_0 = sva::MotionVecd(Eigen::Vector6d::Zero()) |
||
) |
Safe version.
std::domain_error | If there is a mismatch between mb and mbc. |
RBDYN_DLLAPI void rbd::sForwardKinematics | ( | const MultiBody & | mb, |
MultiBodyConfig & | mbc | ||
) |
Safe version.
std::domain_error | If there is a mismatch between mb and mbc. |
RBDYN_DLLAPI void rbd::sForwardVelocity | ( | const MultiBody & | mb, |
MultiBodyConfig & | mbc | ||
) |
Safe version.
std::domain_error | If there is a mismatch between mb and mbc. |
RBDYN_DLLAPI void rbd::sIntegration | ( | const MultiBody & | mb, |
MultiBodyConfig & | mbc, | ||
double | step, | ||
double | prec = 1e-10 |
||
) |
safe version of
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.
qi | Initial orientation. |
wi | Initial rotation speed. |
wD | Constant acceleration. |
step | Integration step. |
relEps | Stopping criterion for the underlying Magnus expansion, relatively to the norm of its first term. |
absEps | Absolute precision required on the underlying Magnus expansion. |
breakOnWarning | If true, computation is stopped right after the underlying Magnus expansion when it returns a warning, and qi is returned, otherwise perform the full computation. |
RBDYN_DLLAPI Eigen::VectorXd rbd::sParamToVector | ( | const MultiBody & | mb, |
const std::vector< std::vector< double >> & | v | ||
) |
Safe version of
std::out_of_range | if param and Eigen vector mismatch. |
RBDYN_DLLAPI void rbd::sParamToVector | ( | const std::vector< std::vector< double >> & | v, |
Eigen::Ref< Eigen::VectorXd > | e | ||
) |
Safe version of
std::out_of_range | if param and Eigen vector mismatch. |
RBDYN_DLLAPI std::vector<std::vector<double> > rbd::sVectorToDof | ( | const MultiBody & | mb, |
const Eigen::VectorXd & | e | ||
) |
RBDYN_DLLAPI sva::RBInertiad rbd::sVectorToInertia | ( | const Eigen::VectorXd & | vec | ) |
Safe version of
std::out_of_range | if the vector don't have 10 rows. |
RBDYN_DLLAPI void rbd::sVectorToParam | ( | const Eigen::Ref< const Eigen::VectorXd > & | e, |
std::vector< std::vector< double >> & | v | ||
) |
Safe version of
std::out_of_range | if param and Eigen vector mismatch. |
RBDYN_DLLAPI std::vector<std::vector<double> > rbd::sVectorToParam | ( | const MultiBody & | mb, |
const Eigen::VectorXd & | e | ||
) |
Safe version of
std::out_of_range | if param and Eigen vector mismatch. |
RBDYN_DLLAPI std::vector<std::vector<double> > rbd::vectorToDof | ( | const MultiBody & | mb, |
const Eigen::VectorXd & | e | ||
) |
Convert dof vector to Eigen Vector.
mb | MultiBody used has model. |
e | Eigen vector. |
RBDYN_DLLAPI sva::RBInertiad rbd::vectorToInertia | ( | const Eigen::Matrix< double, 10, 1 > & | vec | ) |
Convert a phi vector into a RBInertiad.
RBDYN_DLLAPI void rbd::vectorToParam | ( | const Eigen::Ref< const Eigen::VectorXd > & | e, |
std::vector< std::vector< double >> & | v | ||
) |
Convert parameter vector to Eigen Vector.
e | Eigen vector. |
v | Output parameter vector (must be of the good size). |