Add basic suction gripper to Panda in Omniverse Isaac

In this blog post, we will add a suction gripper to the Panda robotic arm in NVIDIA’s Omniverse Isaac simulation environment. In our latest contribution, we added the Panda robotic arm to Isaac Sim and controlled it with MoveIt! via ros_bridge. We will continue this series by modifying the arm’s model and by adding the suction gripper functionality. The resulting robotic arm model will be able to grip rigid bodies with its gripper in the simulation.

Blender

We will start by creating a suction gripper 3d model with Blender. The model will be fairly simple: We will create a simple cube and attach it to the last link of the Panda robotic arm. We start by resizing the default cube that appears when Blender is started. We choose 0.1 by 0.1 by 0.04 meters as it fits perfectly to Panda’s last link with these dimensions. Then, we move the cube’s coordinate system origin along its z-axis by 0.02 m to the bottom. Finally, we save the model as .stl file to the franka_description ROS repository at meshes/collision and meshes/visual.

Robot Model

We will add the cube that we exported from Blender in to Panda in its model file panda_arm.urdf. We will accomplish this by first adding the gripper link as panda_eef and pointing to the cube .stl file. panda_joint_eef connects links panda_link8 and panda_eef to each other as fixed joint. Additionally, we will create a tip link panda_tip for easier configuration of the suction gripper in Isaac Sim and also easier planning with MoveIt!.

<link name="panda_eef">
  <visual>
    <geometry>
      <mesh filename="package://franka_description/meshes/visual/gripper.stl" />
    </geometry>
  </visual>
  <collision>
    <geometry>
      <mesh filename="package://franka_description/meshes/collision/gripper.stl" />
    </geometry>
  </collision>
</link>
<joint name="panda_joint_eef" type="fixed">
  <origin rpy="0 0 0" xyz="0 0 0" />
  <parent link="panda_link8" />
  <child link="panda_eef" />
</joint>
<link name="panda_tip" />
<joint name="panda_joint_tip" type="fixed">
  <origin rpy="0 1.57 0" xyz="0 0 0.04" />
  <parent link="panda_eef" />
  <child link="panda_tip" />
</joint>

We can visualize the resulting robot model in RViz by using the urdf_tutorial repository. Copy the robot model panda_arm.urdf to the urdf_tutorial repository and start the display script with the model as parameter:

ros2 launch urdf_tutorial display.launch.py model:=urdf/panda_arm.urdf

We can see that the new links and the suction gripper cube were inserted correctly into the robot model. The x-axis of the final link points towards the last link or inwards. This is important as the the suction gripper in Isaac Sim is configured in x-axis direction by default.

It is also important to reset the joint effort limits in the robot model file in order to eliminate weird behavior of the robotic arm after the importing the robot URDF into Isaac Sim. We will set the maximum effort and velocity values to 0 and the Isaac Sim will allow the maximum value for these parameters in the simulation. Finally, we will remove the safety_controller tags as those are not necessary in Isaac Sim:

<joint name="panda_joint7" type="revolute">
  <origin rpy="1.5707963267948966 0 0" xyz="0.088 0 0" />
  <parent link="panda_link6" />
  <child link="panda_link7" />
  <axis xyz="0 0 1" />
  <limit effort="0" lower="-2.8973" upper="2.8973" velocity="0" />
</joint>

Isaac Sim

Now that we have prepared Panda arm’s robot model we can import it using the same routine as in our previous blog post. There, we first imported the URDF file franka_description/panda_arm.urdf using Isaac Sim’s URDF importer. In a subsequent step, we modified the resulting .usda file to move the arm’s articulation to the root XForm panda. Below is a gallery illustrating the URDF import process in Isaac Sim:

We will also add a ground plane and a cube to our scene.usda file. We will attempt to pick the cube with the suction gripper. It is important to mention, that we added rigid body properties, enabled collisions and most importantly, added a small mass. If no mass is specified, the suction mechanism will not work in our testing.

def Cube "Cube" (
    prepend apiSchemas = ["PhysicsRigidBodyAPI", "PhysxRigidBodyAPI", "PhysicsCollisionAPI", "PhysxCollisionAPI", "PhysicsMassAPI"]
)
{
    float3[] extent = [(-0.5, -0.5, -0.5), (0.5, 0.5, 0.5)]
    float physics:mass = 0.000001
    bool physics:collisionEnabled = 1
    bool physics:kinematicEnabled = 0
    bool physics:rigidBodyEnabled = 1
    double size = 1
    quatd xformOp:orient = (1, 0, 0, 0)
    double3 xformOp:scale = (0.1, 0.1, 0.2)
    double3 xformOp:translate = (0.5, 0, 0.1)
    uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"]
}

In our extension code, we will modify the ui_builder.py file to add a button that closes the suction gripper. In scenario.py, we will initialize the suction gripper with the new init_gripper() method:

def init_gripper(self):
    self._dc = dc.acquire_dynamic_control_interface()
    self.sgp = Surface_Gripper_Properties()
    self.sgp.d6JointPath = "/World/panda/panda_tip/d6FixedJoint"
    self.sgp.parentPath = "/World/panda/panda_tip"
    self.sgp.offset = dc.Transform()  # Offset the transform to the base of the Cone
    self.sgp.offset.p.x = -0.001
    self.sgp.offset.r = [1.0, 0, 0, 0]
    self.sgp.gripThreshold = 0.02
    self.sgp.forceLimit = 1.0e3
    self.sgp.torqueLimit = 1.0e3
    self.sgp.bendAngle = 7.5
    self.sgp.stiffness = 1.0e4
    self.sgp.damping = 1.0e3
    self.sgp.retryClose = True

    self.surface_gripper = Surface_Gripper(self._dc)
    self.surface_gripper.initialize(self.sgp)

We can see a few important aspects of the surface gripper in this method:

  • The Surface Gripper is initialized with the Surface_Gripper_Properties structure
  • The Surface Gripper is attached to a link of the robotic arm with its path in the scene (/World/panda/panda_tip)
  • Various physical and dynamical properties of the suction gripper, e.g. force limit and torque limit can be configured
  • A grip threshold for gripping objects within a specified distance threshold can be specified
  • The retry close attribute retires the suction gripper’s close operation until an object could be picked
  • Perhaps the most important attribute for the configuration is the offset: It specifies where the surface gripper is located and how it is oriented. This specifies in which direction the surface gripper applies suction force. By default, the Surface Gripper applies suction along the x-axis. When the Surface_Gripper class is initialized with with the Surface_Gripper_Properties structure, the suction direction cannot be changed. But the offset parameter can be used to alter the position and orientation of the internal coordinate system to apply suction force at an arbitrary direction.

Result

The resulting ROS package can be started with the following commands:

ros2 launch isaac_moveit_sample simulation.launch.py

The Isaac Sim extension can be opened from the top navigation bar. We now have two windows: RViz for the motion planning pipeline for Panda and Isaac Sim with panda arm simulation running on Load and Run. We will load and run the simulation in Isaac Sim and start a motion planning and execution request which will move Panda to the cube. Next, we will click the GRASP button in Isaac Sim. Finally, when we plan and execute a path to a position over the cube, the arm moves with the cube without releasing it.

Isaac – Suction Gripper Result: Sample Pick and Hold Execution with RViz

The custom ROS package as well as the modified franka_description and Isaac Sim extension repositories are available in my GitHub profile.