5. Adding a New Manipulator¶
5.1. Learning Objectives¶
This tutorial shows how to add a new manipulator to isaac sim starting with a URDF representing the manipulator robot and going through tuning it, adding a follow target example and finally performing a pick and place task.
After this tutorial, you will be able to create a pick and place task as well as its controller for a new manipulator in Omniverse Isaac Sim. In this tutorial we will use the cobotta pro 900 robot from denso.
Note that all the files created in this tutorial are available at /standalone_examples/api/omni.isaac.manipulators/cobotta_900 for verification.
30-35 Minutes Tutorial
5.2. Getting Started¶
Prerequisites
Review the Core API Hello World and GUI Tutorial series Isaac Sim Interface prior to beginning this tutorial.
5.3. Creating the Robot USD file from URDF¶
5.3.1. Using the URDF Importer¶
Let’s begin by importing the urdf using the urdf importer utility provided in Omniverse Isaac Sim to create the USD file.
copy the urdf assets (cobotta_pro_900.urdf, cobotta_pro_900_visualization and onrobot_rg6_visualization) under a new folder URDF_Folder_Path/cobotta_pro_900. These assets could be found at /exts/omni.isaac.urdf/data/urdf/robots/cobotta_pro_900
Launch Omniverse Isaac Sim using the launcher.
Open the URDF Importer through Isaac Utils > Workflows > URDF Importer
In the extension window, choose the URDF file under Import > Input File, check Create Physics Scene and Fix Base Link and choose the Joint Drive Type to be Position.
Click on Import in the extension window.
Close the URDF Importer extension window.
Check that a USD file got created under URDF_Folder_Path/cobotta_pro_900/cobotta_pro_900/cobotta_pro_900.usd. Note that it got added as a reference in the stage which means that you can’t modify and save the reference to the original usd. To do so, the usd file needs be opened and not added as a reference.
Press Play button on the left (make sure no errors are being printed at this point on the console)
To know more about the URDF Importer usage, take a look at the Import URDF tutorial and URDF Importer manual.
5.3.2. Inspect the Articulation¶
Let’s make sure that the joints are reponsive for position control.
Create a new stage through File > New. A defaultLight is added to the new stage as seen.
Create XForm under World and rename it to denso.
Add the robot usd as a reference to the new denso xform.
Add a physics scene to the stage.
Open the Articulation Inspector through Isaac Utils > Workflows > Articulation Inspector and press Play button
Choose the prim_path that corresponds to the articulation under Select Articulation, value is World/denso
Familiarize yourself with the dofs in the artculation under DOF View. Notice that each of the dofs has a target position as 0 and that the gripper has 6 joints. Additonaly take a note of the gripper dof names to use with the Parallel Gripper class provided in Omniverse Isaac Sim, to simplify the pick and place controller we will use 2 joints only for the gripper control. (specifically we will use “finger_joint” and “right_outer_knuckle_joint” to grip the object and we will set dof 7 and 8 to 0.628 so that they are out of the way when the other joints grip the cube). Inspect these dofs further to understand the gripper better.
Try changing the target position with the slider and double check that the dof position reaches the target specified.
Close the Articulation Inspector extension window.
To know more about the Articulation Inspector usage, take a look at the Articulation Inspector manual.
5.3.3. Gains Tuning¶
Next we tune the stiffness and the damping gains so that the cobotta robot has smooth and stable motions while reaching the target positions.
Open the usd file at URDF_Folder_Path/cobotta_pro_900/cobotta_pro_900/cobotta_pro_900.usd. Note that we are not adding it as a reference to be able to save the new gains to the usd file.
Add a physics scene through Create > Physics > Physics Scene
Open the Gain Tuner through Isaac Utils > Workflows > Gain Tuner and press the Play button.
Choose the prim_path that corresponds to the articulation under Select Articulation, value is World/denso
Navigate to the Test Joint Positions panel and click on Start next to Send Position Targets to start sending new position targets to the denso robot.
click on Randomize next to Randomize Position Targets
Validate the motion of the arm and gripper to the target joint positions (should produce a smooth and stable motion). Scale the damping and stiffness if not satisfied with the motion through navigating to the Gains panel and specifying the stiffness multiplier as well as the damping multipler and press on SCALE.
For the purpose of this tutorial scale the default gains by 0.0001 and 0.001 as the stiffness and the damping multipliers respectively, so the resulting Stiffness and Damping are 10000 and 10000 respectively.
Save the USD file and move on to the next step if satisified with the motion to target of the articulation, otherwise go to the previous step (don’t forget to delete the physics scene before saving the usd file). Note: for the cobotta_pro_900 robot no tuning is needed for a simple pick and place.
Close the Gain Tuner extension window.
To know more about the Gain Tuner usage, take a look at the Gain Tuner manual.
5.4. Controlling the Gripper¶
Next we start a simple script where we open and close the gripper repeatedly in order to verify that we can load the usd file and do simple control with it.
Create a new python file under a new folder COBOTTA_SCRIPTS_PATH/gripper_control.py (Note: this example uses the standalone workflow).
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
from omni.isaac.kit import SimulationApp simulation_app = SimulationApp({"headless": False}) from omni.isaac.core import World from omni.isaac.manipulators import SingleManipulator from omni.isaac.manipulators.grippers import ParallelGripper from omni.isaac.core.utils.stage import add_reference_to_stage from omni.isaac.core.utils.types import ArticulationAction import numpy as np my_world = World(stage_units_in_meters=1.0) #TODO: change this to your own path asset_path = "/home/user_name/cobotta_pro_900/cobotta_pro_900/cobotta_pro_900.usd" add_reference_to_stage(usd_path=asset_path, prim_path="/World/cobotta") #define the gripper gripper = ParallelGripper( #We chose the following values while inspecting the articulation end_effector_prim_path="/World/cobotta/onrobot_rg6_base_link", joint_prim_names=["finger_joint", "right_outer_knuckle_joint"], joint_opened_positions=np.array([0, 0]), joint_closed_positions=np.array([0.628, -0.628]), action_deltas=np.array([-0.628, 0.628]), ) #define the manipulator my_denso = my_world.scene.add(SingleManipulator(prim_path="/World/cobotta", name="cobotta_robot", end_effector_prim_name="onrobot_rg6_base_link", gripper=gripper)) #set the default positions of the other gripper joints to be opened so #that its out of the way of the joints we want to control when gripping an object for instance. joints_default_positions = np.zeros(12) joints_default_positions[7] = 0.628 joints_default_positions[8] = 0.628 my_denso.set_joints_default_state(positions=joints_default_positions) my_world.scene.add_default_ground_plane() my_world.reset() i = 0 while simulation_app.is_running(): my_world.step(render=True) if my_world.is_playing(): if my_world.current_time_step_index == 0: my_world.reset() i += 1 gripper_positions = my_denso.gripper.get_joint_positions() if i < 500: #close the gripper slowly my_denso.gripper.apply_action( ArticulationAction(joint_positions=[gripper_positions[0] + 0.1, gripper_positions[1] - 0.1])) if i > 500: #open the gripper slowly my_denso.gripper.apply_action( ArticulationAction(joint_positions=[gripper_positions[0] - 0.1, gripper_positions[1] + 0.1])) if i == 1000: i = 0 simulation_app.close()
Run it using
./python.sh /standalone_examples/api/omni.isaac.manipulators/cobotta_900/gripper_control.py
.

5.5. Adding a Follow Target Task¶
Next we add a follow target task with a target cube for the cobotta robot to follow with its end effector.
Create a new python file under a new folder COBOTTA_SCRIPTS_PATH/tasks/follow_target.py to define the task class there.
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
from omni.isaac.manipulators import SingleManipulator from omni.isaac.manipulators.grippers import ParallelGripper from omni.isaac.core.utils.stage import add_reference_to_stage import omni.isaac.core.tasks as tasks from typing import Optional import numpy as np # Inheriting from the base class Follow Target class FollowTarget(tasks.FollowTarget): def __init__( self, name: str = "denso_follow_target", target_prim_path: Optional[str] = None, target_name: Optional[str] = None, target_position: Optional[np.ndarray] = None, target_orientation: Optional[np.ndarray] = None, offset: Optional[np.ndarray] = None, ) -> None: tasks.FollowTarget.__init__( self, name=name, target_prim_path=target_prim_path, target_name=target_name, target_position=target_position, target_orientation=target_orientation, offset=offset, ) return def set_robot(self) -> SingleManipulator: #TODO: change this to the robot usd file. asset_path = "/home/user_name/cobotta_pro_900/cobotta_pro_900/cobotta_pro_900.usd" add_reference_to_stage(usd_path=asset_path, prim_path="/World/cobotta") gripper = ParallelGripper( end_effector_prim_path="/World/cobotta/onrobot_rg6_base_link", joint_prim_names=["finger_joint", "right_outer_knuckle_joint"], joint_opened_positions=np.array([0, 0]), joint_closed_positions=np.array([0.628, -0.628]), action_deltas=np.array([-0.628, 0.628])) manipulator = SingleManipulator(prim_path="/World/cobotta", name="cobotta_robot", end_effector_prim_name="onrobot_rg6_base_link", gripper=gripper) joints_default_positions = np.zeros(12) joints_default_positions[7] = 0.628 joints_default_positions[8] = 0.628 manipulator.set_joints_default_state(positions=joints_default_positions) return manipulator
Create a new python file at COBOTTA_SCRIPTS_PATH/follow_target_example.py to run the follow target example.
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
from omni.isaac.kit import SimulationApp simulation_app = SimulationApp({"headless": False}) from omni.isaac.core import World from tasks.follow_target import FollowTarget import numpy as np my_world = World(stage_units_in_meters=1.0) #Initialize the Follow Target task with a target location for the cube to be followed by the end effector my_task = FollowTarget(name="denso_follow_target", target_position=np.array([0.5, 0, 0.5])) my_world.add_task(my_task) my_world.reset() task_params = my_world.get_task("denso_follow_target").get_params() target_name = task_params["target_name"]["value"] denso_name = task_params["robot_name"]["value"] my_denso = my_world.scene.get_object(denso_name) articulation_controller = my_denso.get_articulation_controller() while simulation_app.is_running(): my_world.step(render=True) if my_world.is_playing(): if my_world.current_time_step_index == 0: my_world.reset() observations = my_world.get_observations() print(observations) simulation_app.close()
Run it using
./python.sh /standalone_examples/api/omni.isaac.manipulators/cobotta_900/follow_target_example.py
.Next we try to follow the target with a plain Inverse Kinemetics solver provided in Omniverse Isaac Sim. We need to point the solver to the urdf and the robot description files, so let’s create new yaml file at COBOTTA_SCRIPTS_PATH/rmpflow/robot_descriptor.yaml.
Copy the following into the robot description file
1 2 3 4 5 6 7 8 9 10 11 12 13 14
api_version: 1.0 cspace: - joint_1 - joint_2 - joint_3 - joint_4 - joint_5 - joint_6 root_link: world default_q: [ 0.00, 0.00, 0.00, 0.00, 0.00, 0.00 ] cspace_to_urdf_rules: [] composite_task_spaces: []
Create a new python file at COBOTTA_SCRIPTS_PATH/ik_solver.py to define the IK solver class there.
1 2 3 4 5 6 7 8 9 10 11 12 13 14
from omni.isaac.motion_generation import ArticulationKinematicsSolver, LulaKinematicsSolver from omni.isaac.core.articulations import Articulation from typing import Optional class KinematicsSolver(ArticulationKinematicsSolver): def __init__(self, robot_articulation: Articulation, end_effector_frame_name: Optional[str] = None) -> None: #TODO: change the config path self._kinematics = LulaKinematicsSolver(robot_description_path="COBOTTA_SCRIPTS_PATH/rmpflow/robot_descriptor.yaml", urdf_path="/home/user_name/cobotta_pro_900/cobotta_pro_900.urdf") if end_effector_frame_name is None: end_effector_frame_name = "onrobot_rg6_base_link" ArticulationKinematicsSolver.__init__(self, robot_articulation, self._kinematics, end_effector_frame_name) return
Modify the COBOTTA_SCRIPTS_PATH/follow_target_example.py script to follow the target using an IK solver.
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
from omni.isaac.kit import SimulationApp simulation_app = SimulationApp({"headless": False}) from omni.isaac.core import World from tasks.follow_target import FollowTarget import numpy as np from ik_solver import KinematicsSolver import carb my_world = World(stage_units_in_meters=1.0) #Initialize the Follow Target task with a target location for the cube to be followed by the end effector my_task = FollowTarget(name="denso_follow_target", target_position=np.array([0.5, 0, 0.5])) my_world.add_task(my_task) my_world.reset() task_params = my_world.get_task("denso_follow_target").get_params() target_name = task_params["target_name"]["value"] denso_name = task_params["robot_name"]["value"] my_denso = my_world.scene.get_object(denso_name) #initialize the controller my_controller = KinematicsSolver(my_denso) articulation_controller = my_denso.get_articulation_controller() while simulation_app.is_running(): my_world.step(render=True) if my_world.is_playing(): if my_world.current_time_step_index == 0: my_world.reset() observations = my_world.get_observations() actions, succ = my_controller.compute_inverse_kinematics( target_position=observations[target_name]["position"], target_orientation=observations[target_name]["orientation"], ) if succ: articulation_controller.apply_action(actions) else: carb.log_warn("IK did not converge to a solution. No action is being taken.") simulation_app.close()
Run it using
./python.sh /standalone_examples/api/omni.isaac.manipulators/cobotta_900/follow_target_example.py
.
5.6. Using RMPflow to Control the Robot¶
Next we try using RMPFlow to follow the target so let’s create a new yaml file at COBOTTA_SCRIPTS_PATH/rmpflow/denso_rmpflow_common.yaml and copy the following into it.
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
joint_limit_buffers: [.01, .01, .01, .01, .01, .01] rmp_params: cspace_target_rmp: metric_scalar: 50. position_gain: 100. damping_gain: 50. robust_position_term_thresh: .5 inertia: 1. cspace_trajectory_rmp: p_gain: 100. d_gain: 10. ff_gain: .25 weight: 50. cspace_affine_rmp: final_handover_time_std_dev: .25 weight: 2000. joint_limit_rmp: metric_scalar: 1000. metric_length_scale: .01 metric_exploder_eps: 1e-3 metric_velocity_gate_length_scale: .01 accel_damper_gain: 200. accel_potential_gain: 1. accel_potential_exploder_length_scale: .1 accel_potential_exploder_eps: 1e-2 joint_velocity_cap_rmp: max_velocity: 1. velocity_damping_region: .3 damping_gain: 1000.0 metric_weight: 100. target_rmp: accel_p_gain: 30. accel_d_gain: 85. accel_norm_eps: .075 metric_alpha_length_scale: .05 min_metric_alpha: .01 max_metric_scalar: 10000 min_metric_scalar: 2500 proximity_metric_boost_scalar: 20. proximity_metric_boost_length_scale: .02 xi_estimator_gate_std_dev: 20000. accept_user_weights: false axis_target_rmp: accel_p_gain: 210. accel_d_gain: 60. metric_scalar: 10 proximity_metric_boost_scalar: 3000. proximity_metric_boost_length_scale: .08 xi_estimator_gate_std_dev: 20000. accept_user_weights: false collision_rmp: damping_gain: 50. damping_std_dev: .04 damping_robustness_eps: 1e-2 damping_velocity_gate_length_scale: .01 repulsion_gain: 800. repulsion_std_dev: .01 metric_modulation_radius: .5 metric_scalar: 10000. metric_exploder_std_dev: .02 metric_exploder_eps: .001 damping_rmp: accel_d_gain: 30. metric_scalar: 50. inertia: 100. canonical_resolve: max_acceleration_norm: 50. projection_tolerance: .01 verbose: false body_cylinders: - name: base pt1: [0,0,.333] pt2: [0,0,0.] radius: .05 body_collision_controllers: - name: onrobot_rg6_base_link radius: .05
Create a new python file under a new folder COBOTTA_SCRIPTS_PATH/controllers/rmpflow.py to define the RMPFlow Controller class there.
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
import omni.isaac.motion_generation as mg from omni.isaac.core.articulations import Articulation class RMPFlowController(mg.MotionPolicyController): def __init__(self, name: str, robot_articulation: Articulation, physics_dt: float = 1.0 / 60.0) -> None: # TODO: chamge the follow paths self.rmpflow = mg.lula.motion_policies.RmpFlow(robot_description_path="COBOTTA_SCRIPTS_PATH/rmpflow/robot_descriptor.yaml", rmpflow_config_path="COBOTTA_SCRIPTS_PATH/rmpflow/denso_rmpflow_common.yaml", urdf_path="/home/user_name/cobotta_pro_900/cobotta_pro_900.urdf", end_effector_frame_name="onrobot_rg6_base_link", maximum_substep_size=0.00334) self.articulation_rmp = mg.ArticulationMotionPolicy(robot_articulation, self.rmpflow, physics_dt) mg.MotionPolicyController.__init__(self, name=name, articulation_motion_policy=self.articulation_rmp) self._default_position, self._default_orientation = ( self._articulation_motion_policy._robot_articulation.get_world_pose() ) self._motion_policy.set_robot_base_pose( robot_position=self._default_position, robot_orientation=self._default_orientation ) return def reset(self): mg.MotionPolicyController.reset(self) self._motion_policy.set_robot_base_pose( robot_position=self._default_position, robot_orientation=self._default_orientation )
Modify the COBOTTA_SCRIPTS_PATH/follow_target_example.py script to follow the target using an IK solver.
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
from omni.isaac.kit import SimulationApp simulation_app = SimulationApp({"headless": False}) from omni.isaac.core import World from tasks.follow_target import FollowTarget import numpy as np from controllers.rmpflow import RMPFlowController my_world = World(stage_units_in_meters=1.0) #Initialize the Follow Target task with a target location for the cube to be followed by the end effector my_task = FollowTarget(name="denso_follow_target", target_position=np.array([0.5, 0, 0.5])) my_world.add_task(my_task) my_world.reset() task_params = my_world.get_task("denso_follow_target").get_params() target_name = task_params["target_name"]["value"] denso_name = task_params["robot_name"]["value"] my_denso = my_world.scene.get_object(denso_name) #initialize the controller my_controller = RMPFlowController(name="target_follower_controller", robot_articulation=my_denso) my_controller.reset() articulation_controller = my_denso.get_articulation_controller() while simulation_app.is_running(): my_world.step(render=True) if my_world.is_playing(): if my_world.current_time_step_index == 0: my_world.reset() my_controller.reset() observations = my_world.get_observations() actions = my_controller.forward( target_end_effector_position=observations[target_name]["position"], target_end_effector_orientation=observations[target_name]["orientation"], ) articulation_controller.apply_action(actions) simulation_app.close()
Run it using
./python.sh /standalone_examples/api/omni.isaac.manipulators/cobotta_900/follow_target_example.py
.
5.7. Adding a PickPlace Task¶
Next we add a pick and place task with a cube for the cobotta robot to pick and place at a target goal location.
Create a new python file at COBOTTA_SCRIPTS_PATH/tasks/pick_place.py to define the task class there.
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
from omni.isaac.manipulators import SingleManipulator from omni.isaac.manipulators.grippers import ParallelGripper from omni.isaac.core.utils.stage import add_reference_to_stage import omni.isaac.core.tasks as tasks from typing import Optional import numpy as np class PickPlace(tasks.PickPlace): def __init__( self, name: str = "denso_pick_place", cube_initial_position: Optional[np.ndarray] = None, cube_initial_orientation: Optional[np.ndarray] = None, target_position: Optional[np.ndarray] = None, offset: Optional[np.ndarray] = None, ) -> None: tasks.PickPlace.__init__( self, name=name, cube_initial_position=cube_initial_position, cube_initial_orientation=cube_initial_orientation, target_position=target_position, cube_size=np.array([0.0515, 0.0515, 0.0515]), offset=offset, ) return def set_robot(self) -> SingleManipulator: #TODO: change the asset path here asset_path = "/home/user_name/cobotta_pro_900/cobotta_pro_900/cobotta_pro_900.usd" add_reference_to_stage(usd_path=asset_path, prim_path="/World/cobotta") gripper = ParallelGripper( end_effector_prim_path="/World/cobotta/onrobot_rg6_base_link", joint_prim_names=["finger_joint", "right_outer_knuckle_joint"], joint_opened_positions=np.array([0, 0]), joint_closed_positions=np.array([0.628, -0.628]), action_deltas=np.array([-0.2, 0.2]) ) manipulator = SingleManipulator(prim_path="/World/cobotta", name="cobotta_robot", end_effector_prim_name="onrobot_rg6_base_link", gripper=gripper) joints_default_positions = np.zeros(12) joints_default_positions[7] = 0.628 joints_default_positions[8] = 0.628 manipulator.set_joints_default_state(positions=joints_default_positions) return manipulator
Create a new python file at COBOTTA_SCRIPTS_PATH/pick_place_example.py to run the follow target example.
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
from omni.isaac.kit import SimulationApp simulation_app = SimulationApp({"headless": False}) from omni.isaac.core import World import numpy as np from tasks.pick_place import PickPlace my_world = World(stage_units_in_meters=1.0) target_position = np.array([-0.3, 0.6, 0]) target_position[2] = 0.0515 / 2.0 my_task = PickPlace(name="denso_pick_place", target_position=target_position) my_world.add_task(my_task) my_world.reset() task_params = my_world.get_task("denso_pick_place").get_params() denso_name = task_params["robot_name"]["value"] my_denso = my_world.scene.get_object(denso_name) articulation_controller = my_denso.get_articulation_controller() while simulation_app.is_running(): my_world.step(render=True) if my_world.is_playing(): if my_world.current_time_step_index == 0: my_world.reset() observations = my_world.get_observations() print(observations) simulation_app.close()
Run it using
./python.sh /standalone_examples/api/omni.isaac.manipulators/cobotta_900/pick_place_example.py
.
5.8. Adding a PickPlace Controller¶
Next we try to pick and place the cube with a simple PickPlaceController provided in Omniverse Isaac Sim. Create a new python file at COBOTTA_SCRIPTS_PATH/controllers/pick_place.py and copy the following into it.
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
import omni.isaac.manipulators.controllers as manipulators_controllers from omni.isaac.manipulators.grippers import ParallelGripper from .rmpflow import RMPFlowController from omni.isaac.core.articulations import Articulation class PickPlaceController(manipulators_controllers.PickPlaceController): def __init__( self, name: str, gripper: ParallelGripper, robot_articulation: Articulation, events_dt=None ) -> None: if events_dt is None: #These values needs to be tuned in general, you checkout each event in execution and slow it down or speed #it up depends on how smooth the movments are events_dt = [0.005, 0.002, 1, 0.05, 0.0008, 0.005, 0.0008, 0.1, 0.0008, 0.008] manipulators_controllers.PickPlaceController.__init__( self, name=name, cspace_controller=RMPFlowController( name=name + "_cspace_controller", robot_articulation=robot_articulation ), gripper=gripper, events_dt=events_dt, #This value can be changed start_picking_height=0.6 ) return
Modify the python file at COBOTTA_SCRIPTS_PATH/pick_place_example.py to run the pick and place routine using cobotta.
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
from omni.isaac.kit import SimulationApp simulation_app = SimulationApp({"headless": False}) from omni.isaac.core import World import numpy as np from tasks.pick_place import PickPlace from controllers.pick_place import PickPlaceController my_world = World(stage_units_in_meters=1.0) target_position = np.array([-0.3, 0.6, 0]) target_position[2] = 0.0515 / 2.0 my_task = PickPlace(name="denso_pick_place", target_position=target_position) my_world.add_task(my_task) my_world.reset() my_denso = my_world.scene.get_object("cobotta_robot") #initialize the controller my_controller = PickPlaceController(name="controller", robot_articulation=my_denso, gripper=my_denso.gripper) task_params = my_world.get_task("denso_pick_place").get_params() articulation_controller = my_denso.get_articulation_controller() i = 0 while simulation_app.is_running(): my_world.step(render=True) if my_world.is_playing(): if my_world.current_time_step_index == 0: my_world.reset() my_controller.reset() observations = my_world.get_observations() #forward the observation values to the controller to get the actions actions = my_controller.forward( picking_position=observations[task_params["cube_name"]["value"]]["position"], placing_position=observations[task_params["cube_name"]["value"]]["target_position"], current_joint_positions=observations[task_params["robot_name"]["value"]]["joint_positions"], # This offset needs tuning as well end_effector_offset=np.array([0, 0, 0.25]), ) if my_controller.is_done(): print("done picking and placing") articulation_controller.apply_action(actions) simulation_app.close()
Run it using
./python.sh /standalone_examples/api/omni.isaac.manipulators/cobotta_900/pick_place_example.py
.
5.9. Summary¶
This tutorial covered the following topics:
Importing a robot using the URDF Importer.
Inspecting the robot usd using the Articulation Inspector.
Tuning the robot gains using the Gain Tuner.
Adding follow target as well as pick and place tasks.
Adding controllers to solve the tasks specified.
Adding simple rmpflow config files.
5.9.1. Further Learning¶
Next learn more on how to create the rmpflow config files as well as the detailed explanation of most of the fields at Configuring RMPflow for a New Manipulator