iDynTree::Model class

Class that represents a generic multibody model.

A model is composed by rigid bodies (i.e. links) connected by joints. Each joint can have from 0 to 6 degrees of freedom.

Each link has a "link frame" rigidly attached to it. Additionally, other rigidly attachable frames can be defined for each link.

The model contains also a serialization for the different elements, i.e. a function between:

For simplicity, these mappings are build when building the model. In particular the link and joint indices are assigned when the links and joint are added to the model using the addLink and addJoint methods.

The DOF indices are also assigned when the joint is added to the model with the addJoint method. For example if a model is composed only of 0 or 1 DOF joints and the 1 DOFs joints are added before the 0 DOFs then the joint index and dof index for 1 DOF joints will be coincident (this is how the URDF parser is actually implemented). For this reason the current implementation does not have a concept of DOF explicit identifier, i.e. a getDOFName(DOFIndex dofIndex) method does not exist.

The frame indices between 0 and getNrOfLinks()-1 are always assigned to the "main" link frame of the link with the same index. The frame indices between getNrOfLinks() and getNrOfFrames()-1 are assigned when the additional frame is added to the model with the addAdditionalFrameToLink call. All the additional frame indices are incremented by 1 whenever a new link is added, to ensure that its "link frame" has a frame index in the 0...getNrOfLinks()-1 range.

Constructors, destructors, conversion operators

Model()
Costructor.
Model(const Model& other)
Copy costructor.
~Model() virtual
Destructor.

Public functions

auto operator=(const Model& other) -> Model&
Copy operator.
auto copy() const -> Model
Copy the model.
auto getNrOfLinks() const -> size_t
Get the number of links in the model.
auto getPackageDirs() const -> const std::vector<std::string>&
void setPackageDirs(const std::vector<std::string>& packageDirs)
auto getLinkName(const LinkIndex linkIndex) const -> std::string
Get the name of a link given its index, or an LINK_INVALID_NAME string if linkIndex < 0 or >= getNrOfLinks()
auto getLinkIndex(const std::string& linkName) const -> LinkIndex
auto isValidLinkIndex(const LinkIndex index) const -> bool
Check if a given LinkIndex is valid.
auto getLink(const LinkIndex linkIndex) -> LinkPtr
auto getLink(const LinkIndex linkIndex) const -> LinkConstPtr
auto addLink(const std::string& name, const Link& link) -> LinkIndex
auto getNrOfJoints() const -> size_t
Get number of joints in the model.
auto getJointName(const JointIndex index) const -> std::string
Get the name of a joint given its index, or an JOINT_INVALID_NAME if linkIndex < 0 or >= getNrOfLinks()
auto getTotalMass() const -> double
Get the total mass of the robot.
auto getJointIndex(const std::string& jointName) const -> JointIndex
Get the index of a joint, given a jointName.
auto getJoint(const JointIndex index) -> IJointPtr
auto getJoint(const JointIndex index) const -> IJointConstPtr
auto isValidJointIndex(const JointIndex index) const -> bool
Check if a given JointIndex is valid.
auto isLinkNameUsed(const std::string linkName) const -> bool
Check if a name is already used for a link in the model.
auto isJointNameUsed(const std::string jointName) const -> bool
Check if a name is already used for a joint in the model.
auto isFrameNameUsed(const std::string frameName) const -> bool
Check if a name is already used for a frame in the model.
auto addJoint(const std::string& jointName, IJointConstPtr joint) -> JointIndex
Add a joint to the model.
auto addJoint(const std::string& link1, const std::string& link2, const std::string& jointName, IJointConstPtr joint) -> JointIndex
Add a joint to the model, and specify the two links that are connected by the specified joints.
auto addJointAndLink(const std::string& existingLink, const std::string& jointName, IJointConstPtr joint, const std::string& newLinkName, Link& newLink) -> JointIndex
Add a joint to the model, and add also a link.
auto insertLinkToExistingJointAndAddJointForDisplacedLink(const std::string& existingJoint, const std::string& unmovableLink, const Transform& _unmovableLink_X_newLink, const std::string& jointName, IJointConstPtr joint, const std::string& newLinkName, Link& newLink) -> JointIndex
Displace a link by inserting a new link and a new joint.
auto getNrOfPosCoords() const -> size_t
Get the dimension of the vector used to parametrize the positions of the joints of the robot.
auto getNrOfDOFs() const -> size_t
Get the number of degrees of freedom of the joint of the robot.
auto getNrOfFrames() const -> size_t
Get the number of frames in the model.
auto addAdditionalFrameToLink(const std::string& linkName, const std::string& frameName, iDynTree::Transform link_H_frame) -> bool
Add an additional frame to a link.
auto getFrameName(const FrameIndex frameIndex) const -> std::string
Get the name of a frame given its index.
auto getFrameIndex(const std::string& frameName) const -> FrameIndex
Get the index of a frame given its name.
auto isValidFrameIndex(const FrameIndex index) const -> bool
Check if a given FrameIndex is valid.
auto getFrameTransform(const FrameIndex frameIndex) const -> Transform
Get the tranform of the frame with respect to the main frame of the link, returned as link_H_frame tranform with refFrame : the link main frame and frame : the frame with index frameIndex .
auto getFrameLink(const FrameIndex frameIndex) const -> LinkIndex
Get the link at which the frame with index frameIndex is attached.
auto getLinkAdditionalFrames(const LinkIndex lnkIndex, std::vector<FrameIndex>& frameIndeces) const -> bool
Get the additional frames of a specified link.
auto getNrOfNeighbors(const LinkIndex link) const -> unsigned int
Get the nr of neighbors of a given link.
auto getNeighbor(const LinkIndex link, unsigned int neighborIndex) const -> Neighbor
Get the neighbor of a link.
auto setDefaultBaseLink(const LinkIndex linkIndex) -> bool
Set the default base link, used for generation of the default traversal.
auto getDefaultBaseLink() const -> LinkIndex
Get the default base link, used for generation of the default traversal.
auto computeFullTreeTraversal(Traversal& traversal) const -> bool
Compute a Traversal of all the links in the Model, doing a Depth First Search starting at the default base.
auto computeFullTreeTraversal(Traversal& traversal, const LinkIndex traversalBase) const -> bool
Compute a Traversal of all the links in the Model, doing a Depth First Search starting at the given traversalBase.
auto getInertialParameters(VectorDynSize& modelInertialParams) const -> bool
Get the inertial parameters of the links of the model in vector forms.
auto updateInertialParameters(const VectorDynSize& modelInertialParams) -> bool
Update the inertial parameters of the links of the model.
auto visualSolidShapes() -> ModelSolidShapes&
Get the ModelSolidShapes meant for visualization.
auto visualSolidShapes() const -> const ModelSolidShapes&
Get the ModelSolidShapes meant for visualization (const version)
auto collisionSolidShapes() -> ModelSolidShapes&
Get the ModelSolidShapes meant for collision checking.
auto collisionSolidShapes() const -> const ModelSolidShapes&
Get the ModelSolidShapes meant for collision checking (const version)
auto sensors() -> SensorsList&
Get the (mutable) sensors associated with the model.
auto sensors() const -> const SensorsList&
Get the (const) sensors associated with the model.
auto toString() const -> std::string
Get a printable representation of the Model.
auto isValid() const -> bool
Check if the model is valid.

Function documentation

Model iDynTree::Model::copy() const

Copy the model.

Get a copy of the model.

const std::vector<std::string>& iDynTree::Model::getPackageDirs() const

Returns a vector containing all the directories of the meshes

bool iDynTree::Model::isValidLinkIndex(const LinkIndex index) const

Check if a given LinkIndex is valid.

Returns true if the index is valid, false otherwise.

A link index is valid if is different from LINK_INVALID_INDEX and 0 =< index < getNrOfLinks()-1

JointIndex iDynTree::Model::getJointIndex(const std::string& jointName) const

Get the index of a joint, given a jointName.

If the jointName is not found in the model, return JOINT_INVALID_INDEX .

bool iDynTree::Model::isValidJointIndex(const JointIndex index) const

Check if a given JointIndex is valid.

Returns true if the index is valid, false otherwise.

A joint index is valid if is different from JOINT_INVALID_INDEX and 0 =< index < getNrOfJoints()-1

bool iDynTree::Model::isLinkNameUsed(const std::string linkName) const

Check if a name is already used for a link in the model.

Returns true if a name is used by a link in a model, false otherwise.

bool iDynTree::Model::isJointNameUsed(const std::string jointName) const

Check if a name is already used for a joint in the model.

Returns true if a name is used by a joint in a model, false otherwise.

bool iDynTree::Model::isFrameNameUsed(const std::string frameName) const

Check if a name is already used for a frame in the model.

Returns true if a name is used by a frame in a model, false otherwise.

JointIndex iDynTree::Model::addJoint(const std::string& jointName, IJointConstPtr joint)

Add a joint to the model.

Returns the JointIndex of the added joint, or JOINT_INVALID_INDEX if there was an error in adding the joint.

The two links to which the joint is connected are specified in the joint itself, throught the appropriate methods.

JointIndex iDynTree::Model::addJoint(const std::string& link1, const std::string& link2, const std::string& jointName, IJointConstPtr joint)

Add a joint to the model, and specify the two links that are connected by the specified joints.

Returns the JointIndex of the added joint, or JOINT_INVALID_INDEX if there was an error in adding the joint.

The setAttachedLinks of the passed joint is called appropriately, to ensure consistency in the model.

JointIndex iDynTree::Model::addJointAndLink(const std::string& existingLink, const std::string& jointName, IJointConstPtr joint, const std::string& newLinkName, Link& newLink)

Add a joint to the model, and add also a link.

Returns the JointIndex of the added joint, or JOINT_INVALID_INDEX if there was an error in adding the joint.

The added joints connects an existing link of the model to the newly added link. The setAttachedLinks of the passed joint is called appropriately, to ensure consistency in the model.

JointIndex iDynTree::Model::insertLinkToExistingJointAndAddJointForDisplacedLink(const std::string& existingJoint, const std::string& unmovableLink, const Transform& _unmovableLink_X_newLink, const std::string& jointName, IJointConstPtr joint, const std::string& newLinkName, Link& newLink)

Displace a link by inserting a new link and a new joint.

Parameters
existingJoint in is where the new link will be inserted.
unmovableLink in is the link that was previously connected to the displaced link by the existingJoint.
_unmovableLink_X_newLink
jointName in is the name of the new joint.
joint in is the new joint connecting the new link and the link that was displaced.
newLinkName in is the name of the new link.
newLink in is the new link that will be attached to the unmovable link using the existingJoint. The setAttachedLinks of the new joint and the existing joint are edited appropriately, to ensure consistency in the model.
Returns the JointIndex of the added joint, or JOINT_INVALID_INDEX if there was an error in adding the joint.

Displace a link by replacing it with a new link in the existing joint and insert new joint between the new link and the displaced link. Inputs:

size_t iDynTree::Model::getNrOfPosCoords() const

Get the dimension of the vector used to parametrize the positions of the joints of the robot.

This number can be obtained by summing the getNrOfPosCoords of all the joints of the model.

size_t iDynTree::Model::getNrOfDOFs() const

Get the number of degrees of freedom of the joint of the robot.

This number can be obtained by summing the getNrOfDOFs of all the joints of the model.

size_t iDynTree::Model::getNrOfFrames() const

Get the number of frames in the model.

Returns the number of frames in the model.

bool iDynTree::Model::addAdditionalFrameToLink(const std::string& linkName, const std::string& frameName, iDynTree::Transform link_H_frame)

Add an additional frame to a link.

Parameters
linkName in the link to which attach the additional frame.
frameName in the name of the frame added to the model.
link_H_frame in the pose of added frame with respect to the link main frame, expressed with a transform with: refFrame: the main link frame frame: the added frame
Returns true if all went well, false if an error occured.

std::string iDynTree::Model::getFrameName(const FrameIndex frameIndex) const

Get the name of a frame given its index.

Parameters
frameIndex in the index of the frame whose name is requested.
Returns the name of a frame given its index, or a FRAME_INVALID_NAME string if frameIndex < 0 or >= getNrOfFrames()

FrameIndex iDynTree::Model::getFrameIndex(const std::string& frameName) const

Get the index of a frame given its name.

Parameters
frameName in the name of the frame for which the index is requested.
Returns the index of the frame, of FRAME_INVALID_INDEX if frameName is not not a frame name.

bool iDynTree::Model::isValidFrameIndex(const FrameIndex index) const

Check if a given FrameIndex is valid.

Returns true if the index is valid, false otherwise.

A frame index is valid if is different from FRAME_INVALID_INDEX and 0 =< index < getNrOfFrames()-1

Transform iDynTree::Model::getFrameTransform(const FrameIndex frameIndex) const

Get the tranform of the frame with respect to the main frame of the link, returned as link_H_frame tranform with refFrame : the link main frame and frame : the frame with index frameIndex .

Parameters
frameIndex in the index of the frame for which transform is requested.
Returns the link_H_frame transform, or an identity tranform if frameIndex < 0 or frameIndex >= getNrOfFrames .

bool iDynTree::Model::getLinkAdditionalFrames(const LinkIndex lnkIndex, std::vector<FrameIndex>& frameIndeces) const

Get the additional frames of a specified link.

Returns true if the specified link is a valid link, false otherwise.

Neighbor iDynTree::Model::getNeighbor(const LinkIndex link, unsigned int neighborIndex) const

Get the neighbor of a link.

neighborIndex should be >= 0 and <= getNrOfNeighbors(link)

LinkIndex iDynTree::Model::getDefaultBaseLink() const

Get the default base link, used for generation of the default traversal.

Returns index of the default base link, if valid

If no link are present in model, returns LINK_INVALID_INDEX. If setDefaultBaseLink was never called but at least a link has been added to the model, returns 0 (i.e. the index of the first link added to the model.

bool iDynTree::Model::computeFullTreeTraversal(Traversal& traversal) const

Compute a Traversal of all the links in the Model, doing a Depth First Search starting at the default base.

Parameters
traversal out traversal of all links in the model
Returns true if all went well, false otherwise.

bool iDynTree::Model::computeFullTreeTraversal(Traversal& traversal, const LinkIndex traversalBase) const

Compute a Traversal of all the links in the Model, doing a Depth First Search starting at the given traversalBase.

Parameters
traversal out traversal of all links in the model
traversalBase in base (root) link in the traversal
Returns true if all went well, false otherwise

bool iDynTree::Model::getInertialParameters(VectorDynSize& modelInertialParams) const

Get the inertial parameters of the links of the model in vector forms.

Parameters
modelInertialParams out vector of inertial parameters
Returns true if all went well, false otherwise.

This methods gets the inertial parameters (mass, center of mass, 3D inertia matrix) of the links of the robot.

The output vector of inertial parameters must have 10*getNrOfLinks() elements, each 10 elements subvector corresponds to the inertial parameters of one link, following the serialization induced by the link indices (link 0 corresponds to elements 0-9, link 1 to 10-19, etc).

The mapping between the SpatialInertia class and the Vector10 elements is the one defined in SpatialInertia::asVector() method.

bool iDynTree::Model::updateInertialParameters(const VectorDynSize& modelInertialParams)

Update the inertial parameters of the links of the model.

Parameters
modelInertialParams in vector of inertial parameters
Returns true if all went well, false otherwise.

This methods modifies the inertial parameters (mass, center of mass, 3D inertia matrix) of the links of the robot.

The input vector of inertial parameters must have 10*getNrOfLinks() elements, each 10 elements subvector corresponds to the inertial parameters of one link, following the serialization induced by the link indices (link 0 corresponds to elements 0-9, link 1 to 10-19, etc).

The mapping between the SpatialInertia class and the Vector10 elements is the one defined in SpatialInertia::asVector() method.

ModelSolidShapes& iDynTree::Model::visualSolidShapes()

Get the ModelSolidShapes meant for visualization.

Returns a reference to ModelSolidShapes meant for visualization.

const ModelSolidShapes& iDynTree::Model::visualSolidShapes() const

Get the ModelSolidShapes meant for visualization (const version)

Returns a reference to ModelSolidShapes meant for visualization.

ModelSolidShapes& iDynTree::Model::collisionSolidShapes()

Get the ModelSolidShapes meant for collision checking.

Returns a reference to ModelSolidShapes meant for visualization.

const ModelSolidShapes& iDynTree::Model::collisionSolidShapes() const

Get the ModelSolidShapes meant for collision checking (const version)

Returns a reference to ModelSolidShapes meant for visualization.

SensorsList& iDynTree::Model::sensors()

Get the (mutable) sensors associated with the model.

Returns a (mutable) reference to SensorsList associated with the model.

const SensorsList& iDynTree::Model::sensors() const

Get the (const) sensors associated with the model.

Returns a (const) reference to SensorsList associated with the model.

std::string iDynTree::Model::toString() const

Get a printable representation of the Model.

Useful for debugging.

bool iDynTree::Model::isValid() const

Check if the model is valid.

Useful for debugging.