Skip to content

Adding a Manipulator Robot

Learning Objectives

After completing this tutorial, you will have learned:

  • How to add a manipulator robot (Franka Panda) to the scene
  • How to implement pick-and-place operations using the PickPlaceController
  • How to modularize tasks by inheriting from BaseTask
  • How to use the pre-built task classes available in Isaac Sim

Getting Started

Prerequisites

Estimated Time

Approximately 15-20 minutes.

Preparing the Source Code

This tutorial continues editing the hello_world.py file from the Hello World sample. If you are continuing from the previous tutorial, you can proceed as-is. If you are resuming on a different day, follow these steps to open the source code:

  1. Activate Windows > Examples > Robotics Examples to open the Robotics Examples tab.
  2. Click Robotics Examples > General > Hello World.
  3. Click the Open Source Code button to open hello_world.py in Visual Studio Code.

For detailed instructions, refer to the "Opening the Hello World Sample" section in Hello World.

Warning

Pressing STOP then PLAY may not properly reset the world. Use the RESET button to restart the simulation.

Creating the Scene

In the previous tutorials, we used a wheeled robot (Jetbot). Here, we introduce a new type of robot — a manipulator (robot arm).

Isaac Sim provides a dedicated Franka class for the Franka Panda robot, offering manipulator-specific features such as access to the gripper and end-effector instances.

from isaacsim.examples.interactive.base_sample import BaseSample
# Extension containing Franka-related tasks and controllers
from isaacsim.robot.manipulators.examples.franka import Franka
from isaacsim.core.api.objects import DynamicCuboid
import numpy as np


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        world = self.get_world()
        world.scene.add_default_ground_plane()
        # Franka is a robot-specific class that provides extra functionalities
        # such as gripper and end-effector instances
        franka = world.scene.add(
            Franka(prim_path="/World/Fancy_Franka", name="fancy_franka")
        )
        # Add a cube for the Franka to pick up
        world.scene.add(
            DynamicCuboid(
                prim_path="/World/random_cube",
                name="fancy_cube",
                position=np.array([0.3, 0.3, 0.3]),     # Initial cube position
                scale=np.array([0.0515, 0.0515, 0.0515]),# Cube size
                color=np.array([0, 0, 1.0]),              # Blue
            )
        )
        return

Save the code and verify the simulation:

  1. Press Ctrl+S to save the code and hot-reload Isaac Sim.
  2. Click File > New From Stage Template > Empty to create a new world, then click LOAD.
  3. Verify that the Franka robot and blue cube appear in the scene.

Using the PickAndPlace Controller

Next, we use the Franka's pick-and-place controller to pick up the cube and move it to a different location.

The PickPlaceController operates as a state machine, automatically executing the following sequence:

  1. Move to the cube's position
  2. Close the gripper to grasp the cube
  3. Move to the goal position
  4. Open the gripper to place the cube
events_dt parameter (execution speed for each state)

Internally, PickPlaceController subdivides the 4 steps above into 10 finer states (move, descend, close, lift, move, descend, open, lift, etc.). The events_dt parameter is a list that controls the execution speed (interpolation amount per step) for each state.

Default values are provided, so you don't normally need to specify this. However, you can set it explicitly when running multiple robots simultaneously or when you want to adjust motion speed. We will use this in Tutorial 6.

from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.robot.manipulators.examples.franka import Franka
from isaacsim.core.api.objects import DynamicCuboid
from isaacsim.robot.manipulators.examples.franka.controllers import PickPlaceController  # Pick and place controller
import numpy as np


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        world = self.get_world()
        world.scene.add_default_ground_plane()
        franka = world.scene.add(
            Franka(prim_path="/World/Fancy_Franka", name="fancy_franka")
        )
        world.scene.add(
            DynamicCuboid(
                prim_path="/World/random_cube",
                name="fancy_cube",
                position=np.array([0.3, 0.3, 0.3]),
                scale=np.array([0.0515, 0.0515, 0.0515]),
                color=np.array([0, 0, 1.0]),
            )
        )
        return

    async def setup_post_load(self):
        self._world = self.get_world()
        self._franka = self._world.scene.get_object("fancy_franka")
        self._fancy_cube = self._world.scene.get_object("fancy_cube")
        # Initialize the PickPlaceController
        self._controller = PickPlaceController(
            name="pick_place_controller",
            gripper=self._franka.gripper,            # Gripper instance
            robot_articulation=self._franka,          # Robot articulation
        )
        self._world.add_physics_callback("sim_step", callback_fn=self.physics_step)
        # Set the gripper to the open position
        self._franka.gripper.set_joint_positions(self._franka.gripper.joint_opened_positions)
        # In async workflow (Extension Worlflow etc.), use the async version of play
        await self._world.play_async()
        return

    # Called after the RESET button is pressed
    # Any reset logic should be placed here
    async def setup_post_reset(self):
        self._controller.reset()
        self._franka.gripper.set_joint_positions(self._franka.gripper.joint_opened_positions)
        await self._world.play_async()
        return

    def physics_step(self, step_size):
        cube_position, _ = self._fancy_cube.get_world_pose()
        goal_position = np.array([-0.3, -0.3, 0.0515 / 2.0])  # Goal placement position
        current_joint_positions = self._franka.get_joint_positions()
        # The controller computes actions for each stage of pick and place
        actions = self._controller.forward(
            picking_position=cube_position,
            placing_position=goal_position,
            current_joint_positions=current_joint_positions,
        )
        self._franka.apply_action(actions)
        # Pause simulation when the state machine reaches the final state
        if self._controller.is_done():
            self._world.pause()
        return

Save the code and verify the simulation:

  1. Press Ctrl+S to save, then do File > New From Stage Template > Empty and click LOAD.
  2. Press the PLAY button and observe the Franka picking up the cube and placing it at the goal position.
  3. The simulation automatically pauses when the operation is complete.

Franka performing pick and place

What is a Task?

So far, the scene creation (setup_scene), controller initialization (setup_post_load), and physics step handling (physics_step) are all mixed together in the HelloWorld class.

A Task is a mechanism for modularizing specific work within the scene. By defining a task class that inherits from BaseTask, you can independently manage the following:

Method Description
set_up_scene Place assets needed for the task in the scene
get_observations Return observation data needed to solve the task
pre_step(control_index, simulation_time) Logic executed before each physics step (e.g., task completion check)
post_reset Initialization logic after reset

The pre_step arguments control_index is an index that auto-increments with each physics step (0, 1, 2, ...), and simulation_time is the elapsed time in seconds since the simulation started. Both are passed automatically by the World, so you do not need to manage them manually.

By modularizing tasks, you can reuse the same task across different robots and scenes.

Using the Pre-built PickPlace Task

Let's first learn the basics of tasks by using a pre-built task provided by Isaac Sim. For Franka, the PickPlace task achieves the same functionality as the previous section with more organized code.

Key features of pre-built tasks:

  • Dynamically retrieve task parameters (robot name, cube name, etc.) via get_params()
  • Modify parameters during simulation via set_params()
  • Retrieve all task observations at once via world.get_observations()
from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.robot.manipulators.examples.franka.tasks import PickPlace        # Pre-built task
from isaacsim.robot.manipulators.examples.franka.controllers import PickPlaceController


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        world = self.get_world()
        # Add the pre-built PickPlace task
        world.add_task(PickPlace(name="awesome_task"))
        return

    async def setup_post_load(self):
        self._world = self.get_world()
        # Dynamically retrieve task parameters
        # {"task_param_name": {"value": [value], "modifiable": [True/False]}}
        task_params = self._world.get_task("awesome_task").get_params()
        self._franka = self._world.scene.get_object(task_params["robot_name"]["value"])
        self._cube_name = task_params["cube_name"]["value"]
        self._controller = PickPlaceController(
            name="pick_place_controller",
            gripper=self._franka.gripper,
            robot_articulation=self._franka,
        )
        self._world.add_physics_callback("sim_step", callback_fn=self.physics_step)
        await self._world.play_async()
        return

    async def setup_post_reset(self):
        self._controller.reset()
        await self._world.play_async()
        return

    def physics_step(self, step_size):
        current_observations = self._world.get_observations()
        actions = self._controller.forward(
            picking_position=current_observations[self._cube_name]["position"],
            placing_position=current_observations[self._cube_name]["target_position"],
            current_joint_positions=current_observations[self._franka.name]["joint_positions"],
        )
        self._franka.apply_action(actions)
        if self._controller.is_done():
            self._world.pause()
        return

Compared to the previous section's code, notice how setup_scene has become simpler. Scene construction (placing Franka and the cube) is handled automatically inside the task, allowing the HelloWorld class to focus on task registration and controller execution.

Creating a Custom Task

Now that you understand how to use tasks, let's create your own by inheriting from BaseTask. Custom tasks allow you to add unique logic such as task completion detection and visual feedback.

The following code defines a FrankaPlaying task that changes the cube's color to green when it reaches the goal position.

from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.robot.manipulators.examples.franka import Franka
from isaacsim.core.api.objects import DynamicCuboid
from isaacsim.robot.manipulators.examples.franka.controllers import PickPlaceController
from isaacsim.core.api.tasks import BaseTask  # Base class for tasks
import numpy as np


class FrankaPlaying(BaseTask):
    # We only override a subset of available task methods here
    # Other overridable methods include: calculate_metrics, is_done, etc.
    def __init__(self, name):
        super().__init__(name=name, offset=None)
        self._goal_position = np.array([-0.3, -0.3, 0.0515 / 2.0])
        self._task_achieved = False
        return

    # Place all assets needed for the task in the scene
    def set_up_scene(self, scene):
        super().set_up_scene(scene)
        scene.add_default_ground_plane()
        self._cube = scene.add(
            DynamicCuboid(
                prim_path="/World/random_cube",
                name="fancy_cube",
                position=np.array([0.3, 0.3, 0.3]),
                scale=np.array([0.0515, 0.0515, 0.0515]),
                color=np.array([0, 0, 1.0]),
            )
        )
        self._franka = scene.add(
            Franka(prim_path="/World/Fancy_Franka", name="fancy_franka")
        )
        return

    # Return observation data needed to solve the task
    def get_observations(self):
        cube_position, _ = self._cube.get_world_pose()
        current_joint_positions = self._franka.get_joint_positions()
        observations = {
            self._franka.name: {
                "joint_positions": current_joint_positions,
            },
            self._cube.name: {
                "position": cube_position,
                "goal_position": self._goal_position,
            },
        }
        return observations

    # Called before each physics step
    # Check if the task is accomplished and provide visual feedback
    def pre_step(self, control_index, simulation_time):
        cube_position, _ = self._cube.get_world_pose()
        if not self._task_achieved and np.mean(np.abs(self._goal_position - cube_position)) < 0.02:
            # Change the cube's color to green when it reaches the goal
            self._cube.get_applied_visual_material().set_color(color=np.array([0, 1.0, 0]))
            self._task_achieved = True
        return

    # Called after each reset
    # Open the gripper and reset the cube's color to blue
    def post_reset(self):
        self._franka.gripper.set_joint_positions(self._franka.gripper.joint_opened_positions)
        self._cube.get_applied_visual_material().set_color(color=np.array([0, 0, 1.0]))
        self._task_achieved = False
        return


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        world = self.get_world()
        # Add the task to the world
        world.add_task(FrankaPlaying(name="my_first_task"))
        return

    async def setup_post_load(self):
        self._world = self.get_world()
        # The world has already called the task's set_up_scene (during the first reset)
        # so we can retrieve the task objects
        self._franka = self._world.scene.get_object("fancy_franka")
        self._controller = PickPlaceController(
            name="pick_place_controller",
            gripper=self._franka.gripper,
            robot_articulation=self._franka,
        )
        self._world.add_physics_callback("sim_step", callback_fn=self.physics_step)
        await self._world.play_async()
        return

    async def setup_post_reset(self):
        self._controller.reset()
        await self._world.play_async()
        return

    def physics_step(self, step_size):
        # Get all task observations
        current_observations = self._world.get_observations()
        actions = self._controller.forward(
            picking_position=current_observations["fancy_cube"]["position"],
            placing_position=current_observations["fancy_cube"]["goal_position"],
            current_joint_positions=current_observations["fancy_franka"]["joint_positions"],
        )
        self._franka.apply_action(actions)
        if self._controller.is_done():
            self._world.pause()
        return

With a custom task, you can add unique features not available in pre-built tasks (such as changing the cube's color in pre_step). On the other hand, you need to implement scene construction and observation definitions yourself.

Summary

This tutorial covered the following topics:

  1. Adding the Franka Panda manipulator robot to the scene
  2. Implementing pick-and-place operations using the PickPlaceController
  3. Using the pre-built PickPlace task to learn the basics of task usage
  4. Creating a custom task by inheriting from BaseTask and adding custom logic

Next Steps

Proceed to the next tutorial, "Adding Multiple Robots," to learn how to build a simulation where multiple robots cooperate.

Note

The following tutorials continue to use the Extension Workflow for development. Converting to the Standalone Workflow follows the same approach as learned in Hello World.