4. Adding a Manipulator Robot¶
4.1. Learning Objectives¶
This tutorial introduces a second robot to the simulation, a Franka Panda manipulator.
It describes how to add the robot to the scene and use its PickAndPlaceController
class.
After this tutorial, you will have more experience using different robot and controller classes
in Omniverse Isaac Sim.
15-20 Minute Tutorial
4.2. Getting Started¶
Prerequisites
Review Adding A Controller prior to beginning this tutorial.
Begin with the source code open from the previous tutorial, Adding A Controller.
4.3. Creating the Scene¶
Begin by adding a Franka robot from the omni.isaac.franka
extension, as well as a cube for
the Franka to pick up.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 from omni.isaac.examples.base_sample import BaseSample # This extension has franka related tasks and controllers as well from omni.isaac.franka import Franka from omni.isaac.core.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() # Robot specific class that provides extra functionalities # such as having gripper and end_effector instances. franka = world.scene.add(Franka(prim_path="/World/Fancy_Franka", name="fancy_franka")) # add a cube for 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]), scale=np.array([0.0515, 0.0515, 0.0515]), color=np.array([0, 0, 1.0]), ) ) return
4.4. Using the PickAndPlace Controller¶
Add a pick-and-place controller from omni.isaac.franka
so that the Franka picks up the cube
and places it somewhere else.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 from omni.isaac.examples.base_sample import BaseSample from omni.isaac.franka import Franka from omni.isaac.core.objects import DynamicCuboid from omni.isaac.franka.controllers import PickPlaceController 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 a pick and place controller 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) # World has pause, stop, play..etc # Note: if async version exists, use it in any async function is this workflow self._franka.gripper.set_joint_positions(self._franka.gripper.joint_opened_positions) await self._world.play_async() return # This function is called after Reset button is pressed # Resetting anything in the world should happen 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]) current_joint_positions = self._franka.get_joint_positions() actions = self._controller.forward( picking_position=cube_position, placing_position=goal_position, current_joint_positions=current_joint_positions, ) self._franka.apply_action(actions) # Only for the pick and place controller, indicating if the state # machine reached the final state. if self._controller.is_done(): self._world.pause() return
4.5. What is a Task?¶
The Task class in Omniverse Isaac Sim provides a way to modularize the scene
creation, information retrieval, and calculating metrics. It is useful to create more complex scenes
with advanced logic. You will need to re-write the previous code using the Task
class.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 from omni.isaac.examples.base_sample import BaseSample from omni.isaac.franka import Franka from omni.isaac.core.objects import DynamicCuboid from omni.isaac.franka.controllers import PickPlaceController from omni.isaac.core.tasks import BaseTask import numpy as np class FrankaPlaying(BaseTask): #NOTE: we only cover here a subset of the task functions that are available, # checkout the base class for all the available functions to override. # ex: 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 # Here we setup all the assets that we care about in this task. 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 # Information exposed to solve the task is returned from the task through get_observations 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, # for instance we can check here if the task was accomplished by # changing the color of the cube once its accomplished 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: # Visual Materials are applied by default to the cube # in this case the cube has a visual material of type # PreviewSurface, we can set its color once the target is reached. self._cube.get_applied_visual_material().set_color(color=np.array([0, 1.0, 0])) self._task_achieved = True return # Called after each reset, # for instance we can always set the gripper to be opened at the beginning after each reset # also we can set the cube's color to be 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() # We add the task to the world here world.add_task(FrankaPlaying(name="my_first_task")) return async def setup_post_load(self): self._world = self.get_world() # The world already called the setup_scene from the task (with first reset of the world) # 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): # Gets all the tasks 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
4.6. Use the Pick and Place Task¶
Omniverse Isaac Sim also provides different tasks under the many robot extensions.
Re-write the previous code using the PickPlace
class.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 from omni.isaac.examples.base_sample import BaseSample from omni.isaac.franka.tasks import PickPlace from omni.isaac.franka.controllers import PickPlaceController class HelloWorld(BaseSample): def __init__(self) -> None: super().__init__() return def setup_scene(self): world = self.get_world() # We add the task to the world here world.add_task(PickPlace(name="awesome_task")) return async def setup_post_load(self): self._world = self.get_world() # The world already called the setup_scene from the task so # we can retrieve the task objects # Each defined task in the robot extensions # has set_params and get_params to allow for changing tasks during # simulation, {"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): # Gets all the tasks observations 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
4.7. Summary¶
This tutorial covered the following topics:
Adding a manipulator robot to the scene.
Using Controller Classes from Omniverse Isaac Sim.
Modularizing the creation of scene objects and interacting with them through Task Classes.
Using Task Classes from the robot extensions in Omniverse Isaac Sim.
4.7.1. Next Steps¶
Continue to the next tutorial in our Essential Tutorials series, Adding Multiple Robots, to learn how to add multiple robots to the simulation.