Adding a New Manipulator
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
Getting Started
Prerequisites
Review the Core API Hello World and GUI Tutorial series Isaac Sim Interface prior to beginning this tutorial.
Enabled the URDF Importer extension
Creating the Robot USD file from URDF
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 /extscache/omni.importer.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, choose the Joint Drive Type to be Position, and uncheck the Parse Mimic Joint tag.
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.
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 Physics Inspector through Window > Simulation > Physics Authoring Toolbar and then on the Physics Tool bar Settings > Physics Inspector.
Select the cobotta robot in the stage and click on the refresh button in the Physics Inspector extension window.
Familiarize yourself with the dofs in the articulation under DOF View. Notice that each of the dofs has a default target position as 0 and that the gripper has 6 joints. Additionally 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.
To know more about the Physics Inspector usage, go to Physics Inspector
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 so that we can 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 /cobotta_pro_900
Click Sinusoidal Gains Test
Tune the gains until each joint perfectly tracks the position and velocity sinusoids. This can be done easily with the SET STIFF GAINS button.
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 Extension manual.
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).
1from isaacsim import SimulationApp 2 3simulation_app = SimulationApp({"headless": False}) 4 5from omni.isaac.core import World 6from omni.isaac.manipulators import SingleManipulator 7from omni.isaac.manipulators.grippers import ParallelGripper 8from omni.isaac.core.utils.stage import add_reference_to_stage 9from omni.isaac.core.utils.types import ArticulationAction 10import numpy as np 11 12my_world = World(stage_units_in_meters=1.0) 13#TODO: change this to your own path 14asset_path = "/home/user_name/cobotta_pro_900/cobotta_pro_900/cobotta_pro_900.usd" 15add_reference_to_stage(usd_path=asset_path, prim_path="/World/cobotta") 16#define the gripper 17gripper = ParallelGripper( 18 #We chose the following values while inspecting the articulation 19 end_effector_prim_path="/World/cobotta/onrobot_rg6_base_link", 20 joint_prim_names=["finger_joint", "right_outer_knuckle_joint"], 21 joint_opened_positions=np.array([0, 0]), 22 joint_closed_positions=np.array([0.628, -0.628]), 23 action_deltas=np.array([-0.628, 0.628]), 24) 25#define the manipulator 26my_denso = my_world.scene.add(SingleManipulator(prim_path="/World/cobotta", name="cobotta_robot", 27 end_effector_prim_name="onrobot_rg6_base_link", gripper=gripper)) 28#set the default positions of the other gripper joints to be opened so 29#that its out of the way of the joints we want to control when gripping an object for instance. 30joints_default_positions = np.zeros(12) 31joints_default_positions[7] = 0.628 32joints_default_positions[8] = 0.628 33my_denso.set_joints_default_state(positions=joints_default_positions) 34my_world.scene.add_default_ground_plane() 35my_world.reset() 36 37i = 0 38while simulation_app.is_running(): 39 my_world.step(render=True) 40 if my_world.is_playing(): 41 if my_world.current_time_step_index == 0: 42 my_world.reset() 43 i += 1 44 gripper_positions = my_denso.gripper.get_joint_positions() 45 if i < 500: 46 #close the gripper slowly 47 my_denso.gripper.apply_action( 48 ArticulationAction(joint_positions=[gripper_positions[0] + 0.1, gripper_positions[1] - 0.1])) 49 if i > 500: 50 #open the gripper slowly 51 my_denso.gripper.apply_action( 52 ArticulationAction(joint_positions=[gripper_positions[0] - 0.1, gripper_positions[1] + 0.1])) 53 if i == 1000: 54 i = 0 55 56simulation_app.close()
Run it using
./python.sh standalone_examples/api/omni.isaac.manipulators/cobotta_900/gripper_control.py
.
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.
1from omni.isaac.manipulators import SingleManipulator 2from omni.isaac.manipulators.grippers import ParallelGripper 3from omni.isaac.core.utils.stage import add_reference_to_stage 4import omni.isaac.core.tasks as tasks 5from typing import Optional 6import numpy as np 7 8 9# Inheriting from the base class Follow Target 10class FollowTarget(tasks.FollowTarget): 11 def __init__( 12 self, 13 name: str = "denso_follow_target", 14 target_prim_path: Optional[str] = None, 15 target_name: Optional[str] = None, 16 target_position: Optional[np.ndarray] = None, 17 target_orientation: Optional[np.ndarray] = None, 18 offset: Optional[np.ndarray] = None, 19 ) -> None: 20 tasks.FollowTarget.__init__( 21 self, 22 name=name, 23 target_prim_path=target_prim_path, 24 target_name=target_name, 25 target_position=target_position, 26 target_orientation=target_orientation, 27 offset=offset, 28 ) 29 return 30 31 def set_robot(self) -> SingleManipulator: 32 #TODO: change this to the robot usd file. 33 asset_path = "/home/user_name/cobotta_pro_900/cobotta_pro_900/cobotta_pro_900.usd" 34 add_reference_to_stage(usd_path=asset_path, prim_path="/World/cobotta") 35 gripper = ParallelGripper( 36 end_effector_prim_path="/World/cobotta/onrobot_rg6_base_link", 37 joint_prim_names=["finger_joint", "right_outer_knuckle_joint"], 38 joint_opened_positions=np.array([0, 0]), 39 joint_closed_positions=np.array([0.628, -0.628]), 40 action_deltas=np.array([-0.628, 0.628])) 41 manipulator = SingleManipulator(prim_path="/World/cobotta", 42 name="cobotta_robot", 43 end_effector_prim_name="onrobot_rg6_base_link", 44 gripper=gripper) 45 joints_default_positions = np.zeros(12) 46 joints_default_positions[7] = 0.628 47 joints_default_positions[8] = 0.628 48 manipulator.set_joints_default_state(positions=joints_default_positions) 49 return manipulator
Create a new python file at COBOTTA_SCRIPTS_PATH/follow_target_example.py to run the follow target example.
1from isaacsim import SimulationApp 2 3simulation_app = SimulationApp({"headless": False}) 4 5from omni.isaac.core import World 6from tasks.follow_target import FollowTarget 7import numpy as np 8 9my_world = World(stage_units_in_meters=1.0) 10#Initialize the Follow Target task with a target location for the cube to be followed by the end effector 11my_task = FollowTarget(name="denso_follow_target", target_position=np.array([0.5, 0, 0.5])) 12my_world.add_task(my_task) 13my_world.reset() 14task_params = my_world.get_task("denso_follow_target").get_params() 15target_name = task_params["target_name"]["value"] 16denso_name = task_params["robot_name"]["value"] 17my_denso = my_world.scene.get_object(denso_name) 18articulation_controller = my_denso.get_articulation_controller() 19while simulation_app.is_running(): 20 my_world.step(render=True) 21 if my_world.is_playing(): 22 if my_world.current_time_step_index == 0: 23 my_world.reset() 24 observations = my_world.get_observations() 25 print(observations) 26simulation_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
1api_version: 1.0 2cspace: 3 - joint_1 4 - joint_2 5 - joint_3 6 - joint_4 7 - joint_5 8 - joint_6 9root_link: world 10default_q: [ 11 0.00, 0.00, 0.00, 0.00, 0.00, 0.00 12] 13cspace_to_urdf_rules: [] 14composite_task_spaces: []
Create a new python file at COBOTTA_SCRIPTS_PATH/ik_solver.py to define the IK solver class there.
1from omni.isaac.motion_generation import ArticulationKinematicsSolver, LulaKinematicsSolver 2from omni.isaac.core.articulations import Articulation 3from typing import Optional 4 5 6class KinematicsSolver(ArticulationKinematicsSolver): 7 def __init__(self, robot_articulation: Articulation, end_effector_frame_name: Optional[str] = None) -> None: 8 #TODO: change the config path 9 self._kinematics = LulaKinematicsSolver(robot_description_path="COBOTTA_SCRIPTS_PATH/rmpflow/robot_descriptor.yaml", 10 urdf_path="/home/user_name/cobotta_pro_900/cobotta_pro_900.urdf") 11 if end_effector_frame_name is None: 12 end_effector_frame_name = "onrobot_rg6_base_link" 13 ArticulationKinematicsSolver.__init__(self, robot_articulation, self._kinematics, end_effector_frame_name) 14 return
Modify the COBOTTA_SCRIPTS_PATH/follow_target_example.py script to follow the target using an IK solver.
1from isaacsim import SimulationApp 2 3simulation_app = SimulationApp({"headless": False}) 4 5from omni.isaac.core import World 6from tasks.follow_target import FollowTarget 7import numpy as np 8from ik_solver import KinematicsSolver 9import carb 10 11my_world = World(stage_units_in_meters=1.0) 12#Initialize the Follow Target task with a target location for the cube to be followed by the end effector 13my_task = FollowTarget(name="denso_follow_target", target_position=np.array([0.5, 0, 0.5])) 14my_world.add_task(my_task) 15my_world.reset() 16task_params = my_world.get_task("denso_follow_target").get_params() 17target_name = task_params["target_name"]["value"] 18denso_name = task_params["robot_name"]["value"] 19my_denso = my_world.scene.get_object(denso_name) 20#initialize the controller 21my_controller = KinematicsSolver(my_denso) 22articulation_controller = my_denso.get_articulation_controller() 23while simulation_app.is_running(): 24 my_world.step(render=True) 25 if my_world.is_playing(): 26 if my_world.current_time_step_index == 0: 27 my_world.reset() 28 observations = my_world.get_observations() 29 actions, succ = my_controller.compute_inverse_kinematics( 30 target_position=observations[target_name]["position"], 31 target_orientation=observations[target_name]["orientation"], 32 ) 33 if succ: 34 articulation_controller.apply_action(actions) 35 else: 36 carb.log_warn("IK did not converge to a solution. No action is being taken.") 37simulation_app.close()
Run it using
./python.sh standalone_examples/api/omni.isaac.manipulators/cobotta_900/follow_target_example.py
.
Note
The robot doesn’t have self collision enabled for tutorial purposes only so the cobotta robot links might overlap in some scenarios.
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.
1joint_limit_buffers: [.01, .01, .01, .01, .01, .01] 2rmp_params: 3 cspace_target_rmp: 4 metric_scalar: 50. 5 position_gain: 100. 6 damping_gain: 50. 7 robust_position_term_thresh: .5 8 inertia: 1. 9 cspace_trajectory_rmp: 10 p_gain: 100. 11 d_gain: 10. 12 ff_gain: .25 13 weight: 50. 14 cspace_affine_rmp: 15 final_handover_time_std_dev: .25 16 weight: 2000. 17 joint_limit_rmp: 18 metric_scalar: 1000. 19 metric_length_scale: .01 20 metric_exploder_eps: 1e-3 21 metric_velocity_gate_length_scale: .01 22 accel_damper_gain: 200. 23 accel_potential_gain: 1. 24 accel_potential_exploder_length_scale: .1 25 accel_potential_exploder_eps: 1e-2 26 joint_velocity_cap_rmp: 27 max_velocity: 1. 28 velocity_damping_region: .3 29 damping_gain: 1000.0 30 metric_weight: 100. 31 target_rmp: 32 accel_p_gain: 30. 33 accel_d_gain: 85. 34 accel_norm_eps: .075 35 metric_alpha_length_scale: .05 36 min_metric_alpha: .01 37 max_metric_scalar: 10000 38 min_metric_scalar: 2500 39 proximity_metric_boost_scalar: 20. 40 proximity_metric_boost_length_scale: .02 41 xi_estimator_gate_std_dev: 20000. 42 accept_user_weights: false 43 axis_target_rmp: 44 accel_p_gain: 210. 45 accel_d_gain: 60. 46 metric_scalar: 10 47 proximity_metric_boost_scalar: 3000. 48 proximity_metric_boost_length_scale: .08 49 xi_estimator_gate_std_dev: 20000. 50 accept_user_weights: false 51 collision_rmp: 52 damping_gain: 50. 53 damping_std_dev: .04 54 damping_robustness_eps: 1e-2 55 damping_velocity_gate_length_scale: .01 56 repulsion_gain: 800. 57 repulsion_std_dev: .01 58 metric_modulation_radius: .5 59 metric_scalar: 10000. 60 metric_exploder_std_dev: .02 61 metric_exploder_eps: .001 62 damping_rmp: 63 accel_d_gain: 30. 64 metric_scalar: 50. 65 inertia: 100. 66canonical_resolve: 67 max_acceleration_norm: 50. 68 projection_tolerance: .01 69 verbose: false 70body_cylinders: 71 - name: base 72 pt1: [0,0,.333] 73 pt2: [0,0,0.] 74 radius: .05 75body_collision_controllers: 76 - name: onrobot_rg6_base_link 77 radius: .05
Create a new python file under a new folder COBOTTA_SCRIPTS_PATH/controllers/rmpflow.py to define the RMPFlow Controller class there.
1import omni.isaac.motion_generation as mg 2from omni.isaac.core.articulations import Articulation 3 4 5class RMPFlowController(mg.MotionPolicyController): 6 def __init__(self, name: str, robot_articulation: Articulation, physics_dt: float = 1.0 / 60.0) -> None: 7 # TODO: change the follow paths 8 self.rmpflow = mg.lula.motion_policies.RmpFlow(robot_description_path="COBOTTA_SCRIPTS_PATH/rmpflow/robot_descriptor.yaml", 9 rmpflow_config_path="COBOTTA_SCRIPTS_PATH/rmpflow/denso_rmpflow_common.yaml", 10 urdf_path="/home/user_name/cobotta_pro_900/cobotta_pro_900.urdf", 11 end_effector_frame_name="onrobot_rg6_base_link", 12 maximum_substep_size=0.00334) 13 14 self.articulation_rmp = mg.ArticulationMotionPolicy(robot_articulation, self.rmpflow, physics_dt) 15 16 mg.MotionPolicyController.__init__(self, name=name, articulation_motion_policy=self.articulation_rmp) 17 self._default_position, self._default_orientation = ( 18 self._articulation_motion_policy._robot_articulation.get_world_pose() 19 ) 20 self._motion_policy.set_robot_base_pose( 21 robot_position=self._default_position, robot_orientation=self._default_orientation 22 ) 23 return 24 25 def reset(self): 26 mg.MotionPolicyController.reset(self) 27 self._motion_policy.set_robot_base_pose( 28 robot_position=self._default_position, robot_orientation=self._default_orientation 29 )
Modify the COBOTTA_SCRIPTS_PATH/follow_target_example.py script to follow the target using an IK solver.
1from isaacsim import SimulationApp 2 3simulation_app = SimulationApp({"headless": False}) 4 5from omni.isaac.core import World 6from tasks.follow_target import FollowTarget 7import numpy as np 8from controllers.rmpflow import RMPFlowController 9 10my_world = World(stage_units_in_meters=1.0) 11#Initialize the Follow Target task with a target location for the cube to be followed by the end effector 12my_task = FollowTarget(name="denso_follow_target", target_position=np.array([0.5, 0, 0.5])) 13my_world.add_task(my_task) 14my_world.reset() 15task_params = my_world.get_task("denso_follow_target").get_params() 16target_name = task_params["target_name"]["value"] 17denso_name = task_params["robot_name"]["value"] 18my_denso = my_world.scene.get_object(denso_name) 19#initialize the controller 20my_controller = RMPFlowController(name="target_follower_controller", robot_articulation=my_denso) 21my_controller.reset() 22articulation_controller = my_denso.get_articulation_controller() 23while simulation_app.is_running(): 24 my_world.step(render=True) 25 if my_world.is_playing(): 26 if my_world.current_time_step_index == 0: 27 my_world.reset() 28 my_controller.reset() 29 observations = my_world.get_observations() 30 actions = my_controller.forward( 31 target_end_effector_position=observations[target_name]["position"], 32 target_end_effector_orientation=observations[target_name]["orientation"], 33 ) 34 articulation_controller.apply_action(actions) 35simulation_app.close()
Run it using
./python.sh standalone_examples/api/omni.isaac.manipulators/cobotta_900/follow_target_example.py
.
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.
1from omni.isaac.manipulators import SingleManipulator 2from omni.isaac.manipulators.grippers import ParallelGripper 3from omni.isaac.core.utils.stage import add_reference_to_stage 4import omni.isaac.core.tasks as tasks 5from typing import Optional 6import numpy as np 7 8 9class PickPlace(tasks.PickPlace): 10 def __init__( 11 self, 12 name: str = "denso_pick_place", 13 cube_initial_position: Optional[np.ndarray] = None, 14 cube_initial_orientation: Optional[np.ndarray] = None, 15 target_position: Optional[np.ndarray] = None, 16 offset: Optional[np.ndarray] = None, 17 ) -> None: 18 tasks.PickPlace.__init__( 19 self, 20 name=name, 21 cube_initial_position=cube_initial_position, 22 cube_initial_orientation=cube_initial_orientation, 23 target_position=target_position, 24 cube_size=np.array([0.0515, 0.0515, 0.0515]), 25 offset=offset, 26 ) 27 return 28 29 def set_robot(self) -> SingleManipulator: 30 #TODO: change the asset path here 31 asset_path = "/home/user_name/cobotta_pro_900/cobotta_pro_900/cobotta_pro_900.usd" 32 add_reference_to_stage(usd_path=asset_path, prim_path="/World/cobotta") 33 gripper = ParallelGripper( 34 end_effector_prim_path="/World/cobotta/onrobot_rg6_base_link", 35 joint_prim_names=["finger_joint", "right_outer_knuckle_joint"], 36 joint_opened_positions=np.array([0, 0]), 37 joint_closed_positions=np.array([0.628, -0.628]), 38 action_deltas=np.array([-0.2, 0.2]) ) 39 manipulator = SingleManipulator(prim_path="/World/cobotta", 40 name="cobotta_robot", 41 end_effector_prim_name="onrobot_rg6_base_link", 42 gripper=gripper) 43 joints_default_positions = np.zeros(12) 44 joints_default_positions[7] = 0.628 45 joints_default_positions[8] = 0.628 46 manipulator.set_joints_default_state(positions=joints_default_positions) 47 return manipulator
Create a new python file at COBOTTA_SCRIPTS_PATH/pick_place_example.py to run the follow target example.
1from isaacsim import SimulationApp 2 3simulation_app = SimulationApp({"headless": False}) 4 5from omni.isaac.core import World 6import numpy as np 7from tasks.pick_place import PickPlace 8 9my_world = World(stage_units_in_meters=1.0) 10 11 12target_position = np.array([-0.3, 0.6, 0]) 13target_position[2] = 0.0515 / 2.0 14my_task = PickPlace(name="denso_pick_place", target_position=target_position) 15my_world.add_task(my_task) 16my_world.reset() 17task_params = my_world.get_task("denso_pick_place").get_params() 18denso_name = task_params["robot_name"]["value"] 19my_denso = my_world.scene.get_object(denso_name) 20articulation_controller = my_denso.get_articulation_controller() 21while simulation_app.is_running(): 22 my_world.step(render=True) 23 if my_world.is_playing(): 24 if my_world.current_time_step_index == 0: 25 my_world.reset() 26 observations = my_world.get_observations() 27 print(observations) 28simulation_app.close()
Run it using
./python.sh standalone_examples/api/omni.isaac.manipulators/cobotta_900/pick_place_example.py
.
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.
1import omni.isaac.manipulators.controllers as manipulators_controllers 2from omni.isaac.manipulators.grippers import ParallelGripper 3from .rmpflow import RMPFlowController 4from omni.isaac.core.articulations import Articulation 5 6 7class PickPlaceController(manipulators_controllers.PickPlaceController): 8 def __init__( 9 self, 10 name: str, 11 gripper: ParallelGripper, 12 robot_articulation: Articulation, 13 events_dt=None 14 ) -> None: 15 if events_dt is None: 16 #These values needs to be tuned in general, you checkout each event in execution and slow it down or speed 17 #it up depends on how smooth the movments are 18 events_dt = [0.005, 0.002, 1, 0.05, 0.0008, 0.005, 0.0008, 0.1, 0.0008, 0.008] 19 manipulators_controllers.PickPlaceController.__init__( 20 self, 21 name=name, 22 cspace_controller=RMPFlowController( 23 name=name + "_cspace_controller", robot_articulation=robot_articulation 24 ), 25 gripper=gripper, 26 events_dt=events_dt, 27 #This value can be changed 28 start_picking_height=0.6 29 ) 30 return
Modify the python file at COBOTTA_SCRIPTS_PATH/pick_place_example.py to run the pick and place routine using cobotta.
1from isaacsim import SimulationApp 2 3simulation_app = SimulationApp({"headless": False}) 4 5from omni.isaac.core import World 6import numpy as np 7from tasks.pick_place import PickPlace 8from controllers.pick_place import PickPlaceController 9 10my_world = World(stage_units_in_meters=1.0) 11 12 13target_position = np.array([-0.3, 0.6, 0]) 14target_position[2] = 0.0515 / 2.0 15my_task = PickPlace(name="denso_pick_place", target_position=target_position) 16 17my_world.add_task(my_task) 18my_world.reset() 19my_denso = my_world.scene.get_object("cobotta_robot") 20#initialize the controller 21my_controller = PickPlaceController(name="controller", robot_articulation=my_denso, gripper=my_denso.gripper) 22task_params = my_world.get_task("denso_pick_place").get_params() 23articulation_controller = my_denso.get_articulation_controller() 24i = 0 25while simulation_app.is_running(): 26 my_world.step(render=True) 27 if my_world.is_playing(): 28 if my_world.current_time_step_index == 0: 29 my_world.reset() 30 my_controller.reset() 31 observations = my_world.get_observations() 32 #forward the observation values to the controller to get the actions 33 actions = my_controller.forward( 34 picking_position=observations[task_params["cube_name"]["value"]]["position"], 35 placing_position=observations[task_params["cube_name"]["value"]]["target_position"], 36 current_joint_positions=observations[task_params["robot_name"]["value"]]["joint_positions"], 37 # This offset needs tuning as well 38 end_effector_offset=np.array([0, 0, 0.25]), 39 ) 40 if my_controller.is_done(): 41 print("done picking and placing") 42 articulation_controller.apply_action(actions) 43simulation_app.close()
Run it using
./python.sh standalone_examples/api/omni.isaac.manipulators/cobotta_900/pick_place_example.py
.
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.
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