In this tutorial we will learn to create URDFs for typical industrial manipulators. The URDF XML format is very expressive and allows many different ways of defining the same geometry. We will discuss specific conventions that are meant to:
The arm path planning methods that are used by ROS-Industrial are collision aware. In order to take advantage of this capability 3D information about the robot geometry is required.
Link coordinate systems must be created before exporting STL files from 3D CAD models. The coordinate system present in vendor supplied CAD models are rarely in the desired position. The desired coordinate systems should adhere to the following:
File->Export as URDF
), double check that the Origin_global feature that was created by the URDF exporter is oriented correctly (X-axis forward, Z-axis up) . If it is not correctly oriented, manually correct it by editing the feature, then rerun the URDF Configuration tool to regenerate the URDF file.The URDF allows for two types of 3D models, visual and collision models.
A visual model is used for display purposes only. These models can be highly detailed because they are not used for collision checking. Visual models can be exported directly from a CAD package. Make certain to export binary STLs.
Collision models should not be highly detailed. The more detailed these models, the longer it takes to perform collision checks. Collision models should be simple, yet encompass the entire link geometry. It is suggested the convex hulls be created from visual STLs, using a 3D mesh tool such as !MeshLab (Filters->Remeshing, Simplification and Reconstruction->Convex Hull
).
Filters->Normals, Curvatures and Orientation->Invert Faces Orientation
). In case of inconsistent normal orientation (mesh shows transparent areas), use Filters->Normals, Curvatures and Orientation->Re-Orient all faces coherently
.As you step through the following to create a URDF for your robot, adhere to the following conventions:
While it is possible to write an explicit URDF for a particular industrial arm, a more general XACRO approach is taken. A XACRO is a type of URDF macro that can be used to generate a URDF. We take this approach because industrial manipulators are often combined with custom end-effectors, requiring a custom URDF. By writing a XACRO that can generate the manipulator portion of the URDF, we provide flexible and extensible library that can be used to generate any custom robot.
For an example, see:
https://raw.github.com/ros-industrial/motoman/hydro-devel/motoman_sia10d_support/urdf/sia10d_macro.xacro sia10d_macro.xacro
(check this link)
For more information on creating an XACRO, see the [[xacro/Tutorials XACRO tutorials]].
By convention and in order to match common industrial robot frames, several additional frames should be added to the XACRO
base_link
The base_link shall be positioned in the logical base position (oriented by convention, z-axis up, x-axis forward). This frame name is by ROS convention. Typically this frame is the first frame of the robot tied to the first link.
tool0
The tool0 frame shall match exactly the tool0 defined by the robot controller.
The transform between the last robot link and tool0 can be defined in any way, as long as the transform is fixed between the two.
<link name="${prefix}tool0" />
<joint name="${prefix}link_6-tool0" type="fixed">
<parent link="${prefix}link_6" />
<child link="${prefix}tool0" />
<origin xyz="0.0 0 0.0" rpy="0.0 0.0 0.0" />
</joint>
base
The base frame shall match exactly the base defined by the robot controller. The transform between base and base_link can be defined in any way, as long as the transform is fixed between the two (i.e. not across a movable joint). The preference is for the base to be defined relative to base_link
<link name="${prefix}base" />
<joint name="${prefix}base_link-base" type="fixed">
<parent link="${prefix}base_link" />
<child link="${prefix}base" />
<origin xyz="0.0 0 0.0" rpy="0.0 0.0 0.0" />
</joint>
In order to generate a URDF for your robot, another XACRO must be written to call the XACRO created in the previous step. See https://raw.github.com/ros-industrial/motoman/hydro-devel/motoman_sia10d_support/urdf/sia10d.xacro sia10d.xacro for an example.
To generate the actual URDF and check the result:
rosrun xacro xacro.py <<xacro_file>> > <<urdf_file>>
rosrun urdf_parser check_urdf <<urdf_file>>
If successful, the commands above will generate a URDF of your industrial manipulator. As an example, see the https://raw.github.com/ros-industrial/motoman/hydro-devel/motoman_sia10d_support/urdf/sia10d.urdf sia10d.urdf
This section is meant to demonstrate why a XACRO is used instead of directly writing the URDF. In the case where an end-effector is added to the robot, the XACRO comes in handy.
See the following robot + end-effector http://code.google.com/p/swri-ros-pkg/source/browse/trunk/swri_demos/longhorn/cfg/longhorn.xacro example
It is very important that the information within the URDF is accurate. Specifically, the joint limits and orientations will used in the following steps and must be correct. To visualize your robot run the following:
roslaunch urdf_tutorial display.launch model:=<<urdf_file>> gui:=True
Use the GUI sliders to verify the joint orientation (i.e. plus/minus moves the actual robot). Also verify that the joint limits match.
Comments loading please wait.
Unfortunately if this is an https site comments will not load. Please change to use http for comments to load. in the future we plan to support https comments too.