(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Converting SimMechanics To URDF!

Description: A step by step tutorial.

Keywords: AdvancedCategory

Tutorial Level:

Here's an example of how to use and configure simmechanics_to_urdf, using a simple arm that moves in a plane, heretofore referred to as the Planar Arm.

This tutorial uses files found in the simmechanics_tutorial package. The files were generated using the SimMechanics bridge in conjunction with ProEngineer. I have placed them all in a folder called planar_arm. The XML generated by SimMechanics is TEST_ARM_ASSY.xml. All test commands assume you are in the simmechanics_tutorial directory.

Things to Know About the Sim Mechanics XML Structure

  • Each piece is defined with a "Body" tag. These will correspond with URDF Links.
  • Each Body has a number of reference frames associated with it.
    • The first is called "CG" for the center of gravity
    • The second is "CS1" which defines the visual origin.
    • The rest "CS2" to "CSN" (for some N) may correspond with Joints. Each of these frames has a ref attribute, which is usually a number.
  • Some of the reference frames and bodies are for "RootPart"s. These are useless to us and generally define some sort of meta-structure which we cannot use.

  • Each joint is defined with a "SimpleJoint" tag, which defines a joint between two reference frames, using their ref attribute.

First Attempt: No parameters

This tool will not let you run it without a configuration file. Create a blank file called planar.yaml and run it with that.

rosrun simmechanics_to_urdf convert.py planar_arm/TEST_ARM_ASSY.xml planar.yaml xml > planar.urdf

This should create a URDF file. However, if we check it using check_urdf1, we get errors.

> rosrun urdf_parser check_urdf planar.urdf 
[ INFO] [1310515139.835126053]: Joint 'BASE_PLATE--BASE_BLOCK1' is of type PRISMATIC without limits
[ INFO] [1310515139.835207139]: Joint 'BASE_BLOCK--LINK_11' is of type PRISMATIC without limits
[ERROR] [1310515139.835280891]: Joint 'LINK_1--CAPSTAN_OUTER_BEARING_RING1' is of type REVOLUTE but it does not specify limits
[ERROR] [1310515139.835307640]: joint xml is not initialized correctly
ERROR: Model Parsing the xml failed

check_urdf doesn't like the fact that the limits on prismatic joints aren't set. To fix errors from here on out, we need to know a little bit about the model. For instance, there shouldn't be a joint, prismatic or otherwise between the BASE_PLATE and BASE_BLOCK. As explained in the Tree vs. Graph section of the documentation, Sim Mechanics has a hard time figuring out whether joints are fixed in complicated structures. We must manually define which joints can move and which can't.

Examining the generated tree structure

The tool makes several assumptions about the graph when converting it to a tree for URDF. To see what the tree looks like, you can create a visual representation of the graph with the tool.

To display the graph,

> rosrun simmechanics_to_urdf convert.py planar_arm/TEST_ARM_ASSY.xml graph | dot -Tpng | display

or to save it,

> rosrun simmechanics_to_urdf convert.py planar_arm/TEST_ARM_ASSY.xml graph | dot -Tpng > initial_graph.png

What does all this mean? Each link becomes a node in the graph, with each edge representing a joint. The joints can have a number of different attributes.

  • Thin lines represent fixed joints, and thick lines represent flexible joints.
  • Black lines are 'regular' unmodified joints.
  • Blue lines are joints that have had their direction reversed.
  • Yellow lines represent joints that have been removed in order to preserve tree structure.

Reversed Joints

Consider the link marked "LINK23", which corresponds with the Body with nodeID 43/41/39 in the original XML. In the original XML, there are reference frames for each of the attached Bodies. The one we're concerned with is ref=141, which connects to STUB3.

If we look at the SimpleJoint defined on line 6505, we'll see that the joint defines the base (or parent in URDF terms) as ref=141 and the follower (or child) as ref=142. This means that SimMechanics considers LINK23 to be the parent of STUB3. However, the traversal from the root element (BASE_PLATE1) to this element (LINK23), STUB3 comes first. So, the tool reverses the direction of the joint.

As a general rule, you don't need to fix anything with reversed joints. They are just noting that something was fixed. If the direction of the tree is not to your liking, change the root node, as discussed below.

Removed Joints

Consider the links marked LINK_11, STOP_BLOCK1 and OUTER_BEARING_RING1. In the original XML, LINK_11 was a parent to both other pieces, and OUTER_BEARING_RING1 was a parent to STOP_BLOCK1. This creates a graph structure. The tool arbitrarily picked the latter joint to remove, thus it is marked as yellow.

Freezing Joints

Prior knowledge of the model tells me that there should only be 3* non-fixed joints in the model, but our initial run output 17. So, the first thing to do is to freeze all the joints by adding the following line to our configuration file.

freezeAll: True

This produces a model that checks out with check_urdf.

*Technically, 6, but we're ignoring 3 for now.

Fixing the Meshes

Let's try to view it in Rviz.

roslaunch planar_test.launch model:=planar.urdf

That gives us many errors of the type:

[ERROR] [1310518804.382120436]: Error retrieving file [BASE_BLOCK_prt.stl]: Couldn't resolve host 'BASE_BLOCK_prt.stl'
[ERROR] [1310518804.383079147]: Could not load model 'BASE_BLOCK_prt.stl' for link 'BASE_BLOCK1': OGRE EXCEPTION(6:FileNotFoundException): Cannot locate resource BASE_BLOCK_prt.stl in resource group Autodetect or any other group. in ResourceGroupManager::openResource at /tmp/buildd/ros-diamondback-visualization-common-1.4.1/debian/ros-diamondback-visualization-common/opt/ros/diamondback/stacks/visualization_common/ogre/build/ogre_src_v1-7-1/OgreMain/src/OgreResourceGroupManager.cpp (line 753)

Our generated URDF contains the line

   1 <mesh filename="BASE_PLATE_prt.stl"/>

There are three problems here.

  • Our files are in the planar_arm directory.
  • Those filenames are all lower-case.
  • The files are the ascii versions.

To solve the last problem, we can create binary versions of the files with this command.

rosrun simmechanics_to_urdf convertToBinaries.py planar_arm/

Super-conveniently, there are also options to fix the first two problems. Add the following lines to the configuration file.

filenameformat: "package://simmechanics_tutorial/planar_arm/%sb"
forcelowercase: True

This will insert the original filename, converted to lowercase where the %s is. The final b refers to the binary version of the file.

Regenerating the URDF and viewing that gives us this.

https://wu-ros-pkg.svn.sourceforge.net/svnroot/wu-ros-pkg/stacks/urdf_tools/trunk/simmechanics_tutorial/toobig.png

My spoon is too big! Rather, all the meshes are too big. While ROS uses meters for scale, the program generating the meshes used inches, generating meshes that are several times too large. Hence, we scale down. Add the following line.

scale: ".0254 .0254 .0254"

This gives you a model that looks like this:

https://wu-ros-pkg.svn.sourceforge.net/svnroot/wu-ros-pkg/stacks/urdf_tools/trunk/simmechanics_tutorial/fixed.png

Now the only problem is that it doesn't move.

Adding Flexible Joints

We need to add flexible joints back into the model. But where? This again calls for knowledge of the model you're working with. For instance, I know there needs to be a revolute joint between KAYDON_JAX020XP01 and STUB1. In fact, we need a joint between every KAYDON and STUB. Hence, we look at the visualization, and next to each of the arrows representing those joints, we find a pair of numbers: 53:54, 79:80, and 115:116. These represent which reference frames are being joined.

To re-insert the joints, we refer to the first number in each of these pairs and add the following lines to our config.

redefinedjoints:
   53:  {name: ARM_JOINT1}
   79:  {name: ARM_JOINT2}
   115: {name: ARM_JOINT3}

This creates 3 joints with the respective names. They default to continuous if no other type is specified.

To see this in action, add a parameter to your launch command.

roslaunch planar_test.launch model:=planar.urdf gui:=True

With this visualization, you can see the joints go too far and need limits. We can define those fairly easily as well.

redefinedjoints:
   53:  {name: ARM_JOINT1,  type: revolute, limits: {effort: 30, velocity: 1.0, lower: -1.57079, upper: 1.57079}}
   79:  {name: ARM_JOINT2,  type: revolute, limits: {effort: 30, velocity: 1.0, lower: -1.57079, upper: 1.57079}}
   115: {name: ARM_JOINT3,  type: revolute, limits: {effort: 30, velocity: 1.0, lower: -1.57079, upper: 1.57079}}

There! Now we should have a correctly articulated model.

  1. For Diamondback and earlier releases, check_urdf script is in urdf, not urdf_parser (1)

Wiki: simmechanics_to_urdf/Tutorials/Converting SimMechanics To URDF (last edited 2011-07-22 03:57:40 by hsu)