Randomization Snippets#

Examples of randomization using USD and Isaac Sim APIs. These examples demonstrate how to randomize scenes for synthetic data generation (SDG) in scenarios where default replicator randomizers are not sufficient or applicable.

The snippets are designed to align with the structure and function names used in the replicator example snippets. In comparison they also have the option to write the data to disk by stetting write_data=True.

Prerequisites:

  • Familiarity with USD.

  • Ability to execute code from the Script Editor.

  • Understanding basic replicator concepts, such as subframes.

Randomizing Light Sources#

This snippet sets up a new environment containing a cube and a sphere; it then spawns a given number of lights and randomizes selected attributes for these lights over a specified number of frames.

../_images/isaac_tutorial_replicator_randomization_lights.gif
Randomizing Light Sources
 1import asyncio
 2import os
 3
 4import numpy as np
 5import omni.kit.commands
 6import omni.replicator.core as rep
 7import omni.usd
 8from isaacsim.core.utils.semantics import add_update_semantics
 9from pxr import Gf, Sdf, UsdGeom
10
11omni.usd.get_context().new_stage()
12stage = omni.usd.get_context().get_stage()
13
14sphere = stage.DefinePrim("/World/Sphere", "Sphere")
15UsdGeom.Xformable(sphere).AddTranslateOp().Set((0.0, 1.0, 1.0))
16add_update_semantics(sphere, "sphere", "class")
17
18cube = stage.DefinePrim("/World/Cube", "Cube")
19UsdGeom.Xformable(cube).AddTranslateOp().Set((0.0, -2.0, 2.0))
20add_update_semantics(cube, "cube", "class")
21
22plane_path = "/World/Plane"
23omni.kit.commands.execute("CreateMeshPrimWithDefaultXform", prim_path=plane_path, prim_type="Plane")
24plane_prim = stage.GetPrimAtPath(plane_path)
25plane_prim.CreateAttribute("xformOp:scale", Sdf.ValueTypeNames.Double3, False).Set(Gf.Vec3d(10, 10, 1))
26
27
28def sphere_lights(num):
29    lights = []
30    for i in range(num):
31        # "CylinderLight", "DiskLight", "DistantLight", "DomeLight", "RectLight", "SphereLight"
32        prim_type = "SphereLight"
33        next_free_path = omni.usd.get_stage_next_free_path(stage, f"/World/{prim_type}", False)
34        light_prim = stage.DefinePrim(next_free_path, prim_type)
35        UsdGeom.Xformable(light_prim).AddTranslateOp().Set((0.0, 0.0, 0.0))
36        UsdGeom.Xformable(light_prim).AddRotateXYZOp().Set((0.0, 0.0, 0.0))
37        UsdGeom.Xformable(light_prim).AddScaleOp().Set((1.0, 1.0, 1.0))
38        light_prim.CreateAttribute("inputs:enableColorTemperature", Sdf.ValueTypeNames.Bool).Set(True)
39        light_prim.CreateAttribute("inputs:colorTemperature", Sdf.ValueTypeNames.Float).Set(6500.0)
40        light_prim.CreateAttribute("inputs:radius", Sdf.ValueTypeNames.Float).Set(0.5)
41        light_prim.CreateAttribute("inputs:intensity", Sdf.ValueTypeNames.Float).Set(30000.0)
42        light_prim.CreateAttribute("inputs:color", Sdf.ValueTypeNames.Color3f).Set((1.0, 1.0, 1.0))
43        light_prim.CreateAttribute("inputs:exposure", Sdf.ValueTypeNames.Float).Set(0.0)
44        light_prim.CreateAttribute("inputs:diffuse", Sdf.ValueTypeNames.Float).Set(1.0)
45        light_prim.CreateAttribute("inputs:specular", Sdf.ValueTypeNames.Float).Set(1.0)
46        lights.append(light_prim)
47    return lights
48
49
50async def run_randomizations_async(num_frames, lights, write_data=True, delay=0):
51    if write_data:
52        writer = rep.WriterRegistry.get("BasicWriter")
53        out_dir = os.path.join(os.getcwd(), "_out_rand_lights")
54        print(f"Writing data to {out_dir}..")
55        writer.initialize(output_dir=out_dir, rgb=True)
56        rp = rep.create.render_product("/OmniverseKit_Persp", (512, 512))
57        writer.attach(rp)
58
59    for _ in range(num_frames):
60        for light in lights:
61            light.GetAttribute("xformOp:translate").Set(
62                (np.random.uniform(-5, 5), np.random.uniform(-5, 5), np.random.uniform(4, 6))
63            )
64            scale_rand = np.random.uniform(0.5, 1.5)
65            light.GetAttribute("xformOp:scale").Set((scale_rand, scale_rand, scale_rand))
66            light.GetAttribute("inputs:colorTemperature").Set(np.random.normal(4500, 1500))
67            light.GetAttribute("inputs:intensity").Set(np.random.normal(25000, 5000))
68            light.GetAttribute("inputs:color").Set(
69                (np.random.uniform(0.1, 0.9), np.random.uniform(0.1, 0.9), np.random.uniform(0.1, 0.9))
70            )
71
72        if write_data:
73            await rep.orchestrator.step_async(rt_subframes=16)
74        else:
75            await omni.kit.app.get_app().next_update_async()
76        if delay > 0:
77            await asyncio.sleep(delay)
78
79
80num_frames = 10
81lights = sphere_lights(10)
82asyncio.ensure_future(run_randomizations_async(num_frames=num_frames, lights=lights, delay=0.2))

Randomizing Textures#

The snippet sets up an environment, spawns a given number of cubes and spheres, and randomizes their textures for the given number of frames. After the randomizations their original materials are reassigned. The snippet also showcases how to create a new material and assign it to a prim.

../_images/isaac_tutorial_replicator_randomization_textures.gif
Randomizing Textures
  1import asyncio
  2import os
  3
  4import numpy as np
  5import omni.replicator.core as rep
  6import omni.usd
  7from isaacsim.storage.native import get_assets_root_path
  8from isaacsim.core.utils.semantics import add_update_semantics, get_semantics
  9from pxr import Gf, Sdf, UsdGeom, UsdShade
 10
 11omni.usd.get_context().new_stage()
 12stage = omni.usd.get_context().get_stage()
 13dome_light = stage.DefinePrim("/World/DomeLight", "DomeLight")
 14dome_light.CreateAttribute("inputs:intensity", Sdf.ValueTypeNames.Float).Set(1000.0)
 15
 16sphere = stage.DefinePrim("/World/Sphere", "Sphere")
 17UsdGeom.Xformable(sphere).AddTranslateOp().Set((0.0, 0.0, 1.0))
 18add_update_semantics(sphere, "sphere", "class")
 19
 20num_cubes = 10
 21for _ in range(num_cubes):
 22    prim_type = "Cube"
 23    next_free_path = omni.usd.get_stage_next_free_path(stage, f"/World/{prim_type}", False)
 24    cube = stage.DefinePrim(next_free_path, prim_type)
 25    UsdGeom.Xformable(cube).AddTranslateOp().Set((np.random.uniform(-3.5, 3.5), np.random.uniform(-3.5, 3.5), 1))
 26    scale_rand = np.random.uniform(0.25, 0.5)
 27    UsdGeom.Xformable(cube).AddScaleOp().Set((scale_rand, scale_rand, scale_rand))
 28    add_update_semantics(cube, "cube", "class")
 29
 30plane_path = "/World/Plane"
 31omni.kit.commands.execute("CreateMeshPrimWithDefaultXform", prim_path=plane_path, prim_type="Plane")
 32plane_prim = stage.GetPrimAtPath(plane_path)
 33plane_prim.CreateAttribute("xformOp:scale", Sdf.ValueTypeNames.Double3, False).Set(Gf.Vec3d(10, 10, 1))
 34
 35
 36def get_shapes():
 37    stage = omni.usd.get_context().get_stage()
 38    shapes = []
 39    for prim in stage.Traverse():
 40        sem_dict = get_semantics(prim)
 41        sem_values = sem_dict.values()
 42        if ("class", "cube") in sem_values or ("class", "sphere") in sem_values:
 43            shapes.append(prim)
 44    return shapes
 45
 46
 47shapes = get_shapes()
 48
 49
 50def create_omnipbr_material(mtl_url, mtl_name, mtl_path):
 51    stage = omni.usd.get_context().get_stage()
 52    omni.kit.commands.execute("CreateMdlMaterialPrim", mtl_url=mtl_url, mtl_name=mtl_name, mtl_path=mtl_path)
 53    material_prim = stage.GetPrimAtPath(mtl_path)
 54    shader = UsdShade.Shader(omni.usd.get_shader_from_material(material_prim, get_prim=True))
 55
 56    # Add value inputs
 57    shader.CreateInput("diffuse_color_constant", Sdf.ValueTypeNames.Color3f)
 58    shader.CreateInput("reflection_roughness_constant", Sdf.ValueTypeNames.Float)
 59    shader.CreateInput("metallic_constant", Sdf.ValueTypeNames.Float)
 60
 61    # Add texture inputs
 62    shader.CreateInput("diffuse_texture", Sdf.ValueTypeNames.Asset)
 63    shader.CreateInput("reflectionroughness_texture", Sdf.ValueTypeNames.Asset)
 64    shader.CreateInput("metallic_texture", Sdf.ValueTypeNames.Asset)
 65
 66    # Add other attributes
 67    shader.CreateInput("project_uvw", Sdf.ValueTypeNames.Bool)
 68
 69    # Add texture scale and rotate
 70    shader.CreateInput("texture_scale", Sdf.ValueTypeNames.Float2)
 71    shader.CreateInput("texture_rotate", Sdf.ValueTypeNames.Float)
 72
 73    material = UsdShade.Material(material_prim)
 74    return material
 75
 76
 77def create_materials(num):
 78    MDL = "OmniPBR.mdl"
 79    mtl_name, _ = os.path.splitext(MDL)
 80    MAT_PATH = "/World/Looks"
 81    materials = []
 82    for _ in range(num):
 83        prim_path = omni.usd.get_stage_next_free_path(stage, f"{MAT_PATH}/{mtl_name}", False)
 84        mat = create_omnipbr_material(mtl_url=MDL, mtl_name=mtl_name, mtl_path=prim_path)
 85        materials.append(mat)
 86    return materials
 87
 88
 89materials = create_materials(len(shapes))
 90
 91
 92async def run_randomizations_async(num_frames, materials, textures, write_data=True, delay=0):
 93    if write_data:
 94        writer = rep.WriterRegistry.get("BasicWriter")
 95        out_dir = os.path.join(os.getcwd(), "_out_rand_textures")
 96        print(f"Writing data to {out_dir}..")
 97        writer.initialize(output_dir=out_dir, rgb=True)
 98        rp = rep.create.render_product("/OmniverseKit_Persp", (512, 512))
 99        writer.attach(rp)
100
101    # Apply the new materials and store the initial ones to reassign later
102    initial_materials = {}
103    for i, shape in enumerate(shapes):
104        cur_mat, _ = UsdShade.MaterialBindingAPI(shape).ComputeBoundMaterial()
105        initial_materials[shape] = cur_mat
106        UsdShade.MaterialBindingAPI(shape).Bind(materials[i], UsdShade.Tokens.strongerThanDescendants)
107
108    for _ in range(num_frames):
109        for mat in materials:
110            shader = UsdShade.Shader(omni.usd.get_shader_from_material(mat, get_prim=True))
111            diffuse_texture = np.random.choice(textures)
112            shader.GetInput("diffuse_texture").Set(diffuse_texture)
113            project_uvw = np.random.choice([True, False], p=[0.9, 0.1])
114            shader.GetInput("project_uvw").Set(bool(project_uvw))
115            texture_scale = np.random.uniform(0.1, 1)
116            shader.GetInput("texture_scale").Set((texture_scale, texture_scale))
117            texture_rotate = np.random.uniform(0, 45)
118            shader.GetInput("texture_rotate").Set(texture_rotate)
119
120        if write_data:
121            await rep.orchestrator.step_async(rt_subframes=4)
122        else:
123            await omni.kit.app.get_app().next_update_async()
124        if delay > 0:
125            await asyncio.sleep(delay)
126
127    # Reassign the initial materials
128    for shape, mat in initial_materials.items():
129        if mat:
130            UsdShade.MaterialBindingAPI(shape).Bind(mat, UsdShade.Tokens.strongerThanDescendants)
131        else:
132            UsdShade.MaterialBindingAPI(shape).UnbindAllBindings()
133
134
135assets_root_path = get_assets_root_path()
136textures = [
137    assets_root_path + "/NVIDIA/Materials/vMaterials_2/Ground/textures/aggregate_exposed_diff.jpg",
138    assets_root_path + "/NVIDIA/Materials/vMaterials_2/Ground/textures/gravel_track_ballast_diff.jpg",
139    assets_root_path + "/NVIDIA/Materials/vMaterials_2/Ground/textures/gravel_track_ballast_multi_R_rough_G_ao.jpg",
140    assets_root_path + "/NVIDIA/Materials/vMaterials_2/Ground/textures/rough_gravel_rough.jpg",
141]
142
143num_frames = 10
144asyncio.ensure_future(run_randomizations_async(num_frames, materials, textures, delay=0.2))

Sequential Randomizations#

The snippet provides an example of more complex randomizations, where the results of the first randomization are used to determine the next randomization. It uses a custom sampler function to set the location of the camera by iterating over (almost) equidistant points on a sphere. The snippet starts by setting up the environment, a forklift, a pallet, a bin, and a dome light. For every randomization frame, it cycles through the dome light textures, moves the pallet to a random location, and then moves the bin so that it is fully on top of the pallet. Finally, it moves the camera to a new location on the sphere, ensuring it faces the bin.

../_images/isaac_tutorial_replicator_randomization_chained_persp.gif ../_images/isaac_tutorial_replicator_randomization_chained_sphere.gif
Sequential Randomizations
  1import asyncio
  2import itertools
  3import os
  4
  5import numpy as np
  6import omni.replicator.core as rep
  7import omni.usd
  8from isaacsim.storage.native import get_assets_root_path
  9from pxr import Gf, Usd, UsdGeom, UsdLux
 10
 11
 12# https://arxiv.org/pdf/0912.4540.pdf
 13def next_point_on_sphere(idx, num_points, radius=1, origin=(0, 0, 0)):
 14    offset = 2.0 / num_points
 15    inc = np.pi * (3.0 - np.sqrt(5.0))
 16    z = ((idx * offset) - 1) + (offset / 2)
 17    phi = ((idx + 1) % num_points) * inc
 18    r = np.sqrt(1 - pow(z, 2))
 19    y = np.cos(phi) * r
 20    x = np.sin(phi) * r
 21    return [(x * radius) + origin[0], (y * radius) + origin[1], (z * radius) + origin[2]]
 22
 23
 24assets_root_path = get_assets_root_path()
 25FORKLIFT_PATH = assets_root_path + "/Isaac/Props/Forklift/forklift.usd"
 26PALLET_PATH = assets_root_path + "/Isaac/Props/Pallet/pallet.usd"
 27BIN_PATH = assets_root_path + "/Isaac/Props/KLT_Bin/small_KLT_visual.usd"
 28
 29omni.usd.get_context().new_stage()
 30stage = omni.usd.get_context().get_stage()
 31
 32dome_light = UsdLux.DomeLight.Define(stage, "/World/Lights/DomeLight")
 33dome_light.GetIntensityAttr().Set(1000)
 34
 35forklift_prim = stage.DefinePrim("/World/Forklift", "Xform")
 36forklift_prim.GetReferences().AddReference(FORKLIFT_PATH)
 37if not forklift_prim.GetAttribute("xformOp:translate"):
 38    UsdGeom.Xformable(forklift_prim).AddTranslateOp()
 39forklift_prim.GetAttribute("xformOp:translate").Set((-4.5, -4.5, 0))
 40
 41pallet_prim = stage.DefinePrim("/World/Pallet", "Xform")
 42pallet_prim.GetReferences().AddReference(PALLET_PATH)
 43if not pallet_prim.GetAttribute("xformOp:translate"):
 44    UsdGeom.Xformable(pallet_prim).AddTranslateOp()
 45if not pallet_prim.GetAttribute("xformOp:rotateXYZ"):
 46    UsdGeom.Xformable(pallet_prim).AddRotateXYZOp()
 47
 48bin_prim = stage.DefinePrim("/World/Bin", "Xform")
 49bin_prim.GetReferences().AddReference(BIN_PATH)
 50if not bin_prim.GetAttribute("xformOp:translate"):
 51    UsdGeom.Xformable(bin_prim).AddTranslateOp()
 52if not bin_prim.GetAttribute("xformOp:rotateXYZ"):
 53    UsdGeom.Xformable(bin_prim).AddRotateXYZOp()
 54
 55cam = stage.DefinePrim("/World/Camera", "Camera")
 56if not cam.GetAttribute("xformOp:translate"):
 57    UsdGeom.Xformable(cam).AddTranslateOp()
 58if not cam.GetAttribute("xformOp:orient"):
 59    UsdGeom.Xformable(cam).AddOrientOp()
 60
 61
 62async def run_randomizations_async(
 63    num_frames, dome_light, dome_textures, pallet_prim, bin_prim, write_data=True, delay=0
 64):
 65    if write_data:
 66        writer = rep.WriterRegistry.get("BasicWriter")
 67        out_dir = os.path.join(os.getcwd(), "_out_rand_sphere_scan")
 68        print(f"Writing data to {out_dir}..")
 69        writer.initialize(output_dir=out_dir, rgb=True)
 70        rp_persp = rep.create.render_product("/OmniverseKit_Persp", (512, 512), name="PerspView")
 71        rp_cam = rep.create.render_product(str(cam.GetPath()), (512, 512), name="SphereView")
 72        writer.attach([rp_cam, rp_persp])
 73
 74    textures_cycle = itertools.cycle(dome_textures)
 75
 76    bb_cache = UsdGeom.BBoxCache(time=Usd.TimeCode.Default(), includedPurposes=[UsdGeom.Tokens.default_])
 77    pallet_size = bb_cache.ComputeWorldBound(pallet_prim).GetRange().GetSize()
 78    pallet_length = pallet_size.GetLength()
 79    bin_size = bb_cache.ComputeWorldBound(bin_prim).GetRange().GetSize()
 80
 81    for i in range(num_frames):
 82        # Set next background texture every nth frame and run an app update
 83        if i % 5 == 0:
 84            dome_light.GetTextureFileAttr().Set(next(textures_cycle))
 85            await omni.kit.app.get_app().next_update_async()
 86
 87        # Randomize pallet pose
 88        pallet_prim.GetAttribute("xformOp:translate").Set(
 89            Gf.Vec3d(np.random.uniform(-1.5, 1.5), np.random.uniform(-1.5, 1.5), 0)
 90        )
 91        rand_z_rot = np.random.uniform(-90, 90)
 92        pallet_prim.GetAttribute("xformOp:rotateXYZ").Set(Gf.Vec3d(0, 0, rand_z_rot))
 93        pallet_tf_mat = omni.usd.get_world_transform_matrix(pallet_prim)
 94        pallet_rot = pallet_tf_mat.ExtractRotation()
 95        pallet_pos = pallet_tf_mat.ExtractTranslation()
 96
 97        # Randomize bin position on top of the rotated pallet area making sure the bin is fully on the pallet
 98        rand_transl_x = np.random.uniform(-pallet_size[0] / 2 + bin_size[0] / 2, pallet_size[0] / 2 - bin_size[0] / 2)
 99        rand_transl_y = np.random.uniform(-pallet_size[1] / 2 + bin_size[1] / 2, pallet_size[1] / 2 - bin_size[1] / 2)
100
101        # Adjust bin position to account for the random rotation of the pallet
102        rand_z_rot_rad = np.deg2rad(rand_z_rot)
103        rot_adjusted_transl_x = rand_transl_x * np.cos(rand_z_rot_rad) - rand_transl_y * np.sin(rand_z_rot_rad)
104        rot_adjusted_transl_y = rand_transl_x * np.sin(rand_z_rot_rad) + rand_transl_y * np.cos(rand_z_rot_rad)
105        bin_prim.GetAttribute("xformOp:translate").Set(
106            Gf.Vec3d(
107                pallet_pos[0] + rot_adjusted_transl_x,
108                pallet_pos[1] + rot_adjusted_transl_y,
109                pallet_pos[2] + pallet_size[2] + bin_size[2] / 2,
110            )
111        )
112        # Keep bin rotation aligned with pallet
113        bin_prim.GetAttribute("xformOp:rotateXYZ").Set(pallet_rot.GetAxis() * pallet_rot.GetAngle())
114
115        # Get next camera position on a sphere looking at the bin with a randomized distance
116        rand_radius = np.random.normal(3, 0.5) * pallet_length
117        bin_pos = omni.usd.get_world_transform_matrix(bin_prim).ExtractTranslation()
118        cam_pos = next_point_on_sphere(i, num_points=num_frames, radius=rand_radius, origin=bin_pos)
119        cam.GetAttribute("xformOp:translate").Set(Gf.Vec3d(*cam_pos))
120
121        eye = Gf.Vec3d(*cam_pos)
122        target = Gf.Vec3d(*bin_pos)
123        up_axis = Gf.Vec3d(0, 0, 1)
124        look_at_quatd = Gf.Matrix4d().SetLookAt(eye, target, up_axis).GetInverse().ExtractRotation().GetQuat()
125        cam.GetAttribute("xformOp:orient").Set(Gf.Quatf(look_at_quatd))
126
127        if write_data:
128            await rep.orchestrator.step_async(rt_subframes=4)
129        else:
130            await omni.kit.app.get_app().next_update_async()
131        if delay > 0:
132            await asyncio.sleep(delay)
133
134
135num_frames = 90
136dome_textures = [
137    assets_root_path + "/NVIDIA/Assets/Skies/Cloudy/champagne_castle_1_4k.hdr",
138    assets_root_path + "/NVIDIA/Assets/Skies/Clear/evening_road_01_4k.hdr",
139    assets_root_path + "/NVIDIA/Assets/Skies/Clear/mealie_road_4k.hdr",
140    assets_root_path + "/NVIDIA/Assets/Skies/Clear/qwantani_4k.hdr",
141]
142asyncio.ensure_future(run_randomizations_async(num_frames, dome_light, dome_textures, pallet_prim, bin_prim, delay=0.2))

Physics-based Randomized Volume Filling#

The snippet randomizes the stacking of objects on multiple surfaces. It randomly spawns a given number of pallets in the selected areas and then spawns physically simulated boxes on top of them. A temporary collision box area is created around the pallets to prevent the boxes from falling off. Once all the boxes have been dropped, they are moved in various directions and finally pulled towards the center of the pallet for more stable stacking. Finally, the collision area is removed, after which the boxes can also fall to the ground. To allow easier sliding of the boxes into more stable positions, their friction is temporarily reduced during the simulation.

../_images/isaac_tutorial_replicator_randomization_volume_fill.gif ../_images/isaac_tutorial_replicator_randomization_volume_fill_warehouse.gif
Physics-based Randomized Volume Filling
  1import asyncio
  2import random
  3from itertools import chain
  4
  5import carb
  6import omni.kit.app
  7import omni.usd
  8from isaacsim.core.utils.bounds import compute_aabb, compute_obb, create_bbox_cache
  9from isaacsim.storage.native import get_assets_root_path
 10from omni.physx import get_physx_simulation_interface
 11from pxr import (
 12    Gf,
 13    PhysicsSchemaTools,
 14    PhysxSchema,
 15    Sdf,
 16    Usd,
 17    UsdGeom,
 18    UsdPhysics,
 19    UsdShade,
 20    UsdUtils,
 21)
 22
 23
 24# Add transformation properties to the prim (if not already present)
 25def set_transform_attributes(prim, location=None, orientation=None, rotation=None, scale=None):
 26    if location is not None:
 27        if not prim.HasAttribute("xformOp:translate"):
 28            UsdGeom.Xformable(prim).AddTranslateOp()
 29        prim.GetAttribute("xformOp:translate").Set(location)
 30    if orientation is not None:
 31        if not prim.HasAttribute("xformOp:orient"):
 32            UsdGeom.Xformable(prim).AddOrientOp()
 33        prim.GetAttribute("xformOp:orient").Set(orientation)
 34    if rotation is not None:
 35        if not prim.HasAttribute("xformOp:rotateXYZ"):
 36            UsdGeom.Xformable(prim).AddRotateXYZOp()
 37        prim.GetAttribute("xformOp:rotateXYZ").Set(rotation)
 38    if scale is not None:
 39        if not prim.HasAttribute("xformOp:scale"):
 40            UsdGeom.Xformable(prim).AddScaleOp()
 41        prim.GetAttribute("xformOp:scale").Set(scale)
 42
 43
 44# Enables collisions with the asset (without rigid body dynamics the asset will be static)
 45def add_colliders(prim):
 46    # Iterate descendant prims (including root) and add colliders to mesh or primitive types
 47    for desc_prim in Usd.PrimRange(prim):
 48        if desc_prim.IsA(UsdGeom.Mesh) or desc_prim.IsA(UsdGeom.Gprim):
 49            # Physics
 50            if not desc_prim.HasAPI(UsdPhysics.CollisionAPI):
 51                collision_api = UsdPhysics.CollisionAPI.Apply(desc_prim)
 52            else:
 53                collision_api = UsdPhysics.CollisionAPI(desc_prim)
 54            collision_api.CreateCollisionEnabledAttr(True)
 55
 56        # Add mesh specific collision properties only to mesh types
 57        if desc_prim.IsA(UsdGeom.Mesh):
 58            if not desc_prim.HasAPI(UsdPhysics.MeshCollisionAPI):
 59                mesh_collision_api = UsdPhysics.MeshCollisionAPI.Apply(desc_prim)
 60            else:
 61                mesh_collision_api = UsdPhysics.MeshCollisionAPI(desc_prim)
 62            mesh_collision_api.CreateApproximationAttr().Set("convexHull")
 63
 64
 65# Enables rigid body dynamics (physics simulation) on the prim (having valid colliders is recommended)
 66def add_rigid_body_dynamics(prim, disable_gravity=False, angular_damping=None):
 67    # Physics
 68    if not prim.HasAPI(UsdPhysics.RigidBodyAPI):
 69        rigid_body_api = UsdPhysics.RigidBodyAPI.Apply(prim)
 70    else:
 71        rigid_body_api = UsdPhysics.RigidBodyAPI(prim)
 72    rigid_body_api.CreateRigidBodyEnabledAttr(True)
 73    # PhysX
 74    if not prim.HasAPI(PhysxSchema.PhysxRigidBodyAPI):
 75        physx_rigid_body_api = PhysxSchema.PhysxRigidBodyAPI.Apply(prim)
 76    else:
 77        physx_rigid_body_api = PhysxSchema.PhysxRigidBodyAPI(prim)
 78    physx_rigid_body_api.GetDisableGravityAttr().Set(disable_gravity)
 79    if angular_damping is not None:
 80        physx_rigid_body_api.CreateAngularDampingAttr().Set(angular_damping)
 81
 82
 83# Create a new prim with the provided asset URL and transform properties
 84def create_asset(stage, asset_url, path, location=None, rotation=None, orientation=None, scale=None):
 85    prim_path = omni.usd.get_stage_next_free_path(stage, path, False)
 86    reference_url = asset_url if asset_url.startswith("omniverse://") else get_assets_root_path() + asset_url
 87    prim = stage.DefinePrim(prim_path, "Xform")
 88    prim.GetReferences().AddReference(reference_url)
 89    set_transform_attributes(prim, location=location, rotation=rotation, orientation=orientation, scale=scale)
 90    return prim
 91
 92
 93# Create a new prim with the provided asset URL and transform properties including colliders
 94def create_asset_with_colliders(stage, asset_url, path, location=None, rotation=None, orientation=None, scale=None):
 95    prim = create_asset(stage, asset_url, path, location, rotation, orientation, scale)
 96    add_colliders(prim)
 97    return prim
 98
 99
100# Create collision walls around the top surface of the prim with the given height and thickness
101def create_collision_walls(stage, prim, bbox_cache=None, height=2, thickness=0.3, material=None, visible=False):
102    # Use the untransformed axis-aligned bounding box to calculate the prim surface size and center
103    if bbox_cache is None:
104        bbox_cache = UsdGeom.BBoxCache(Usd.TimeCode.Default(), includedPurposes=[UsdGeom.Tokens.default_])
105    local_range = bbox_cache.ComputeWorldBound(prim).GetRange()
106    width, depth, local_height = local_range.GetSize()
107    # Raise the midpoint height to the prim's surface
108    mid = local_range.GetMidpoint() + Gf.Vec3d(0, 0, local_height / 2)
109
110    # Define the walls (name, location, size) with the specified thickness added externally to the surface and height
111    walls = [
112        ("floor", (mid[0], mid[1], mid[2] - thickness / 2), (width, depth, thickness)),
113        ("ceiling", (mid[0], mid[1], mid[2] + height + thickness / 2), (width, depth, thickness)),
114        ("left_wall", (mid[0] - (width + thickness) / 2, mid[1], mid[2] + height / 2), (thickness, depth, height)),
115        ("right_wall", (mid[0] + (width + thickness) / 2, mid[1], mid[2] + height / 2), (thickness, depth, height)),
116        ("front_wall", (mid[0], mid[1] + (depth + thickness) / 2, mid[2] + height / 2), (width, thickness, height)),
117        ("back_wall", (mid[0], mid[1] - (depth + thickness) / 2, mid[2] + height / 2), (width, thickness, height)),
118    ]
119
120    # Use the parent prim path to create the walls as children (use local coordinates)
121    prim_path = prim.GetPath()
122    collision_walls = []
123    for name, location, size in walls:
124        prim = stage.DefinePrim(f"{prim_path}/{name}", "Cube")
125        scale = (size[0] / 2.0, size[1] / 2.0, size[2] / 2.0)
126        set_transform_attributes(prim, location=location, scale=scale)
127        add_colliders(prim)
128        if not visible:
129            UsdGeom.Imageable(prim).MakeInvisible()
130        if material is not None:
131            mat_binding_api = UsdShade.MaterialBindingAPI.Apply(prim)
132            mat_binding_api.Bind(material, UsdShade.Tokens.weakerThanDescendants, "physics")
133        collision_walls.append(prim)
134    return collision_walls
135
136
137# Slide the assets independently in perpendicular directions and then pull them all together towards the given center
138async def apply_forces_async(stage, boxes, pallet, strength=550, strength_center_multiplier=2):
139    timeline = omni.timeline.get_timeline_interface()
140    timeline.play()
141    # Get the pallet center and forward vector to apply forces in the perpendicular directions and towards the center
142    pallet_tf: Gf.Matrix4d = UsdGeom.Xformable(pallet).ComputeLocalToWorldTransform(Usd.TimeCode.Default())
143    pallet_center = pallet_tf.ExtractTranslation()
144    pallet_rot: Gf.Rotation = pallet_tf.ExtractRotation()
145    force_forward = Gf.Vec3d(pallet_rot.TransformDir(Gf.Vec3d(1, 0, 0))) * strength
146    force_right = Gf.Vec3d(pallet_rot.TransformDir(Gf.Vec3d(0, 1, 0))) * strength
147
148    physx_api = get_physx_simulation_interface()
149    stage_id = UsdUtils.StageCache.Get().GetId(stage).ToLongInt()
150    for box_prim in boxes:
151        body_path = PhysicsSchemaTools.sdfPathToInt(box_prim.GetPath())
152        forces = [force_forward, force_right, -force_forward, -force_right]
153        for force in chain(forces, forces):
154            box_tf: Gf.Matrix4d = UsdGeom.Xformable(box_prim).ComputeLocalToWorldTransform(Usd.TimeCode.Default())
155            box_position = carb.Float3(*box_tf.ExtractTranslation())
156            physx_api.apply_force_at_pos(stage_id, body_path, carb.Float3(force), box_position, "Force")
157            for _ in range(10):
158                await omni.kit.app.get_app().next_update_async()
159
160    # Pull all box at once to the pallet center
161    for box_prim in boxes:
162        body_path = PhysicsSchemaTools.sdfPathToInt(box_prim.GetPath())
163        box_tf: Gf.Matrix4d = UsdGeom.Xformable(box_prim).ComputeLocalToWorldTransform(Usd.TimeCode.Default())
164        box_location = box_tf.ExtractTranslation()
165        force_to_center = (pallet_center - box_location) * strength * strength_center_multiplier
166        physx_api.apply_force_at_pos(stage_id, body_path, carb.Float3(*force_to_center), carb.Float3(*box_location))
167    for _ in range(20):
168        await omni.kit.app.get_app().next_update_async()
169    timeline.pause()
170
171
172# Create a new stage and and run the example scenario
173async def stack_boxes_on_pallet_async(pallet_prim, boxes_urls_and_weights, num_boxes, drop_height=1.5, drop_margin=0.2):
174    pallet_path = pallet_prim.GetPath()
175    print(f"[BoxStacking] Running scenario for pallet {pallet_path} with {num_boxes} boxes..")
176    stage = omni.usd.get_context().get_stage()
177    bbox_cache = UsdGeom.BBoxCache(Usd.TimeCode.Default(), includedPurposes=[UsdGeom.Tokens.default_])
178
179    # Create a custom physics material to allow the boxes to easily slide into stacking positions
180    material_path = f"{pallet_path}/Looks/PhysicsMaterial"
181    default_material = UsdShade.Material.Define(stage, material_path)
182    physics_material = UsdPhysics.MaterialAPI.Apply(default_material.GetPrim())
183    physics_material.CreateRestitutionAttr().Set(0.0)  # Inelastic collision (no bouncing)
184    physics_material.CreateStaticFrictionAttr().Set(0.01)  # Small friction to allow sliding of stationary boxes
185    physics_material.CreateDynamicFrictionAttr().Set(0.01)  # Small friction to allow sliding of moving boxes
186
187    # Apply the physics material to the pallet
188    mat_binding_api = UsdShade.MaterialBindingAPI.Apply(pallet_prim)
189    mat_binding_api.Bind(default_material, UsdShade.Tokens.weakerThanDescendants, "physics")
190
191    # Create collision walls around the top of the pallet and apply the physics material to them
192    collision_walls = create_collision_walls(
193        stage, pallet_prim, bbox_cache, height=drop_height + drop_margin, material=default_material
194    )
195
196    # Create the random boxes (without physics) with the specified weights and sort them by size (volume)
197    box_urls, box_weights = zip(*boxes_urls_and_weights)
198    rand_boxes_urls = random.choices(box_urls, weights=box_weights, k=num_boxes)
199    boxes = [create_asset(stage, box_url, f"{pallet_path}_Boxes/Box_{i}") for i, box_url in enumerate(rand_boxes_urls)]
200    boxes.sort(key=lambda box: bbox_cache.ComputeLocalBound(box).GetVolume(), reverse=True)
201
202    # Calculate the drop area above the pallet taking into account the pallet surface, drop height and the margin
203    # Note: The boxes can be spawned colliding with the surrounding collision walls as they will be pushed inwards
204    pallet_range = bbox_cache.ComputeWorldBound(pallet_prim).GetRange()
205    pallet_width, pallet_depth, pallet_heigth = pallet_range.GetSize()
206    # Move the spawn center at the given height above the pallet surface
207    spawn_center = pallet_range.GetMidpoint() + Gf.Vec3d(0, 0, pallet_heigth / 2 + drop_height)
208    spawn_width, spawn_depth = pallet_width / 2 - drop_margin, pallet_depth / 2 - drop_margin
209
210    # Use the pallet local-to-world transform to apply the local random offsets relative to the pallet
211    pallet_tf: Gf.Matrix4d = UsdGeom.Xformable(pallet_prim).ComputeLocalToWorldTransform(Usd.TimeCode.Default())
212    pallet_rot: Gf.Rotation = pallet_tf.ExtractRotation()
213
214    # Simulate dropping the boxes from random poses on the pallet
215    timeline = omni.timeline.get_timeline_interface()
216    for box_prim in boxes:
217        # Create a random location and orientation for the box within the drop area in local frame
218        local_loc = spawn_center + Gf.Vec3d(
219            random.uniform(-spawn_width, spawn_width), random.uniform(-spawn_depth, spawn_depth), 0
220        )
221        axes = [Gf.Vec3d(1, 0, 0), Gf.Vec3d(0, 1, 0), Gf.Vec3d(0, 0, 1)]
222        angles = [random.choice([180, 90, 0, -90, -180]) + random.uniform(-3, 3) for _ in axes]
223        local_rot = Gf.Rotation()
224        for axis, angle in zip(axes, angles):
225            local_rot *= Gf.Rotation(axis, angle)
226
227        # Transform the local pose to the pallet's world coordinate system
228        world_loc = pallet_tf.Transform(local_loc)
229        world_quat = Gf.Quatf((pallet_rot * local_rot).GetQuat())
230
231        # Set the spawn pose and enable collisions and rigid body dynamics with dampened angular movements
232        set_transform_attributes(box_prim, location=world_loc, orientation=world_quat)
233        add_colliders(box_prim)
234        add_rigid_body_dynamics(box_prim, angular_damping=0.9)
235
236        # Bind the physics material to the box (allow frictionless sliding)
237        mat_binding_api = UsdShade.MaterialBindingAPI.Apply(box_prim)
238        mat_binding_api.Bind(default_material, UsdShade.Tokens.weakerThanDescendants, "physics")
239        # Wait for an app update to load the new attributes
240        await omni.kit.app.get_app().next_update_async()
241
242        # Play simulation for a few frames for each box
243        timeline.play()
244        for _ in range(20):
245            await omni.kit.app.get_app().next_update_async()
246        timeline.pause()
247
248    # Iteratively apply forces to the boxes to move them around then pull them all together towards the pallet center
249    await apply_forces_async(stage, boxes, pallet_prim)
250
251    # Remove rigid body dynamics of the boxes until all other scenarios are completed
252    for box in boxes:
253        UsdPhysics.RigidBodyAPI(box).GetRigidBodyEnabledAttr().Set(False)
254
255    # Increase the friction to prevent sliding of the boxes on the pallet before removing the collision walls
256    physics_material.CreateStaticFrictionAttr().Set(0.9)
257    physics_material.CreateDynamicFrictionAttr().Set(0.9)
258
259    # Remove collision walls
260    for wall in collision_walls:
261        stage.RemovePrim(wall.GetPath())
262    return boxes
263
264
265# Run the example scenario
266async def run_box_stacking_scenarios_async(num_pallets=1, env_url=None):
267    # List of pallets and boxes to randomly choose from with their respective weights
268    pallets_urls_and_weights = [
269        ("/Isaac/Environments/Simple_Warehouse/Props/SM_PaletteA_01.usd", 0.25),
270        ("/Isaac/Environments/Simple_Warehouse/Props/SM_PaletteA_02.usd", 0.75),
271    ]
272    boxes_urls_and_weights = [
273        ("/Isaac/Environments/Simple_Warehouse/Props/SM_CardBoxA_01.usd", 0.02),
274        ("/Isaac/Environments/Simple_Warehouse/Props/SM_CardBoxB_01.usd", 0.06),
275        ("/Isaac/Environments/Simple_Warehouse/Props/SM_CardBoxC_01.usd", 0.12),
276        ("/Isaac/Environments/Simple_Warehouse/Props/SM_CardBoxD_01.usd", 0.80),
277    ]
278
279    # Load a predefined or create a new stage
280    if env_url is not None:
281        env_path = env_url if env_url.startswith("omniverse://") else get_assets_root_path() + env_url
282        omni.usd.get_context().open_stage(env_path)
283        stage = omni.usd.get_context().get_stage()
284    else:
285        omni.usd.get_context().new_stage()
286        stage = omni.usd.get_context().get_stage()
287        distant_light = stage.DefinePrim("/World/Lights/DistantLight", "DistantLight")
288        distant_light.CreateAttribute("inputs:intensity", Sdf.ValueTypeNames.Float).Set(400.0)
289        if not distant_light.HasAttribute("xformOp:rotateXYZ"):
290            UsdGeom.Xformable(distant_light).AddRotateXYZOp()
291        distant_light.GetAttribute("xformOp:rotateXYZ").Set((0, 60, 0))
292        dome_light = stage.DefinePrim("/World/Lights/DomeLight", "DomeLight")
293        dome_light.CreateAttribute("inputs:intensity", Sdf.ValueTypeNames.Float).Set(500.0)
294
295    # Spawn the pallets
296    pallets = []
297    pallets_urls, pallets_weights = zip(*pallets_urls_and_weights)
298    rand_pallet_urls = random.choices(pallets_urls, weights=pallets_weights, k=num_pallets)
299    # Custom pallet poses for the environment
300    custom_pallet_locations = [
301        (-9.3, 5.3, 1.3),
302        (-9.3, 7.3, 1.3),
303        (-9.3, -0.6, 1.3),
304    ]
305    random.shuffle(custom_pallet_locations)
306    for i, pallet_url in enumerate(rand_pallet_urls):
307        # Use a custom location for every other pallet
308        if env_url is not None:
309            if i % 2 == 0 and custom_pallet_locations:
310                rand_loc = Gf.Vec3d(*custom_pallet_locations.pop())
311            else:
312                rand_loc = Gf.Vec3d(-6.5, i * 1.75, 0) + Gf.Vec3d(random.uniform(-0.2, 0.2), random.uniform(0, 0.2), 0)
313        else:
314            rand_loc = Gf.Vec3d(i * 1.5, 0, 0) + Gf.Vec3d(random.uniform(0, 0.2), random.uniform(-0.2, 0.2), 0)
315        rand_rot = (0, 0, random.choice([180, 90, 0, -90, -180]) + random.uniform(-15, 15))
316        pallet_prim = create_asset_with_colliders(
317            stage, pallet_url, f"/World/Pallet_{i}", location=rand_loc, rotation=rand_rot
318        )
319        pallets.append(pallet_prim)
320
321    # Stack the boxes on the pallets
322    total_boxes = []
323    for pallet in pallets:
324        if env_url is not None:
325            rand_num_boxes = random.randint(8, 15)
326            stacked_boxes = await stack_boxes_on_pallet_async(
327                pallet, boxes_urls_and_weights, num_boxes=rand_num_boxes, drop_height=1.0
328            )
329        else:
330            rand_num_boxes = random.randint(12, 20)
331            stacked_boxes = await stack_boxes_on_pallet_async(pallet, boxes_urls_and_weights, num_boxes=rand_num_boxes)
332        total_boxes.extend(stacked_boxes)
333
334    # Re-enable rigid body dynamics of the boxes and run the simulation for a while
335    for box in total_boxes:
336        UsdPhysics.RigidBodyAPI(box).GetRigidBodyEnabledAttr().Set(True)
337    timeline = omni.timeline.get_timeline_interface()
338    timeline.play()
339    for _ in range(200):
340        await omni.kit.app.get_app().next_update_async()
341    timeline.pause()
342
343
344async def run_scenarios_async():
345    await run_box_stacking_scenarios_async(num_pallets=6)
346    await run_box_stacking_scenarios_async(num_pallets=6, env_url="/Isaac/Environments/Simple_Warehouse/warehouse.usd")
347
348
349asyncio.ensure_future(run_scenarios_async())

Simready Assets SDG Example#

Script editor example for using SimReady Assets to randomize the scene. SimReady Assets are physically accurate 3D objects with realistic properties, behavior, and data connections that are optimized for simulation.

Note

The example can only run in async mode and requires the SimReady Explorer window to be enabled to process the search requests.

The example script will create an SDG randomization and capture pipeline scenario with a table, a plate, and a number of items on top of the plate. The scene will be simulated for a while and then the captured images will be saved to disk.

The standalone example can also be run directly (on Windows use python.bat instead of python.sh):

./python.sh standalone_examples/api/isaacsim.replicator.examples/simready_assets_sdg.py
../_images/isim_5.0_replicator_tut_viewport_randomization_simready_assets.jpg
Simready Assets SDG Example
  1import asyncio
  2import os
  3import random
  4
  5import omni.kit.app
  6import omni.replicator.core as rep
  7import omni.timeline
  8import omni.usd
  9from isaacsim.core.utils.semantics import upgrade_prim_semantics_to_labels
 10from pxr import Gf, Sdf, Usd, UsdGeom, UsdPhysics
 11
 12# Make sure the simready explorer extension is enabled
 13ext_manager = omni.kit.app.get_app().get_extension_manager()
 14if not ext_manager.is_extension_enabled("omni.simready.explorer"):
 15    ext_manager.set_extension_enabled_immediate("omni.simready.explorer", True)
 16import omni.simready.explorer as sre
 17
 18
 19def enable_simready_explorer():
 20    if sre.get_instance().browser_model is None:
 21        import omni.kit.actions.core as actions
 22
 23        actions.execute_action("omni.simready.explorer", "toggle_window")
 24
 25
 26async def search_assets_async():
 27    print(f"Searching for simready assets...")
 28    tables = await sre.find_assets(["table", "furniture"])
 29    plates = await sre.find_assets(["plate"])
 30    bowls = await sre.find_assets(["bowl"])
 31    dishes = plates + bowls
 32    fruits = await sre.find_assets(["fruit"])
 33    vegetables = await sre.find_assets(["vegetable"])
 34    items = fruits + vegetables
 35    return tables, dishes, items
 36
 37
 38async def run_simready_randomization_async(stage, camera_prim, render_product, tables, dishes, items):
 39    print(f"Creating new temp layer for randomizing the scene...")
 40    simready_temp_layer = Sdf.Layer.CreateAnonymous("TempSimreadyLayer")
 41    session = stage.GetSessionLayer()
 42    session.subLayerPaths.append(simready_temp_layer.identifier)
 43
 44    with Usd.EditContext(stage, simready_temp_layer):
 45        # Load the simready assets with rigid body properties
 46        variants = {"PhysicsVariant": "RigidBody"}
 47
 48        # Choose a random table from the list of tables and add it to the stage with physics
 49        table_asset = random.choice(tables)
 50        print(f"\tAdding table '{table_asset.name}' with colliders and disabled rigid body properties")
 51        _, table_prim_path = sre.add_asset_to_stage(table_asset.main_url, variants=variants, payload=True)
 52        table_prim = stage.GetPrimAtPath(table_prim_path)
 53        upgrade_prim_semantics_to_labels(table_prim)
 54        if not table_prim.HasAPI(UsdPhysics.RigidBodyAPI):
 55            rigid_body_api = UsdPhysics.RigidBodyAPI.Apply(table_prim)
 56        else:
 57            rigid_body_api = UsdPhysics.RigidBodyAPI(table_prim)
 58        rigid_body_api.CreateRigidBodyEnabledAttr(False)
 59
 60        # Compute the height of the table from its bounding box
 61        bbox_cache = UsdGeom.BBoxCache(Usd.TimeCode.Default(), includedPurposes=[UsdGeom.Tokens.default_])
 62        table_bbox = bbox_cache.ComputeWorldBound(table_prim)
 63        table_size = table_bbox.GetRange().GetSize()
 64
 65        # Choose one random plate from the list of plates
 66        dish_asset = random.choice(dishes)
 67        _, dish_prim_path = sre.add_asset_to_stage(dish_asset.main_url, variants=variants, payload=True)
 68
 69        dish_prim = stage.GetPrimAtPath(dish_prim_path)
 70        upgrade_prim_semantics_to_labels(dish_prim)
 71
 72        # Compute the height of the plate from its bounding box
 73        dish_bbox = bbox_cache.ComputeWorldBound(dish_prim)
 74        dish_size = dish_bbox.GetRange().GetSize()
 75
 76        # Get a random position for the plate near the center of the table
 77        placement_reduction = 0.75
 78        x_range = (table_size[0] - dish_size[0]) / 2 * placement_reduction
 79        y_range = (table_size[1] - dish_size[1]) / 2 * placement_reduction
 80        dish_x = random.uniform(-x_range, x_range)
 81        dish_y = random.uniform(-y_range, y_range)
 82        dish_z = table_size[2] + dish_size[2] / 2
 83
 84        # Move the plate to the random position on the table
 85        dish_location = Gf.Vec3f(dish_x, dish_y, dish_z)
 86        dish_prim.GetAttribute("xformOp:translate").Set(dish_location)
 87        print(f"\tAdded '{dish_asset.name}' at: {dish_location}")
 88
 89        # Spawn a random number of items above the plate
 90        num_items = random.randint(2, 4)
 91        print(f"\tAdding {num_items} items above the plate '{dish_asset.name}':")
 92        item_prims = []
 93        for _ in range(num_items):
 94            item_asset = random.choice(items)
 95            _, item_prim_path = sre.add_asset_to_stage(item_asset.main_url, variants=variants, payload=True)
 96            item_prim = stage.GetPrimAtPath(item_prim_path)
 97            upgrade_prim_semantics_to_labels(item_prim)
 98            item_prims.append(item_prim)
 99
100        current_z = dish_z
101        xy_offset = dish_size[0] / 4
102        for item_prim in item_prims:
103            item_bbox = bbox_cache.ComputeWorldBound(item_prim)
104            item_size = item_bbox.GetRange().GetSize()
105            item_x = dish_x + random.uniform(-xy_offset, xy_offset)
106            item_y = dish_y + random.uniform(-xy_offset, xy_offset)
107            item_z = current_z + item_size[2] / 2
108            item_location = Gf.Vec3f(item_x, item_y, item_z)
109            item_prim.GetAttribute("xformOp:translate").Set(item_location)
110            print(f"\t\t'{item_prim.GetName()}' at: {item_location}")
111            current_z += item_size[2]
112
113        num_sim_steps = 25
114        print(f"\tRunning the simulation for {num_sim_steps} steps for the items to settle...")
115        timeline = omni.timeline.get_timeline_interface()
116        timeline.play()
117        for _ in range(num_sim_steps):
118            await omni.kit.app.get_app().next_update_async()
119        print(f"\tPausing the simulation")
120        timeline.pause()
121
122        print(f"\tMoving the camera above the scene to capture the scene...")
123        camera_prim.GetAttribute("xformOp:translate").Set(Gf.Vec3f(dish_x, dish_y, dish_z + 2))
124        render_product.hydra_texture.set_updates_enabled(True)
125        await rep.orchestrator.step_async(delta_time=0.0, rt_subframes=16)
126        render_product.hydra_texture.set_updates_enabled(False)
127        await omni.kit.app.get_app().next_update_async()
128
129    print("\tStopping the timeline")
130    timeline.stop()
131    await omni.kit.app.get_app().next_update_async()
132
133    print(f"\tRemoving the temp layer")
134    session.subLayerPaths.remove(simready_temp_layer.identifier)
135    simready_temp_layer = None
136
137
138async def run_simready_randomizations_async(num_scenarios):
139    await omni.usd.get_context().new_stage_async()
140    stage = omni.usd.get_context().get_stage()
141    rep.orchestrator.set_capture_on_play(False)
142    random.seed(15)
143
144    # Add lights to the scene
145    dome_light = stage.DefinePrim("/World/DomeLight", "DomeLight")
146    dome_light.CreateAttribute("inputs:intensity", Sdf.ValueTypeNames.Float).Set(500.0)
147    distant_light = stage.DefinePrim("/World/DistantLight", "DistantLight")
148    if not distant_light.GetAttribute("xformOp:rotateXYZ"):
149        UsdGeom.Xformable(distant_light).AddRotateXYZOp()
150    distant_light.GetAttribute("xformOp:rotateXYZ").Set((-75, 0, 0))
151    distant_light.CreateAttribute("inputs:intensity", Sdf.ValueTypeNames.Float).Set(2500)
152
153    # Simready explorer window needs to be created for the search to work
154    enable_simready_explorer()
155
156    # Search for the simready assets
157    tables, dishes, items = await search_assets_async()
158    print(f"\tFound {len(tables)} tables, {len(dishes)} dishes, {len(items)} items")
159
160    # Create the writer and the render product for capturing the scene
161    output_dir = os.path.join(os.getcwd(), "_out_simready_assets")
162    print(f"\tInitializing writer, output directory: {output_dir}...")
163    writer = rep.writers.get("BasicWriter")
164    writer.initialize(output_dir=output_dir, rgb=True)
165
166    # Disable the render by default, enable it when capturing the scene
167    camera_prim = stage.DefinePrim("/World/SceneCamera", "Camera")
168    UsdGeom.Xformable(camera_prim).AddTranslateOp()
169    rp = rep.create.render_product(camera_prim.GetPath(), (512, 512))
170    rp.hydra_texture.set_updates_enabled(False)
171    writer.attach(rp)
172
173    for i in range(num_scenarios):
174        print(f"Running simready randomization scenario {i}..")
175        await run_simready_randomization_async(
176            stage=stage, camera_prim=camera_prim, render_product=rp, tables=tables, dishes=dishes, items=items
177        )
178
179    print("Waiting for the data collection to complete")
180    await rep.orchestrator.wait_until_complete_async()
181    print("Detaching writer and destroying render product")
182    writer.detach()
183    rp.destroy()
184
185
186num_scenarios = 5
187print(f"Running {num_scenarios} simready randomization scenarios...")
188asyncio.ensure_future(run_simready_randomizations_async(num_scenarios))
Simready Assets SDG Example
  1from isaacsim import SimulationApp
  2
  3simulation_app = SimulationApp(launch_config={"headless": False})
  4
  5import asyncio
  6import os
  7import random
  8
  9import omni.kit.app
 10import omni.replicator.core as rep
 11import omni.timeline
 12import omni.usd
 13from pxr import Gf, Sdf, Usd, UsdGeom, UsdPhysics
 14
 15# Make sure the simready explorer extension is enabled
 16ext_manager = omni.kit.app.get_app().get_extension_manager()
 17if not ext_manager.is_extension_enabled("omni.simready.explorer"):
 18    ext_manager.set_extension_enabled_immediate("omni.simready.explorer", True)
 19import omni.simready.explorer as sre
 20
 21
 22def enable_simready_explorer():
 23    if sre.get_instance().browser_model is None:
 24        import omni.kit.actions.core as actions
 25
 26        actions.execute_action("omni.simready.explorer", "toggle_window")
 27
 28
 29async def search_assets_async():
 30    print(f"\tSearching for simready assets...")
 31    tables = await sre.find_assets(["table", "furniture"])
 32    plates = await sre.find_assets(["plate"])
 33    bowls = await sre.find_assets(["bowl"])
 34    dishes = plates + bowls
 35    fruits = await sre.find_assets(["fruit"])
 36    vegetables = await sre.find_assets(["vegetable"])
 37    items = fruits + vegetables
 38    return tables, dishes, items
 39
 40
 41def run_simready_randomization(stage, camera_prim, render_product, tables, dishes, items):
 42    print(f"Creating new temp layer for randomizing the scene...")
 43    simready_temp_layer = Sdf.Layer.CreateAnonymous("TempSimreadyLayer")
 44    session = stage.GetSessionLayer()
 45    session.subLayerPaths.append(simready_temp_layer.identifier)
 46    with Usd.EditContext(stage, simready_temp_layer):
 47        # Load the simready assets with rigid body properties
 48        variants = {"PhysicsVariant": "RigidBody"}
 49
 50        # Choose a random table from the list of tables and add it to the stage with physics
 51        table_asset = random.choice(tables)
 52        _, table_prim_path = sre.add_asset_to_stage(table_asset.main_url, variants=variants, payload=True)
 53        print(f"\tAdded '{table_asset.name}'")
 54
 55        print(f"\tDisabling rigid body properties and keeping only colliders...")
 56        # Disable the rigid body properties and keep only the colliders
 57        table_prim = stage.GetPrimAtPath(table_prim_path)
 58        if not table_prim.HasAPI(UsdPhysics.RigidBodyAPI):
 59            rigid_body_api = UsdPhysics.RigidBodyAPI.Apply(table_prim)
 60        else:
 61            rigid_body_api = UsdPhysics.RigidBodyAPI(table_prim)
 62        rigid_body_api.CreateRigidBodyEnabledAttr(False)
 63
 64        # Compute the height of the table from its bounding box
 65        bbox_cache = UsdGeom.BBoxCache(Usd.TimeCode.Default(), includedPurposes=[UsdGeom.Tokens.default_])
 66        table_bbox = bbox_cache.ComputeWorldBound(table_prim)
 67        table_size = table_bbox.GetRange().GetSize()
 68
 69        # Choose one random plate from the list of plates
 70        dish_asset = random.choice(dishes)
 71        _, dish_prim_path = sre.add_asset_to_stage(dish_asset.main_url, variants=variants, payload=True)
 72        print(f"\tAdded '{dish_asset.name}'")
 73
 74        # Compute the height of the plate from its bounding box
 75        dish_prim = stage.GetPrimAtPath(dish_prim_path)
 76        dish_bbox = bbox_cache.ComputeWorldBound(dish_prim)
 77        dish_size = dish_bbox.GetRange().GetSize()
 78
 79        # Get a random position for the plate on the table using the two sizes
 80        dish_x = random.uniform(-table_size[0] / 2 + dish_size[0] / 2, table_size[0] / 2 - dish_size[0] / 2)
 81        dish_y = random.uniform(-table_size[1] / 2 + dish_size[1] / 2, table_size[1] / 2 - dish_size[1] / 2)
 82        dish_z = table_size[2] + dish_size[2] / 2
 83
 84        # Move the plate to the random position on the table
 85        dish_prim.GetAttribute("xformOp:translate").Set(Gf.Vec3f(dish_x, dish_y, dish_z))
 86
 87        # Spawn a random number of items
 88        num_items = random.randint(2, 4)
 89        item_prims = []
 90        for _ in range(num_items):
 91            item_asset = random.choice(items)
 92            _, item_prim_path = sre.add_asset_to_stage(item_asset.main_url, variants=variants, payload=True)
 93            item_prims.append(stage.GetPrimAtPath(item_prim_path))
 94        print(f"\tAdded {[item.GetName() for item in item_prims]}")
 95
 96        # Move the items on top of each other above the plate
 97        current_z = dish_z
 98        xy_offset = dish_size[0] / 4
 99        for item_prim in item_prims:
100            item_bbox = bbox_cache.ComputeWorldBound(item_prim)
101            item_size = item_bbox.GetRange().GetSize()
102            item_x = dish_x + random.uniform(-xy_offset, xy_offset)
103            item_y = dish_y + random.uniform(-xy_offset, xy_offset)
104            item_z = current_z + item_size[2] / 2
105            item_prim.GetAttribute("xformOp:translate").Set(Gf.Vec3f(item_x, item_y, item_z))
106            current_z += item_size[2]
107
108        # Run the simulation for several frames for the items to settle
109        print(f"\tRunning the simulation for the items to settle...")
110        timeline = omni.timeline.get_timeline_interface()
111        timeline.play()
112        for _ in range(25):
113            simulation_app.update()
114        print(f"\tPausing the simulation")
115        timeline.pause()
116
117        # Move the camera above the dish
118        print(f"\tMoving the camera above the dish and capturing the scene...")
119        camera_prim.GetAttribute("xformOp:translate").Set(Gf.Vec3f(dish_x, dish_y, dish_z + 2))
120
121        # Toggle the render product and capture the scene
122        render_product.hydra_texture.set_updates_enabled(True)
123        rep.orchestrator.step(delta_time=0.0, rt_subframes=16)
124        render_product.hydra_texture.set_updates_enabled(False)
125        print("\tStoping the timeline")
126        timeline.stop()
127
128    simulation_app.update()
129    session.subLayerPaths.remove(simready_temp_layer.identifier)
130    simready_temp_layer = None
131    print(f"\tRemoved the temp layer")
132
133
134def run_simready_randomizations(num_scenarios):
135    omni.usd.get_context().new_stage()
136    stage = omni.usd.get_context().get_stage()
137    rep.orchestrator.set_capture_on_play(False)
138    random.seed(8)
139    rep.set_global_seed(8)
140
141    # Add lights to the scene
142    dome_light = stage.DefinePrim("/World/DomeLight", "DomeLight")
143    dome_light.CreateAttribute("inputs:intensity", Sdf.ValueTypeNames.Float).Set(500.0)
144    distant_light = stage.DefinePrim("/World/DistantLight", "DistantLight")
145    if not distant_light.GetAttribute("xformOp:rotateXYZ"):
146        UsdGeom.Xformable(distant_light).AddRotateXYZOp()
147    distant_light.GetAttribute("xformOp:rotateXYZ").Set((-75, 0, 0))
148    distant_light.CreateAttribute("inputs:intensity", Sdf.ValueTypeNames.Float).Set(2500)
149
150    # Simready explorer window needs to be created for the search to work
151    enable_simready_explorer()
152
153    # Search for the simready assets and wait until the task is complete
154    search_task = asyncio.ensure_future(search_assets_async())
155    while not search_task.done():
156        simulation_app.update()
157    tables, dishes, items = search_task.result()
158    print(f"\tFound {len(tables)} tables, {len(dishes)} dishes, {len(items)} items")
159
160    # Create the writer and the render product for capturing the scene
161    output_dir = os.path.join(os.getcwd(), "_out_simready_assets")
162    print(f"\tWriting to {output_dir}...")
163    writer = rep.writers.get("BasicWriter")
164    writer.initialize(output_dir=output_dir, rgb=True)
165
166    # Disable the render by default, enable it when capturing the scene
167    camera_prim = stage.DefinePrim("/World/SceneCamera", "Camera")
168    UsdGeom.Xformable(camera_prim).AddTranslateOp()
169    rp = rep.create.render_product(camera_prim.GetPath(), (512, 512))
170    rp.hydra_texture.set_updates_enabled(False)
171    writer.attach(rp)
172
173    # Create the scenarios and capture the scene
174    for i in range(num_scenarios):
175        print(f"Running simready randomization scenario {i}..")
176        run_simready_randomization(
177            stage=stage, camera_prim=camera_prim, render_product=rp, tables=tables, dishes=dishes, items=items
178        )
179
180    print("Waiting for the data collection to complete")
181    rep.orchestrator.wait_until_complete()
182    print("Detaching writer and destroying render product")
183    writer.detach()
184    rp.destroy()
185
186
187num_scenarios = 5
188print(f"Running {num_scenarios} simready randomization scenarios...")
189run_simready_randomizations(num_scenarios)
190
191simulation_app.close()