Problem: Your Custom Robot Won't Load in Isaac Gym
You have a URDF model of your robot but Isaac Gym throws cryptic errors about missing meshes, broken joints, or physics instability when you try to load it.
You'll learn:
- How to prepare URDF files for Isaac Gym's PhysX backend
- Fix common asset loading failures and collision issues
- Configure asset properties for stable RL training
Time: 20 min | Level: Intermediate
Why This Happens
Isaac Gym uses NVIDIA PhysX for physics simulation, which has stricter requirements than standard robotics simulators. URDFs designed for Gazebo or PyBullet often have incompatible mesh formats, missing inertia tensors, or collision geometries that PhysX rejects.
Common symptoms:
RuntimeError: Failed to load assetwith no clear reason- Robot falls through the ground or explodes on contact
- Joints drift or become unstable during simulation
- Mesh visualization works but physics fails
Solution
Step 1: Verify URDF Structure
# Check your URDF is valid XML
xmllint --noout your_robot.urdf
# Install Isaac Gym (if not already done)
cd isaacgym/python
pip install -e . --break-system-packages
Expected: No XML parsing errors. Isaac Gym imports successfully.
If it fails:
- Error: "xmllint not found": Install with
sudo apt install libxml2-utils - Isaac Gym import fails: Ensure you have CUDA 11.3+ and downloaded Isaac Gym from NVIDIA
Step 2: Convert Meshes to Compatible Formats
Isaac Gym supports OBJ and STL for collision geometry, but works best with simplified meshes.
# mesh_converter.py
import trimesh
import os
def prepare_mesh_for_isaac(input_path, output_path, simplify=True):
"""Convert and simplify meshes for Isaac Gym"""
mesh = trimesh.load(input_path)
if simplify:
# Reduce polygon count for physics stability
# PhysX performs better with <5000 triangles per mesh
target_faces = min(mesh.faces.shape[0], 5000)
mesh = mesh.simplify_quadric_decimation(target_faces)
# Export as OBJ (best compatibility)
mesh.export(output_path)
print(f"Converted: {input_path} -> {output_path}")
print(f" Faces: {mesh.faces.shape[0]}, Vertices: {mesh.vertices.shape[0]}")
# Convert all meshes in your robot package
mesh_dir = "your_robot_description/meshes"
for mesh_file in os.listdir(mesh_dir):
if mesh_file.endswith(('.dae', '.stl')):
input_path = os.path.join(mesh_dir, mesh_file)
output_path = os.path.join(mesh_dir, mesh_file.replace('.dae', '.obj').replace('.stl', '.obj'))
prepare_mesh_for_isaac(input_path, output_path)
Why this works: PhysX is optimized for low-polygon meshes. High-resolution meshes cause collision detection slowdowns and numerical instability.
Run it:
pip install trimesh --break-system-packages
python mesh_converter.py
Step 3: Update URDF Mesh References
<!-- Before: Collada or STL references -->
<visual>
<geometry>
<mesh filename="package://robot_description/meshes/base_link.dae"/>
</geometry>
</visual>
<!-- After: OBJ with absolute or relative paths -->
<visual>
<geometry>
<mesh filename="meshes/base_link.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<!-- Use simplified geometry for collisions -->
<mesh filename="meshes/base_link_collision.obj"/>
</geometry>
</collision>
Critical: Remove package:// URIs. Isaac Gym resolves paths relative to the asset root directory you specify in code.
Step 4: Load Asset in Isaac Gym
# load_custom_robot.py
from isaacgym import gymapi
import os
# Initialize gym
gym = gymapi.acquire_gym()
# Create simulation with optimal settings for custom assets
sim_params = gymapi.SimParams()
sim_params.dt = 1.0 / 60.0 # 60 Hz physics
sim_params.substeps = 2 # Improves stability for complex models
sim_params.physx.solver_type = 1 # TGS solver (more stable)
sim_params.physx.num_position_iterations = 8
sim_params.physx.num_velocity_iterations = 1
sim = gym.create_sim(0, 0, gymapi.SIM_PHYSX, sim_params)
# Configure asset loading options
asset_options = gymapi.AssetOptions()
asset_options.fix_base_link = False # Set True for fixed-base robots
asset_options.flip_visual_attachments = False
asset_options.use_mesh_materials = True
# Critical: These settings prevent common loading failures
asset_options.default_dof_drive_mode = gymapi.DOF_MODE_EFFORT
asset_options.armature = 0.01 # Joint damping for stability
asset_options.thickness = 0.001 # Collision margin
asset_options.density = 1000.0 # Default density if missing from URDF
# Set asset root directory (parent of your URDF)
asset_root = "/path/to/your_robot_description"
asset_file = "urdf/your_robot.urdf"
# Load the asset
print(f"Loading {asset_file}...")
robot_asset = gym.load_asset(sim, asset_root, asset_file, asset_options)
print("✓ Asset loaded successfully!")
# Get asset properties
num_dofs = gym.get_asset_dof_count(robot_asset)
num_bodies = gym.get_asset_rigid_body_count(robot_asset)
print(f"Robot has {num_dofs} DOFs and {num_bodies} rigid bodies")
Expected output:
Loading urdf/your_robot.urdf...
✓ Asset loaded successfully!
Robot has 7 DOFs and 8 rigid bodies
If it fails:
- Error: "Failed to load asset": Check mesh paths are correct relative to
asset_root - Robot explodes: Increase
armatureto 0.1 or setfix_base_link = Truefor testing - Meshes not visible: Set
asset_options.use_mesh_materials = True
Step 5: Create Environment and Test Physics
# Add ground plane
plane_params = gymapi.PlaneParams()
plane_params.normal = gymapi.Vec3(0, 0, 1) # Z-up
gym.add_ground(sim, plane_params)
# Create environment
env = gym.create_env(sim, gymapi.Vec3(-1, -1, 0), gymapi.Vec3(1, 1, 2), 1)
# Spawn robot at origin with small height offset
pose = gymapi.Transform()
pose.p = gymapi.Vec3(0, 0, 0.5) # Prevent ground penetration
pose.r = gymapi.Quat(0, 0, 0, 1)
actor_handle = gym.create_actor(env, robot_asset, pose, "robot", 0, 1)
# Set viewer
cam_props = gymapi.CameraProperties()
viewer = gym.create_viewer(sim, cam_props)
gym.viewer_camera_look_at(viewer, None, gymapi.Vec3(2, 2, 1), gymapi.Vec3(0, 0, 0.5))
# Run simulation for 5 seconds
for i in range(300):
gym.simulate(sim)
gym.fetch_results(sim, True)
gym.step_graphics(sim)
gym.draw_viewer(viewer, sim, True)
gym.sync_frame_time(sim)
gym.destroy_viewer(viewer)
gym.destroy_sim(sim)
You should see: Your robot standing on the ground plane without exploding or falling through.
Verification
Run the complete script:
python load_custom_robot.py
Success indicators:
- No error messages during asset loading
- Robot renders with proper meshes and colors
- Robot maintains stable contact with ground
- Joints don't drift or oscillate wildly
Physics test:
# Apply a small force to verify physics response
gym.apply_rigid_body_force_at_pos_tensors(
sim,
force_tensor, # Small upward force
pos_tensor, # Center of mass
gymapi.ENV_SPACE
)
Robot should move realistically without instability.
Common Issues and Fixes
Issue: "Asset has no collision geometry"
Solution: Add collision meshes to URDF. Isaac Gym requires explicit collision tags.
<link name="base_link">
<visual>
<geometry><mesh filename="meshes/base_visual.obj"/></geometry>
</visual>
<collision>
<geometry>
<!-- Use simpler mesh or primitives -->
<box size="0.5 0.3 0.2"/>
</geometry>
</collision>
<inertial>
<mass value="5.0"/>
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
</inertial>
</link>
Issue: Robot jitters or phases through objects
Solution: Adjust contact parameters in your asset options.
asset_options.armature = 0.1 # Increase joint damping
asset_options.thickness = 0.002 # Larger collision margin
# Also increase simulation substeps
sim_params.substeps = 4
sim_params.physx.num_position_iterations = 16 # More solver iterations
Issue: Missing inertial properties cause crashes
Solution: Calculate proper inertia tensors using MeshLab or add defaults.
# Quick fix: Override with reasonable defaults
asset_options.override_inertia = True
asset_options.override_com = True
For production, calculate proper inertias:
# Use meshlab to compute inertia
meshlab -i your_mesh.obj -o properties.txt -s compute_inertia.mlx
What You Learned
- Isaac Gym requires simplified meshes and explicit collision geometry
- PhysX has stricter stability requirements than Gazebo/PyBullet
- Asset options like
armatureandthicknessare critical for stable physics - URDF paths must be relative to your specified asset root
Limitations:
- Complex meshes (>10k triangles) slow down simulation significantly
- Closed kinematic chains need special handling with constraints
- Self-collisions require careful collision filtering setup
Asset Optimization Checklist
- All meshes converted to OBJ format
- Collision meshes have <5000 triangles
- Every link has inertial properties
- URDF paths are relative (no
package://) -
armatureset between 0.01-0.1 for stability - Ground plane prevents falling through floor
- Initial pose has clearance above ground (z ≥ 0.5)
- Tested with
substeps = 2andsolver_type = 1
Tested on Isaac Gym Preview 4, Ubuntu 22.04, CUDA 12.1, Python 3.10