Actin®  Version 5.3.0
Software for Robotics Simulation and Control
URDF Import Guide

Overview

Actin (running on Ubuntu 16.04) can import URDF files and convert them to Actin models. This conversion is mostly automatic, but preparing the URDF files correctly will save time. This guides provides information on how to modify your URDF files for import and some considerations of how to break up URDF into multiple files, one per manipulator.

Importing

Actin Viewer can open URDF files directly (extension .urdf) and will convert these files automatically. Any errors during import and displayed in the console window output. Importation of URDF files only works with the Ubuntu build of Actin Viewer.

URDF Elements

Single Robot: Only one <robot> object can be imported in a single RDF file. Since Actin defines manipulator as an articulated robot or an object in the environment that can be involved in collisions, you will likely have to break up your URDF into multiple files.

Materials: When importing materials, the version of ROS libraries linked with Actin Viewer do not support attributes for ambient, diffuse, specular and emissive. Instead, colors in RGBA format are converted to the same value for the shape attributes ambient, diffuse, and specular. This often leads to values that are too high for the ambient and specular properties, and they can be edited manually after the model is converted.

Material Repeat Definition: In some URDF files we’ve seen, the materials are defined at the top, and then redefined each time. This is not necessary. After defining the material tag, it can just be referenced inside of the <visual> tag, such as <material name=”linkMatl”/> without having to redefine the texture and color each time.

World Root: In URDF files there is often a link defined as world to which all other links are connected. But in Actin we expect the base of the robot to the root of the manipulator. The solution to this is to remove the world link and joints connecting the robot base to the world link.

Joint Limits: The joint limits can be defined in the <joint> tag in URDF, and are converted directly. If no limits are defined, then the joint limits for revolute joints become MAX and MIN double. These are too large to be useful, so adding something reasonable like +/- 200 deg works.

Joint Axes: These must be correctly defined in the <joint> tag in order to for the kinematics to function properly inside of Actin. Look for joints with axis defined at (0 0 0 ) and correct before import.

Bounding Volumes: Using convex meshes for bounding volumes is not recommended, particularly when moving toward hardware control in near real time. The primitive bounding volumes (capsule, sphere, lozenge, etc) should be used instead as collision detection will be much faster. You can delete and redefine bounding volumes in Actin Viewer.

Motion Constraint: The import creates two default motion constraint sets to constrain the motion of the end effector. The first contains a point end effector constraint (3 DOF for position) to constrain the motion of the end effector link, and the second contains a joint control end effector to constrain the robot in joint space. You will likely want to create additional motion constraint sets and motion constraints to constrain the end effector based on your application, such as Frame End Effector with 6DOF constraint or Free-Spin-in-Z with 5DOF constraint. Link Names: The URDF importer in Actin does not record the link name, but instead uses the joint names for the links. This should be fixed in an upcoming release of Actin.

Checklist

Here’s a quick checklist on how to prepare your URDF files.

  1. Make mesh references relative to the location of the URDF file.
  2. Limit the URDF to a single robot. Do not include other workspace elements or their joints and/or links.
  3. Put each object (defined as a robot) in its own URDF file. You can convert each one, save as .ecz file in Actin Viewer and then merge these objects later. This is good practice since the robots are independent from their environment.
  4. The robot base should be the URDF root. Remove the world link and ensure that the robot base is the root link. If you have more than one root, you’ll see an error message from ROS in the console window when importing.
  5. Remove joints that connect the robot base to the world link.
  6. Your joints should have reasonable joint limits and max joint speed. Do this in the URDF file or you can use Joint Configuration in Actin (Menu → Edit → Advanced)

    URDFImporter_image1.png
    Joint Configuration from the Menu
  7. Your joints should have the correct axis assigned to the joint: e.g. <axis xyz="0 0 1" />
  8. After importing, edit the Up Vector to be (0 0 1), assuming that your system coordinate frame up vector is the positive Z axis. This makes mouse-drag rotation work as expected. (View → Up Vector).

    URDFImporter_image2.png
    Up Vector from the Menu
  9. You’ll likely need to adjust the ambient and specular values for the Shape Attributes. Choose small values such as (0.1 0.1 0.1) or #191919 as a web color.
  10. Either use primitive bounding volumes (collision geometry) in URDF or replace them with primitive bounding volumes in Actin Viewer.
  11. Use the Manipulator Configuration in Actin Viewer to test the joint rotation, limits and axis orientation. Use the toolbar icon that looks like a set of 3 sliders.

    URDFImporter_image3.png
    Toolbar Icon for Manipulator Configuration
  12. Once the joint limits and rotate are correct, load the status plugin. (Menu → Plugins → Load Plugin). You use this to spot unwanted collisions.

    URDFImporter_image4.png
    Load Plugins from Menu
  13. In simulation mode, click the Guide Mode icon to move the end effector (EE). Hold down the shift key and drag the orbital graphic (dragger) around. The robot EE should follow if control is running (play pressed). If not, you may not have joint axes defined correctly (step #6) or there are unwanted collisions.
  14. Edit the collision map to turn off collision between adjacent links. By default all inter-link collisions are excluded. You should not exclude collisions between non-adjacent links that might collide.
URDFImporter_image5a.png
The converted robot

URDF Example File

Notice that only the links and joints for the robot proper are included.

1 <robot name="panda">
2  <link name="panda_link0">
3  <visual>
4  <origin xyz="0 0 0" rpy="0 -0 0" />
5  <geometry>
6  <mesh filename="meshdata/link0.47e3-9baf-4269-211f.dae" scale="1 1 1" />
7  </geometry>
8  </visual>
9  <collision>
10  <origin xyz="0 0 0" rpy="0 -0 0" />
11  <geometry>
12  <mesh filename="meshdata/link0.5ed7-ed04-2a84-fad1.stl" scale="1 1 1" />
13  </geometry>
14  </collision>
15  </link>
16  <link name="panda_link1">
17  <visual>
18  <origin xyz="0 0 0" rpy="0 -0 0" />
19  <geometry>
20  <mesh filename="meshdata/link1.bc82-1838-b74e-07cf.dae" scale="1 1 1" />
21  </geometry>
22  </visual>
23  <collision>
24  <origin xyz="0 0 0" rpy="0 -0 0" />
25  <geometry>
26  <mesh filename="meshdata/link1.7a95-e69e-8555-9a9e.stl" scale="1 1 1" />
27  </geometry>
28  </collision>
29  </link>
30  <link name="panda_link2">
31  <visual>
32  <origin xyz="0 0 0" rpy="0 -0 0" />
33  <geometry>
34  <mesh filename="meshdata/link2.f2de-57e9-0d6e-055d.dae" scale="1 1 1" />
35  </geometry>
36  </visual>
37  <collision>
38  <origin xyz="0 0 0" rpy="0 -0 0" />
39  <geometry>
40  <mesh filename="meshdata/link2.32f1-c22c-98ff-20ea.stl" scale="1 1 1" />
41  </geometry>
42  </collision>
43  </link>
44  <link name="panda_link3">
45  <visual>
46  <origin xyz="0 0 0" rpy="0 -0 0" />
47  <geometry>
48  <mesh filename="meshdata/link3.e398-51aa-4e17-43ed.dae" scale="1 1 1" />
49  </geometry>
50  </visual>
51  <collision>
52  <origin xyz="0 0 0" rpy="0 -0 0" />
53  <geometry>
54  <mesh filename="meshdata/link3.6c1d-0aa4-fe21-56ec.stl" scale="1 1 1" />
55  </geometry>
56  </collision>
57  </link>
58  <link name="panda_link4">
59  <visual>
60  <origin xyz="0 0 0" rpy="0 -0 0" />
61  <geometry>
62  <mesh filename="meshdata/link4.b78c-8560-695e-4b01.dae" scale="1 1 1" />
63  </geometry>
64  </visual>
65  <collision>
66  <origin xyz="0 0 0" rpy="0 -0 0" />
67  <geometry>
68  <mesh filename="meshdata/link4.5c9a-1fa3-932a-3074.stl" scale="1 1 1" />
69  </geometry>
70  </collision>
71  </link>
72  <link name="panda_link5">
73  <visual>
74  <origin xyz="0 0 0" rpy="0 -0 0" />
75  <geometry>
76  <mesh filename="meshdata/link5.138b-87c6-43ac-3970.dae" scale="1 1 1" />
77  </geometry>
78  </visual>
79  <collision>
80  <origin xyz="0 0 0" rpy="0 -0 0" />
81  <geometry>
82  <mesh filename="meshdata/link5.a427-df4a-79e3-b241.stl" scale="1 1 1" />
83  </geometry>
84  </collision>
85  </link>
86  <link name="panda_link6">
87  <visual>
88  <origin xyz="0 0 0" rpy="0 -0 0" />
89  <geometry>
90  <mesh filename="meshdata/link6.913d-e3f3-5066-2791.dae" scale="1 1 1" />
91  </geometry>
92  </visual>
93  <collision>
94  <origin xyz="0 0 0" rpy="0 -0 0" />
95  <geometry>
96  <mesh filename="meshdata/link6.5b44-530b-329c-9f84.stl" scale="1 1 1" />
97  </geometry>
98  </collision>
99  </link>
100  <link name="panda_link7">
101  <visual>
102  <origin xyz="0 0 0" rpy="0 -0 0" />
103  <geometry>
104  <mesh filename="meshdata/link7.a92c-ae64-28a8-92e7.dae" scale="1 1 1" />
105  </geometry>
106  </visual>
107  <collision>
108  <origin xyz="0 0 0" rpy="0 -0 0" />
109  <geometry>
110  <mesh filename="meshdata/link7.909e-0a49-ced8-31d9.stl" scale="1 1 1" />
111  </geometry>
112  </collision>
113  </link>
114  <joint name="panda_joint1" type="revolute">
115  <origin xyz="0 0 0.333" rpy="0 -0 0" />
116  <axis xyz="0 0 1" />
117  <parent link="panda_link0" />
118  <child link="panda_link1" />
119  <limit effort="87" velocity="2.175" lower="-2.8973" upper="2.8973" />
120  <safety_controller k_position="100" k_velocity="40" soft_lower_limit="-2.8973" soft_upper_limit="2.8973" />
121  </joint>
122  <joint name="panda_joint2" type="revolute">
123  <origin xyz="0 0 0" rpy="-1.5708 0 0" />
124  <axis xyz="0 0 1" />
125  <parent link="panda_link1" />
126  <child link="panda_link2" />
127  <limit effort="87" velocity="2.175" lower="-1.7628" upper="1.7628" />
128  <safety_controller k_position="100" k_velocity="40" soft_lower_limit="-1.7628" soft_upper_limit="1.7628" />
129  </joint>
130  <joint name="panda_joint3" type="revolute">
131  <origin xyz="0 -0.316 0" rpy="1.5708 -0 0" />
132  <axis xyz="0 0 1" />
133  <parent link="panda_link2" />
134  <child link="panda_link3" />
135  <limit effort="87" velocity="2.175" lower="-2.8973" upper="2.8973" />
136  <safety_controller k_position="100" k_velocity="40" soft_lower_limit="-2.8973" soft_upper_limit="2.8973" />
137  </joint>
138  <joint name="panda_joint4" type="revolute">
139  <origin xyz="0.0825 0 0" rpy="1.5708 -0 0" />
140  <axis xyz="0 0 1" />
141  <parent link="panda_link3" />
142  <child link="panda_link4" />
143  <limit effort="87" velocity="2.175" lower="-3.0718" upper="-0.0698" />
144  <safety_controller k_position="100" k_velocity="40" soft_lower_limit="-3.0718" soft_upper_limit="-0.0698" />
145  </joint>
146  <joint name="panda_joint5" type="revolute">
147  <origin xyz="-0.0825 0.384 0" rpy="-1.5708 0 0" />
148  <axis xyz="0 0 1" />
149  <parent link="panda_link4" />
150  <child link="panda_link5" />
151  <limit effort="12" velocity="2.61" lower="-2.8973" upper="2.8973" />
152  <safety_controller k_position="100" k_velocity="40" soft_lower_limit="-2.8973" soft_upper_limit="2.8973" />
153  </joint>
154  <joint name="panda_joint6" type="revolute">
155  <origin xyz="0 0 0" rpy="1.5708 -0 0" />
156  <axis xyz="0 0 1" />
157  <parent link="panda_link5" />
158  <child link="panda_link6" />
159  <limit effort="12" velocity="2.61" lower="-0.0175" upper="3.7525" />
160  <safety_controller k_position="100" k_velocity="40" soft_lower_limit="-0.0175" soft_upper_limit="3.7525" />
161  </joint>
162  <joint name="panda_joint7" type="revolute">
163  <origin xyz="0.088 0 0" rpy="1.5708 -0 0" />
164  <axis xyz="0 0 1" />
165  <parent link="panda_link6" />
166  <child link="panda_link7" />
167  <limit effort="12" velocity="2.61" lower="-2.8973" upper="2.8973" />
168  <safety_controller k_position="100" k_velocity="40" soft_lower_limit="-2.8973" soft_upper_limit="2.8973" />
169  </joint>
170 </robot>
Created by Energid Technologies www.energid.com
Copyright © 2016 Energid. All trademarks mentioned in this document are property of their respective owners.