Using scatter_2d in Isaac Sim Script Editor

The goal is:

  1. create a plane
  2. use scatter_2d to scatter pallets into the plane in a collision free fashion
  3. randomize the camera movement such that it always looks at the average position of pallets

Currently, when I click on preview after clicking on Run button in Isaac Sim interactive, I only see the plane through camera. Also, I am not sure if the units or ordering of x, y, z are correct. I couldn’t find a guide on further detailing of camera movement.

import omni.replicator.core as rep
from datetime import datetime
import omni.usd



import omni.isaac.core.utils.bounds as bounds_utils
import omni.isaac.core.utils.prims as prims_utils


with rep.new_layer():
    # Define paths for the character, the props, the environment and the surface where the assets will be scattered in.

    PALLET_URL = "omniverse://localhost/NVIDIA/Assets/ArchVis/Industrial/Pallets/Pallet_B1.usd"
    
    
    plane = rep.create.plane(scale=2000, visible=True, semantics=[("class", "plane")])
    print('plane type: ', type(plane))
    
    # bb_cache = bounds_utils.create_bbox_cache()

    # combined_range_arr = bounds_utils.compute_combined_aabb(bb_cache, prim_paths=plane)

    # min_x, min_y, min_z, max_x, max_y, max_z = combined_range_arr
    # print('min_x {}, min_y {}, min_z {}, max_x {}, max_y {}, and max_z {}'.format(
    #     min_x, min_y, min_z, max_x, max_y, max_z))
    
    # stage = omni.usd.get_context().get_stage()
   
    with plane:
        rep.physics.collider()
    
    print('type of plane: ', print(plane))
    

    def scatter_pallets(prim):
        pallets = rep.create.from_usd(PALLET_URL, semantics=[('class', 'pallet')], count=5)
        with pallets:
            rep.physics.collider()
            rep.modify.pose(scale=0.001)
            rep.randomizer.scatter_2d(surface_prims=plane, check_for_collisions=True)
            
        return pallets

    # Register randomization

    rep.randomizer.register(scatter_pallets)


    # Setup camera and attach it to render product
    camera = rep.create.camera(
        position=(871, 80, 343),
        focus_distance=800,
        f_stop=100,
        focal_length=40
        
        # focal_length = 24,
        # focus_distance = 400,
        # f_stop = 0.0
 
    )
    distance_light = rep.create.light(rotation=(315,0,0), intensity=3000, light_type="distant")
    render_product = rep.create.render_product(camera, resolution=(1024, 1024))


    timestamp = datetime.now().strftime("%Y_%m_%d-%I_%M_%S_%p")
    # Initialize and attach writer
    writer = rep.WriterRegistry.get("BasicWriter")
    writer.initialize(output_dir="/home/mona/Desktop/Isaac_Sim_Dummy_Out/pallet/" + timestamp , rgb=True, bounding_box_2d_tight=True)
    writer.attach([render_product])

    with rep.trigger.on_frame(num_frames=100):

        pallets = rep.randomizer.scatter_pallets(plane)
        with camera:
            rep.modify.pose(position=rep.distribution.uniform((600, 80, 300), (800, 100, 400)), look_at=pallets)

For example, when manipulating the camera params from the stage, I can see this is a good view:

But I am not sure how it can translate to the scripting and scaling in Isaac Sim.

Hi there,

for 1 and 2 you can use the offline_generation’s register_scatter_boxes function example. For 3 AFAIK it is not possible using replicator, only by extending the API with custom omnigraph nodes.

For 3 you could randomize the assets using the Isaac Sim / USD API and use Replicator to write the data (either from writers or annotators). Here is a more complex randomization example using Isaac Sim API that you could use as a starting example:

import os
import asyncio
import itertools

import numpy as np
import omni
from omni.isaac.core.utils.nucleus import get_assets_root_path
from pxr import Gf, Usd, UsdGeom, UsdLux
import omni.replicator.core as rep

# https://stackoverflow.com/questions/9600801/evenly-distributing-n-points-on-a-sphere
# https://arxiv.org/pdf/0912.4540.pdf
def next_point_on_sphere(idx, num_points, radius=1, origin=(0, 0, 0)):
    offset = 2.0 / num_points
    inc = np.pi * (3.0 - np.sqrt(5.0))
    z = ((idx * offset) - 1) + (offset / 2)
    phi = ((idx + 1) % num_points) * inc
    r = np.sqrt(1 - pow(z, 2))
    y = np.cos(phi) * r
    x = np.sin(phi) * r
    return [(x * radius) + origin[0], (y * radius) + origin[1], (z * radius) + origin[2]]


assets_root_path = get_assets_root_path()
FORKLIFT_PATH = assets_root_path + "/Isaac/Props/Forklift/forklift.usd"
PALLET_PATH = assets_root_path + "/Isaac/Props/Pallet/pallet.usd"
BIN_PATH = assets_root_path + "/Isaac/Props/KLT_Bin/small_KLT.usd"

stage = omni.usd.get_context().get_stage()

dome_light = UsdLux.DomeLight.Define(stage, "/World/Lights/DomeLight")
dome_light.GetIntensityAttr().Set(1000)

forklift_prim = stage.DefinePrim("/World/Forklift", "Xform")
forklift_prim.GetReferences().AddReference(FORKLIFT_PATH)
if not forklift_prim.GetAttribute("xformOp:translate"):
    UsdGeom.Xformable(forklift_prim).AddTranslateOp()
forklift_prim.GetAttribute("xformOp:translate").Set((-3, -3, 0))

pallet_prim = stage.DefinePrim("/World/Pallet", "Xform")
pallet_prim.GetReferences().AddReference(PALLET_PATH)
if not pallet_prim.GetAttribute("xformOp:translate"):
    UsdGeom.Xformable(pallet_prim).AddTranslateOp()
if not pallet_prim.GetAttribute("xformOp:rotateXYZ"):
    UsdGeom.Xformable(pallet_prim).AddRotateXYZOp()

bin_prim = stage.DefinePrim("/World/Bin", "Xform")
bin_prim.GetReferences().AddReference(BIN_PATH)
if not bin_prim.GetAttribute("xformOp:translate"):
    UsdGeom.Xformable(bin_prim).AddTranslateOp()
if not bin_prim.GetAttribute("xformOp:rotateXYZ"):
    UsdGeom.Xformable(bin_prim).AddRotateXYZOp()

cam = stage.DefinePrim("/World/Camera", "Camera")
if not cam.GetAttribute("xformOp:translate"):
    UsdGeom.Xformable(cam).AddTranslateOp()
if not cam.GetAttribute("xformOp:orient"):
    UsdGeom.Xformable(cam).AddOrientOp()


async def run_randomizations_async(num_frames, dome_light, dome_textures, pallet_prim, bin_prim, delay=0):
    textures_cycle = itertools.cycle(dome_textures)

    bb_cache = UsdGeom.BBoxCache(time=Usd.TimeCode.Default(), includedPurposes=[UsdGeom.Tokens.default_])
    pallet_size = bb_cache.ComputeWorldBound(pallet_prim).GetRange().GetSize()
    bin_size = bb_cache.ComputeWorldBound(bin_prim).GetRange().GetSize()

    out_dir = os.path.join(os.getcwd(), "_out_isaac_randomizer")
    print(f"Writing to {out_dir}")
    writer = rep.WriterRegistry.get("BasicWriter")
    writer.initialize(output_dir=out_dir, rgb=True)
    rp = rep.create.render_product(str(cam.GetPath()), (512, 512))
    writer.attach(rp)

    for i in range(num_frames):
        # Set next background texture
        dome_light.GetTextureFileAttr().Set(next(textures_cycle))

        # Make sure materials are properly loaded
        for _ in range(5):
            await omni.kit.app.get_app().next_update_async()

        # Randomize pallet pose
        pallet_prim.GetAttribute("xformOp:translate").Set(
            Gf.Vec3d(np.random.uniform(-2, 2), np.random.uniform(-2, 2), 0)
        )
        rand_z_rot = np.random.uniform(-90, 90)
        pallet_prim.GetAttribute("xformOp:rotateXYZ").Set(Gf.Vec3d(0, 0, rand_z_rot))
        pallet_tf_mat = omni.usd.get_world_transform_matrix(pallet_prim)
        pallet_rot = pallet_tf_mat.ExtractRotation()
        pallet_pos = pallet_tf_mat.ExtractTranslation()

        # Randomize bin position on top of the rotated pallet area making sure the bin is fully on the pallet
        rand_transl_x = np.random.uniform(-pallet_size[0] / 2 + bin_size[0] / 2, pallet_size[0] / 2 - bin_size[0] / 2)
        rand_transl_y = np.random.uniform(-pallet_size[1] / 2 + bin_size[1] / 2, pallet_size[1] / 2 - bin_size[1] / 2)
        # Adjust bin position to account for the random rotation of the pallet
        rand_z_rot_rad = np.deg2rad(rand_z_rot)
        rot_adjusted_transl_x = rand_transl_x * np.cos(rand_z_rot_rad) - rand_transl_y * np.sin(rand_z_rot_rad)
        rot_adjusted_transl_y = rand_transl_x * np.sin(rand_z_rot_rad) + rand_transl_y * np.cos(rand_z_rot_rad)
        bin_prim.GetAttribute("xformOp:translate").Set(
            Gf.Vec3d(
                pallet_pos[0] + rot_adjusted_transl_x,
                pallet_pos[1] + rot_adjusted_transl_y,
                pallet_pos[2] + pallet_size[2] + bin_size[2] / 2,
            )
        )
        # Keep bin rotation aligned with pallet
        bin_prim.GetAttribute("xformOp:rotateXYZ").Set(pallet_rot.GetAxis() * pallet_rot.GetAngle())

        # Get next camera position on a sphere looking at the bin with a randomized distance
        pallet_length = pallet_size.GetLength()
        rand_radius = np.random.uniform(2, 8) * pallet_length
        bin_pos = omni.usd.get_world_transform_matrix(bin_prim).ExtractTranslation()
        cam_pos = next_point_on_sphere(i, num_points=num_frames, radius=rand_radius, origin=bin_pos)
        cam.GetAttribute("xformOp:translate").Set(Gf.Vec3d(*cam_pos))

        eye = Gf.Vec3d(*cam_pos)
        target = Gf.Vec3d(*bin_pos)
        up_axis = Gf.Vec3d(0, 0, 1)
        look_at_quatd = Gf.Matrix4d().SetLookAt(eye, target, up_axis).GetInverse().ExtractRotation().GetQuat()
        cam.GetAttribute("xformOp:orient").Set(Gf.Quatf(look_at_quatd))

        await rep.orchestrator.step_async()
        await omni.kit.app.get_app().next_update_async()
        if delay > 0:
            await asyncio.sleep(delay)


num_frames = 120
dome_textures = [
    assets_root_path + "/NVIDIA/Assets/Skies/Cloudy/champagne_castle_1_4k.hdr",
    assets_root_path + "/NVIDIA/Assets/Skies/Clear/evening_road_01_4k.hdr",
    assets_root_path + "/NVIDIA/Assets/Skies/Clear/mealie_road_4k.hdr",
    assets_root_path + "/NVIDIA/Assets/Skies/Clear/qwantani_4k.hdr",
]
asyncio.ensure_future(run_randomizations_async(num_frames, dome_light, dome_textures, pallet_prim, bin_prim, delay=0.2))