Isaac Sim Cheatsheet
Installation & Launch
# Launch Isaac Sim
~/.local/share/ov/pkg/isaac_sim-*/isaac-sim.sh
# Headless mode (no GUI)
~/.local/share/ov/pkg/isaac_sim-*/isaac-sim.sh --headless
# Run Python script
~/.local/share/ov/pkg/isaac_sim-*/python.sh my_script.py
# Set environment variable
export ISAACSIM_PATH=~/.local/share/ov/pkg/isaac_sim-*
Basic Python Script Template
from omni.isaac.kit import SimulationApp
simulation_app = SimulationApp({"headless": False})
from omni.isaac.core import World
from omni.isaac.core.objects import DynamicCuboid
from omni.isaac.core.robots import Robot
# Create world
world = World()
# Add objects
cube = DynamicCuboid(
prim_path="/World/Cube",
position=[0, 0, 1.0],
size=0.5,
color=[1, 0, 0]
)
# Reset and run
world.reset()
for i in range(1000):
world.step(render=True)
simulation_app.close()
World Management
from omni.isaac.core import World
# Create world
world = World(stage_units_in_meters=1.0)
# Add ground plane
world.scene.add_default_ground_plane()
# Reset simulation
world.reset()
# Single simulation step
world.step(render=True)
# Get current time
current_time = world.current_time_step_index
# Pause/Resume
world.pause()
world.play()
Loading Robots
from omni.isaac.core.robots import Robot
from omni.isaac.core.utils.stage import add_reference_to_stage
# Load robot from USD file
add_reference_to_stage(
usd_path="/path/to/robot.usd",
prim_path="/World/MyRobot"
)
robot = world.scene.add(
Robot(prim_path="/World/MyRobot", name="my_robot")
)
# Get joint names
joint_names = robot.dof_names
print(f"Joints: {joint_names}")
# Get number of DOF
num_dof = robot.num_dof
# Get joint positions
joint_positions = robot.get_joint_positions()
# Set joint positions
robot.set_joint_positions([0.0, 0.5, -1.0, 0.5, 0.0, 0.0])
# Set joint velocities
robot.set_joint_velocities([0.1, 0.0, 0.0, 0.0, 0.1, 0.0])
# Apply joint efforts (torques)
robot.apply_action(ArticulationAction(joint_efforts=[10, 0, 0, 0, 0, 0]))
Camera Setup
from omni.isaac.core.utils.prims import create_prim
from omni.isaac.sensor import Camera
# Create camera
camera = Camera(
prim_path="/World/Camera",
position=[2.0, 2.0, 2.0],
orientation=[0, 0, 0, 1], # quaternion (x,y,z,w)
frequency=30,
resolution=(1920, 1080)
)
# Initialize
camera.initialize()
# Get RGB image
rgb_data = camera.get_rgba()[:, :, :3]
# Get depth
depth_data = camera.get_depth()
# Get camera intrinsics
intrinsics = camera.get_intrinsics_matrix()
ROS 2 Bridge
# Enable ROS 2 bridge
import omni.isaac.ros2_bridge
# ROS 2 Camera publisher
from omni.isaac.ros2_bridge import ROS2CameraHelper
camera_helper = ROS2CameraHelper(
camera_prim_path="/World/Camera",
topic_name="/camera/image_raw",
frame_id="camera_link"
)
# ROS 2 Odometry publisher
from omni.isaac.core.utils.extensions import enable_extension
enable_extension("omni.isaac.ros2_bridge")
# Check ROS 2 topics (in separate terminal)
# ros2 topic list
Physics Configuration
from omni.isaac.core.utils.physics import simulate_async
# Get physics scene
physics_scene = world.get_physics_context()
# Set gravity
physics_scene.set_gravity([0, 0, -9.81])
# Set physics timestep
physics_scene.set_physics_dt(1/60) # 60 Hz
# Set solver iterations
physics_scene.set_solver_iterations(4)
Adding Objects
from omni.isaac.core.objects import (
DynamicCuboid,
DynamicSphere,
DynamicCylinder,
VisualCuboid,
FixedCuboid
)
# Dynamic cube (affected by physics)
cube = DynamicCuboid(
prim_path="/World/Cube",
position=[0, 0, 1],
size=0.5,
color=[1, 0, 0],
mass=1.0
)
# Static sphere (visual only)
sphere = VisualCuboid(
prim_path="/World/Sphere",
position=[1, 0, 0],
radius=0.3,
color=[0, 1, 0]
)
# Apply force to object
cube.apply_force([100, 0, 0]) # 100N in x direction
Articulation Actions
from omni.isaac.core.utils.types import ArticulationAction
# Position control
action = ArticulationAction(
joint_positions=[0.0, 0.5, -1.0],
joint_indices=[0, 1, 2] # Optional: specific joints
)
robot.apply_action(action)
# Velocity control
action = ArticulationAction(
joint_velocities=[0.1, 0.0, -0.1]
)
robot.apply_action(action)
# Torque control
action = ArticulationAction(
joint_efforts=[10.0, 5.0, 8.0]
)
robot.apply_action(action)
Sensors
LiDAR
from omni.isaac.range_sensor import LidarRtx
lidar = LidarRtx(
prim_path="/World/Lidar",
position=[0, 0, 1.0]
)
# Initialize
lidar.initialize()
# Get point cloud
point_cloud = lidar.get_point_cloud_data()
# Get linear depth data
depth_data = lidar.get_linear_depth_data()
IMU
from omni.isaac.sensor import IMUSensor
imu = IMUSensor(
prim_path="/World/Robot/IMU",
frequency=100
)
imu.initialize()
# Get linear acceleration
lin_acc = imu.get_linear_acceleration()
# Get angular velocity
ang_vel = imu.get_angular_velocity()
Replicator (Synthetic Data Generation)
import omni.replicator.core as rep
# Create randomizer
def randomize_scene():
with rep.trigger.on_frame():
# Randomize lighting
rep.randomizer.light(intensity=(500, 2000))
# Randomize object positions
rep.randomizer.scatter_2d(
surface_prims=["/World/Ground"],
scatter_prims=["/World/Cube"],
num_objects=10
)
# Randomize materials
rep.randomizer.materials(
materials=["OmniPBR"],
input_prims=["/World/Cube"]
)
# Setup writer for data export
writer = rep.WriterRegistry.get("BasicWriter")
writer.initialize(
output_dir="/tmp/synthetic_data",
rgb=True,
bounding_box_2d_tight=True
)
# Run for N frames
rep.orchestrator.run(num_frames=100)
Utilities
Transformations
from omni.isaac.core.utils.rotations import (
euler_angles_to_quat,
quat_to_euler_angles
)
# Euler to quaternion
quat = euler_angles_to_quat([0, 0, 1.57]) # 90 degrees yaw
# Quaternion to Euler
euler = quat_to_euler_angles([0, 0, 0.707, 0.707])
Stage Utilities
from omni.isaac.core.utils.stage import (
get_current_stage,
add_reference_to_stage,
get_stage_units
)
# Get current stage
stage = get_current_stage()
# Add asset to stage
add_reference_to_stage(
usd_path="/Isaac/Robots/Franka/franka.usd",
prim_path="/World/Franka"
)
# Get stage units (meters)
units = get_stage_units()
Common Workflows
Load & Control Robot
from omni.isaac.kit import SimulationApp
simulation_app = SimulationApp({"headless": False})
from omni.isaac.core import World
from omni.isaac.core.utils.stage import add_reference_to_stage
from omni.isaac.core.robots import Robot
from omni.isaac.core.utils.types import ArticulationAction
# Create world
world = World()
world.scene.add_default_ground_plane()
# Load Franka robot
add_reference_to_stage(
usd_path="/Isaac/Robots/Franka/franka.usd",
prim_path="/World/Franka"
)
robot = world.scene.add(Robot(prim_path="/World/Franka"))
# Reset
world.reset()
# Control loop
for i in range(1000):
# Move joints sinusoidally
import numpy as np
t = i * 0.01
positions = np.sin(t) * np.array([0.5, 0.3, 0.5, 0.3, 0.5, 0.3, 0.5])
robot.apply_action(ArticulationAction(joint_positions=positions))
world.step(render=True)
simulation_app.close()
Record Camera Data
import numpy as np
import cv2
from omni.isaac.sensor import Camera
camera = Camera(
prim_path="/World/Camera",
frequency=30,
resolution=(640, 480)
)
camera.initialize()
# Capture loop
for i in range(100):
world.step(render=True)
# Get RGB
rgb = camera.get_rgba()[:, :, :3]
# Save image
cv2.imwrite(f"/tmp/frame_{i:04d}.png", rgb[:, :, ::-1]) # BGR for OpenCV
Performance Tips
# Disable rendering for faster sim
world.step(render=False)
# Use fabric interface for large scenes
from omni.isaac.core.prims import RigidPrimView
cubes = RigidPrimView(prim_paths_expr="/World/Cubes/Cube_*")
cubes.set_world_poses(positions, orientations) # Batched operation
# Reduce physics substeps
physics_context.set_solver_iterations(2) # Lower for speed
# Use GPU pipeline for rendering
# Edit → Preferences → Rendering → Enable RTX Real-Time
Debugging
# Print current prim path
print(cube.prim_path)
# Check if prim exists
from omni.isaac.core.utils.prims import is_prim_path_valid
is_valid = is_prim_path_valid("/World/Cube")
# Get prim attribute
from omni.isaac.core.utils.prims import get_prim_at_path
prim = get_prim_at_path("/World/Cube")
print(prim.GetAttribute("xformOp:translate").Get())
# Enable physics debug visualization
physics_context.enable_scene_query_support()
Common Issues
Issue: SimulationApp must be first import
# Correct order:
from omni.isaac.kit import SimulationApp
simulation_app = SimulationApp({"headless": False})
# Then import everything else:
from omni.isaac.core import World
Issue: Robot not moving
# Ensure world is reset
world.reset()
# Check if robot is initialized
robot.initialize()
# Verify physics is enabled
physics_context = world.get_physics_context()
Issue: Camera returns None
# Initialize camera first
camera.initialize()
# Step world before reading
world.step(render=True)
# Then get data
rgb = camera.get_rgba()
Resources
- Isaac Sim Docs: https://docs.omniverse.nvidia.com/isaacsim/
- Python API: https://docs.omniverse.nvidia.com/py/isaacsim/
- Examples:
~/.local/share/ov/pkg/isaac_sim-*/standalone_examples/ - Assets:
/Isaac/(in Content Browser)