file
ModelTransformers.hCollection of function to modify model in various ways.
In this file a series of functions for transforming Model objects are provided
Namespaces
- namespace iDynTree
Functions
- auto removeFakeLinks(const Model& modelWithFakeLinks, Model& modelWithoutFakeLinks) -> bool
- \function Remove all fake links in the model, transforming them in frames.
- auto createReducedModel(const Model& fullModel, const std::vector<std::string>& jointsInReducedModel, Model& reducedModel) -> bool
- This function takes in input a iDynTree::
Model and an ordered list of joints and returns a model with just the joint specified in the list, with that exact order. - auto createReducedModel(const Model& fullModel, const std::vector<std::string>& jointsInReducedModel, Model& reducedModel, const std::unordered_map<std::string, double>& removedJointPositions) -> bool
- This function takes in input a iDynTree::
Model and an ordered list of joints and returns a model with just the joint specified in the list, with that exact order. - auto createModelWithNormalizedJointNumbering(const Model& model, const std::string& baseForNormalizedJointNumbering, Model& reducedModel) -> bool
- Given a specified base, return a model with a "normalized" joint numbering for that base.
-
auto extractSubModel(const iDynTree::
Model& fullModel, const iDynTree:: Traversal& subModelTraversal, iDynTree:: Model& outputSubModel) -> bool - Extract sub model from sub model traversal.
-
auto addValidNamesToAllSolidShapes(const iDynTree::
Model& inputModel, iDynTree:: Model& outputModel) -> bool - Add automatically generated names to all visual and collision solid shapes of the model.
-
auto moveLinkFramesToBeCompatibleWithURDFWithGivenBaseLink(const iDynTree::
Model& inputModel, iDynTree:: Model& outputModel) -> bool - Transform the input model in model that can be exported as URDF with the given base link.
Function documentation
bool removeFakeLinks(const Model& modelWithFakeLinks, Model& modelWithoutFakeLinks)
\function Remove all fake links in the model, transforming them in frames.
Given a Model in input, this function copies all its links and joints to the model in output, except for links that recognized as "fake links".
The condition for a link to be classified as "fake link" are:
- The link has a zero mass.
- The link is a leaf, i.e. it is connected to only one neighbor.
- The link is connected to its only neighbor with a fixed joint.
Once a "fake link" has been identified to respect this two conditions, it and the joint that it connects it to its only neighbor is not copied to the output model, but a frame with the same name of the "fake link" and with the same transform is added to the model.
bool createReducedModel(const Model& fullModel, const std::vector<std::string>& jointsInReducedModel, Model& reducedModel)
This function takes in input a iDynTree::
All other joints are be removed by lumping (i.e. fusing together) the inertia of the links that are connected by that joint, assuming the joint to be in "rest" position (i.e. zero for revolute or prismatic joints). The links eliminated with this process are be added back to the reduced model as "frames", and are copied in the same way all the additional frames of the lumped links.
bool createReducedModel(const Model& fullModel, const std::vector<std::string>& jointsInReducedModel, Model& reducedModel, const std::unordered_map<std::string, double>& removedJointPositions)
This function takes in input a iDynTree::
All other joints are be removed by lumping (i.e. fusing together) the inertia of the links that are connected by that joint, assuming the joint to be in "rest" position (i.e. zero for revolute or prismatic joints), or the position specified in the removedJointPositions if a given joint is specified in removedJointPositions
bool createModelWithNormalizedJointNumbering(const Model& model, const std::string& baseForNormalizedJointNumbering, Model& reducedModel)
Given a specified base, return a model with a "normalized" joint numbering for that base.
Returns | true if all went well, false if there was an error in conversion. |
---|
This function takes in input a iDynTree::
bool extractSubModel(const iDynTree:: Model& fullModel,
const iDynTree:: Traversal& subModelTraversal,
iDynTree:: Model& outputSubModel)
Extract sub model from sub model traversal.
Returns | true if all went well, false if there was an error in creating the sub model. |
---|
This function creates a new iDynTree::
bool addValidNamesToAllSolidShapes(const iDynTree:: Model& inputModel,
iDynTree:: Model& outputModel)
Add automatically generated names to all visual and collision solid shapes of the model.
Returns | true if all went well, false if there was an error in creating the sub model. |
---|
This function creates a new iDynTree::
For links that already have at least either collision or visual with valid name, all the corresponding shapes (collision or visual) will not be modified.
For links in which all shapes of a given type that do not have a valid name, a name will be generated as the following:
- If there is a single collision or visual element in the link, it will be named <linkName>_collision or <linkName>_visual
- If there are multiple collision or visual elements in the link, the solid shapes will be <linkName>_collision_0, <linkName>_collision_1, ... <linkName>_collision_n or <linkName>_visual_0, <linkName>_visual_1, ... <linkName>_visual_n
bool moveLinkFramesToBeCompatibleWithURDFWithGivenBaseLink(const iDynTree:: Model& inputModel,
iDynTree:: Model& outputModel)
Transform the input model in model that can be exported as URDF with the given base link.
Returns | true if all went well, false if there was an error in creating the sub model. |
---|
In iDynTree, the link frame can be placed without constraint w.r.t. to the joints to which the link is connected. On the other hand, in the URDF format, the origin of the frame of the child link connected to its parent with a non-fixed joint must lay on the axis of the joint.
That means that if you want to export a model with an arbitrary base link, some link frame will need to be moved to respect the constraint given by the URDF format. This function perform exactly this transformation, ensuring that inertia, visual and collision information is probably accounted for, and leaving the original link frames in the model as "additional frames" with the naming scheme <linkName>_original_frame .
Note that the operation done depends on the base link used, if you want to use a different base link, change the default base link of the model via inputModel.setDefaultBaseLink method.