Interacting with a surface gripper#
This tutorial shows how to interact with an articulated robot with a surface gripper attached to its end-effector in the simulation. It is a continuation of the Interacting with an articulation tutorial, where we learned how to interact with an articulated robot. Note that as of IsaacSim 5.0 the surface gripper are only supported on the cpu backend.
The Code#
The tutorial corresponds to the run_surface_gripper.py script in the scripts/tutorials/01_assets
directory.
Code for run_surface_gripper.py
1# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
2# All rights reserved.
3#
4# SPDX-License-Identifier: BSD-3-Clause
5
6"""This script demonstrates how to spawn a pick-and-place robot equipped with a surface gripper and interact with it.
7
8.. code-block:: bash
9
10 # Usage
11 ./isaaclab.sh -p scripts/tutorials/01_assets/run_surface_gripper.py --device=cpu
12
13When running this script make sure the --device flag is set to cpu. This is because the surface gripper is
14currently only supported on the CPU.
15"""
16
17"""Launch Isaac Sim Simulator first."""
18
19import argparse
20
21from isaaclab.app import AppLauncher
22
23# add argparse arguments
24parser = argparse.ArgumentParser(description="Tutorial on spawning and interacting with a Surface Gripper.")
25# append AppLauncher cli args
26AppLauncher.add_app_launcher_args(parser)
27# tutorials should open Kit visualizer by default
28parser.set_defaults(visualizer=["kit"])
29# parse the arguments
30args_cli = parser.parse_args()
31
32# launch omniverse app
33app_launcher = AppLauncher(args_cli)
34simulation_app = app_launcher.app
35
36"""Rest everything follows."""
37
38import torch
39import warp as wp
40from isaaclab_physx.assets import SurfaceGripper, SurfaceGripperCfg
41
42import isaaclab.sim as sim_utils
43from isaaclab.assets import Articulation
44from isaaclab.sim import SimulationContext
45
46##
47# Pre-defined configs
48##
49from isaaclab_assets import PICK_AND_PLACE_CFG # isort:skip
50
51
52def design_scene():
53 """Designs the scene."""
54 # Ground-plane
55 cfg = sim_utils.GroundPlaneCfg()
56 cfg.func("/World/defaultGroundPlane", cfg)
57 # Lights
58 cfg = sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
59 cfg.func("/World/Light", cfg)
60
61 # Create separate groups called "Origin1", "Origin2"
62 # Each group will have a robot in it
63 origins = [[2.75, 0.0, 0.0], [-2.75, 0.0, 0.0]]
64 # Origin 1
65 sim_utils.create_prim("/World/Origin1", "Xform", translation=origins[0])
66 # Origin 2
67 sim_utils.create_prim("/World/Origin2", "Xform", translation=origins[1])
68
69 # Articulation: First we define the robot config
70 pick_and_place_robot_cfg = PICK_AND_PLACE_CFG.copy()
71 pick_and_place_robot_cfg.prim_path = "/World/Origin.*/Robot"
72 pick_and_place_robot = Articulation(cfg=pick_and_place_robot_cfg)
73
74 # Surface Gripper: Next we define the surface gripper config
75 surface_gripper_cfg = SurfaceGripperCfg()
76 # We need to tell the View which prim to use for the surface gripper
77 surface_gripper_cfg.prim_path = "/World/Origin.*/Robot/picker_head/SurfaceGripper"
78 # We can then set different parameters for the surface gripper, note that if these parameters are not set,
79 # the View will try to read them from the prim.
80 surface_gripper_cfg.max_grip_distance = 0.1 # [m] (Maximum distance at which the gripper can grasp an object)
81 surface_gripper_cfg.shear_force_limit = 500.0 # [N] (Force limit in the direction perpendicular direction)
82 surface_gripper_cfg.coaxial_force_limit = 500.0 # [N] (Force limit in the direction of the gripper's axis)
83 surface_gripper_cfg.retry_interval = 0.1 # seconds (Time the gripper will stay in a grasping state)
84 # We can now spawn the surface gripper
85 surface_gripper = SurfaceGripper(cfg=surface_gripper_cfg)
86
87 # return the scene information
88 scene_entities = {"pick_and_place_robot": pick_and_place_robot, "surface_gripper": surface_gripper}
89 return scene_entities, origins
90
91
92def run_simulator(
93 sim: sim_utils.SimulationContext, entities: dict[str, Articulation | SurfaceGripper], origins: torch.Tensor
94):
95 """Runs the simulation loop."""
96 # Extract scene entities
97 robot: Articulation = entities["pick_and_place_robot"]
98 surface_gripper: SurfaceGripper = entities["surface_gripper"]
99
100 # Define simulation stepping
101 sim_dt = sim.get_physics_dt()
102 count = 0
103 # Simulation loop
104 while simulation_app.is_running():
105 # Reset
106 if count % 500 == 0:
107 # reset counter
108 count = 0
109 # reset the scene entities
110 # root state
111 # we offset the root state by the origin since the states are written in simulation world frame
112 # if this is not done, then the robots will be spawned at the (0, 0, 0) of the simulation world
113 root_pose = robot.data.default_root_pose.torch.clone()
114 root_pose[:, :3] += origins
115 robot.write_root_pose_to_sim_index(root_pose=root_pose)
116 root_vel = robot.data.default_root_vel.torch.clone()
117 robot.write_root_velocity_to_sim_index(root_velocity=root_vel)
118 # set joint positions with some noise
119 joint_pos, joint_vel = (
120 robot.data.default_joint_pos.torch.clone(),
121 robot.data.default_joint_vel.torch.clone(),
122 )
123 joint_pos += torch.rand_like(joint_pos) * 0.1
124 robot.write_joint_position_to_sim_index(position=joint_pos)
125 robot.write_joint_velocity_to_sim_index(velocity=joint_vel)
126 # clear internal buffers
127 robot.reset()
128 print("[INFO]: Resetting robot state...")
129 # Opens the gripper and makes sure the gripper is in the open state
130 surface_gripper.reset()
131 print("[INFO]: Resetting gripper state...")
132
133 # Sample a random command between -1 and 1.
134 gripper_commands = torch.rand(surface_gripper.num_instances) * 2.0 - 1.0
135 # The gripper behavior is as follows:
136 # -1 < command < -0.3 --> Gripper is Opening
137 # -0.3 < command < 0.3 --> Gripper is Idle
138 # 0.3 < command < 1 --> Gripper is Closing
139 print(f"[INFO]: Gripper commands: {gripper_commands}")
140 mapped_commands = [
141 "Opening" if command < -0.3 else "Closing" if command > 0.3 else "Idle" for command in gripper_commands
142 ]
143 print(f"[INFO]: Mapped commands: {mapped_commands}")
144 # Set the gripper command
145 surface_gripper.set_grippers_command(gripper_commands)
146 # Write data to sim
147 surface_gripper.write_data_to_sim()
148 # Perform step
149 sim.step()
150 # Increment counter
151 count += 1
152 # Read the gripper state from the simulation
153 surface_gripper.update(sim_dt)
154 # Read the gripper state from the buffer
155 surface_gripper_state = surface_gripper.state
156 # The gripper state is a list of integers that can be mapped to the following:
157 # -1 --> Open
158 # 0 --> Closing
159 # 1 --> Closed
160 # Print the gripper state
161 print(f"[INFO]: Gripper state: {surface_gripper_state}")
162 mapped_commands = [
163 "Open" if state == -1 else "Closing" if state == 0 else "Closed"
164 for state in wp.to_torch(surface_gripper_state).tolist()
165 ]
166 print(f"[INFO]: Mapped commands: {mapped_commands}")
167
168
169def main():
170 """Main function."""
171 # Load kit helper
172 sim_cfg = sim_utils.SimulationCfg(device=args_cli.device)
173 sim = SimulationContext(sim_cfg)
174 # Set main camera
175 sim.set_camera_view([2.75, 7.5, 10.0], [2.75, 0.0, 0.0])
176 # Design scene
177 scene_entities, scene_origins = design_scene()
178 scene_origins = torch.tensor(scene_origins, device=sim.device)
179 # Play the simulator
180 sim.reset()
181 # Now we are ready!
182 print("[INFO]: Setup complete...")
183 # Run the simulator
184 run_simulator(sim, scene_entities, scene_origins)
185
186
187if __name__ == "__main__":
188 # run the main function
189 main()
190 # close sim app
191 simulation_app.close()
The Code Explained#
Designing the scene#
Similarly to the previous tutorial, we populate the scene with a ground plane and a distant light. Then, we spawn an articulation from its USD file. This time a pick-and-place robot is spawned. The pick-and-place robot is a simple robot with 3 driven axes, its gantry allows it to move along the x and y axes, as well as up and down along the z-axis. Furthermore, the robot end-effector is outfitted with a surface gripper. The USD file for the pick-and-place robot contains the robot’s geometry, joints, and other physical properties as well as the surface gripper. Before implementing a similar gripper on your own robot, we recommend to check out the USD file for the gripper found on Isaaclab’s Nucleus.
For the pick-and-place robot, we use its pre-defined configuration object, you can find out more about it in the
Writing an Asset Configuration tutorial. For the surface gripper, we also need to create a configuration
object. This is done by instantiating a assets.SurfaceGripperCfg object and passing it the relevant
parameters.
The available parameters are:
max_grip_distance: The maximum distance at which the gripper can grasp an object.shear_force_limit: The maximum force the gripper can exert in the direction perpendicular to the gripper’s axis.coaxial_force_limit: The maximum force the gripper can exert in the direction of the gripper’s axis.retry_interval: The time the gripper will stay in a grasping state.
As seen in the previous tutorial, we can spawn the articulation into the scene in a similar fashion by creating
an instance of the assets.Articulation class by passing the configuration object to its constructor. The same
principle applies to the surface gripper. By passing the configuration object to the assets.SurfaceGripper
constructor, the surface gripper is created and can be added to the scene. In practice, the object will only be
initialized when the play button is pressed.
# Create separate groups called "Origin1", "Origin2"
# Each group will have a robot in it
origins = [[2.75, 0.0, 0.0], [-2.75, 0.0, 0.0]]
# Origin 1
sim_utils.create_prim("/World/Origin1", "Xform", translation=origins[0])
# Origin 2
sim_utils.create_prim("/World/Origin2", "Xform", translation=origins[1])
# Articulation: First we define the robot config
pick_and_place_robot_cfg = PICK_AND_PLACE_CFG.copy()
pick_and_place_robot_cfg.prim_path = "/World/Origin.*/Robot"
pick_and_place_robot = Articulation(cfg=pick_and_place_robot_cfg)
# Surface Gripper: Next we define the surface gripper config
surface_gripper_cfg = SurfaceGripperCfg()
# We need to tell the View which prim to use for the surface gripper
surface_gripper_cfg.prim_path = "/World/Origin.*/Robot/picker_head/SurfaceGripper"
# We can then set different parameters for the surface gripper, note that if these parameters are not set,
# the View will try to read them from the prim.
surface_gripper_cfg.max_grip_distance = 0.1 # [m] (Maximum distance at which the gripper can grasp an object)
surface_gripper_cfg.shear_force_limit = 500.0 # [N] (Force limit in the direction perpendicular direction)
surface_gripper_cfg.coaxial_force_limit = 500.0 # [N] (Force limit in the direction of the gripper's axis)
surface_gripper_cfg.retry_interval = 0.1 # seconds (Time the gripper will stay in a grasping state)
# We can now spawn the surface gripper
surface_gripper = SurfaceGripper(cfg=surface_gripper_cfg)
Running the simulation loop#
Continuing from the previous tutorial, we reset the simulation at regular intervals, set commands to the articulation, step the simulation, and update the articulation’s internal buffers.
Resetting the simulation#
To reset the surface gripper, we only need to call the SurfaceGripper.reset() method which will reset the
internal buffers and caches.
# Opens the gripper and makes sure the gripper is in the open state
surface_gripper.reset()
Stepping the simulation#
Applying commands to the surface gripper involves two steps:
Setting the desired commands: This sets the desired gripper commands (Open, Close, or Idle).
Writing the data to the simulation: Based on the surface gripper’s configuration, this step handles writes the converted values to the PhysX buffer.
In this tutorial, we use a random command to set the gripper’s command. The gripper behavior is as follows:
-1 < command < -0.3 –> Gripper is Opening
-0.3 < command < 0.3 –> Gripper is Idle
0.3 < command < 1 –> Gripper is Closing
At every step, we randomly sample commands and set them to the gripper by calling the
SurfaceGripper.set_grippers_command() method. After setting the commands, we call the
SurfaceGripper.write_data_to_sim() method to write the data to the PhysX buffer. Finally, we step
the simulation.
# Sample a random command between -1 and 1.
gripper_commands = torch.rand(surface_gripper.num_instances) * 2.0 - 1.0
# The gripper behavior is as follows:
# -1 < command < -0.3 --> Gripper is Opening
# -0.3 < command < 0.3 --> Gripper is Idle
# 0.3 < command < 1 --> Gripper is Closing
print(f"[INFO]: Gripper commands: {gripper_commands}")
mapped_commands = [
"Opening" if command < -0.3 else "Closing" if command > 0.3 else "Idle" for command in gripper_commands
]
print(f"[INFO]: Mapped commands: {mapped_commands}")
# Set the gripper command
surface_gripper.set_grippers_command(gripper_commands)
# Write data to sim
surface_gripper.write_data_to_sim()
Updating the state#
To know the current state of the surface gripper, we can query the assets.SurfaceGripper.state() property.
This property returns a tensor of size [num_envs] where each element is either -1, 0, or 1
corresponding to the gripper state. This property is updated every time the assets.SurfaceGripper.update() method
is called.
-1–> Gripper is Open0–> Gripper is Closing1–> Gripper is Closed
# Read the gripper state from the simulation
surface_gripper.update(sim_dt)
# Read the gripper state from the buffer
surface_gripper_state = surface_gripper.state
The Code Execution#
To run the code and see the results, let’s run the script from the terminal:
./isaaclab.sh -p scripts/tutorials/01_assets/run_surface_gripper.py --device cpu
This command should open a stage with a ground plane, lights, and two pick-and-place robots.
In the terminal, you should see the gripper state and the command being printed.
To stop the simulation, you can either close the window, or press Ctrl+C in the terminal.
In this tutorial, we learned how to create and interact with a surface gripper. We saw how to set commands and query the gripper state. We also saw how to update its buffers to read the latest state from the simulation.
In addition to this tutorial, we also provide a few other scripts that spawn different robots. These are included
in the scripts/demos directory. You can run these scripts as:
# Spawn many pick-and-place robots and perform a pick-and-place task
./isaaclab.sh -p scripts/demos/pick_and_place.py
Note that in practice, the users would be expected to register their assets.SurfaceGripper instances inside
a isaaclab.InteractiveScene object, which will automatically handle the calls to the
assets.SurfaceGripper.write_data_to_sim() and assets.SurfaceGripper.update() methods.
# Create a scene
scene = InteractiveScene()
# Register the surface gripper
scene.surface_grippers["gripper"] = surface_gripper