SDF template for grippers
SDFormat (SDF) can be used to create a gripper within
Flowstate. In the below templates, important
details are provided in the comments (i.e., <!-- this is a comment -->):
Note: Complex meshes with a large number of polygons will cause slow performance of the simulator when used as collision meshes. We recommend using either a simplified mesh or primitive shapes (e.g., box, sphere, cylinder) for collisions.
Current limitations
- Only supports one
<include>and does not support nested<include>s. - The zip file used to create the
SceneObjectmust only contain the SDF file(s) and mesh(es). Zipping the directory that holds these files will result in an error. - For suction grippers, the
<joint>that connects the gripper base and suction must beprismaticwith a buffer threshold between the two links. See below example for more details.
Suction gripper
For a full example, download this Schmalz ECBPMi suction gripper zip. The gripper onboarding workflow in Flowstate requires a corresponding configuration file to function properly. For an OPC UA configuration example, use schmalz_suction_gripper_opcua_service_config.txt. For a Realtime control configuration example, use schmalz_suction_gripper_realtime_control_service_config.txt.
<?xml version="1.0" encoding="UTF-8"?>
<!--
Note: xmlns:intrinsic="https://intrinsic.ai" is required for the custom
attribute listed in the <frame> tag below.
-->
<sdf version="1.11" xmlns:intrinsic="https://intrinsic.ai/">
<model name="suction_gripper">
<!--
Since many suction grippers can have interchange-able suction types,
we've broken up the base and suction so that the suction type can be
switched. In this example, the gripper's base link is called
'gripper_base' and the suction link called 'gripper_suction'.
-->
<link name="gripper_base">
<visual name="base_visual">
<geometry>
<!-- Can be a mesh or primitive shape; this example uses a mesh. -->
<mesh>
<uri>relative/path/to/mesh/suction_base</uri>
</mesh>
</geometry>
</visual>
<collision name="base_collision">
<geometry>
<!-- Fill this section with a mesh or primitive shape;
this is used for motion planning and physics.
See http://sdformat.org/spec?ver=1.11&elem=geometry for
available types. -->
</geometry>
</collision>
</link>
<link name="gripper_suction">
<visual name="suction_visual">
<geometry>
<!-- Can be a mesh or primitive shape; this example uses a mesh. -->
<mesh>
<uri>relative/path/to/mesh/suction</uri>
</mesh>
</geometry>
</visual>
<collision name="suction_collision">
<geometry>
<!--
Fill this section with a mesh or primitive shape;
this is used for motion planning and physics.
See http://sdformat.org/spec?ver=1.11&elem=geometry for
available types.
-->
</geometry>
</collision>
</link>
<!--
Since this gripper is broken up into two separate links, we need a
joint to attach them together.
There is a limitation where a buffer between the two parent and child
links is required, this will be addressed in the future.
-->
<joint name="base_suction_joint" type="prismatic">
<parent>gripper_base</parent>
<child>gripper_suction</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-0.0015</lower>
<upper>0</upper>
</limit>
</axis>
</joint>
<!--
Specify a tool frame that represents center of the suction.
If the gripper has multiple suction cups, this should be in the center.
The z-axis should be pointing out (e.g., if the suction cups are facing
down, the z-axis should also face down). Modify the <pose> tag accordingly.
When you load the model into Flowstate, this tool frame will be displayed.
Note: Flowstate ignores many implicit Gazebo frames.
intrinsic:create_entity="true" is required for the frame to be created
in the Flowstate World.
-->
<frame name="tool_frame"
attached_to="gripper_suction"
intrinsic:create_entity="true">
<pose>0 0 0 0 3.141592654 0</pose>
</frame>
</model>
</sdf>
Pinch gripper
For a full example, download this SCHUNK KGG 100-80 pinch gripper zip. The gripper onboarding workflow in Flowstate requires a corresponding configuration file to function properly. For an OPC UA configuration example, use schunk_pinch_gripper_opcua_service_config.txt. For a Realtime control configuration example, use schunk_pinch_gripper_realtime_control_service_config.txt.
Note, this example does not have gripping attachments on the fingers
but one can test it out to see the mechanism working. This also by default
has the gripping closed so the service configuration requires the field
is_default_closed: true.
<?xml version="1.0" encoding="UTF-8"?>
<!--
Note: xmlns:intrinsic="https://intrinsic.ai" is required for the custom
attribute listed in the <frame> tag below.
-->
<sdf version="1.11" xmlns:intrinsic="https://intrinsic.ai/">
<model name='pinch_gripper'>
<!--
Two prismatic joints are required for the pinch gripper.
Below, 3 links are listed, one for the body base and two separate finger
links which will be later used in the <joint> fields.
-->
<link name="gripper_base">
<visual name="base_visual">
<geometry>
<!-- Can be a mesh or primitive shape; this example uses a mesh. -->
<mesh>
<uri>relative/path/to/mesh/pinch_base</uri>
</mesh>
</geometry>
</visual>
<collision name="base_collision">
<geometry>
<!-- Fill this section with a mesh or primitive shape;
this is used for motion planning and physics.
See http://sdformat.org/spec?ver=1.11&elem=geometry for
available types. -->
</geometry>
</collision>
</link>
<link name="finger_1">
<!--
Note that if the model starts in a closed position, you will need
to update the Intrinsic Service config to have the parameter
`is_default_closed: true`.
-->
<visual name ="finger_1_visual">
<!-- Can be a mesh or primitive shape; this example uses a mesh. -->
<mesh>
<uri>relative/path/to/mesh/finger1</uri>
</mesh>
</geometry>
</visual>
<collision name ="finger_1_collision">
<geometry>
<!-- Fill this section with a mesh or primitive shape;
this is used for motion planning and physics.
See http://sdformat.org/spec?ver=1.11&elem=geometry for
available types. -->
</geometry>
</collision>
</link>
<link name="finger_2">
<!--
Note that if the model starts in a closed position, you will need
to update the Intrinsic Service config to have the parameter
`is_default_closed: true`.
-->
<visual name="finger_2_collision">
<geometry>
<!-- Can be a mesh or primitive shape; this example uses a mesh. -->
<mesh>
<uri>relative/path/to/mesh/finger2</uri>
</mesh>
</geometry>
</geometry>
</visual>
<collision name="finger_2_collision">
<geometry>
<!-- Fill this section with a mesh or primitive shape;
this is used for motion planning and physics.
See http://sdformat.org/spec?ver=1.11&elem=geometry for
available types. -->
</geometry>
</collision>
</link>
<!--
Exactly 2 prismatic joints are required for simulation to work.
These joints attach each finger to the gripper base.
-->
<joint name="gripper_1_joint_prismatic" type="prismatic">
<parent>gripper_base</parent>
<child>finger_1</child>
<!--
The axis is required to state the direction in which the joint
can move. In this example, it can move in the -x direction.
-->
<axis>
<xyz>-1 0 0</xyz>
<!--
The axis limits are essential for grasp and release commands
so they can be mapped to the correct position of the finger
joints in the digital twin. The lower limit must be 0 and
the upper limit must be positive value.
-->
<limit>
<lower>0.0</lower>
<upper>0.04</upper>
</limit>
</axis>
</joint>
<joint name="gripper_2_joint_prismatic" type="prismatic">
<parent>gripper_base</parent>
<child>finger_2</child>
<!--
In this example, the joint can move in the +x direction.
-->
<axis>
<xyz>1 0 0</xyz>
<!--
The lower limit must be 0 and the upper must be positive.
See above gripper_1_joint_prismatic axis limit notes for more details.
-->
<limit>
<lower>0.0</lower>
<upper>0.04</upper>
</limit>
</axis>
</joint>
<!--
Specify a tool frame that represents center of the pinch portion of the
gripper. The z-axis should be pointing out.
When you load the model into Flowstate, this tool frame will be displayed.
This is not necessarily required to get the gripper working but is helpful
for skills that could use it.
Note: Flowstate ignores many implicit Gazebo frames.
intrinsic:create_entity="true" is required for the frame to be created
in the Flowstate World.
-->
<frame name="tool_frame"
attached_to="gripper_base"
intrinsic:create_entity="true">
<pose>0 0 -0.03 0 3.141592654 0</pose>
</frame>
</model>
</sdf>