Isaac Gym1 $\to$ Omniverse Isaac Gym2 & Orbit3

With the shift from Isaac Gym to Isaac Sim at NVIDIA, we have migrated all the environments from this work to Orbit. We encourage all users to migrate to the new framework for their applications.4

Simulation Setup

The API is procedural and data-oriented rather than object-oriented.

from isaacgym import gymapi

gym = gymapi.acquire_gym()

# get default set of parameters
sim_params = gymapi.SimParams()
# set common parameters
sim_params.dt = 1 / 60
sim_params.substeps = 2
# Gym defaults to y-up for legacy reasons!
sim_params.up_axis = gymapi.UP_AXIS_Z
sim_params.gravity = gymapi.Vec3(0.0, 0.0, -9.8)
# set PhysX-specific parameters
sim_params.physx.use_gpu = True
sim_params.physx.solver_type = 1
sim_params.physx.num_position_iterations = 6
sim_params.physx.num_velocity_iterations = 1
sim_params.physx.contact_offset = 0.01
sim_params.physx.rest_offset = 0.0
# set Flex-specific parameters
sim_params.flex.solver_type = 5
sim_params.flex.num_outer_iterations = 4
sim_params.flex.num_inner_iterations = 20
sim_params.flex.relaxation = 0.8
sim_params.flex.warm_start = 0.5

# The sim object contains physics and graphics contexts
sim = gym.create_sim(compute_device_id, graphics_device_id, gymapi.SIM_PHYSX, sim_params)

# configure the ground plane
plane_params = gymapi.PlaneParams()
plane_params.normal = gymapi.Vec3(0, 0, 1) # z-up!
plane_params.distance = 0
plane_params.static_friction = 1
plane_params.dynamic_friction = 1
plane_params.restitution = 0
# create the ground plane
gym.add_ground(sim, plane_params)

# Loading Assets
asset_root = "../../assets"
asset_file = "urdf/franka_description/robots/franka_panda.urdf"
asset = gym.load_asset(sim, asset_root, asset_file)

# set up the env grid
num_envs = 64
envs_per_row = 8
env_spacing = 2.0
env_lower = gymapi.Vec3(-env_spacing, 0.0, -env_spacing)
env_upper = gymapi.Vec3(env_spacing, env_spacing, env_spacing)

# cache some common handles for later use
envs = []
actor_handles = []

# create and populate the environments
for i in range(num_envs):
    env = gym.create_env(sim, env_lower, env_upper, envs_per_row)
    envs.append(env)

    height = random.uniform(1.0, 2.5)

    pose = gymapi.Transform()
    pose.p = gymapi.Vec3(0.0, height, 0.0)

    actor_handle = gym.create_actor(env, asset, pose, "MyActor", i, 1)
    actor_handles.append(actor_handle)

# create a viewer
cam_props = gymapi.CameraProperties()
viewer = gym.create_viewer(sim, cam_props)

# Running the Simulation
while not gym.query_viewer_has_closed(viewer):

    # step the physics
    gym.simulate(sim)
    gym.fetch_results(sim, True)

    # update the viewer
    gym.step_graphics(sim);
    gym.draw_viewer(viewer, sim, True)

    # Wait for dt to elapse in real time.
    # This synchronizes the physics simulation with the rendering rate.
    gym.sync_frame_time(sim)

# Cleanup
gym.destroy_viewer(viewer)
gym.destroy_sim(sim)

Tensor API

The Gym tensor API uses GPU-compatible data representations for interacting with simulations. It allows accessing the physics state directly on the GPU without copying data back and forth from the host.

Contact Tensors

The net contact force tensor contains the net contact forces experienced by each rigid body during the last simulation step, with the forces expressed as 3D vectors. It is a read-only tensor with shape (num_rigid_bodies, 3).

_net_cf = gym.acquire_net_contact_force_tensor(sim)
net_cf = gymtorch.wrap_tensor(_net_cf)

gym.refresh_net_contact_force_tensor(sim)

Force Sensors

  • Rigid Body Force Sensors
  • Joint Force Sensors

Control Tensors

# apply forces at given positions
gym.apply_rigid_body_force_at_pos_tensors(sim, force_tensor, pos_tensor, gymapi.ENV_SPACE)

Simulation Tuning

  • dt: Simulation timestep, the default is $\mathbf{\dfrac{1}{60}}$s. it determines the frequency at which you interact with the simulation
  • substeps: Number of simulation substeps, the default is $\mathbf{2}$. The effective simulation timestep is $\dfrac{\text{dt}}{\text{substeps}}$

To improve solver convergence, usually only position iterations number should be increased. Velocity iterations can negatively impact solver convergence.

Terrains

The net contact force reporting (gym.acquire_net_contact_force_tensor()) of rigid bodies colliding with triangle meshes is known to be unreliable at the moment. Due to interactions with triangle edges the reported forces can be largely reduced or even completely missed at some timesteps. The net contact force reporting will be improved in the future. As a workaround we propose to use force sensors (gym.create_asset_force_sensor()) or filter the reported contact net contact forces in the environment.

API

  • class isaacgym.gymapi.Gym
    • acquire_actor_root_state_tensor (13_state = 3_pos + 4_quat + 3_lin_vel + 3_ang_vel)
    • acquire_dof_force_tensor
    • acquire_dof_state_tensor
    • acquire_force_sensor_tensor
    • acquire_jacobian_tensor
    • acquire_mass_matrix_tensor
    • acquire_net_contact_force_tensor
    • acquire_rigid_body_state_tensor
    • apply_rigid_body_force_at_pos_tensors
    • apply_rigid_body_force_tensors
    • create_asset_force_sensor
    • set_actor_root_state_tensor
    • set_dof_actuation_force_tensor
    • set_dof_position_target_tensor
    • set_dof_state_tensor
    • set_dof_velocity_target_tensor
    • set_rigid_body_state_tensor

FAQ

  • DOF vs Joint? DOF ≈ Joint
  • Attractor? target in IK