[Bug] Urdf import not working
Describe the bug
My code to import an URDF file into my DirectRLEnvCfg stopped working with the new IsaacSim update.
Steps to reproduce
This is my code:
@configclass
class Go2EnvCfg(DirectRLEnvCfg):
#* Simulation
sim: SimulationCfg = SimulationCfg(
dt=1 / 200,
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,
),
)
#* Terrain
terrain = TerrainImporterCfg(
prim_path="/World/ground",
terrain_type="plane",
collision_group=-1,
physics_material=sim_utils.RigidBodyMaterialCfg(
friction_combine_mode="multiply",
restitution_combine_mode="multiply",
static_friction=1.0,
dynamic_friction=1.0,
restitution=0.0,
),
debug_vis=False,
)
#* Scene
scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=4096, env_spacing=5.0, replicate_physics=False)
#* Robot
robot = ArticulationCfg(
prim_path="/World/envs/env_.*/Robot",
spawn=sim_utils.UrdfFileCfg(
asset_path="source/thesis/resources/go2_manip_description/urdf/go2_manip_comb.urdf",
usd_dir=f"source/thesis/resources/go2_manip_description/usd",
usd_file_name="go2_manip_exported",
fix_base=False,
force_usd_conversion=True,
activate_contact_sensors=True,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
retain_accelerations=False,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=1000.0,
max_depenetration_velocity=1.0,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=0
),
joint_drive=UrdfConverterCfg.JointDriveCfg(
gains=UrdfConverterCfg.JointDriveCfg.PDGainsCfg(stiffness=None, damping=None) #stiffness=100.0, damping=1.0
),
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 0.4),
joint_pos={
".*L_hip_joint": 0.1,
".*R_hip_joint": -0.1,
"F[L,R]_thigh_joint": 0.8,
"R[L,R]_thigh_joint": 1.0,
".*_calf_joint": -1.5,
"joint_connector_gripper": 0.0,
},
joint_vel={".*": 0.0},
),
soft_joint_pos_limit_factor=0.9,
actuators={
"base_legs": DCMotorCfg(
joint_names_expr=[".*_hip_joint", ".*_thigh_joint", ".*_calf_joint"],
effort_limit=23.5,
saturation_effort=23.5,
velocity_limit=30.0,
stiffness=25.0,
damping=0.5,
friction=0.0,
),
# TODO: get real attribute information
"base_arm": DCMotorCfg(
joint_names_expr=["joint_connector_gripper"],
effort_limit=5.0,
saturation_effort=5.0,
velocity_limit=10.0,
stiffness=3.0,
damping=0.5,
friction=0.0,
),
},
)
Error Code (added printing statements to "sim.schemas.schemas.py activate_contact_sensors-function" to understand the prims and it looks like only one prim of the robot is detected):
2025-01-31 06:10:44 [8,121ms] [Warning] [omni.usd] Warning: in _ReportErrors at line 2890 of /builds/omniverse/usd-ci/USD/pxr/usd/usd/stage.cpp -- In </World/envs/env_0/Robot>: Could not open asset @configuration/go2_manip_exported_physics.usd@ for payload introduced by @source/thesis/resources/go2_manip_description/usd/go2_manip_exported.usd@</go_manip_description{Physics=PhysX}>. (recomposing stage on stage @anon:0x25529420:World0.usd@ <0x28175460>)
2025-01-31 06:10:44 [8,121ms] [Warning] [omni.usd] Warning: in _ReportErrors at line 2890 of /builds/omniverse/usd-ci/USD/pxr/usd/usd/stage.cpp -- In </World/envs/env_0/Robot>: Could not open asset @configuration/go2_manip_exported_sensor.usd@ for payload introduced by @source/thesis/resources/go2_manip_description/usd/go2_manip_exported.usd@</go_manip_description{Sensor=Sensors}>. (recomposing stage on stage @anon:0x25529420:World0.usd@ <0x28175460>)
2025-01-31 06:10:44 [8,162ms] [Warning] [isaaclab.sim.utils] Could not perform 'modify_rigid_body_properties' on any prims under: '/World/envs/env_0/Robot'. This might be because of the following reasons:
(1) The desired attribute does not exist on any of the prims.
(2) The desired attribute exists on an instanced prim.
Discovered list of instanced prim paths: []
2025-01-31 06:10:44 [8,162ms] [Warning] [isaaclab.sim.utils] Could not perform 'modify_articulation_root_properties' on any prims under: '/World/envs/env_0/Robot'. This might be because of the following reasons:
(1) The desired attribute does not exist on any of the prims.
(2) The desired attribute exists on an instanced prim.
Discovered list of instanced prim paths: []
['/World/envs/env_0/Robot', '/World/envs/env_1/Robot', '/World/envs/env_2/Robot', '/World/envs/env_3/Robot']
all_prims: [Usd.Prim(</World/envs/env_0/Robot>)]
child_prim: []
[INFO]: Time taken for scene creation : 0.773408 seconds
Error executing job with overrides: []
Traceback (most recent call last):
File "/home/yannick/IsaacLab/source/isaaclab_tasks/isaaclab_tasks/utils/hydra.py", line 101, in hydra_main
func(env_cfg, agent_cfg, *args, **kwargs)
File "/home/yannick/IsaacLab/scripts/reinforcement_learning/rsl_rl/train.py", line 105, in main
env = gym.make(args_cli.task, cfg=env_cfg, render_mode="rgb_array" if args_cli.video else None)
File "/home/yannick/anaconda3/envs/isaaclab_new/lib/python3.10/site-packages/gymnasium/envs/registration.py", line 740, in make
env = env_creator(**env_spec_kwargs)
File "/home/yannick/IsaacLab/source/thesis/thesis/quadruped_direct/go2_env.py", line 27, in __init__
super().__init__(cfg, render_mode, **kwargs)
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/envs/direct_rl_env.py", line 123, in __init__
self._setup_scene()
File "/home/yannick/IsaacLab/source/thesis/thesis/quadruped_direct/go2_env.py", line 106, in _setup_scene
self._robot = Articulation(self.cfg.robot)
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/assets/articulation/articulation.py", line 99, in __init__
super().__init__(cfg)
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/assets/asset_base.py", line 77, in __init__
self.cfg.spawn.func(
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/sim/utils.py", line 277, in wrapper
schemas.activate_contact_sensors(prim_paths[0], cfg.activate_contact_sensors)
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/sim/schemas/schemas.py", line 519, in activate_contact_sensors
raise ValueError(
ValueError: No contact sensors added to the prim: '/World/envs/env_0/Robot'. This means that no rigid bodies are present under this prim. Please check the prim path.
I also tried to import the URDF into IsaacSim using the UI and saw that now also some "configurations"-folder is created in the USD export folder. When visualising the different configurations I found out that "_base" and "_physics" are visualized normally but the "_sensors" looks empty.
System Info
Describe the characteristic of your environment:
- Commit: 157a19e
- Isaac Sim Version: 4.5.0.0
- OS: Ubuntu 22.04.5 LTS
- GPU: RTX 3090
- CUDA: 12.4
- GPU Driver: 550.120
Thank you for your help =)
Thank you for posting this. We'll take a look.
I think it is a more general problem. I am also trying to spawn an USD object which I imported from a stl-file and I get a similar error:
['/World/envs/env_0/bin_small', '/World/envs/env_1/bin_small', '/World/envs/env_2/bin_small', '/World/envs/env_3/bin_small']
2025-02-01 00:12:03 [8,679ms] [Warning] [isaaclab.sim.utils] Could not perform 'modify_rigid_body_properties' on any prims under: '/World/envs/env_0/bin_big'. This might be because of the following reasons:
(1) The desired attribute does not exist on any of the prims.
(2) The desired attribute exists on an instanced prim.
Discovered list of instanced prim paths: []
['/World/envs/env_0/bin_big', '/World/envs/env_1/bin_big', '/World/envs/env_2/bin_big', '/World/envs/env_3/bin_big']
['/World/ground/physicsMaterial']
['/World/Light']
['/World/Markers/marker_bin_small/sphere/geometry/material']
['/World/Markers/marker_bin_small/sphere']
['/World/Markers/marker_bin_big/sphere/geometry/material']
['/World/Markers/marker_bin_big/sphere']
2025-02-01 00:12:03 [8,995ms] [Warning] [isaaclab.scene.interactive_scene] Collision filtering can only be automatically enabled when replicate_physics=True. Please call scene.filter_collisions(global_prim_paths) to filter collisions across environments.
[INFO]: Time taken for scene creation : 1.794014 seconds
[INFO]: Scene manager: <class InteractiveScene>
Number of environments: 4
Environment spacing : 5.0
Source prim name : /World/envs/env_0
Global prim paths : ['/World/ground']
Replicate physics : False
[INFO]: Starting the simulation. This may take a few seconds. Please wait...
Traceback (most recent call last):
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/assets/asset_base.py", line 94, in <lambda>
lambda event, obj=weakref.proxy(self): obj._initialize_callback(event),
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/assets/asset_base.py", line 265, in _initialize_callback
self._initialize_impl()
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/assets/rigid_object/rigid_object.py", line 417, in _initialize_impl
raise RuntimeError(
RuntimeError: Failed to find a rigid body when resolving '/World/envs/env_.*/bin_small'. Please ensure that the prim has 'USD RigidBodyAPI' applied.
Traceback (most recent call last):
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/assets/asset_base.py", line 94, in <lambda>
lambda event, obj=weakref.proxy(self): obj._initialize_callback(event),
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/assets/asset_base.py", line 265, in _initialize_callback
self._initialize_impl()
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/assets/rigid_object/rigid_object.py", line 417, in _initialize_impl
raise RuntimeError(
RuntimeError: Failed to find a rigid body when resolving '/World/envs/env_.*/bin_big'. Please ensure that the prim has 'USD RigidBodyAPI' applied.
2025-02-01 00:12:05 [10,592ms] [Warning] [omni.hydra.scene_delegate.plugin] Calling getBypassRenderSkelMeshProcessing for prim /World/envs/env_0/Robot/FR_thigh/visuals.proto_mesh_1_id1 that has not been populated
[INFO]: Time taken for simulation start : 1.759270 seconds
[INFO] Event Manager: <EventManager> contains 2 active terms.
+--------------------------------------+
| Active Event Terms in Mode: 'startup' |
+----------+---------------------------+
| Index | Name |
+----------+---------------------------+
| 0 | physics_material |
| 1 | add_base_mass |
+----------+---------------------------+
+-------------------------------------+
| Active Event Terms in Mode: 'reset' |
+---------+---------------------------+
| Index | Name |
+---------+---------------------------+
| 0 | reset_robot_base |
| 1 | reset_bin_small |
| 2 | reset_bin_big |
| 3 | reset_robot_joints |
+---------+---------------------------+
Creating window for environment.
ManagerLiveVisualizer cannot be created for manager: action_manager, Manager does not exist
ManagerLiveVisualizer cannot be created for manager: observation_manager, Manager does not exist
[INFO]: Completed setting up the environment...
> Target link 'grasping_point_link' at id 0
Error executing job with overrides: []
Traceback (most recent call last):
File "/home/yannick/IsaacLab/source/isaaclab_tasks/isaaclab_tasks/utils/hydra.py", line 101, in hydra_main
func(env_cfg, agent_cfg, *args, **kwargs)
File "/home/yannick/IsaacLab/scripts/reinforcement_learning/rsl_rl/train.py", line 129, in main
env = RslRlVecEnvWrapper(env)
File "/home/yannick/IsaacLab/source/isaaclab_rl/isaaclab_rl/rsl_rl/vecenv_wrapper.py", line 89, in __init__
self.env.reset()
File "/home/yannick/anaconda3/envs/isaaclab_new/lib/python3.10/site-packages/gymnasium/wrappers/common.py", line 400, in reset
return super().reset(seed=seed, options=options)
File "/home/yannick/anaconda3/envs/isaaclab_new/lib/python3.10/site-packages/gymnasium/core.py", line 328, in reset
return self.env.reset(seed=seed, options=options)
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/envs/direct_rl_env.py", line 275, in reset
self._reset_idx(indices)
File "/home/yannick/IsaacLab/source/thesis/thesis/quadruped_direct/go2_env.py", line 371, in _reset_idx
super()._reset_idx(env_ids) # type: ignore
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/envs/direct_rl_env.py", line 565, in _reset_idx
self.scene.reset(env_ids)
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/scene/interactive_scene.py", line 425, in reset
rigid_object.reset(env_ids)
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/assets/rigid_object/rigid_object.py", line 103, in reset
self._external_force_b[env_ids] = 0.0
AttributeError: 'RigidObject' object has no attribute '_external_force_b'
Hi @YannickP99 and @RandomOakForest, I also met this issue and would like to kindly ask if you have fixed it?
Hey @linchangyi1, unfortunately I wasnt able to fix it so I migrated back to the previous version
Thanks for your reply @YannickP99
@RandomOakForest Could you please take a look at this bug~ Thanks a lot!
It seems this bug was reported (https://github.com/isaac-sim/IsaacLab/issues/1536) last year
Oh okay. I am using commit ea766783 from the 27th January and my code is working fine.
Are you able to share the URDF file you are having issues with? It could be the new URDF importer had some modifications in the paths where the schemas are being applied to.
yes sure here is the urdf. In case you need the whole folder, i can share it with you too,
<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by
Stephen Brawner ([email protected])
Commit Version: 1.6.0-4-g7f85cfe Build Version: 1.6.7995.38578
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot name="go_manip_description">
<link name="base">
<inertial>
<origin xyz="0.021112 0 -0.005366" rpy="0 0 0" />
<mass value="6.921" />
<inertia ixx="0.02448" ixy="0.00012166" ixz="0.0014849" iyy="0.098077" iyz="-3.12E-05" izz="0.107" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="../dae/base.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<box size="0.3762 0.0935 0.114" />
</geometry>
</collision>
</link>
<link name="Head_upper">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0.001" />
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06" />
</inertial>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<cylinder radius="0.05" length="0.09" />
</geometry>
</collision>
</link>
<joint name="Head_upper_joint" type="fixed" dont_collapse="true">
<origin xyz="0.285 0 0.01" rpy="0 0 0" />
<parent link="base" />
<child link="Head_upper" />
<axis xyz="1 0 0" />
</joint>
<!-- <link name="Head_lower">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0.001" />
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06" />
</inertial>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<sphere radius="0.047" />
</geometry>
</collision>
</link>
<joint name="Head_lower_joint"
type="fixed" dont_collapse="true">
<origin xyz="0.008 0 -0.07" rpy="0 0 0" />
<parent link="Head_upper" />
<child link="Head_lower" />
<axis xyz="1 0 0" />
</joint> -->
<link name="FL_hip">
<inertial>
<origin xyz="-0.0054 0.00194 -0.000105" rpy="0 0 0" />
<mass value="0.678" />
<inertia ixx="0.00048" ixy="-3.01E-06" ixz="1.11E-06" iyy="0.000884" iyz="-1.42E-06" izz="0.000596" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="../dae/hip.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0.08 0" />
<geometry>
<cylinder length="0.04" radius="0.046" />
</geometry>
</collision>
</link>
<joint name="FL_hip_joint"
type="revolute">
<origin xyz="0.1934 0.0465 0" rpy="0 0 0" />
<parent link="base" />
<child link="FL_hip" />
<axis xyz="1 0 0" />
<limit lower="-1.0472" upper="1.0472" effort="23.7" velocity="30.1" />
</joint>
<link name="FL_thigh">
<inertial>
<origin xyz="-0.00374 -0.0223 -0.0327" rpy="0 0 0" />
<mass value="1.152" />
<inertia ixx="0.00584" ixy="8.72E-05" ixz="-0.000289" iyy="0.0058" iyz="0.000808" izz="0.00103" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="../dae/thigh.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065" />
<geometry>
<box size="0.213 0.0245 0.034" />
</geometry>
</collision>
</link>
<joint name="FL_thigh_joint"
type="revolute">
<origin xyz="0 0.0955 0" rpy="0 0 0" />
<parent link="FL_hip" />
<child link="FL_thigh" />
<axis xyz="0 1 0" />
<limit lower="-1.5708" upper="3.4907" effort="23.7" velocity="30.1" />
</joint>
<link name="FL_calf">
<inertial>
<origin xyz="0.00548 -0.000975 -0.115" rpy="0 0 0" />
<mass value="0.154" />
<inertia ixx="0.00108" ixy="3.4E-07" ixz="1.72E-05" iyy="0.0011" iyz="8.28E-06" izz="3.29E-05" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="../dae/calf.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 -0.21 0" xyz="0.008 0 -0.06" />
<geometry>
<cylinder length="0.12" radius="0.012" />
</geometry>
</collision>
</link>
<joint name="FL_calf_joint"
type="revolute">
<origin xyz="0 0 -0.213" rpy="0 0 0" />
<parent link="FL_thigh" />
<child link="FL_calf" />
<axis xyz="0 1 0" />
<limit lower="-2.7227" upper="-0.83776" effort="45.43" velocity="15.70" />
</joint>
<link name="FL_calflower">
<collision>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<cylinder length="0.065" radius="0.011" />
</geometry>
</collision>
</link>
<joint name="FL_calflower_joint"
type="fixed">
<origin xyz="0.020 0 -0.148" rpy="0 0.05 0" />
<parent link="FL_calf" />
<child link="FL_calflower" />
<axis xyz="1 0 0" />
</joint>
<link name="FL_calflower1">
<collision>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<cylinder length="0.03" radius="0.0155" />
</geometry>
</collision>
</link>
<joint name="FL_calflower1_joint"
type="fixed">
<origin xyz="-0.01 0 -0.04" rpy="0 0.48 0" />
<parent link="FL_calflower" />
<child link="FL_calflower1" />
<axis xyz="1 0 0" />
</joint>
<link name="FL_foot">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0.04" />
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="../dae/foot.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.002 0 0" />
<geometry>
<sphere radius="0.022" />
</geometry>
</collision>
</link>
<joint name="FL_foot_joint"
type="fixed" dont_collapse="true">
<origin xyz="0 0 -0.213" rpy="0 0 0" />
<parent link="FL_calf" />
<child link="FL_foot" />
<axis xyz="1 0 0" />
</joint>
<link name="FR_hip">
<inertial>
<origin xyz="-0.0054 -0.00194 -0.000105" rpy="0 0 0" />
<mass value="0.678" />
<inertia ixx="0.00048" ixy="3.01E-06" ixz="1.11E-06" iyy="0.000884" iyz="1.42E-06" izz="0.000596" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="3.1415 0 0" />
<geometry>
<mesh filename="../dae/hip.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.08 0" />
<geometry>
<cylinder length="0.04" radius="0.046" />
</geometry>
</collision>
</link>
<joint name="FR_hip_joint" type="revolute">
<origin xyz="0.1934 -0.0465 0" rpy="0 0 0" />
<parent link="base" />
<child link="FR_hip" />
<axis xyz="1 0 0" />
<limit lower="-1.0472" upper="1.0472" effort="23.7" velocity="30.1" />
</joint>
<link name="FR_thigh">
<inertial>
<origin xyz="-0.00374 0.0223 -0.0327" rpy="0 0 0" />
<mass value="1.152" />
<inertia ixx="0.00584" ixy="-8.72E-05" ixz="-0.000289" iyy="0.0058" iyz="-0.000808" izz="0.00103" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="../dae/thigh_mirror.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065" />
<geometry>
<box size="0.213 0.0245 0.034" />
</geometry>
</collision>
</link>
<joint name="FR_thigh_joint" type="revolute">
<origin xyz="0 -0.0955 0" rpy="0 0 0" />
<parent link="FR_hip" />
<child link="FR_thigh" />
<axis xyz="0 1 0" />
<limit lower="-1.5708" upper="3.4907" effort="23.7" velocity="30.1" />
</joint>
<link name="FR_calf">
<inertial>
<origin xyz="0.00548 0.000975 -0.115" rpy="0 0 0" />
<mass value="0.154" />
<inertia ixx="0.00108" ixy="-3.4E-07" ixz="1.72E-05" iyy="0.0011" iyz="-8.28E-06" izz="3.29E-05" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="../dae/calf_mirror.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 -0.2 0" xyz="0.01 0 -0.06" />
<geometry>
<cylinder length="0.12" radius="0.013" />
</geometry>
</collision>
</link>
<joint name="FR_calf_joint" type="revolute">
<origin xyz="0 0 -0.213" rpy="0 0 0" />
<parent link="FR_thigh" />
<child link="FR_calf" />
<axis xyz="0 1 0" />
<limit lower="-2.7227" upper="-0.83776" effort="45.43" velocity="15.70" />
</joint>
<link name="FR_calflower">
<collision>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<cylinder length="0.065" radius="0.011" />
</geometry>
</collision>
</link>
<joint name="FR_calflower_joint" type="fixed">
<origin xyz="0.020 0 -0.148" rpy="0 0.05 0" />
<parent link="FR_calf" />
<child link="FR_calflower" />
<axis xyz="1 0 0" />
</joint>
<link name="FR_calflower1">
<collision>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<cylinder length="0.03" radius="0.0155" />
</geometry>
</collision>
</link>
<joint name="FR_calflower1_joint"
type="fixed">
<origin xyz="-0.01 0 -0.04" rpy="0 0.48 0" />
<parent link="FR_calflower" />
<child link="FR_calflower1" />
<axis xyz="1 0 0" />
</joint>
<link name="FR_foot">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0.04" />
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="../dae/foot.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.002 0 0" />
<geometry>
<sphere radius="0.022" />
</geometry>
</collision>
</link>
<joint name="FR_foot_joint"
type="fixed" dont_collapse="true">
<origin xyz="0 0 -0.213" rpy="0 0 0" />
<parent link="FR_calf" />
<child link="FR_foot" />
<axis xyz="1 0 0" />
</joint>
<link name="RL_hip">
<inertial>
<origin xyz="0.0054 0.00194 -0.000105" rpy="0 0 0" />
<mass value="0.678" />
<inertia ixx="0.00048" ixy="3.01E-06" ixz="-1.11E-06" iyy="0.000884" iyz="-1.42E-06" izz="0.000596" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 3.1415 0" />
<geometry>
<mesh filename="../dae/hip.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0.08 0" />
<geometry>
<cylinder length="0.04" radius="0.046" />
</geometry>
</collision>
</link>
<joint name="RL_hip_joint"
type="revolute">
<origin xyz="-0.1934 0.0465 0" rpy="0 0 0" />
<parent link="base" />
<child link="RL_hip" />
<axis xyz="1 0 0" />
<limit lower="-1.0472" upper="1.0472" effort="23.7" velocity="30.1" />
</joint>
<link name="RL_thigh">
<inertial>
<origin xyz="-0.00374 -0.0223 -0.0327" rpy="0 0 0" />
<mass value="1.152" />
<inertia ixx="0.00584" ixy="8.72E-05" ixz="-0.000289" iyy="0.0058" iyz="0.000808" izz="0.00103" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="../dae/thigh.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065" />
<geometry>
<box size="0.213 0.0245 0.034" />
</geometry>
</collision>
</link>
<joint name="RL_thigh_joint"
type="revolute">
<origin xyz="0 0.0955 0" rpy="0 0 0" />
<parent link="RL_hip" />
<child link="RL_thigh" />
<axis xyz="0 1 0" />
<limit lower="-0.5236" upper="4.5379" effort="23.7" velocity="30.1" />
</joint>
<link name="RL_calf">
<inertial>
<origin xyz="0.00548 -0.000975 -0.115" rpy="0 0 0" />
<mass value="0.154" />
<inertia ixx="0.00108" ixy="3.4E-07" ixz="1.72E-05" iyy="0.0011" iyz="8.28E-06" izz="3.29E-05" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="../dae/calf.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 -0.2 0" xyz="0.01 0 -0.06" />
<geometry>
<cylinder length="0.12" radius="0.013" />
</geometry>
</collision>
</link>
<joint name="RL_calf_joint"
type="revolute">
<origin xyz="0 0 -0.213" rpy="0 0 0" />
<parent link="RL_thigh" />
<child link="RL_calf" />
<axis xyz="0 1 0" />
<limit lower="-2.7227" upper="-0.83776" effort="45.43" velocity="15.70" />
</joint>
<link name="RL_calflower">
<collision>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<cylinder length="0.065" radius="0.011" />
</geometry>
</collision>
</link>
<joint name="RL_calflower_joint"
type="fixed">
<origin xyz="0.020 0 -0.148" rpy="0 0.05 0" />
<parent link="RL_calf" />
<child link="RL_calflower" />
<axis xyz="1 0 0" />
</joint>
<link name="RL_calflower1">
<collision>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<cylinder length="0.03" radius="0.0155" />
</geometry>
</collision>
</link>
<joint name="RL_calflower1_joint"
type="fixed">
<origin xyz="-0.01 0 -0.04" rpy="0 0.48 0" />
<parent link="RL_calflower" />
<child link="RL_calflower1" />
<axis xyz="1 0 0" />
</joint>
<link name="RL_foot">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0.04" />
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="../dae/foot.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.002 0 0" />
<geometry>
<sphere radius="0.022" />
</geometry>
</collision>
</link>
<joint name="RL_foot_joint"
type="fixed" dont_collapse="true">
<origin xyz="0 0 -0.213" rpy="0 0 0" />
<parent link="RL_calf" />
<child link="RL_foot" />
<axis xyz="1 0 0" />
</joint>
<link name="RR_hip">
<inertial>
<origin xyz="0.0054 -0.00194 -0.000105" rpy="0 0 0" />
<mass value="0.678" />
<inertia ixx="0.00048" ixy="-3.01E-06" ixz="-1.11E-06" iyy="0.000884" iyz="1.42E-06" izz="0.000596" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="3.1415 3.1415 0" />
<geometry>
<mesh filename="../dae/hip.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.08 0" />
<geometry>
<cylinder length="0.04" radius="0.046" />
</geometry>
</collision>
</link>
<joint name="RR_hip_joint"
type="revolute">
<origin xyz="-0.1934 -0.0465 0" rpy="0 0 0" />
<parent link="base" />
<child link="RR_hip" />
<axis xyz="1 0 0" />
<limit lower="-1.0472" upper="1.0472" effort="23.7" velocity="30.1" />
</joint>
<link name="RR_thigh">
<inertial>
<origin xyz="-0.00374 0.0223 -0.0327" rpy="0 0 0" />
<mass value="1.152" />
<inertia ixx="0.00584" ixy="-8.72E-05" ixz="-0.000289" iyy="0.0058" iyz="-0.000808" izz="0.00103" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="../dae/thigh_mirror.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065" />
<geometry>
<box size="0.213 0.0245 0.034" />
</geometry>
</collision>
</link>
<joint name="RR_thigh_joint"
type="revolute">
<origin xyz="0 -0.0955 0" rpy="0 0 0" />
<parent link="RR_hip" />
<child link="RR_thigh" />
<axis xyz="0 1 0" />
<limit lower="-0.5236" upper="4.5379" effort="23.7" velocity="30.1" />
</joint>
<link name="RR_calf">
<inertial>
<origin xyz="0.00548 0.000975 -0.115" rpy="0 0 0" />
<mass value="0.154" />
<inertia ixx="0.00108" ixy="-3.4E-07" ixz="1.72E-05" iyy="0.0011" iyz="-8.28E-06" izz="3.29E-05" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="../dae/calf_mirror.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 -0.2 0" xyz="0.01 0 -0.06" />
<geometry>
<cylinder length="0.12" radius="0.013" />
</geometry>
</collision>
</link>
<joint name="RR_calf_joint"
type="revolute">
<origin xyz="0 0 -0.213" rpy="0 0 0" />
<parent link="RR_thigh" />
<child link="RR_calf" />
<axis xyz="0 1 0" />
<limit lower="-2.7227" upper="-0.83776" effort="45.43" velocity="15.70" />
</joint>
<link name="RR_calflower">
<collision>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<cylinder length="0.065" radius="0.011" />
</geometry>
</collision>
</link>
<joint name="RR_calflower_joint"
type="fixed">
<origin xyz="0.020 0 -0.148" rpy="0 0.05 0" />
<parent link="RR_calf" />
<child link="RR_calflower" />
<axis xyz="1 0 0" />
</joint>
<link name="RR_calflower1">
<collision>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<cylinder length="0.03" radius="0.0155" />
</geometry>
</collision>
</link>
<joint name="RR_calflower1_joint"
type="fixed">
<origin xyz="-0.01 0 -0.04" rpy="0 0.48 0" />
<parent link="RR_calflower" />
<child link="RR_calflower1" />
<axis xyz="1 0 0" />
</joint>
<link name="RR_foot">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0.04" />
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="../dae/foot.dae" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.002 0 0" />
<geometry>
<sphere radius="0.022" />
</geometry>
</collision>
</link>
<joint name="RR_foot_joint"
type="fixed" dont_collapse="true">
<origin xyz="0 0 -0.213" rpy="0 0 0" />
<parent link="RR_calf" />
<child link="RR_foot" />
<axis xyz="1 0 0" />
</joint>
<!-- <link name="imu">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0" />
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
</inertial>
</link>
<joint name="imu_joint"
type="fixed">
<origin xyz="-0.02557 0 0.04232" rpy="0 0 0" />
<parent link="base" />
<child link="imu" />
<axis xyz="1 0 0" />
</joint> -->
<link name="connector_link2">
<inertial>
<mass value="0.186" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="2125853e-9" ixy="-1715628e-9" ixz="2594205e-9" iyy="6703760e-9" iyz="-871254e-9" izz="5887880e-9" />
</inertial>
<visual>
<origin xyz="-0.056 -0.0157 -0.15" rpy="0 -1.065 -1.5708" />
<geometry>
<mesh filename="../meshes/connector_link2.STL" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 -0.03" rpy="0 0 0" />
<geometry>
<box size="0.04 0.09 0.18" />
</geometry>
</collision>
</link>
<joint name="connector_joint"
type="fixed" dont_collapse="true">
<origin xyz="0.015 0 -0.072" rpy="0 -1.8326 0" />
<parent link="Head_upper" />
<child link="connector_link2" />
<axis xyz="1 0 0" />
</joint>
<link name="link3_gripper">
<inertial>
<mass value="0.141" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="3945827e-09" ixy="-2286749e-09" ixz="6485986e-09" iyy="15759186e-09" iyz="-1198773e-09" izz="12799466e-09" />
</inertial>
<visual>
<origin xyz="-0.05 -0.05 0.037" rpy="0 1.571 0" />
<geometry>
<mesh filename="../meshes/Link3_gripper.STL" scale="0.001 0.001 0.001" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin xyz="0.008 0.085 0" rpy="0 0 0" />
<geometry>
<box size="0.04 0.17 0.07265" />
</geometry>
</collision>
<collision>
<origin xyz="-0.032 0.09 0" rpy="0 0 0" />
<geometry>
<box size="0.04 0.025 0.055" />
</geometry>
</collision>
</link>
<joint name="joint_connector_gripper" type="revolute">
<origin xyz="0 0 -0.113" rpy="-1.571 0 0" />
<parent link="connector_link2" />
<child link="link3_gripper" />
<axis xyz="0 0 -1" />
<limit lower="-1.571" upper="1.571" effort="5" velocity="30.1" />
</joint>
<link name="grasping_point_link">
<inertial>
<mass value="0.00001" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.1e-09" ixy="0.0" ixz="0.0" iyy="0.1e-09" iyz="0.0" izz="0.1e-09" />
</inertial>
<!-- <visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="0.001"/>
</geometry>
<material name="">
<color rgba="1 0 0 1" />
</material>
</visual> -->
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<empty/>
</geometry>
</collision>
</link>
<joint name="joint_grasping_point" type="fixed">
<parent link="link3_gripper"/>
<child link="grasping_point_link"/>
<origin xyz="-0.005 0.163 0" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<limit lower="0" upper="0" />
</joint>
</robot>
Here is the whole folder containing all mesh files go2_manip_description.zip
@kellyguo11 I suspect that the issue in the URDF converter mentioned here (https://github.com/isaac-sim/IsaacLab/issues/1800) likely causes the following problem when processing the USD in IsaacLab.
I have a similar issue. I just ran the conversion script that returned the following error:
2025-02-10 09:10:08 [36,489ms] [Error] [omni.kit.commands.command] Failed to execute a command: URDFImportRobot.
File "/home/myname/isaac-lab-workspace/IsaacLab/scripts/tools/convert_urdf.py", line 134, in <module>
main()
File "/home/myname/isaac-lab-workspace/IsaacLab/scripts/tools/convert_urdf.py", line 104, in main
urdf_converter = UrdfConverter(urdf_converter_cfg)
File "/home/myname/isaac-lab-workspace/IsaacLab/source/isaaclab/isaaclab/sim/converters/urdf_converter.py", line 55, in __init__
super().__init__(cfg=cfg)
File "/home/myname/isaac-lab-workspace/IsaacLab/source/isaaclab/isaaclab/sim/converters/asset_converter_base.py", line 106, in __init__
self._convert_asset(cfg)
File "/home/myname/isaac-lab-workspace/IsaacLab/source/isaaclab/isaaclab/sim/converters/urdf_converter.py", line 84, in _convert_asset
omni.kit.commands.execute(
File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/commands/command.py", line 463, in execute
result = omni.kit.undo.execute(command, name, kwargs)
[...skipped...]
File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/undo/undo.py", line 78, in execute
result = _execute(command, name, level, history_key)
File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/undo/undo.py", line 459, in _execute
raise error
File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/undo/undo.py", line 420, in _execute
result = command.do()
File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/isaacsim.asset.importer.urdf-2.3.10+106.4.0.lx64.r.cp310/isaacsim/asset/importer/urdf/scripts/commands.py", line 145, in do
return self._urdf_interface.import_robot(
<class 'RuntimeError'> Used null prim
I have a similar issue. I just ran the conversion script that returned the following error:
2025-02-10 09:10:08 [36,489ms] [Error] [omni.kit.commands.command] Failed to execute a command: URDFImportRobot. File "/home/myname/isaac-lab-workspace/IsaacLab/scripts/tools/convert_urdf.py", line 134, in <module> main() File "/home/myname/isaac-lab-workspace/IsaacLab/scripts/tools/convert_urdf.py", line 104, in main urdf_converter = UrdfConverter(urdf_converter_cfg) File "/home/myname/isaac-lab-workspace/IsaacLab/source/isaaclab/isaaclab/sim/converters/urdf_converter.py", line 55, in __init__ super().__init__(cfg=cfg) File "/home/myname/isaac-lab-workspace/IsaacLab/source/isaaclab/isaaclab/sim/converters/asset_converter_base.py", line 106, in __init__ self._convert_asset(cfg) File "/home/myname/isaac-lab-workspace/IsaacLab/source/isaaclab/isaaclab/sim/converters/urdf_converter.py", line 84, in _convert_asset omni.kit.commands.execute( File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/commands/command.py", line 463, in execute result = omni.kit.undo.execute(command, name, kwargs) [...skipped...] File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/undo/undo.py", line 78, in execute result = _execute(command, name, level, history_key) File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/undo/undo.py", line 459, in _execute raise error File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/undo/undo.py", line 420, in _execute result = command.do() File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/isaacsim.asset.importer.urdf-2.3.10+106.4.0.lx64.r.cp310/isaacsim/asset/importer/urdf/scripts/commands.py", line 145, in do return self._urdf_interface.import_robot( <class 'RuntimeError'> Used null prim
I was able to track this error down to an stl file which the importer did not like. If I reuse an stl file from a previous link this error is gone. All in all the import from urdf is really hard, I would rather go the detour via mujoco xml files.
I can confirm that my urdf was perfectly imported in isaacsim 4.2! For now I would avoid the isaacsim 4.5 importer and rather take the detour to IsaacSim 4.2!
Solution for Ubuntu 22.04 users:
- Delete the entire ov folder located at ~/.local/share/ov.
- Re-run the Isaac Sim selector script:
./isaacsim-selector.sh
This should resolve the URDF import issue.
Solution for Ubuntu 22.04 users:
1. Delete the entire ov folder located at ~/.local/share/ov. 2. Re-run the Isaac Sim selector script:./isaacsim-selector.sh
This should resolve the URDF import issue.
Where is this isaacsim-selector.sh script located ?
@Ycyofmine @RandomOakForest I am still having this problem. I would be very thankful if you could take another look. I am using commit: 70a5ffcdda943fe6b6f450379929a0a9daab4e0b I did delete the local/share/ov folder, but I do not have any file with the name "isaacsim-selector.sh". I tried to convert the urdf model using the proposed script and using the IsaacSim UI, both did not work. This is the error message:
[INFO]: Base environment:
Environment device : cuda:0
Environment seed : 42
Physics step-size : 0.005
Rendering step-size : 0.02
Environment step-size : 0.02
2025-05-04 07:15:18 [3,953ms] [Warning] [omni.usd] Warning: in _ReportErrors at line 2890 of /builds/omniverse/usd-ci/USD/pxr/usd/usd/stage.cpp -- In </World/envs/env_0/Robot>: Could not open asset @configuration/usd_3_physics.usd@ for payload introduced by @source/thesis/resources/go2_manip_description/usd_3/usd_3.usd@</go_manip_description{Physics=PhysX}>. (recomposing stage on stage @anon:0x10ebbd00:World0.usd@ <0x10ec0b50>)
2025-05-04 07:15:18 [3,953ms] [Warning] [omni.usd] Warning: in _ReportErrors at line 2890 of /builds/omniverse/usd-ci/USD/pxr/usd/usd/stage.cpp -- In </World/envs/env_0/Robot>: Could not open asset @configuration/usd_3_sensor.usd@ for payload introduced by @source/thesis/resources/go2_manip_description/usd_3/usd_3.usd@</go_manip_description{Sensor=Sensors}>. (recomposing stage on stage @anon:0x10ebbd00:World0.usd@ <0x10ec0b50>)
2025-05-04 07:15:18 [3,997ms] [Warning] [isaaclab.sim.utils] Could not perform 'modify_rigid_body_properties' on any prims under: '/World/envs/env_0/Robot'. This might be because of the following reasons:
(1) The desired attribute does not exist on any of the prims.
(2) The desired attribute exists on an instanced prim.
Discovered list of instanced prim paths: []
2025-05-04 07:15:18 [3,997ms] [Warning] [isaaclab.sim.utils] Could not perform 'modify_articulation_root_properties' on any prims under: '/World/envs/env_0/Robot'. This might be because of the following reasons:
(1) The desired attribute does not exist on any of the prims.
(2) The desired attribute exists on an instanced prim.
Discovered list of instanced prim paths: []
2025-05-04 07:15:18 [3,997ms] [Warning] [isaaclab.sim.utils] Could not perform 'modify_joint_drive_properties' on any prims under: '/World/envs/env_0/Robot'. This might be because of the following reasons:
(1) The desired attribute does not exist on any of the prims.
(2) The desired attribute exists on an instanced prim.
Discovered list of instanced prim paths: []
[INFO]: Time taken for scene creation : 0.046341 seconds
Error executing job with overrides: []
Traceback (most recent call last):
File "/home/yannick/IsaacLab/source/isaaclab_tasks/isaaclab_tasks/utils/hydra.py", line 101, in hydra_main
func(env_cfg, agent_cfg, *args, **kwargs)
File "/home/yannick/IsaacLab/scripts/reinforcement_learning/rsl_rl/train.py", line 183, in main
env = gym.make(args_cli.task, cfg=env_cfg, render_mode="rgb_array" if args_cli.video else None)
File "/home/yannick/anaconda3/envs/isaaclab_new2/lib/python3.10/site-packages/gymnasium/envs/registration.py", line 740, in make
env = env_creator(**env_spec_kwargs)
File "/home/yannick/IsaacLab/source/thesis/thesis/quadruped_wall/go2_wall_asym_actorcritic.py", line 32, in __init__
super().__init__(cfg, render_mode, **kwargs)
File "/home/yannick/IsaacLab/source/thesis/thesis/quadruped_wall/go2_wall_env.py", line 30, in __init__
super().__init__(cfg, render_mode, **kwargs)
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/envs/direct_rl_env.py", line 127, in __init__
self._setup_scene()
File "/home/yannick/IsaacLab/source/thesis/thesis/quadruped_wall/go2_wall_asym_actorcritic.py", line 37, in _setup_scene
super()._setup_scene()
File "/home/yannick/IsaacLab/source/thesis/thesis/quadruped_wall/go2_wall_env.py", line 128, in _setup_scene
self._robot = Articulation(self.cfg.robot)
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/assets/articulation/articulation.py", line 100, in __init__
super().__init__(cfg)
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/assets/asset_base.py", line 78, in __init__
self.cfg.spawn.func(
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/sim/utils.py", line 276, in wrapper
schemas.activate_contact_sensors(prim_paths[0], cfg.activate_contact_sensors)
File "/home/yannick/IsaacLab/source/isaaclab/isaaclab/sim/schemas/schemas.py", line 519, in activate_contact_sensors
raise ValueError(
ValueError: No contact sensors added to the prim: '/World/envs/env_0/Robot'. This means that no rigid bodies are present under this prim. Please check the prim path.
I am importing the USD using:
go2_gripper = ArticulationCfg(
prim_path="/World/envs/env_.*/Robot",
spawn=sim_utils.UsdFileCfg(
activate_contact_sensors=True,
usd_path="source/thesis/resources/go2_manip_description/usd_3/usd_3.usd",
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
retain_accelerations=True,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=1000.0,
max_depenetration_velocity=1000.0
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=False,
solver_position_iteration_count=4,
solver_velocity_iteration_count=0
),
joint_drive_props=sim_utils.JointDrivePropertiesCfg(drive_type="force") #! test, taken from ShadowHandEnvCfg
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 0.4),
joint_pos={
".*L_hip_joint": 0.1,
".*R_hip_joint": -0.1,
"F[L,R]_thigh_joint": 0.8,
"R[L,R]_thigh_joint": 1.0,
".*_calf_joint": -1.5,
"joint_connector_gripper": 0.0,
},
joint_vel={".*": 0.0},
),
soft_joint_pos_limit_factor=0.9,
# values taken from https://github.com/unitreerobotics/unitree_rl_gym/blob/main/resources/robots/go2/urdf/go2.urdf
actuators={
"hip_joints": DCMotorCfg(
joint_names_expr=[".*_hip_joint"],
effort_limit_sim=23.7,
effort_limit=23.7,
saturation_effort=23.7,
velocity_limit=30.1,
stiffness=35.0,
damping=0.6,
friction=0.0,
),
"thigh_joints": DCMotorCfg(
joint_names_expr=[".*_thigh_joint"],
effort_limit_sim=23.7,
effort_limit=23.7,
saturation_effort=23.7,
velocity_limit=30.1,
stiffness=35.0,
damping=0.6,
friction=0.0,
),
"calf_joints": DCMotorCfg(
joint_names_expr=[".*_calf_joint"],
effort_limit_sim=35.55,
effort_limit=35.55,
saturation_effort=35.55,
velocity_limit=20.06,
stiffness=35.0,
damping=0.6,
friction=0.0,
),
"base_arm": DCMotorCfg(
joint_names_expr=["joint_connector_gripper"],
effort_limit_sim=1.4,
effort_limit=1.4,
saturation_effort=1.4,
velocity_limit=5.0,
stiffness=3.0,
damping=0.5,
friction=0.0,
),
},
)
This is an exported folder containing all URDF data and the exported USD file: urdf_folder.zip
I did two screenshots in IsaacSim which show a different structure in my old (working) and new (not working) USD file. Is this difference correct?
Old model which I exported at 6th february:
Current model export:
Can you make sure you are running the latest URDF Importer, which should be version 2.3.14? The version check and update can be done through the Extension Manager in Isaac Sim.
@kellyguo11 thank you for the response. I updated now to 2.3.14 but it is still not working. I also tried to add the option root_link_name to the UrdfConverterCfg in convert_urdf.py, but it does not help
@kellyguo11 do you have any further advices for me?
Did it work for you if you used the importer directly from the Isaac Sim GUI? trying to narrow down if it's a bug in the Isaac Lab wrapper or in the importer.
Using both variants does not give me a direct error but when I want to use the transformed USD model in my IsaacLab code, it returns the "No contact sensor"-error @kellyguo11
I have a similar issue. I just ran the conversion script that returned the following error:
2025-02-10 09:10:08 [36,489ms] [Error] [omni.kit.commands.command] Failed to execute a command: URDFImportRobot. File "/home/myname/isaac-lab-workspace/IsaacLab/scripts/tools/convert_urdf.py", line 134, in <module> main() File "/home/myname/isaac-lab-workspace/IsaacLab/scripts/tools/convert_urdf.py", line 104, in main urdf_converter = UrdfConverter(urdf_converter_cfg) File "/home/myname/isaac-lab-workspace/IsaacLab/source/isaaclab/isaaclab/sim/converters/urdf_converter.py", line 55, in __init__ super().__init__(cfg=cfg) File "/home/myname/isaac-lab-workspace/IsaacLab/source/isaaclab/isaaclab/sim/converters/asset_converter_base.py", line 106, in __init__ self._convert_asset(cfg) File "/home/myname/isaac-lab-workspace/IsaacLab/source/isaaclab/isaaclab/sim/converters/urdf_converter.py", line 84, in _convert_asset omni.kit.commands.execute( File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/commands/command.py", line 463, in execute result = omni.kit.undo.execute(command, name, kwargs) [...skipped...] File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/undo/undo.py", line 78, in execute result = _execute(command, name, level, history_key) File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/undo/undo.py", line 459, in _execute raise error File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/undo/undo.py", line 420, in _execute result = command.do() File "/home/myname/miniforge3/envs/isaaclab2/lib/python3.10/site-packages/isaacsim/extscache/isaacsim.asset.importer.urdf-2.3.10+106.4.0.lx64.r.cp310/isaacsim/asset/importer/urdf/scripts/commands.py", line 145, in do return self._urdf_interface.import_robot( <class 'RuntimeError'> Used null primI was able to track this error down to an stl file which the importer did not like. If I reuse an stl file from a previous link this error is gone. All in all the import from urdf is really hard, I would rather go the detour via mujoco xml files.
I can confirm that my urdf was perfectly imported in isaacsim 4.2! For now I would avoid the isaacsim 4.5 importer and rather take the detour to IsaacSim 4.2!
Had a very similar issue today while I was trying to convert a URDF file to USD. Although the DAE fliles used for meshes work fine in with IsaacSim 4.2, it somehow errors out in IsaacSim 4.5
2025-05-28 15:01:36 [13,749ms] [Warning] [omni.usd] Warning: in SdfPath at line 81 of /builds/omniverse/usd-ci/USD/pxr/usd/sdf/path.cpp -- Ill-formed SdfPath </visuals/dynaarm_SHOULDER/100_s
houlder_mesh>: syntax error
2025-05-28 15:01:36 [13,749ms] [Warning] [omni.usd] Warning: in SdfPath at line 81 of /builds/omniverse/usd-ci/USD/pxr/usd/sdf/path.cpp -- Ill-formed SdfPath </visuals/dynaarm_SHOULDER/100_s
houlder_mesh>: syntax error
2025-05-28 15:01:36 [13,749ms] [Warning] [omni.usd] Coding Error: in _IsValidPathForCreatingPrim at line 3340 of /builds/omniverse/usd-ci/USD/pxr/usd/usd/stage.cpp -- Path must be an absolut
e path: <>
2025-05-28 15:01:36 [13,751ms] [Error] [omni.kit.commands.command] Failed to execute a command: URDFImportRobot.
File "/IsaacLab-Internal/scripts/tools/convert_urdf.py", line 161, in <module>
main()
File "/IsaacLab-Internal/scripts/tools/convert_urdf.py", line 131, in main
urdf_converter = UrdfConverter(urdf_converter_cfg)
File "/IsaacLab-Internal/source/isaaclab/isaaclab/sim/converters/urdf_converter.py", line 55, in __init__
super().__init__(cfg=cfg)
File "/IsaacLab-Internal/source/isaaclab/isaaclab/sim/converters/asset_converter_base.py", line 106, in __init__
self._convert_asset(cfg)
File "/IsaacLab-Internal/source/isaaclab/isaaclab/sim/converters/urdf_converter.py", line 84, in _convert_asset
omni.kit.commands.execute(
File "/home/ev/miniforge3/envs/isaacenv-4.5/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/commands/command.py", line 463, in execut
e
result = omni.kit.undo.execute(command, name, kwargs)
[...skipped...]
File "/home/ev/miniforge3/envs/isaacenv-4.5/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/undo/undo.py", line 78, in execute
result = _execute(command, name, level, history_key)
File "/home/ev/miniforge3/envs/isaacenv-4.5/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/undo/undo.py", line 459, in _execute
raise error
File "/home/ev/miniforge3/envs/isaacenv-4.5/lib/python3.10/site-packages/isaacsim/extscache/omni.kit.commands-1.4.9+d02c707b.lx64.r.cp310/omni/kit/undo/undo.py", line 420, in _execute
result = command.do()
File "/home/ev/miniforge3/envs/isaacenv-4.5/lib/python3.10/site-packages/isaacsim/extscache/isaacsim.asset.importer.urdf-2.3.10+106.4.0.lx64.r.cp310/isaacsim/asset/importer/urdf/scripts/co
mmands.py", line 145, in do
return self._urdf_interface.import_robot(
<class 'RuntimeError'> Used null prim
Interesting thing is the warning here: 2025-05-28 15:01:36 [13,749ms] [Warning] [omni.usd] Warning: in SdfPath at line 81 of /builds/omniverse/usd-ci/USD/pxr/usd/sdf/path.cpp -- Ill-formed SdfPath </visuals/dynaarm_SHOULDER/100_s houlder_mesh>: syntax error which does not show up with the previous version.
With the older version of IsaacSim, I observe the following warning:
2025-05-28 15:39:59 [14,292ms] [Warning] [omni.importer.urdf] The path material_Material.004 is not a valid usd path, modifying to material_Material_004
URDF importer output:
Generated USD file: xxxxx
Could it be that invalid usd paths are not handled correctly during the import?
Hi, what is the status on this issue?
Hello, I faced the same problem this week. In the end, it was a real simple fix. You have to use absolut paths for the urdf-file you want to convert and for the converted usd-file. I chnaged both really simple with "os":
self.urdf_file_path = os.path.abspath(self.urdf_file_path)
# code to convert urdf
urdf_converter = UrdfConverter(urdf_converter_cfg)
self.usd_path = os.path.abspath(urdf_converter.usd_path)
that doesn't necessarily help since the urdf importer on isaac sim itself doesn't work
Ah okay. I use the urdf-converter from IsaacLab.
Can you confirm you IsaacLab version? Mine is IsaacLab2.2
I had no problem using either below spawner cfg to convert directly from urdf in the file you share to the usd. With contact sensor all working.
spawn=sim_utils.UrdfFileCfg(
asset_path="/.../go2_manip_description/urdf/go2_manip_comb.urdf",
usd_dir=f"/.../go2_manip_description/usd",
usd_file_name="go2_manip_comb.usd",
fix_base=False,
merge_fixed_joints=False,
force_usd_conversion=True,
activate_contact_sensors=True,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
retain_accelerations=False,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=1000.0,
max_depenetration_velocity=1.0,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=0
),
joint_drive=UrdfConverterCfg.JointDriveCfg(
gains=UrdfConverterCfg.JointDriveCfg.PDGainsCfg(stiffness=100, damping=1.) #stiffness=100.0, damping=1.0
),
),
Another way I also tested has no problem was
python script/tools/convert_urdf.py /.../go2_manip_description/urdf/go2_manip_comb.urdf /.../go2_manip_description/usd/go2_manip_comb.usd
then replace above code sim_utils.UrdfFileCfg with sim_utils.UsdFileCfg
Maybe can you try either approach in the most up to date IsaacLab and see if issue persists?
Hi @YannickP99, I am designing scene using InteractiveSceneCfg, I have some CAD and urdf file, I have to attache adapter to the UR10e flange and then attache Inspire Hand. I need some help in doing this.
Hi @YannickP99 @markcfong561 @fhndan89 could you pls confirm that with 2.2 release branch this issue is resolved for you?