Home

Awesome

creo2urdf

Generate URDF model from CREO Parametric mechanisms.

Since it is under development, we cannot guarantee that the user interface of creo2urdf will not implement breaking changes. Be aware of this if you start using the code contained in this repository

CREO Parametric versions supported and tested

Assumptions & limitations

Installation from binaries

[!warning] Users are encountering issues using the dll, see https://github.com/icub-tech-iit/creo2urdf/issues/84

[!NOTE]
The provided dll has not been unlocked, therefore the Toolkit licence is required for using it

Download creo2urdf.zip from the assets of the latest release, and extract it in the folder you like.<br> This archive contains the dll of the plugin and the text folder for running it. <br> Follow the Usage section instructions for completing the installation. <br>

Installation from sources

Dependencies

Right now the creo2urdf plugin needs its dependencies to be compiled and linked statically:

Build creo2urdf

For those who use the CMake integration in Visual Studio, the -DCMAKE_TOOLCHAIN_FILE option should not be passed to CMake command arguments. Instead, the vcpkg.cmake file path must be passed in CMake toolchain file.

Usage

name creo2urdf
Startup dll
Allow_stop True
Delay_start False
exec_file \path\to\creo2urdf.dll
text_dir \path\to\creo2urdf\src\creo2urdf\text
END

Test your installation

The folder examples contains a simple assembly with two links, called 2BARS.asm. You can open the assembly in Creo and then test the installation by clicking on the Creo2Urdf button. The plugin will ask you to select the related .yaml and .csv files, which are provided in the folder.

If the export process was successful, you should see three files": "bar.stl", "barlonger.stl" and "model.urdf".

YAML Parameter File

The YAML format is used to pass parameters to the plugin to customized the conversion process. The parameters accepted by the plugin are documented in the following.

Include Parameters

The YAML can eventually include other YAML files using the includes parameter, if so, the included files are merged with the main file. All internal groups are merged if they are maps, they are overwritten only if an element is not a map, taking precedence over the main file in case of conflicts.

[!NOTE] The includes parameter is not mandatory, but if it is present, it must be a list of strings, containing relative path respect the directory of the main YAML file.

Attribute nameTypeDefault ValueDescription
includesList of strings""List of paths relative to the main YAML directory
Severity Parameters
Attribute nameTypeDefault ValueDescription
warningsAreFatalBooleantrueUsed for throwing fatal errors in case some steps in the exportation of the urdf are failing.
Naming Parameters
Attribute nameTypeDefault ValueDescription
robotNameStringmodel name set in the file PhysicalModelingXMLFileUsed for setting the model name, i.e. the parameter <robot name="..."> in the URDF model file.
renameMap{} (Empty Map)Structure mapping the SimMechanics XML names to the desired URDF names.
Root Parameters
Attribute nameTypeDefault ValueDescription
rootStringFirst body in the fileChanges the root body of the tree
originXYZListemptyChanges the position of the root body
originRPYListemptyChanges the orientation of the root body
Algorithm Parameters
Attribute nameTypeDefault ValueDescription
epsilonFloat4*(Machine eps)Set a custom value for testing whether a number is close to zero
Frame Parameters
Attribute nameTypeDefault ValueDescription
linkFramesArrayemptyStructure 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
exportAllUseraddedBooleanFalseIf 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.
exportedFramesArrayemptyArray 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.
Link Frames Parameters (keys of elements of linkFrames)
Attribute nameTypeDefault ValueDescription
linkNameStringMandatoryname of the link for which we want to set the frame
frameNameStringMandatorydisplayName of the frame that we want to use as link frame. This frame should be attached to the frameReferenceLink link. The default value for frameReferenceLink is linkName
frameReferenceLinkStringemptyframeReferenceLink at which the frame is attached. If frameReferenceLink is empty, it will default to linkName
Exported Frame Parameters (keys of elements of exportedFrames)
Attribute nameTypeDefault ValueDescription
frameNameStringMandatorydisplayName of the frame in which the sensor measure is expressed. The selected frame should be attached to the referenceLink link, but referenceLink can be be omitted if the frameName is unique in the model.
frameReferenceLinkStringemptyframeReferenceLink at which the frame is attached. If referenceLink is empty, it will be selected the first USERADDED frame with the specified frameName
exportedFrameNameStringsensorNameName of the URDF link exported by the exportedFrames option
additionalTransformationListEmptyAdditional transformation applied to the exported frame, it is expressed as [x, y, z, r, p, y] according to the semantics and units of the SDF convention for expressing poses. If the unmodified transformation of the additionalFrame is indicated as linkFrame_H_additionalFrameOld, this parameter specifies the additionalFrameOld_H_additionalFrame transform, and the final transform exported in the URDF is computed as linkFrame_H_additionalFrame = linkFrame_H_additionalFrameOld*additionalFrameOld_H_additionalFrame . If not specified it is assume to be the [0, 0, 0, 0, 0, 0] element and the specified frame is exported in the URDF unmodified.
Mesh Parameters
Attribute nameTypeDefault ValueDescription
filenameformatString%sUsed for translating the filenames in the exported XML to the URDF filenames, using a formatting string. Example: "package://my_package//folder/%sb" - resolves to the package name and adds a "b" at the end to indicate a binary stl.
forcelowercaseBooleanFalseUsed for translating the filenames. Ff True, it forces all filenames to be lower case.
scaleStringNoneIf this parameter is defined, the scale attribute of the mesh in the URDF will be set to its value. Example: "0.01 0.01 0.01" - if your meshes were saved using centimeters as units instead of meters.
stringToRemoveFromMeshFileNameStringNoneThis parameter allows to specify a string that will be removed from the mesh file names. Example: "_prt"
assignedCollisionGeometryArrayNoneStructure for redefining the collision geometry for a given link.
assignedColorsMap{} (Empty Map)If a link is in this map, the color found in the SimMechanics file is substituted with the one passed through this map. The color is represented by a 4 element vector of containing numbers from 0 to 1 representing the red, green, blue and alpha component.
meshFormatStringstl_binaryFormat of the meshes exported. Allowed values: stl_binary, stl_ascii, step
exportMeshesBooleanTrueIf false, the meshes will not be exported.
Assigned collision geometries (keys of elements of assignedCollisionGeometry)
Attribute nameTypeDefault ValueDescription
linkNameStringMandatoryName of the link for which the collision geometry is specified.
geometricShapeDictionaryMandatoryThis dictionary contains the parameters used to define the type and the position of the geometric shape. In particular we have: <ul><li>shape: geometric shape type. Supported "box", "cylinder", "sphere". </li><li>type dependent geometric shape parameters. Refer to SDF Geometry. </li><li>origin: String defining the pose of the geometric shape with respect to the linkFrame. </li></ul>
assignedCollisionGeometry:
  - linkName: r_foot
    geometricShape:
      shape: cylinder
      radius: 0.16
      length: 0.06
      origin: "0.0 0.03 0.0 1.57079632679 0.0 0.0"
  - linkName: l_foot
    geometricShape:
      shape: box
      size: 0.4 0.2 0.1
      origin: "0.0 0.0 0.0 0.0 0.0 0.0"
Inertia parameters

Parameters related to the inertia parameters of a link

Attribute nameTypeDefault ValueDescription
assignedMassesMap{} (Empty Map)If a link is in this map, the mass found in the SimMechanics file is substituted with the one passed through this map. Furthermore, the inertia matrix present in the SimMechanics file is scaled accounting for the new mass (i.e. multiplied by new_mass/old_mass). The mass is expressed in Kg.
assignedInertiasArrayemptyStructure for redefining the inertia tensor (at the COM) for a given link.
Assigned Inertias parameters (elements of assignedInertias parameters)
Attribute nameTypeDefault ValueDescription
linkNameStringMandatoryname of the link for which we want to set the frame
xxStringemptyIf defined, change the Ixx value of the inertia matrix of the link. Unit of measure: Kg*m^2 .
yyStringemptyIf defined, change the Iyy value of the inertia matrix of the link. Unit of measure: Kg*m^2 .
zzStringemptyIf defined, change the Izz value of the inertia matrix of the link. Unit of measure: Kg*m^2 .
assignedMasses:
  link1: 1
  link2: 3

assignedInertias:
  - linkName: link1
    xx: 0.0001
  - linkName: link1
    xx: 0.0003
    yy: 0.0003
    zz: 0.0003
Sensors Parameters

Sensor information can be expressed using arrays of sensor options. Note that given that the URDF still does not support an official format for expressing sensor information, this script will output two different elements for each sensor:

Attribute nameTypeDefault ValueDescription
forceTorqueSensorsArrayemptyArray of option for exporting 6-Axis ForceTorque sensors
sensorsArrayemptyArray of option for exporting generic sensors (e.g. camera, depth, imu, ray..)
ForceTorque Sensors Parameters (keys of elements of forceTorqueSensors)
Attribute nameTypeDefault ValueDescription
jointNameStringemptyName of the Joint for which this sensor measure the ForceTorque.
directionChildToParentBoolTrueTrue if the sensor measures the force excerted by the child on the parent, false otherwise
sensorNameStringjointNameName of the sensor, to be used in the output URDF file
exportFrameInURDFBoolFalseIf true, export a fake URDF link whose frame is coincident with the sensor frame (as if the sensor frame was added to the exportedFrames array).
exportedFrameNameStringsensorName if defined jointName otherwiseName of the URDF link exported by the exportFrameInURDF option
frameNameStringemptyName of the frame in which the sensor measure is expressed. Mandatory if exportFrameInURDF is set to yes.
linkNameStringemptyName of the parent link at which the sensor is rigidly attached. Mandatory if exportFrameInURDF is set to yes.
frameReferenceLinkStringlinkNamelink at which the sensor frame is attached (to make sense, this link should be rigidly attached to the linkName. By default referenceLink is assumed to be linkName.
frameStringemptyThe value of this element may be one of: child, parent, or sensor. It is the frame in which the forces and torques should be expressed. The values parent and child refer to the parent or child links of the joint. The value sensor means the measurement is rotated by the rotation component of the <pose> of this sensor. The translation component of the pose has no effect on the measurement.
sensorBlobsStringemptyArray of strings (possibly on multiple lines) represeting complex XML blobs that will be included as child of the <sensor> element of type "force_torque"

Note that for now the FT sensors sensor frame is required to be coincident with child link frame, due to URDF limitations.

Generic Sensors Parameters (keys of elements of sensors)
Attribute nameTypeDefault ValueDescription
linkNameStringMandatoryName of the Link at which the sensor is rigidly attached.
frameNameStringemptydisplayName of the frame in which the sensor measure is expressed. The selected frame must be attached to the referenceLink link. If empty the frame used for the sensor is coincident with the link frame.
frameReferenceLinkStringlinkNamelink at which the sensor frame is attached (to make sense, this link should be rigidly attached to the linkName. By default referenceLink is assumed to be linkName.
sensorNameStringLinkName_FrameNameName of the sensor, to be used in the output URDF file
exportFrameInURDFBoolFalseIf true, export a fake URDF link whose frame is coincident with the sensor frame (as if the sensor frame was added to the exportedFrames array)
exportedFrameNameStringsensorNameName of the URDF link exported by the exportFrameInURDF option
sensorTypeStringMandatoryType of sensor. Supported: "altimeter", "camera", "contact", "depth", "gps", "gpu_ray", "imu", "logical_camera", "magnetometer", "multicamera", "ray", "rfid", "rfidtag", "sonar", "wireless_receiver", "wireless_transmitter"
updateRateStringMandatoryNumber representing the update rate of the sensor. Expressed in [Hz].
sensorBlobsStringemptyArray of strings (possibly on multiple lines) represeting complex XML blobs that will be included as child of the <sensor> element
XML Blobs options

If you use extensions of URDF, we frequently want to add non-standard tags as child of the <robot> root element. Using the XMLBlobs option, you can pass an array of strings (event on multiple lines) represeting complex XML blobs that you want to include in the converted URDF file. This will be included without modifications in the converted URDF file. Note that every blob must have only one root element.

Attribute nameTypeDefault ValueDescription
XMLBlobs Array of String[] (empty array)List of XML Blobs to include in the URDF file as children of <robot>

CSV Parameter File

By using the a .csv file it is possible to load some joint-related information from a csv file. The rationale for using CSV over YAML for some information related to the model (for example joint limits) is to use a format that it is easier to modify using common spreadsheet tools like Excel/LibreOffice Calc, that can be easily used also by people without a background in computer science.

Format

The CSV file is loaded and parsed using the d99kris/rapidcsv library. Please refer to its documentation for supported dialects of the format.

The CSV file is formed by a header line followed by several content lines, as in this example:

joint_name,lower_limit,upper_limit
torso_yaw,-20.0,20.0
torso_roll,-20.0,20.0

The order of the elements in header line is arbitrary, but the supported attributes are listed in the following:

Attribute nameRequiredUnit of MeasureDescription
joint_nameYes-Name of the joint to which the content line is referring
lower_limitNoDegreeslower attribute of the limit child element of the URDF joint. Please note that we specify this limit here in Degrees, but in the urdf it is expressed in Radians, the plugin will take care of internally converting this parameter.
upper_limitNoDegreesupper attribute of the limit child element of the URDF joint. Please note that we specify this limit here in Degrees, but in the urdf it is expressed in Radians, the plugin will take care of internally converting this parameter.
velocity_limitNoRadians/secondvelocity attribute of the limit child element of the URDF joint.
effort_limitNoNewton meterseffort attribute of the limit child element of the URDF joint.
dampingNoNewton meter seconds / radiansdamping of the dynamics child element of the URDF joint.
frictionNoNewton metersfriction of the dynamics child element of the URDF joint.

Maintainers

This repository is maintained by:

<img src="https://github.com/Nicogene.png" width="40">@Nicogene
<img src="https://github.com/mfussi66.png" width="40">@mfussi66