Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,7 @@ All internal groups are merged if they are maps, they are overwritten only if an
| `linkFrames` | Array | empty | Structure mapping the link names to the displayName of their desired frame. Unfortunatly in URDF the link frame origin placement is not free, but it is constrained to be placed on the parent joint axis, hence this option is for now reserved to the root link and to links connected to their parent by a fixed joint |
| `exportAllUseradded` | Boolean | False | If true, export all frames starting w/ `SCSYS` in the output URDF as fake links i.e. fake link with zero mass connected to a link with a fixed joint. |
| `exportedFrames` | Array | empty | Array of `displayName` of UserAdded frames to export. This are exported as fixed URDF frames, i.e. fake link with zero mass connected to a link with a fixed joint. |
| `exportFirstBaseLinkAdditionalFrameAsFakeURDFBase` | Boolean | false | Controls the `iDynTree::ModelExporterOptions::exportFirstBaseLinkAdditionalFrameAsFakeURDFBase` option for the iDynTree URDF exporter. If this YAML parameter is omitted, `creo2urdf` defaults this iDynTree option to `false` (this is a change from `creo2urdf <= v0.5.11` which defaulted to `true`). This change aims to reduce confusion (see [issue #140](https://github.com/icub-tech-iit/creo2urdf/issues/140), [issue #1201](https://github.com/robotology/idyntree/issues/1201)). Set this YAML parameter to `true` to restore the behavior of `creo2urdf <= v0.5.11` . |

###### Link Frames Parameters (keys of elements of `linkFrames`)
| Attribute name | Type | Default Value | Description |
Expand Down
1 change: 1 addition & 0 deletions src/creo2urdf/include/creo2urdf/Creo2Urdf.h
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,7 @@ class Creo2Urdf : public pfcUICommandActionListener {
std::map<std::string, CollisionGeometryInfo> assigned_collision_geometry_map; /**< Map storing assigned collision geometries. */
YAML::Node config; /**< YAML configuration node, storing the content of the configuration file. */
bool exportAllUseradded{ false }; /**< Flag indicating whether to export all user-added frames. */
bool exportFirstBaseLinkAdditionalFrameAsFakeURDFBase{ false }; /**< Flag to export the first additional frame attached to the base link as fake urdf base. */

std::array<double, 3> scale{ 1.0, 1.0, 1.0 }; /**< Scale factor for the exported model. Useful for converting between m and mm and viceversa. */
std::array<double, 3> originXYZ {0.0, 0.0, 0.0}; /**< Offset of the root link in XYZ (meters) wrt the world frame. */
Expand Down
6 changes: 6 additions & 0 deletions src/creo2urdf/src/Creo2Urdf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -228,6 +228,11 @@ void Creo2Urdf::OnCommand() {
exportAllUseradded = config["exportAllUseradded"].as<bool>();
}

if (config["exportFirstBaseLinkAdditionalFrameAsFakeURDFBase"].IsDefined())
{
exportFirstBaseLinkAdditionalFrameAsFakeURDFBase = config["exportFirstBaseLinkAdditionalFrameAsFakeURDFBase"].as<bool>();
}

readExportedFramesFromConfig();
readAssignedInertiasFromConfig();
readAssignedCollisionGeometryFromConfig();
Expand Down Expand Up @@ -399,6 +404,7 @@ void Creo2Urdf::OnCommand() {

iDynTree::ModelExporterOptions export_options;
export_options.robotExportedName = config["robotName"].Scalar();
export_options.exportFirstBaseLinkAdditionalFrameAsFakeURDFBase = exportFirstBaseLinkAdditionalFrameAsFakeURDFBase;

if (config["root"].IsDefined())
export_options.baseLink = config["root"].Scalar();
Expand Down
Loading