Overview: In this tutorial, Niranjan helps us explore Isaac Sim's Surface Gripper API and demonstrate how to implement surface-based grasping for robotic manipulation tasks. Unlike traditional finger grippers, surface grippers use contact forces and constraints to securely hold objects against gripper surfaces, making them ideal for handling flat objects, sheets, or items that require distributed contact forces.
We'll cover the complete Surface Gripper workflow from basic setup to advanced pick-and-place operations, including parameter tuning for different object types and gripper configurations.
Our tutorial pipeline will:
- Setup Surface Gripper → Configure gripper properties, attach to robot end-effector, and understand the core API methods.
- Parameter Tuning → Learn how grip threshold, force limits, stiffness, and damping affect gripper performance for different objects.
- Control Operations → Master opening, closing, and monitoring gripper status with practical code examples.
- Pick & Place Demo → Implement a complete manipulation task combining surface gripper control with robot motion planning.
By the end, you'll understand how to effectively use Surface Grippers in Isaac Sim for various manipulation scenarios, from delicate electronics handling to robust industrial applications. You'll have practical code examples and parameter guidelines to implement surface gripping in your own robotic simulations.
- Step-by-step of NVIDIA’s UR10 pick-and-place demo:
- ASCII Flow Diagram
- Understanding the SurfaceGripper API
- Core Parameters Breakdown
- Implementing a Tuned Gripper for a Pick & Place Task
- 1. Setup and Basic Configuration
- 2. Parameter Tuning Explained
- 3. Final Pick & Place Demo with Tuning and Logging
- Expected Results
- Further Exploration
Starting point: This a basic pick and place example with no change in the gripper’s state and using the default NVIDIA’s example, we will try to improvise on this code and see how we can leverage existing API’s and examples to understand how to use them for our task’s/work.
Step-by-step of NVIDIA’s UR10 pick-and-place demo:
Initialize simulation
from isaacsim import SimulationApp
simulation_app = SimulationApp({"headless": False})
- Starts Isaac Sim.
headless=False
→ runs with GUI so you can see the simulation.
Imports and argument parsing
import argparse, sys, carb, numpy as np
from isaacsim.core.api import World
from isaacsim.core.api.objects import DynamicCuboid
from isaacsim.core.utils.stage import add_reference_to_stage
from isaacsim.robot.manipulators import SingleManipulator
from isaacsim.robot.manipulators.examples.universal_robots.controllers.pick_place_controller import PickPlaceController
from isaacsim.robot.manipulators.grippers import SurfaceGripper
from isaacsim.storage.native import get_assets_root_path
- Adds modules for:
- World → simulation environment.
- DynamicCuboid → adds a cube object.
- add_reference_to_stage → loads USD robot/gripper assets.
- SingleManipulator → wraps UR10 robot + gripper into a controllable articulation.
- SurfaceGripper → defines a simple suction-like gripper.
- PickPlaceController → high-level pick-and-place policy.
- Uses
argparse
so you can run with-test
to exit quickly.
Load assets
assets_root_path = get_assets_root_path()
if assets_root_path is None:
carb.log_error("Could not find Isaac Sim assets folder")
simulation_app.close()
sys.exit()
- Finds the root path of Isaac assets.
- If not found, exits safely.
Create world and ground plane
my_world = World(stage_units_in_meters=1.0)
my_world.scene.add_default_ground_plane()
- Creates the simulation world (units = meters).
- Adds a ground plane for objects to rest on.
Load robot and gripper
asset_path = assets_root_path + "/Isaac/Robots/UniversalRobots/ur10/ur10.usd"
add_reference_to_stage(usd_path=asset_path, prim_path="/World/UR10")
gripper_usd = assets_root_path + "/Isaac/Robots/UR10/Props/short_gripper.usd"
add_reference_to_stage(usd_path=gripper_usd, prim_path="/World/UR10/ee_link")
- Loads UR10 robot USD into the stage.
- Loads a short gripper USD and attaches it to the robot’s
ee_link
(end effector).
Bind logical gripper + robot articulation
gripper = SurfaceGripper(end_effector_prim_path="/World/UR10/ee_link",
translate=0.1611, direction="x")
ur10 = my_world.scene.add(
SingleManipulator(prim_path="/World/UR10",
name="my_ur10",
end_effector_prim_path="/World/UR10/ee_link",
gripper=gripper))
- Defines a
SurfaceGripper
at the UR10’s end effector. - Wraps the robot + gripper into a
SingleManipulator
object for easy control.
👉 This is where the gripper is attached to the robot both physically (USD parenting) and logically (Python object binding).
Set initial states
ur10.set_joints_default_state(positions=np.array([-np.pi/2, -np.pi/2, -np.pi/2, -np.pi/2, np.pi/2, 0]))
ur10.gripper.set_default_state(opened=True)
- Positions the UR10 into a folded starting pose.
- Keeps the gripper open at the start.
Add cube object
cube = my_world.scene.add(
DynamicCuboid(name="cube",
position=np.array([0.3, 0.3, 0.3]),
prim_path="/World/Cube",
scale=np.array([0.0515, 0.0515, 0.0515]),
size=1.0,
color=np.array([0, 0, 1])))
- Spawns a blue cube in the world at
[0.3, 0.3, 0.3]
. - This will be the object for pick-and-place.
Reset world
my_world.reset()
- Ensures all objects are placed in their starting positions.
Setup controller
my_controller = PickPlaceController(name="pick_place_controller",
gripper=ur10.gripper,
robot_articulation=ur10)
articulation_controller = ur10.get_articulation_controller()
- Creates a high-level pick-and-place controller for the UR10 + gripper.
- Gets low-level articulation controller for applying joint commands.
Main simulation loop
while simulation_app.is_running():
my_world.step(render=True)
- Advances the simulation step-by-step while rendering.
Inside the loop:
- Reset handling
- Get observations & compute actions
- Picks cube position directly.
- Target is hard-coded at
[0.7, 0.7, cube_height/2]
. - Adds small Z-offset to avoid collisions.
- Check completion
- Apply action
- Exit if test mode
If simulation is stopped, reset world and controller.
actions = my_controller.forward(
picking_position=cube.get_local_pose()[0],
placing_position=np.array([0.7, 0.7, 0.0515/2.0]),
current_joint_positions=ur10.get_joint_positions(),
end_effector_offset=np.array([0, 0, 0.02]),
)
if my_controller.is_done():
print("done picking and placing")
articulation_controller.apply_action(actions)
if args.test is True:
break
Close simulation
simulation_app.close()
- shuts down Isaac Sim.
In short:
This script builds a UR10 pick-and-place demo from scratch:
- Loads UR10 USD, attaches a gripper, spawns a cube, and defines a ground plane.
- Configures robot and gripper states.
- Uses a
PickPlaceController
to move the cube from its spawn location to a hard-coded target. - Runs until done (or exits early in
-test
mode).
ASCII Flow Diagram
┌──────────────────────────┐
│ Start Isaac Sim (GUI) │
│ SimulationApp(headless=F)│
└─────────────┬────────────┘
│
▼
┌──────────────────────────┐
│ Create World + Ground │
│ my_world = World() │
│ add_default_ground_plane │
└─────────────┬────────────┘
│
▼
┌──────────────────────────┐
│ Load Robot + Gripper USD │
│ attach gripper at ee_link│
│ create SurfaceGripper │
│ wrap with SingleManipulator
└─────────────┬────────────┘
│
▼
┌──────────────────────────┐
│ Add Cube Object │
│ DynamicCuboid() │
└─────────────┬────────────┘
│
▼
┌──────────────────────────┐
│ Setup Controller │
│ PickPlaceController │
│ ArticulationController │
└─────────────┬────────────┘
│
▼
┌──────────────────────────┐
│ Simulation Loop │
│ world.step() │
│ get obs → compute action │
│ apply action to robot │
│ check done │
└─────────────┬────────────┘
│
▼
┌──────────────────────────┐
│ End Simulation │
│ simulation_app.close() │
└──────────────────────────┘
This tutorial will guide you through configuring, tuning, and using the SurfaceGripper
in NVIDIA Isaac Sim. We'll start with a basic pick-and-place script and transform it into a well-tuned and monitored simulation by diving into the gripper's API.
The goal is to move beyond the default settings and understand how to adapt the gripper's behavior for different objects and tasks.
Understanding the SurfaceGripper API
Before we write code, let's understand our primary tool. When working with a class like SurfaceGripper
, its definition is our documentation. You found the class definition, which is the key to unlocking its features:
class SurfaceGripper(Gripper):
def __init__(
self,
end_effector_prim_path: str,
translate: float = 0,
direction: str = "x",
grip_threshold: float = 0.01,
force_limit: float = 1.0e6,
torque_limit: float = 1.0e4,
bend_angle: float = np.pi / 24,
kp: float = 1.0e2,
kd: float = 1.0e2,
disable_gravity: bool = True,
) -> None:
# ... implementation details ...
This __init__
method tells us exactly what parameters we can set when we create a SurfaceGripper
instance. Let's break down the most important ones.
Core Parameters Breakdown
end_effector_prim_path
: This is a string that specifies the exact part of the robot model where the gripper is attached. In our case, it's"/World/UR10/ee_link"
. This is the reference point for the gripper's position.translate
anddirection
: These work together to define the exact suction point. Thetranslate
value (a float) is the distance in meters to offset from theend_effector_prim_path
along the specifieddirection
axis ('x', 'y', or 'z'). This allows you to place the grip point precisely at the tip of a suction cup model, for instance.- Example:
translate=0.1611
,direction="x"
means the grip point is 0.1611 meters along the end-effector's local X-axis. grip_threshold
: This float is the maximum distance (in meters) from the suction point to an object's surface for a grip to be successful. Think of it as the "activation zone".- Tuning Advice: If your robot isn't perfectly precise, a slightly larger threshold (e.g.,
0.02
) can help ensure a successful pick. For cluttered scenes, a smaller threshold is better to avoid grabbing the wrong object. force_limit
andtorque_limit
: These floats define the strength of the grip. Under the hood, Isaac Sim creates a virtual physics joint to hold the object. These limits determine how much force or torque that joint can withstand before it "breaks" and the robot drops the object.- Tuning Advice: For heavy objects, you must increase these values. For very light or delicate objects, you might lower them to create a more gentle and physically realistic interaction. The default values are very high, representing an almost unbreakable grip.
kp
(Stiffness) andkd
(Damping): These are the physics properties of the virtual joint and are crucial for stability.kp
(Stiffness): Think of this as a spring's tightness. A highkp
makes the connection very rigid; the object will follow the gripper's motion precisely. If it's too high for the object's mass, it can cause jittering or vibrations.kd
(Damping): Think of this as moving the spring through molasses. It reduces oscillations and helps stabilize the grip during fast movements. A highkd
leads to a smoother, more stable grip, but if it's too high, the object might feel like it's lagging behind the gripper.- Tuning Advice: If you observe the picked object shaking or vibrating during transport, the best first step is to increase
kd
. Finding the right balance betweenkp
andkd
is key to smooth manipulation.
Implementing a Tuned Gripper for a Pick & Place Task
Now, let's apply this knowledge. We'll modify the original script to tune the gripper for a specific object—a lightweight cube. We will also add some logging to see what's happening.
Our goal is to create a "gentler" grip for a cube with a mass of 0.1 kg. This means we don't need the massive default force limits and can tune the stiffness/damping for a smooth ride.
1. Setup and Basic Configuration
First, let's modify your initial script to explicitly define the gripper's properties instead of using defaults. This is done when you first create the SurfaceGripper
instance.
In the default script, we have:
gripper = SurfaceGripper(end_effector_prim_path="/World/UR10/ee_link", translate=0.1611, direction="x")
We can expand this to include more parameters from the __init__
method from API documentation.
Script 1: Basic Configuration
This script is a small modification. The key change is in the SurfaceGripper
instantiation, where we explicitly set parameters like force_limit
and grip_threshold
.
2. Parameter Tuning Explained
Understanding what each parameter does is key to adapting the gripper for different objects (e.g., heavy vs. light, slippery vs. rough).
grip_threshold
: This is the maximum distance (in meters) from the suction point that an object can be for the gripper to "grab" it whenclose()
is called.- High Value: Good for imprecise movements, but might grab the wrong object if things are cluttered.
- Low Value: Requires the robot to be very precise. Useful for picking one specific small item from a pile.
force_limit
&torque_limit
: These define the strength of the grip. They set the maximum force/torque the virtual joint connecting the gripper and object can withstand before breaking.- High Value: Necessary for heavy objects, otherwise the object will be dropped.
- Low Value: Good for delicate objects to avoid applying unrealistic forces that might cause physics instabilities in the simulation.
kp
(Stiffness) &kd
(Damping): These control the behavior of the virtual joint. Think of it like a spring connecting the gripper to the object.kp
(Stiffness): A higher value makes the connection more rigid, like a very stiff spring. The object will follow the gripper's motion very tightly. If it's too high, it can cause vibrations.kd
(Damping): A higher value adds "drag" to the connection, reducing oscillations and overshoot. It helps stabilize the grip, especially during fast movements. If it's too high, the object's motion will feel sluggish and lag behind the gripper.
Tuning Strategy 💡:
- Start with default values.
- If the robot drops the object, increase
force_limit
andtorque_limit
. - If the object vibrates or jitters wildly when moving, increase
kd
(damping) or slightly decreasekp
(stiffness). - If the gripper fails to pick up the object even when close, ensure the
grip_threshold
is large enough for the robot's final approach accuracy.
3. Final Pick & Place Demo with Tuning and Logging
This final script combines everything. We'll use the PickPlaceController
for convenience but with tuned parameters for the gripper. We'll also add print statements to log the status of the gripper at key moments.
from isaacsim import SimulationApp
# Start the simulation application
simulation_app = SimulationApp({"headless": False})
import numpy as np
from isaacsim.core.api import World
from isaacsim.core.api.objects import DynamicCuboid
from isaacsim.core.utils.stage import add_reference_to_stage
from isaacsim.robot.manipulators import SingleManipulator
from isaacsim.robot.manipulators.examples.universal_robots.controllers.pick_place_controller import PickPlaceController
from isaacsim.robot.manipulators.grippers import SurfaceGripper
from isaacsim.storage.native import get_assets_root_path
# Setup the world with default ground plane
my_world = World(stage_units_in_meters=1.0)
my_world.scene.add_default_ground_plane()
# Find assets path to locate robot and gripper USD files
assets_root_path = get_assets_root_path()
if assets_root_path is None:
raise Exception("Could not find Isaac Sim assets folder")
# Add the UR10 robot arm to the stage
robot_asset_path = assets_root_path + "/Isaac/Robots/UniversalRobots/ur10/ur10.usd"
add_reference_to_stage(usd_path=robot_asset_path, prim_path="/World/UR10")
# Add the gripper model and attach it to the robot's end-effector link
gripper_usd = assets_root_path + "/Isaac/Robots/UR10/Props/short_gripper.usd"
add_reference_to_stage(usd_path=gripper_usd, prim_path="/World/UR10/ee_link")
# ===============================================================
# == STEP 1: CONFIGURE THE GRIPPER WITH TUNED PARAMETERS ========
# ===============================================================
# Instead of using defaults, we instantiate the gripper with values
# tailored for a lightweight object for a more stable, gentle grip.
print("Configuring a tuned SurfaceGripper...")
gripper = SurfaceGripper(
end_effector_prim_path="/World/UR10/ee_link",
translate=0.1611,
direction="x",
grip_threshold=0.02, # A slightly larger threshold for easier grabbing
force_limit=5e4, # Reduced force for a "gentler" grip
torque_limit=5e2, # Reduced torque
kp=1e4, # Lower stiffness to prevent vibration
kd=1e4 # Higher damping for stability during motion
)
# ===============================================================
# Add the fully configured robot to the scene
ur10 = my_world.scene.add(
SingleManipulator(
prim_path="/World/UR10", name="my_ur10", end_effector_prim_path="/World/UR10/ee_link", gripper=gripper
)
)
# Set the robot's default joint positions
ur10.set_joints_default_state(positions=np.array([-np.pi / 2, -np.pi / 2, -np.pi / 2, -np.pi / 2, np.pi / 2, 0]))
# ===============================================================
# == STEP 2: CONFIGURE THE TARGET OBJECT ========================
# ===============================================================
# We create a cube and explicitly set its mass to be light,
# which justifies our "gentle" gripper settings.
cube = my_world.scene.add(
DynamicCuboid(
name="cube",
position=np.array([0.4, 0.4, 0.025]),
prim_path="/World/Cube",
scale=np.array([0.05, 0.05, 0.05]),
size=1.0,
color=np.array([0, 1, 0]), # Green cube for visibility
mass=0.1 # Explicitly set a light mass in kg
)
)
# ===============================================================
# Reset the world to apply all settings
my_world.reset()
ur10.gripper.set_default_state(opened=True)
# Initialize the high-level Pick and Place controller
my_controller = PickPlaceController(name="pick_place_controller", gripper=ur10.gripper, robot_articulation=ur10)
articulation_controller = ur10.get_articulation_controller()
last_event = None
# Main simulation loop
print("Starting simulation loop...")
while simulation_app.is_running():
my_world.step(render=True)
if my_world.is_playing():
# ===============================================================
# == STEP 3: MONITOR GRIPPER STATUS =============================
# ===============================================================
# This logic checks the controller's current state and prints a
# status message when a gripper command is issued.
current_event = my_controller.get_current_event()
if current_event != last_event:
if current_event == "gripper_close":
# Give the physics engine a frame to update the gripper's status
my_world.step()
is_closed = ur10.gripper.is_closed()
print(f"Gripper CLOSE command issued. Status: {'SUCCESS (Object Gripped)' if is_closed else 'FAILURE (Missed Object)'}")
elif current_event == "gripper_open":
my_world.step()
print(f"Gripper OPEN command issued. Status: {'Object Released'}")
last_event = current_event
# ===============================================================
# Get observations and calculate the next action
observations = my_world.get_observations()
actions = my_controller.forward(
picking_position=cube.get_local_pose()[0],
placing_position=np.array([-0.4, 0.5, 0.05]), # New placing position
current_joint_positions=ur10.get_joint_positions(),
)
# Apply the calculated action to the robot
articulation_controller.apply_action(actions)
# Stop the simulation once the controller is done
if my_controller.is_done():
print("Pick and Place routine has finished.")
my_world.pause()
# Cleanup
simulation_app.close()
Expected Results
When you run the final script, you should observe the following:
- In the Viewport: The UR10 robot arm will move smoothly from its starting position to the green cube. It will lower, pick up the cube, and transport it to the target location (
[-0.4, 0.5, 0.05]
). Because of our tunedkd
value, the motion of the cube while attached to the arm should be stable, without significant shaking. - In the Console: You will see status messages being printed in real-time.
- When the arm is about to pick the cube, you will see:
Gripper CLOSE command issued. Status: SUCCESS (Object Gripped)
- When the arm reaches the destination and drops the cube, you will see:
Gripper OPEN command issued. Status: Object Released
- Finally, the console will print
Pick and Place routine has finished.
Further Exploration
You now have a solid foundation for using the SurfaceGripper
. Here are some experiments you can try to deepen your understanding:
- Heavy Object Challenge: Increase the cube's mass to
5.0
kg but keep theforce_limit
low. Does the robot drop the cube? - Instability Test: Set
kd
to a very low value (e.g.,1.0
). How does the cube behave when the robot arm accelerates? You will likely see it oscillate and jitter. - Precision Test: Make the
grip_threshold
very small (e.g.,0.001
). Does the gripper still manage to pick up the cube, or does it now fail?
This set of scripts and explanations should give you a solid foundation for mastering the SurfaceGripper
in Isaac Sim. You can now confidently tune its parameters for various objects and integrate it into more complex robotic tasks.