Isaac Sim Script Editor: did not match C++ signature for get_world_transform_matrix

I am not sure how I can fix this error. I am adding a pallet in front of the forklift and then intend to throw pallets using scatter_2d on top of it in each frame.

I am running the script below in Isaac Sim Script Editor.

# This needs to be run inside Isaac Sim Script Editor not Omniverse Code Script Editor

import omni.replicator.core as rep
from datetime import datetime
from omni.isaac.core.utils.stage import get_current_stage, open_stage

import omni.isaac.core.utils.bounds as bounds_utils
import omni.isaac.core.utils.prims as prims_utils
from omni.isaac.core.utils.bounds import compute_combined_aabb, create_bbox_cache
from omni.isaac.core.utils.rotations import euler_angles_to_quat, quat_to_euler_angles, lookat_to_quatf

from omni.isaac.core.utils import prims
import omni.usd
from pxr import UsdGeom, Usd, Gf, UsdPhysics, PhysxSchema

import random

import numpy as np


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


FORKLIFT_URL = "omniverse://localhost/NVIDIA/Assets/Isaac/2022.2.1/Isaac/Props/Forklift/forklift.usd"
PALLET_URL = "omniverse://localhost/NVIDIA/Assets/ArchVis/Industrial/Pallets/Pallet_B1.usd"
ENV_URL ="omniverse://localhost/NVIDIA/Assets/Isaac/2022.2.0/Isaac/Samples/Replicator/Stage/full_warehouse_worker_and_anim_cameras.usd"
SCOPE_NAME = "/MyScope"


open_stage(ENV_URL)
stage =get_current_stage()

floor_prims = [x.GetPath() for x in stage.Traverse() if "SM_floor" in x.GetName() and prims_utils.get_prim_type_name(x.GetPath()) == "Xform"]
print('dir floor_prims: ', dir(floor_prims))
bb_cache = bounds_utils.create_bbox_cache()
combined_range_arr = bounds_utils.compute_combined_aabb(bb_cache, prim_paths=floor_prims)

print('combined_range_arr: ', combined_range_arr)

margin = 2
min_x, min_y, min_z, max_x, max_y, max_z = combined_range_arr


def randomize_forklift():
    forklift = rep.create.from_usd(FORKLIFT_URL, semantics=[('class', 'forklift')])
    with forklift:
        rep.physics.collider()
        rep.modify.pose(
            position=rep.distribution.uniform((min_x + margin, min_y + margin, 0), (max_x - margin, max_y - margin, 0)),
            rotation=rep.distribution.uniform((0, 0, -90), (0, 0, 90)),
            scale=100
        )
    return forklift

# Register randomization

rep.randomizer.register(randomize_forklift)


def scatter_pallets(prim):
    # Calculate the bounds of the prim to create a scatter plane of its size
    bb_cache = create_bbox_cache()
    bbox3d_gf = bb_cache.ComputeLocalBound(prim)
    prim_tf_gf = omni.usd.get_world_transform_matrix(prim)

    # Calculate the bounds of the prim
    bbox3d_gf.Transform(prim_tf_gf)
    range_size = bbox3d_gf.GetRange().GetSize()

    # Get the quaterion of the prim in xyzw format from usd
    prim_quat_gf = prim_tf_gf.ExtractRotation().GetQuaternion()
    prim_quat_xyzw = (prim_quat_gf.GetReal(), *prim_quat_gf.GetImaginary())

    # Create a plane on the pallet to scatter the boxes on
    plane_scale = (range_size[0] * 5, range_size[1] * 5, 1)
    plane_pos_gf = prim_tf_gf.ExtractTranslation() + Gf.Vec3d(0, 0, range_size[2])
    plane_rot_euler_deg = quat_to_euler_angles(np.array(prim_quat_xyzw), degrees=True)
    scatter_plane = rep.create.plane(
        scale=plane_scale, position=plane_pos_gf, rotation=plane_rot_euler_deg, visible=False
    )
    pallets = rep.create.from_usd(PALLET_URL, semantics=[('class', 'pallet')], count=2)
    with pallets:
        rep.physics.collider()
        rep.randomizer.scatter_2d(surface_prims=prim, check_for_collisions=True),
        rep.modify.pose(scale=0.01)
    return pallets

# Register randomization

rep.randomizer.register(scatter_pallets)



# Setup camera and attach it to render product
camera = rep.create.camera(
    focus_distance=800,
    # f_stop=0.5,
    f_stop=500,
    #focal_length=613.634
)
render_product = rep.create.render_product(camera, resolution=(640, 480))


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/forklift_warehouse/" + timestamp , rgb=True, bounding_box_2d_tight=True)
writer.attach([render_product])

with rep.trigger.on_frame(num_frames=50):
    forklift = rep.randomizer.randomize_forklift()
    # Spawn the pallet in front of the forklift with a random offset on the Y axis
    print('type of forklift: ', type(forklift))
    forklift_tf = omni.usd.get_world_transform_matrix(forklift) #TODO: I get an error here when replacing forklift with cube
    print('forklift_tf: ', forklift_tf)
    pallet_offset_tf = Gf.Matrix4d().SetTranslate(Gf.Vec3d(0, random.uniform(-1.2, -2.4), 0))
    pallet_pos_gf = (pallet_offset_tf * forklift_tf).ExtractTranslation()
    forklift_quat_gf = forklift_tf.ExtractRotation().GetQuaternion()
    forklift_quat_xyzw = (forklift_quat_gf.GetReal(), *forklift_quat_gf.GetImaginary())

    pallet_prim = prims.create_prim(
        prim_path=f"{SCOPE_NAME}/pallet",
        position=pallet_pos_gf,
        orientation=forklift_quat_xyzw,
        usd_path=PALLET_URL,
        semantic_label="pallet",
    )
    
    print('pallet_prim: ', pallet_prim)
    print('type of pallet prim: ', type(pallet_prim))
    

    pallets = rep.randomizer.scatter_pallets(pallet_prim)
    with camera:
        rep.modify.pose(position=rep.distribution.uniform((min_x + margin, min_y + margin, 4), (max_x - margin, max_y - margin, 7)),
                        look_at=pallets)

Here’s the error message:

I am not sure how I can pass forklift to forklift_tf = omni.usd.get_world_transform_matrix(forklift)

Please note the type of forklift is omni.replicator.core.scripts.utils.utils.ReplicatorItem

How can I convert it to prim?

Hi @mona.jalal - Someone from our team will take a look at this question and provide the response.

If you have the path of the prim in stage, you can access it using GetPrimAtPath:

context = omni.usd.get_context()
stage = context.get_stage()
prim = stage.GetPrimAtPath(path)
1 Like

This topic was automatically closed 14 days after the last reply. New replies are no longer allowed.