%iDynTree model data structures module

Data structures and algorithm to model and implement algorithm on multibody articulated systems.

Classes

class iDynTree::FixedJoint
Class representing a fixed joint, i.e.
class iDynTree::IJoint
Interface (i.e.
class iDynTree::Link
Class that represents a link.
class iDynTree::Model
Class that represents a generic multibody model.
template<unsigned int nrOfPosCoords, unsigned int nrOfDOFs>
class iDynTree::MovableJointImpl
Base template for implementation of non-fixed joints.
class iDynTree::PrismaticJoint
Class representing a prismatic joint, i.e.
class iDynTree::RevoluteJoint
Class representing a revolute joint, i.e.
class iDynTree::Traversal
Class that represents a traversal of a set of links of a Model.

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 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 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.
auto ForwardPositionKinematics(const Model& model, const Traversal& traversal, const Transform& worldHbase, const VectorDynSize& jointPositions, LinkPositions& linkPositions) -> bool
Given a robot floating base configuration (i.e.
auto FreeFloatingJacobianUsingLinkPos(const Model& model, const Traversal& traversal, const JointPosDoubleArray& jointPositions, const LinkPositions& linkPositions, const LinkIndex linkIndex, const Transform& jacobFrame_X_world, const Transform& baseFrame_X_jacobBaseFrame, const MatrixView<double>& jacobian) -> bool
Compute a free floating jacobian.

Function documentation

bool ComputeLinearAndAngularMomentum(const Model& model, const LinkPositions& linkPositions, const LinkVelArray& linkVels, SpatialMomentum& totalMomentum)

Compute the total linear and angular momentum of a robot, expressed in the world frame.

Parameters
model in the used model,
linkPositions in linkPositions(l) contains the world_H_link transform.
linkVels in linkVels(l) contains the link l velocity expressed in l frame.
totalMomentum out total momentum, expressed in world frame.
Returns true if all went well, false otherwise.

bool 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)

Compute the inverse dynamics, i.e.

Parameters
model in The model used for the computation.
traversal in The traversal used for the computation, it defines the used base link.
jointPos in The (internal) joint position of the model.
linksVel in Vector of left-trivialized velocities for each link of the model (for each link $L$ , the corresponding velocity is ${}^L \mathrm{v}_{A, L}$ ).
linksProperAcc in Vector of left-trivialized proper acceleration for each link of the model (for each link $L$ , the corresponding proper acceleration is ${}^L \dot{\mathrm{v}}_{A, L} - \begin{bmatrix} {}^L R_A {}^A g \\ 0_{3\times1} \end{bmatrix} $ ), where $ {}^A g \in \mathbb{R}^3 $ is the gravity acceleration expressed in an inertial frame $A$ . See iDynTree::LinkNetExternalWrenches .
linkExtForces in Vector of external 6D force/torques applied to the links. For each link $L$ , the corresponding external force is ${}_L \mathrm{f}^x_L$ , i.e. the force that the enviroment applies on the on the link $L$ , expressed in the link frame $L$ .
linkIntWrenches out Vector of internal joint force/torques. See iDynTree::LinkInternalWrenches .
baseForceAndJointTorques out Generalized torques output. The base element is the residual force on the base (that is equal to zero if the robot acceleration and the external forces provided in LinkNetExternalWrenches were consistent), while the joint part is composed by the joint torques.

the generalized torques corresponding to a given set of robot accelerations and external force/torques.

bool ArticulatedBodyAlgorithm(const Model& model, const Traversal& traversal, const FreeFloatingPos& robotPos, const FreeFloatingVel& robotVel, const LinkNetExternalWrenches& linkExtWrenches, const JointDOFsDoubleArray& jointTorques, ArticulatedBodyAlgorithmInternalBuffers& buffers, FreeFloatingAcc& robotAcc)

Compute the floating base acceleration of an unconstrianed robot, using as input the external forces and the joint torques.

We follow the algorithm described in Featherstone 2008, modified for the floating base case and for handling fixed joints.

bool 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)

Compute the inverse dynamics of the model as linear function of the inertial parameters.

Parameters
model in The model used for the computation.
traversal in The traversal used for the computation, it defines the used base link.
referenceFrame_H_link in Position of each link w.r.t. to given frame D (tipically an inertial frame A, the base frame B or the mixed frame B[A]). For each link $L$ , the corresponding transform is ${}^D H_L$ .
linksVel in Vector of left-trivialized velocities for each link of the model (for each link $L$ , the corresponding velocity is ${}^L \mathrm{v}_{A, L}$ ).
linksAcc
baseForceAndJointTorquesRegressor out The (6+model.getNrOfDOFs() X 10*model.getNrOfLinks()) inverse dynamics regressor.

This function computes the matrix that multiplied by the vector of inertial parameters of a model (see iDynTree::Model::getInertialParameters) returns the inverse dynamics generalized torques. In particular it is consistent with the result of the iDynTree::RNEADynamicPhase function, i.e. the first six rows of the regressor correspond to the sum of all external force/torques acting on the robot, expressed in the origin and with the orientation of the specified referenceFrame, as defined by the referenceFrame_H_link argument.

bool ForwardPositionKinematics(const Model& model, const Traversal& traversal, const Transform& worldHbase, const VectorDynSize& jointPositions, LinkPositions& linkPositions)

Given a robot floating base configuration (i.e.

Parameters
model in the used model,
traversal in the used traversal,
worldHbase in the world_H_base transform,
jointPositions in the vector of (internal) joint positions,
linkPositions out linkPositions(l) contains the world_H_link transform.
Returns true if all went well, false otherwise.

world_H_base and the joint positions) compute for each link the world_H_link transform.

bool FreeFloatingJacobianUsingLinkPos(const Model& model, const Traversal& traversal, const JointPosDoubleArray& jointPositions, const LinkPositions& linkPositions, const LinkIndex linkIndex, const Transform& jacobFrame_X_world, const Transform& baseFrame_X_jacobBaseFrame, const MatrixView<double>& jacobian)

Compute a free floating jacobian.

Parameters
model in the used model,
traversal in the used traversal,
jointPositions in the vector of (internal) joint positions,
linkPositions in linkPositions(l) contains the world_H_link transform.
linkIndex in the index of the link of which we compute the jacobian.
jacobFrame_X_world in TODO
baseFrame_X_jacobBaseFrame in TODO
jacobian out the computed Jacobian
Returns true if all went well, false otherwise.