file
Dynamics.h
Namespaces
- namespace iDynTree
Classes
- struct iDynTree::ArticulatedBodyAlgorithmInternalBuffers
- Structure of buffers required by ArticulatedBodyAlgorithm.
Functions
- auto ComputeLinearAndAngularMomentum(const Model& model, const LinkPositions& linkPositions, const LinkVelArray& linkVels, SpatialMomentum& totalMomentum) -> bool
- Compute the total linear and angular momentum of a robot, expressed in the world frame.
- auto ComputeLinearAndAngularMomentumDerivativeBias(const Model& model, const LinkPositions& linkPositions, const LinkVelArray& linkVel, const LinkAccArray& linkBiasAcc, Wrench& totalMomentumBias) -> bool
- Compute the total momentum derivatitive bias, i.e.
-
auto RNEADynamicPhase(const iDynTree::
Model& model, const iDynTree:: Traversal& traversal, const iDynTree:: JointPosDoubleArray& jointPos, const iDynTree:: LinkVelArray& linksVel, const iDynTree:: LinkAccArray& linksProperAcc, const iDynTree:: LinkNetExternalWrenches& linkExtForces, iDynTree:: LinkInternalWrenches& linkIntWrenches, iDynTree:: FreeFloatingGeneralizedTorques& baseForceAndJointTorques) -> bool - Compute the inverse dynamics, i.e.
- auto CompositeRigidBodyAlgorithm(const Model& model, const Traversal& traversal, const JointPosDoubleArray& jointPos, LinkCompositeRigidBodyInertias& linkCRBs, FreeFloatingMassMatrix& massMatrix) -> bool
- Compute the floating base mass matrix, using the composite rigid body algorithm.
- auto ArticulatedBodyAlgorithm(const Model& model, const Traversal& traversal, const FreeFloatingPos& robotPos, const FreeFloatingVel& robotVel, const LinkNetExternalWrenches& linkExtWrenches, const JointDOFsDoubleArray& jointTorques, ArticulatedBodyAlgorithmInternalBuffers& buffers, FreeFloatingAcc& robotAcc) -> bool
- Compute the floating base acceleration of an unconstrianed robot, using as input the external forces and the joint torques.
-
auto InverseDynamicsInertialParametersRegressor(const iDynTree::
Model& model, const iDynTree:: Traversal& traversal, const iDynTree:: LinkPositions& referenceFrame_H_link, const iDynTree:: LinkVelArray& linksVel, const iDynTree:: LinkAccArray& linksAcc, iDynTree:: MatrixDynSize& baseForceAndJointTorquesRegressor) -> bool - Compute the inverse dynamics of the model as linear function of the inertial parameters.
Function documentation
bool ComputeLinearAndAngularMomentumDerivativeBias(const Model& model, const LinkPositions& linkPositions, const LinkVelArray& linkVel, const LinkAccArray& linkBiasAcc, Wrench& totalMomentumBias)
Compute the total momentum derivatitive bias, i.e.
the part of the total momentum derivative that does not depend on robot acceleration.
The linear and angular momentum derivative depends on the robot position, velocity and acceleration. This function computes the part that do not depend on the robot accelearation.
This function returns the bias of the derivative of the ComputeLinearAndAngularMomentum function.