![]() |
Tesseract
0.28.4
|
Tesseract is compatible with Universal Robot Description Format (URDF), the native format for describing robots in ROS. In this tutorial, you will find resources for the URDF and important tips.
This section contains a set of tips on making sure that the URDF that you generate can be used with Tesseract. Make sure you go through all these tips before starting to use Tesseract with your robot.
Joint names should not contain any of the following special characters:
-
[
]
(
)
Some URDFs have safety limits set in addition to the joint limits of the robot. Here's an example of the safety controller specified for the Panda robot head pan joint:
<safety_controller k_position="100" k_velocity="1.5" soft_lower_limit="-2.857" soft_upper_limit="2.857"/>
The "soft_lower_limit" field and the "soft_upper_limit" field specify the joint position limits for this joint. Tesseract will compare these limits to the hard limits for the joint specified in the URDF and choose the limits that are more conservative.
Tesseract uses the meshes specified in the URDF for collision checking. The URDF allows you to specify two sets of meshes separately for visualization and collision checking. In general, the visualization meshes can be detailed and pretty, but the collision meshes should be much less detailed. The number of triangles in a mesh affects the amount of time it takes to collision check a robot link. The number of triangles in the whole robot should be on the order of a few thousand.
It is very important to test your URDF out and make sure things are configured properly. Consider using the ROS check_urdf
tool to validate your URDF.
Tesseract provides several extensions to the URDF standard.
Capsule geometry
URDF path: /robot/link/<visual|collision>/geometry/tesseract:capsule
<tesseract:capsule length="<float>" radius="<float>">
Cone geometry
URDF path: /robot/link/<visual|collision>/geometry/tesseract:cone
<tesseract:cone length="<float>" radius="<float>">
Octomap geometry, populated by an octree or point cloud
URDF path: /robot/link/<visual|collision>/geometry/tesseract:octomap
<tesseract:octomap shape_type="box | sphere_inside | sphere_outside">
Nested elements:
Octree file source for octomap geometry
URDF path: /robot/link/<visual|collision>/geometry/tesseract:octomap/tesseract:octree
<tesseract:octree filename="*.octree">
Point cloud file source for octomap geometry
URDF path: /robot/link/<visual|collision>/geometry/tesseract:octomap/tesseract:point_cloud
<tesseract:point_cloud filename="*.pcd" resolution="<float>">
Signed distance field (SDF) mesh geometry
URDF path: /robot/link/<visual|collision>/geometry/tesseract:sdf_mesh`
<tesseract:sdf_mesh filename="*.sdf">
For convenience, Tesseract can automatically convert collision mesh geometries into convex hulls for more efficient collision checking and motion planning. Set the tesseract:make_convex
attribute(s) to enable this behavior.
URDF path: /robot/@tesseract:make_convex="true | false"
URDF path: /robot/link/<visual|collision>/geometry/mesh/@tesseract:make_convex="true | false"