isaac-sim / IsaacLab

Unified framework for robot learning built on NVIDIA Isaac Sim
https://isaac-sim.github.io/IsaacLab
Other
1.62k stars 526 forks source link

[Question] Using the Isaac sim robotAssembler extension with the InteractiveSceneCfg class to attach two robots #405

Open SantiDiazC opened 2 months ago

SantiDiazC commented 2 months ago

Hi, I am trying to attach two different manipulators a UR5 robot arm and a gripper I designed and both defined with their ArticulationCFG class. To attach them I am using Isaac sim Robot assembler extension. It work well when I don't use the InteractiveSceneCFG class. I used a code similar to the example "run_diff_ik.py" and my code is like this:

@configclass
class TableTopSceneCfg(InteractiveSceneCfg):
    """Configuration for a cart-pole scene."""

    # ground plane
    ground = AssetBaseCfg(
        prim_path="/World/defaultGroundPlane",
        spawn=sim_utils.GroundPlaneCfg(),
        init_state=AssetBaseCfg.InitialStateCfg(pos=(0.0, 0.0, -1.05)),
    )

    # lights
    dome_light = AssetBaseCfg(
        prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
    )

    # mount
    table = AssetBaseCfg(
        prim_path="{ENV_REGEX_NS}/Table",
        spawn=sim_utils.UsdFileCfg(
            usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Mounts/Stand/stand_instanceable.usd", scale=(2.0, 2.0, 2.0)
        ),
    )

    # articulation
    if args_cli.robot == "franka_panda":
        robot = FRANKA_PANDA_HIGH_PD_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
    elif args_cli.robot == "ur10":
        robot = UR10_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
    elif args_cli.robot == "ur5":
        robot = UR5_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
    elif args_cli.robot == "ur5_robotiq":
        robot = UR5_ROBOTIQ_CFG .replace(prim_path="{ENV_REGEX_NS}/Robot")
    else:
        raise ValueError(f"Robot {args_cli.robot} is not supported. Valid: franka_panda, ur10, ur5, ur5_robotiq")

    # -- Gripper
    my_gripper_cfg = MY_GRIPPER_CFG.replace(prim_path="{ENV_REGEX_NS}/my_gripper")

    robot_assembler = RobotAssembler()
    assembled_robot = robot_assembler.assemble_articulations(
        base_robot_path="{ENV_REGEX_NS}/Robot",
        attach_robot_path="{ENV_REGEX_NS}/my_gripper/l_base_link",
        base_robot_mount_frame="/tool0",
        attach_robot_mount_frame="",
        fixed_joint_offset = np.array([-0.04,-0.0, 0.0]),
        fixed_joint_orient  = np.array([1.0, -0.0, -0.0, 1.0]),
        mask_all_collisions = True,
        single_robot = False
    )

When I run the code I get the following error:

Traceback (most recent call last):
  File "/home/hri-david/Omniverse/Orbit/Santi_tests/test_ur_ik.py", line 66, in <module>
    class TableTopSceneCfg(InteractiveSceneCfg):
  File "/home/hri-david/Omniverse/Orbit/Santi_tests/test_ur_ik.py", line 106, in TableTopSceneCfg
    assembled_robot = robot_assembler.assemble_articulations(
  File "/home/hri-david/.local/share/ov/pkg/isaac_sim-2023.1.1/exts/omni.isaac.robot_assembler/omni/isaac/robot_assembler/robot_assembler.py", line 383, in assemble_articulations
    assemblage = self.assemble_rigid_bodies(
  File "/home/hri-david/.local/share/ov/pkg/isaac_sim-2023.1.1/exts/omni.isaac.robot_assembler/omni/isaac/robot_assembler/robot_assembler.py", line 314, in assemble_rigid_bodies
    XFormPrim(attach_mount_path, translation=np.array([0, 0, 0]))
  File "/home/hri-david/.local/share/ov/pkg/isaac_sim-2023.1.1/exts/omni.isaac.core/omni/isaac/core/prims/xform_prim.py", line 82, in __init__
    self._prim = define_prim(prim_path=prim_path, prim_type="Xform")
  File "/home/hri-david/.local/share/ov/pkg/isaac_sim-2023.1.1/exts/omni.isaac.core/omni/isaac/core/utils/prims.py", line 206, in define_prim
    return get_current_stage(fabric=fabric).DefinePrim(prim_path, prim_type)
pxr.Tf.ErrorException: 
    Error in 'pxrInternal_v0_22__pxrReserved__::UsdStage::_IsValidPathForCreatingPrim' at line 3340 in file /buildAgent/work/ac88d7d902b57417/USD/pxr/usd/usd/stage.cpp : 'Path must be an absolute path: <>'

Is there a way to solve this error? or get the absolute path of both robots to use the robot_assembler extension? or in any case to make the attachment during run time? (make a fixed joint somehow in a different way)

Thank you in advance!

cjoattesollo commented 1 month ago

Hi, @SantiDiazC I have the same question about this. Also, How did you import RobotAssembler from _isaac_sim with Orbit? Because I have an issue with this error.

from omni.isaac.robot_assembler import RobotAssembler
ModuleNotFoundError: No module named 'omni.isaac.robot_assembler'

Thank you in advance.

SantiDiazC commented 1 month ago

Hi, @SantiDiazC I have the same question about this. Also, How did you import RobotAssembler from _isaac_sim with Orbit? Because I have an issue with this error.

from omni.isaac.robot_assembler import RobotAssembler
ModuleNotFoundError: No module named 'omni.isaac.robot_assembler'

Thank you in advance.

Hi @cjoattesollo , To enable additional extensions from isaac sim or any other dependencies you have to add them to this file: {YOUR_ORBIT_INSTALLATION_ROOT}/Orbit/_isaac_sim/apps/omni.isaac.sim.python.kit like this (i.e at the end of the file):

# Non Isaac Sim Extensions
######################
[dependencies]
"omni.isaac.examples" = {}
"omni.syntheticdata" = {}
"semantics.schema.editor" = {}
"semantics.schema.property" = {}
"omni.replicator.core" = {}
"omni.replicator.replicator_yaml" = {}
"omni.replicator.composer" = {}
"omni.importer.mjcf" = {}
"omni.importer.urdf" = {}
"omni.isaac.robot_assembler" = {}

that will let you use the robot_assembler extension after you launch the sim app in your python script. I don't know if it works by modifying the other files like omni.isaac.sim.python.gym.kit, omni.isaac.sim.gym.kit etc. It would be fine if the developers add some information about it on the documentation (adding additional extensions).

Btw I am still working on using the robot assembler extension with the InteractiveSceneCfg class (multiple envs scene spawn), if you find a solution please tell me :)

cjoattesollo commented 1 month ago

Hi, @SantiDiazC I have the same question about this. Also, How did you import RobotAssembler from _isaac_sim with Orbit? Because I have an issue with this error.

from omni.isaac.robot_assembler import RobotAssembler
ModuleNotFoundError: No module named 'omni.isaac.robot_assembler'

Thank you in advance.

Hi @cjoattesollo , To enable additional extensions from isaac sim or any other dependencies you have to add them to this file: {YOUR_ORBIT_INSTALLATION_ROOT}/Orbit/_isaac_sim/apps/omni.isaac.sim.python.kit like this (i.e at the end of the file):

# Non Isaac Sim Extensions
######################
[dependencies]
"omni.isaac.examples" = {}
"omni.syntheticdata" = {}
"semantics.schema.editor" = {}
"semantics.schema.property" = {}
"omni.replicator.core" = {}
"omni.replicator.replicator_yaml" = {}
"omni.replicator.composer" = {}
"omni.importer.mjcf" = {}
"omni.importer.urdf" = {}
"omni.isaac.robot_assembler" = {}

that will let you use the robot_assembler extension after you launch the sim app in your python script. I don't know if it works by modifying the other files like omni.isaac.sim.python.gym.kit, omni.isaac.sim.gym.kit etc. It would be fine if the developers add some information about it on the documentation (adding additional extensions).

Btw I am still working on using the robot assembler extension with the InteractiveSceneCfg class (multiple envs scene spawn), if you find a solution please tell me :)

Hi, @SantiDiazC .

Have you solved the issue?

I tried to assemble robots added by from omni.isaac.core.utils.stage import add_reference_to_stage from Isaac sim (running in isaac lab) and It works.

usd_path_robot = "robot.usd" 
create_prim(prim_path="/World/Robot", prim_type="Xform", position=[-0.1, 0.45, 0.68])
add_reference_to_stage(usd_path_robot, "/World/Robot")

usd_path_gripper = "gripper.usd"
create_prim(prim_path="/World/Gripper", prim_type="Xform", position=[0.0, 0.0, 0.0])
add_reference_to_stage(usd_path_gripper, "/World/Gripper")

robot_assembler = RobotAssembler()
assembled_robot = robot_assembler.assemble_articulations(base_robot_path="/World/Robot",
                                                       attach_robot_path="/World/Gripper",
                                                       base_robot_mount_frame="/link_ee",
                                                       attach_robot_mount_frame="/link_m",
                                                       mask_all_collisions = True,
                                                       single_robot=False)

Thanks!

SantiDiazC commented 1 month ago

Hi @cjoattesollo , Thanks for your reply, Good to hear you can use now the robot_assembler. In my case I can also make it work in a single environment like you did but using the orbit Articulation class. However, my problem is trying to spawn multiple robots and connect them to the grippers (multiple environments to use them in a RL training for example) using the class. So far I tried modifying the path for the robot and the gripper on the robot assembler constructor, or creating the assemble just before the main process starts, but nothing seems to work so far. I don't know if you want to try something with multiple environments, so if that's the case and you find a solution please let me know! Thank you!!

SantiDiazC commented 1 month ago

I recently updated Orbit from v0.2.0 to v0.3.0 and I found the following error without changing the code: ModuleNotFoundError: No module named 'omni.isaac.robot_assembler To solve this problem for any extension you can follow this solution, that is adding:

from omni.isaac.core.utils.extensions import enable_extension
enable_extension("omni.isaac.robot_assembler")
from omni.isaac.robot_assembler import RobotAssembler, AssembledRobot

(In this case for the robot_assembler extension) I hope it helps if anyone has the same problem in the future.

sangteak601 commented 2 weeks ago

@SantiDiazC I'm also working on this. I haven't found the solution yet but at least I understand the problem you have.

The problem you were facing was because the prims are not spawned until you create environment with configuration in which you were trying to assemble robots.

In other words, you create environment like following.

env_cfg = TableTopSceneCfg()
env = ManagerBasedRLEnv(cfg=env_cfg)

The models are spawned when the second line is called. There is no prim when the first line is called. This is why you can't assemble robots in configuration class.

As a solution, I'm thinking of calling robot assembler on the reset event. With this approach, I could access the prims but now I'm getting different error which is

File "/isaac-sim/exts/omni.isaac.robot_assembler/omni/isaac/robot_assembler/robot_assembler.py", line 446, in assemble_articulations
    assemblage = self.assemble_rigid_bodies(
  File "/isaac-sim/exts/omni.isaac.robot_assembler/omni/isaac/robot_assembler/robot_assembler.py", line 377, in assemble_rigid_bodies
    self._move_obj_b_to_local_pos(
  File "/isaac-sim/exts/omni.isaac.robot_assembler/omni/isaac/robot_assembler/robot_assembler.py", line 555, in _move_obj_b_to_local_pos
    a_rot = quats_to_rot_matrices(a_orient)
  File "/isaac-sim/exts/omni.isaac.core/omni/isaac/core/utils/numpy/rotations.py", line 120, in quats_to_rot_matrices
    rot = Rotation.from_quat(q)
  File "_rotation.pyx", line 637, in scipy.spatial.transform._rotation.Rotation.from_quat
  File "_rotation.pyx", line 514, in scipy.spatial.transform._rotation.Rotation.__init__
  File "/isaac-sim/exts/omni.isaac.ml_archive/pip_prebundle/torch/_tensor.py", line 1064, in __array__
    return self.numpy().astype(dtype, copy=False)
TypeError: can't convert cuda:0 device type tensor to numpy. Use Tensor.cpu() to copy the tensor to host memory first.

I will give an update, if I find anything more.

sangteak601 commented 2 weeks ago

I have delved into this issue further, and these are my conclusions. Hope this helps anyone who has similar issues.

  1. robot assembler extension crashes with backend="torch" Since Isaac Lab supports only torch for the backend, the robot assembler is not working properly at the moment. I think this is a bug so I've created a post on the forum with a comment explaining how to fix it temporarily. If you want to use the extension, you will have to modify robot_assembler.py by yourself.

  2. robot assembler can be used with DirectRLEnv only In my understanding, there is no way to use the robot assembler with ManagerBasedRLEnv. As I mentioned in above comment, calling the robot assembler in the config class is not working since the prims are not spawned yet. The solution I thought of was using it on the reset event, but this is also not possible. This is because changing the root position during runtime is not possible with cuda device. This is explained here.

After fixing the bug with extension, I was able to use robot assembler in _setup_scene method of DirectRLEnv.

In summary, there is no way to use robot assembler in Isaac Lab at the moment because of bug in Isaac Sim itself. You can fix it by modifying the extension code. In that case, you have to call robot assembler in _setup_scene method of DirectRLEnv

SantiDiazC commented 3 days ago

@sangteak601 Thanks for your comments on this, they helped me a lot! As you mention my problem was the InteractiveSceneCfg doesn't spawn the robots so that's the reason I couldn't use the extension, and a similar case using the ManagerBasedRLEnv (config class). On the other hand by fixing the bug on the robot_assembler extension I was able to use it by using the DirectRLEnv instead as you suggested. So as a reference I want to share how to use the extension with the DirectRLEnv:

First define the robots in the EnvConfig class:

@configclass
class MyRobotEnvCfg(DirectRLEnvCfg):
    # env
    episode_length_s = 8.3333  # 500 timesteps
    decimation = 2
    num_actions = 6
    num_observations = 23
    num_states = 0

    # simulation
    sim: SimulationCfg = SimulationCfg(
        dt=1 / 120,
        render_interval=decimation,
        disable_contact_processing=True,
        physics_material=sim_utils.RigidBodyMaterialCfg(
            friction_combine_mode="multiply",
            restitution_combine_mode="multiply",
            static_friction=1.0,
            dynamic_friction=1.0,
            restitution=0.0,
        ),
    )

    # scene
    scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=4096, env_spacing=3.0, replicate_physics=True)

    # robot
    robot = ArticulationCfg(
        prim_path="/World/envs/env_.*/Robot",
        spawn=sim_utils.UsdFileCfg(
            usd_path= get_assets_root_path() + "/Isaac/Robots/UniversalRobots/ur5/ur5.usd",
            activate_contact_sensors=False,
            rigid_props=sim_utils.RigidBodyPropertiesCfg(
                disable_gravity=False,
                max_depenetration_velocity=5.0,
            ),
            articulation_props=sim_utils.ArticulationRootPropertiesCfg(
               enabled_self_collisions=True, solver_position_iteration_count=12, solver_velocity_iteration_count=1
            ),
        ),
        init_state=ArticulationCfg.InitialStateCfg(
            joint_pos={
                "shoulder_pan_joint": 0.0,
                "shoulder_lift_joint": -1.712,
                "elbow_joint": 1.712,
                "wrist_1_joint": 0.0,
                "wrist_2_joint": 0.0,
                "wrist_3_joint": 0.0,
            },
            pos=(1.0, 0.0, 0.0),
            rot=(0.0, 0.0, 0.0, 1.0),
        ),
        actuators={
            "arm": ImplicitActuatorCfg(
                joint_names_expr=[".*"],
                velocity_limit= None, 
                effort_limit= None, 
                stiffness= None, 
                damping=  None, 
            ),
        },
    )

Then use the robot_assembler extension inside the _setup_scene method:

class MyRobotEnv(DirectRLEnv):
    # pre-physics step calls
    #   |-- _pre_physics_step(action)
    #   |-- _apply_action()
    # post-physics step calls
    #   |-- _get_dones()
    #   |-- _get_rewards()
    #   |-- _reset_idx(env_ids)
    #   |-- _get_observations()

    cfg: MyRobotEnvCfg

    def __init__(self, cfg: MyRobotEnvCfg, render_mode: str | None = None, **kwargs):
        super().__init__(cfg, render_mode, **kwargs)
    #
    #    
    def _setup_scene(self):
        self._robot = Articulation(self.cfg.robot)
        self._gripper= Articulation(self.cfg.gripper)
        self.scene.articulations["Robot"] = self._robot

        self.scene.articulations["gripper"] = self._gripper
        print("num envs: ", self.scene.cfg.num_envs)

        for env in range(self.scene.cfg.num_envs):
            robot_assembler = RobotAssembler()
            _ = robot_assembler.assemble_articulations(
                base_robot_path="/World/envs/env_"+str(env)+"/Robot",
                attach_robot_path="/World/envs/env_"+str(env)+"/gripper/gripper_base_link",
                base_robot_mount_frame="/tool0",
                attach_robot_mount_frame="",
                fixed_joint_offset = np.array([-0.04,-0.0, 0.0]),
                fixed_joint_orient  = np.array([1.0, -0.0, -0.0, 1.0]),
                mask_all_collisions = True,
                single_robot = False
            )

I don't know why but when setting the robot assembler like this (which works without using the DirectRLEnv):

attach_robot_path="/World/envs/env_"+str(env)+"/gripper",
attach_robot_mount_frame="gripper_base_link",

so I have to changed it to:

attach_robot_path="/World/envs/env_"+str(env)+"/gripper/gripper_base_link",
attach_robot_mount_frame="",

So In summary I can confirm the extension works with the DirectRLEnv by fixing the bug and using it inside the _setup_scene method. however it would be nice if there is a way to use it with the ManagerBasedRLEnv, so If someone come up with a solution it will be benefitial for many applications I think.

Again thanks a lot @sangteak601