Skip to content

asset_conversion_utils

convert_scene_urdf_to_json(urdf, json_path)

Converts a scene from a URDF file to a JSON file.

This function loads the scene described by the URDF file into the OmniGibson simulator, plays the simulation, and saves the scene to a JSON file. After saving, it removes the "init_info" from the JSON file and saves it again.

Parameters:

Name Type Description Default
urdf str

The file path to the URDF file describing the scene.

required
json_path str

The file path where the JSON file will be saved.

required
Source code in OmniGibson/omnigibson/utils/asset_conversion_utils.py
def convert_scene_urdf_to_json(urdf, json_path):
    """
    Converts a scene from a URDF file to a JSON file.

    This function loads the scene described by the URDF file into the OmniGibson simulator,
    plays the simulation, and saves the scene to a JSON file. After saving, it removes the
    "init_info" from the JSON file and saves it again.

    Args:
        urdf (str): The file path to the URDF file describing the scene.
        json_path (str): The file path where the JSON file will be saved.
    """
    # First, load the requested objects from the URDF into OG
    _load_scene_from_urdf(urdf=urdf)

    # Play the simulator, then save
    og.sim.play()
    Path(os.path.dirname(json_path)).mkdir(parents=True, exist_ok=True)
    og.sim.save(json_paths=[json_path])

    # Load the json, remove the init_info because we don't need it, then save it again
    with open(json_path, "r") as f:
        scene_info = json.load(f)

    scene_info.pop("init_info")

    with open(json_path, "w+") as f:
        json.dump(scene_info, f, cls=_TorchEncoder, indent=4)

convert_urdf_to_usd(urdf_path, obj_category, obj_model, dataset_name='custom_dataset', use_omni_convex_decomp=False, use_usda=False, merge_fixed_joints=False)

Imports an object from a URDF file into the current stage.

Parameters:

Name Type Description Default
urdf_path str

Path to URDF file to import

required
obj_category str

The category of the object.

required
obj_model str

The model name of the object.

required
dataset_name str

The name of the dataset.

'custom_dataset'
use_omni_convex_decomp bool

Whether to use omniverse's built-in convex decomposer for collision meshes

False
use_usda bool

If set, will write files to .usda files instead of .usd (bigger memory footprint, but human-readable)

False
merge_fixed_joints bool

whether to merge fixed joints or not

False

Returns:

Type Description
2 - tuple
  • str: Absolute path to post-processed URDF file used to generate USD
  • str: Absolute path to the imported USD file
Source code in OmniGibson/omnigibson/utils/asset_conversion_utils.py
def convert_urdf_to_usd(
    urdf_path,
    obj_category,
    obj_model,
    dataset_name="custom_dataset",
    use_omni_convex_decomp=False,
    use_usda=False,
    merge_fixed_joints=False,
):
    """
    Imports an object from a URDF file into the current stage.

    Args:
        urdf_path (str): Path to URDF file to import
        obj_category (str): The category of the object.
        obj_model (str): The model name of the object.
        dataset_name (str): The name of the dataset.
        use_omni_convex_decomp (bool): Whether to use omniverse's built-in convex decomposer for collision meshes
        use_usda (bool): If set, will write files to .usda files instead of .usd
            (bigger memory footprint, but human-readable)
        merge_fixed_joints (bool): whether to merge fixed joints or not

    Returns:
        2-tuple:
            - str: Absolute path to post-processed URDF file used to generate USD
            - str: Absolute path to the imported USD file
    """
    # Preprocess input URDF to account for meta links
    dataset_root = get_dataset_path(dataset_name)
    urdf_path = _add_meta_links_to_urdf(
        urdf_path=urdf_path, obj_category=obj_category, obj_model=obj_model, dataset_root=dataset_root
    )
    # Import URDF
    cfg = _create_urdf_import_config(
        use_convex_decomposition=use_omni_convex_decomp,
        merge_fixed_joints=merge_fixed_joints,
    )

    # Pre-clear the scene.
    og.sim.clear()

    model_root_path = pathlib.Path(dataset_root) / "objects" / obj_category / obj_model
    usd_dir = model_root_path / "usd"
    usd_filename = obj_model + (".usda" if use_usda else ".usd")
    usd_path = usd_dir / usd_filename
    log.debug(f"Importing {obj_category}, {obj_model} into path {usd_path}...")
    # Only import if it doesn't exist
    lazy.omni.kit.commands.execute(
        "URDFParseAndImportFile",
        urdf_path=urdf_path,
        import_config=cfg,
        dest_path=str(usd_path),
    )

    # Also clear again to release the file.
    og.sim.clear()

    # Find all the relevant files
    configuration_dir = usd_dir / "configuration"
    physics_usd_path = configuration_dir / f"{obj_model}_physics.usd"
    sensor_usd_path = configuration_dir / f"{obj_model}_sensor.usd"
    base_usd_path = configuration_dir / f"{obj_model}_base.usd"

    # Remove the mixed and sensor files
    usd_path.unlink()
    sensor_usd_path.unlink()

    # Move the materials directory contents
    current_materials = configuration_dir / "materials" / "textures"
    new_materials = model_root_path / "material"
    if current_materials.exists():
        new_materials.mkdir()
        for texture in current_materials.iterdir():
            texture.rename(new_materials / texture.name)

    # Load the physics stage and prepare to flatten it and save it.
    physics_stage = lazy.pxr.Usd.Stage.Open(str(physics_usd_path))

    # Prior to flattening things, we want to remove all instanceable flags and refs. We do this because
    # if you flatten with instancing the flatten function ends up duplicating the whole mesh tree.
    # We keep track to reenable them post-flattening
    instanceable_prims_and_refs = {}
    for prim in physics_stage.Traverse():
        arcs = lazy.pxr.Usd.PrimCompositionQuery.GetDirectReferences(prim).GetCompositionArcs()
        if not arcs:
            continue
        assert len(arcs) == 1, f"Expected only one reference arc for {prim.GetPath()}"
        instanceable_prims_and_refs[str(prim.GetPath())] = (
            str(arcs[0].GetTargetPrimPath()),
            prim.IsInstanceable(),
        )
    for instanceable_prim_path, _ in instanceable_prims_and_refs.items():
        instanceable_prim = physics_stage.GetPrimAtPath(instanceable_prim_path)
        instanceable_prim.SetInstanceable(False)
        instanceable_prim.GetReferences().ClearReferences()

    # Flatten everything and save at the target location.
    physics_stage.Flatten()
    physics_stage.Export(str(usd_path))
    del physics_stage

    # Now reload at the correct path.
    side_stage = lazy.pxr.Usd.Stage.Open(str(usd_path))

    # Return everything back to its original reference state.
    for instanceable_prim_path, (ref, is_instanceable) in instanceable_prims_and_refs.items():
        instanceable_prim = side_stage.GetPrimAtPath(instanceable_prim_path)
        instanceable_prim.SetInstanceable(is_instanceable and _ALLOW_INSTANCING)
        instanceable_prim.GetReferences().AddReference("", ref)

    # Also update the asset paths
    def _update_path(asset_path):
        # Get the absolute path - the asset path is relative to where the USD is.
        absolute_asset_path = (usd_dir / asset_path).resolve()
        absolute_original_materials_path = current_materials.resolve()

        # If the file is not in our current materials directory, we don't update.
        if not absolute_asset_path.is_relative_to(absolute_original_materials_path):
            return asset_path

        # Otherwise, first get the new absolute path of the asset in the new folder
        relative_to_material_dir = absolute_asset_path.relative_to(absolute_original_materials_path)
        absolute_moved_path = new_materials / relative_to_material_dir

        # Finally, find where that file is relative to the path where the USD goes.
        final_path = os.path.relpath(absolute_moved_path, usd_dir.resolve())
        print("Updating", asset_path, "to", final_path)
        return final_path

    lazy.pxr.UsdUtils.ModifyAssetPaths(side_stage.GetRootLayer(), _update_path)

    # Go through all of the prims in the visuals and colliders trees, and promote the mesh prims
    # one level up, so instead of visuals -> linkname -> mesh we just have visuals -> linkname where
    # the linkname prim has the mesh and xforms combined.
    visuals_prim = side_stage.GetPrimAtPath("/visuals")
    colliders_prim = side_stage.GetPrimAtPath("/colliders")
    links = list(visuals_prim.GetChildren()) + list(colliders_prim.GetChildren())
    wrappers = [wrapper for link in links for wrapper in link.GetChildren()]
    for parent_prim in wrappers:
        parent_path = parent_prim.GetPath()
        grandparent_path = parent_path.GetParentPath()

        # Find the child prim - it's actually away at a reference. There should be exactly one.
        references = parent_prim.GetPrimStack()[0].referenceList.prependedItems
        assert len(references) == 1, f"{parent_path} is not a reference!"
        referenced_wrapper_path_str = str(references[0].primPath)
        referenced_wrapper_prim = side_stage.GetPrimAtPath(referenced_wrapper_path_str)
        assert referenced_wrapper_prim.IsValid()

        child_prim = referenced_wrapper_prim.GetChild("mesh")
        assert child_prim.IsValid()
        child_path = child_prim.GetPath()

        # Duplicate the properties on the parent prim onto the child.
        for attr in parent_prim.GetAttributes():
            if attr.IsAuthored():
                # Get attribute info
                attr_name = attr.GetName()
                attr_type = attr.GetTypeName()

                # Create or get the attribute on destination
                dest_attr = child_prim.CreateAttribute(attr_name, attr_type)

                # Copy the value
                if attr.HasValue():
                    dest_attr.Set(attr.Get())

        # Delete the parent prim
        del side_stage.GetRootLayer().GetPrimAtPath(grandparent_path).nameChildren[parent_path.name]

        # Move the child prim to the parent's path.
        assert lazy.pxr.Sdf.CopySpec(side_stage.GetRootLayer(), child_path, side_stage.GetRootLayer(), parent_path)

        # Delete the child's original path
        del side_stage.GetRootLayer().GetPrimAtPath(child_path.GetParentPath()).nameChildren[child_path.name]

    # Remove the meshes hierarchy altogether
    del side_stage.GetRootLayer().rootPrims["meshes"]

    # Delete any collision groups
    for child_prim in list(side_stage.Traverse()):
        if child_prim.GetTypeName() == "PhysicsCollisionGroup":
            del (
                side_stage.GetRootLayer()
                .GetPrimAtPath(child_prim.GetPath().GetParentPath())
                .nameChildren[child_prim.GetPath().name]
            )

    # Find references to correct. The idea here is that we do not want our `visuals` or `collisions`
    # prims to be references, because we want to be able to put properties on the meshes underneath.
    # Instead, we'll just make the mesh prims instanceable.
    found_reference_prims = {}
    for possible_referrer in list(side_stage.Traverse()):
        if not possible_referrer.IsValid():
            continue
        # Check if the prim has a reference on it
        references = possible_referrer.GetPrimStack()[0].referenceList.prependedItems
        if references:
            assert possible_referrer.GetName() in ["visuals", "collisions"]
            assert (
                len(references) == 1
            ), f"Expected exactly one reference for {possible_referrer.GetPath()}, got {len(references)}"
            referrer_path = possible_referrer.GetPath()
            referee_path = references[0].primPath
            found_reference_prims[referrer_path] = referee_path
            del side_stage.GetRootLayer().GetPrimAtPath(referrer_path.GetParentPath()).nameChildren[referrer_path.name]

    # Create references for all of the individual meshes
    for referrer_prim_path, referee_path in found_reference_prims.items():
        referee_prim = side_stage.GetPrimAtPath(referee_path)

        # Create an XFormPrim for the collisions/visuals tree
        referrer_prim = lazy.pxr.UsdGeom.Xform.Define(side_stage, referrer_prim_path)

        # For each of the mesh originals, add a reference to the collisions/visuals prim
        for mesh_original in referee_prim.GetChildren():
            # Get its type
            assert mesh_original.IsValid(), f"Can't find mesh {mesh_original.GetPath()}"
            prim_type = mesh_original.GetTypeName()

            # Create the prim
            name = mesh_original.GetName()
            mesh_prim = side_stage.DefinePrim(referrer_prim.GetPath().AppendChild(name), prim_type)

            # Add the collision APIs
            if referrer_prim_path.name == "collisions":
                collision_api = lazy.pxr.UsdPhysics.CollisionAPI.Apply(mesh_prim)
                mesh_collision_api = lazy.pxr.UsdPhysics.MeshCollisionAPI.Apply(mesh_prim)
                mesh_collision_api.GetApproximationAttr().Set("convexHull")
                convex_hull_api = lazy.pxr.PhysxSchema.PhysxConvexHullCollisionAPI.Apply(mesh_prim)

            # Add the reference to the actual collisions
            mesh_prim.GetReferences().AddReference("", mesh_original.GetPath())

            # Make it instanceable
            mesh_prim.SetInstanceable(_ALLOW_INSTANCING)

    # Flatten everything and save at the target location.
    side_stage.Save()
    del side_stage

    # Remove the old stage files.
    shutil.rmtree(configuration_dir)

    return urdf_path, str(usd_path)

find_all_prim_children_with_type(prim_type, root_prim)

Recursively searches children of @root_prim to find all instances of prim that satisfy type @prim_type

Parameters:

Name Type Description Default
prim_type str

Type of the prim to search

required
root_prim Prim

Root prim to search

required

Returns:

Type Description
list of Usd.Prim

All found prims whose prim type includes @prim_type

Source code in OmniGibson/omnigibson/utils/asset_conversion_utils.py
def find_all_prim_children_with_type(prim_type, root_prim):
    """
    Recursively searches children of @root_prim to find all instances of prim that satisfy type @prim_type

    Args:
        prim_type (str): Type of the prim to search
        root_prim (Usd.Prim): Root prim to search

    Returns:
        list of Usd.Prim: All found prims whose prim type includes @prim_type
    """
    found_prims = []
    for child in root_prim.GetChildren():
        if prim_type in child.GetTypeName():
            found_prims.append(child)
        found_prims += find_all_prim_children_with_type(prim_type=prim_type, root_prim=child)

    return found_prims

generate_collision_meshes(trimesh_mesh, method='coacd', hull_count=32, discard_not_volume=True, error_handling=False)

Generates a set of collision meshes from a trimesh mesh using CoACD.

Parameters:

Name Type Description Default
trimesh_mesh Trimesh

The trimesh mesh to generate the collision mesh from.

required
method str

Method to generate collision meshes. Valid options are {"coacd", "convex"}

'coacd'
hull_count int

If @method="coacd", this sets the max number of hulls to generate

32
discard_not_volume bool

If @method="coacd" and set to True, this discards any generated hulls that are not proper volumes

True
error_handling bool

If true, will run coacd_runner.py and handle the coacd assertion fault by using convex hull instead

False

Returns:

Type Description
List[Trimesh]

The collision meshes.

Source code in OmniGibson/omnigibson/utils/asset_conversion_utils.py
def generate_collision_meshes(
    trimesh_mesh, method="coacd", hull_count=32, discard_not_volume=True, error_handling=False
):
    """
    Generates a set of collision meshes from a trimesh mesh using CoACD.

    Args:
        trimesh_mesh (trimesh.Trimesh): The trimesh mesh to generate the collision mesh from.
        method (str): Method to generate collision meshes. Valid options are {"coacd", "convex"}
        hull_count (int): If @method="coacd", this sets the max number of hulls to generate
        discard_not_volume (bool): If @method="coacd" and set to True, this discards any generated hulls
            that are not proper volumes
        error_handling (bool): If true, will run coacd_runner.py and handle the coacd assertion fault by using convex hull instead

    Returns:
        List[trimesh.Trimesh]: The collision meshes.
    """
    # If the mesh is convex or the mesh is a proper volume and similar to its convex hull, simply return that directly
    if trimesh_mesh.is_convex or (
        trimesh_mesh.is_volume and (trimesh_mesh.volume / trimesh_mesh.convex_hull.volume) > 0.90
    ):
        hulls = [trimesh_mesh.convex_hull]

    elif method == "coacd":
        if error_handling:
            # Run CoACD with error handling
            import subprocess
            import sys
            import tempfile
            import pickle
            import os

            # Create separate temp files with proper extensions
            with tempfile.NamedTemporaryFile(suffix=".pkl", delete=False) as f:
                data_path = f.name
                pickle.dump((trimesh_mesh.vertices, trimesh_mesh.faces, hull_count), f)

            script_path = tempfile.mktemp(suffix=".py")
            result_path = tempfile.mktemp(suffix=".pkl")

            # Run subprocess with clean file paths
            success = (
                subprocess.call(
                    [sys.executable, os.path.join(os.path.dirname(__file__), "coacd_runner.py"), data_path, result_path]
                )
                == 0
            )

            # Process results or fallback
            if success and os.path.exists(result_path):
                with open(result_path, "rb") as f:
                    result = pickle.load(f)

                # Process results as before
                hulls = []
                coacd_vol = 0.0
                for vs, fs in result:
                    hull = trimesh.Trimesh(vertices=vs, faces=fs, process=False)
                    if discard_not_volume and not hull.is_volume:
                        continue
                    hulls.append(hull)
                    coacd_vol += hull.convex_hull.volume

                # Check if we found any valid hulls
                if len(hulls) == 0:
                    print("No valid collision meshes generated, falling back to convex hull")
                    hulls = [trimesh_mesh.convex_hull]
                else:
                    # Compare volume ratios as in original code
                    vol_ratio = coacd_vol / trimesh_mesh.convex_hull.volume
                    if 0.95 < vol_ratio < 1.05:
                        print("MINIMAL CHANGE -- USING CONVEX HULL INSTEAD")
                        hulls = [trimesh_mesh.convex_hull]
            else:
                print("CoACD processing failed, falling back to convex hull")
                hulls = [trimesh_mesh.convex_hull]

            # Clean up temp files
            for path in [data_path, script_path, result_path]:
                if os.path.exists(path):
                    os.remove(path)
        else:
            try:
                import coacd
            except ImportError:
                raise ImportError("Please install the `coacd` package to use this function.")

            # Get the vertices and faces
            coacd_mesh = coacd.Mesh(trimesh_mesh.vertices, trimesh_mesh.faces)

            # Run CoACD with the hull count
            result = coacd.run_coacd(
                coacd_mesh,
                max_convex_hull=hull_count,
                max_ch_vertex=60,
            )

            # Convert the returned vertices and faces to trimesh meshes
            # and assert that they are volumes (and if not, discard them if required)
            hulls = []
            coacd_vol = 0.0
            for vs, fs in result:
                hull = trimesh.Trimesh(vertices=vs, faces=fs, process=False)
                if discard_not_volume and not hull.is_volume:
                    continue
                hulls.append(hull)
                coacd_vol += hull.convex_hull.volume

            # Assert that we got _some_ collision meshes
            assert len(hulls) > 0, "No collision meshes generated!"

            # Compare coacd's generation compared to the original mesh's convex hull
            # If the difference is small (<10% volume difference), simply keep the convex hull
            vol_ratio = coacd_vol / trimesh_mesh.convex_hull.volume
            if 0.95 < vol_ratio < 1.05:
                print("MINIMAL CHANGE -- USING CONVEX HULL INSTEAD")
                # from IPython import embed; embed()
                hulls = [trimesh_mesh.convex_hull]

    elif method == "convex":
        hulls = [trimesh_mesh.convex_hull]

    else:
        raise ValueError(f"Invalid collision mesh generation method specified: {method}")

    # Sanity check all convex hulls
    # For whatever reason, some convex hulls are not true volumes, so we take the convex hull again
    # See https://github.com/mikedh/trimesh/issues/535
    hulls = [hull.convex_hull if not hull.is_volume else hull for hull in hulls]

    # For each hull, simplify so that the complexity is guaranteed to be Omniverse-GPU compatible
    # See https://docs.omniverse.nvidia.com/extensions/latest/ext_physics/rigid-bodies.html#collision-settings
    simplified_hulls = [simplify_convex_hull(hull) for hull in hulls]

    return simplified_hulls

generate_urdf_for_mesh(asset_path, out_dir, category, mdl, collision_method=None, hull_count=32, up_axis='z', scale=1.0, check_scale=False, rescale=False, overwrite=False)

Generate URDF file for either single mesh or articulated files. Each submesh in articulated files (glb, gltf) will be extracted as a separate link.

Parameters:

Name Type Description Default
asset_path str

Path to the input mesh file (.obj, .glb, .gltf)

required
out_dir str

Output directory

required
category str

Category name for the object

required
mdl str

Model name

required
collision_method str or None

Method for generating collision meshes ("convex", "coacd", or None)

None
hull_count int

Maximum number of convex hulls for COACD method

32
up_axis str

Up axis for the model ("y" or "z")

'z'
scale float

User choice scale, will be overwritten if check_scale and rescale

1.0
check_scale bool

Whether to check mesh size based on heuristic

False
rescale bool

Whether to rescale mesh if check_scale

False
overwrite bool

Whether to overwrite existing files

False
Source code in OmniGibson/omnigibson/utils/asset_conversion_utils.py
def generate_urdf_for_mesh(
    asset_path,
    out_dir,
    category,
    mdl,
    collision_method=None,
    hull_count=32,
    up_axis="z",
    scale=1.0,
    check_scale=False,
    rescale=False,
    overwrite=False,
):
    """
    Generate URDF file for either single mesh or articulated files.
    Each submesh in articulated files (glb, gltf) will be extracted as a separate link.

    Args:
        asset_path (str): Path to the input mesh file (.obj, .glb, .gltf)
        out_dir (str): Output directory
        category (str): Category name for the object
        mdl (str): Model name
        collision_method (str or None): Method for generating collision meshes ("convex", "coacd", or None)
        hull_count (int): Maximum number of convex hulls for COACD method
        up_axis (str): Up axis for the model ("y" or "z")
        scale (float): User choice scale, will be overwritten if check_scale and rescale
        check_scale (bool): Whether to check mesh size based on heuristic
        rescale (bool): Whether to rescale mesh if check_scale
        overwrite (bool): Whether to overwrite existing files
    """

    # Convert out_dir to Path object
    if isinstance(out_dir, str):
        out_dir = pathlib.Path(out_dir)
    if isinstance(asset_path, str):
        asset_path = pathlib.Path(asset_path)

    # Validate that the filename starts with a letter. Isaac 4.5 has issues if you don't do this.
    assert asset_path.stem[
        0
    ].isalpha(), f"Invalid asset path: {asset_path}. Isaac Sim expects the filename to start with a letter."

    # Create directory structure
    if not overwrite:
        assert not out_dir.exists(), f"Object directory {out_dir} already exists!"
    out_dir.mkdir(parents=True, exist_ok=True)

    obj_name = "_".join([category, mdl])

    visual_mesh = trimesh.load(str(asset_path), force="mesh", process=False, skip_materials=True)
    if isinstance(visual_mesh, list):
        visual_mesh = visual_mesh[0]  # Take first mesh if multiple

    # Generate collision meshes if requested
    collision_meshes = []
    if collision_method is not None:
        collision_meshes = generate_collision_meshes(
            visual_mesh, method=collision_method, hull_count=hull_count, error_handling=True
        )

    # Keep track of the base transform
    rpy = [0, 0, 0]

    # Handle rotation for up_axis if needed
    if up_axis == "y":
        rpy = [math.pi / 2, 0, 0]

    # Compute new scale if check_scale = True
    new_scale = 1.0

    if check_scale:
        # Find the link with the biggest bounding box
        bbox_size = visual_mesh.bounding_box.extents

        click.echo(f"Visual mesh bounding box size: {bbox_size}")

        # Check if any dimension is too large (> 100)
        if any(size > 5.0 for size in bbox_size):
            if any(size > 50.0 for size in bbox_size):
                if any(size > 500.0 for size in bbox_size):
                    new_scale = 0.001
                else:
                    new_scale = 0.01
            else:
                new_scale = 0.1

            click.echo(
                "Warning: The bounding box sounds a bit large. "
                "We just wanted to confirm this is intentional. You can skip this check by passing check_scale = False."
            )

        # Check if any dimension is too small (< 0.01)
        elif all(size < 0.005 for size in bbox_size):
            new_scale = 1000.0
            click.echo(
                "Warning: The bounding box sounds a bit small. "
                "We just wanted to confirm this is intentional. You can skip this check by passing check_scale = False."
            )

        else:
            click.echo("Size is reasonable, no scaling")

    # Rescale mesh if rescale= True, else scale based on function input scale
    if rescale:
        click.echo(f"Original scale {scale} be overwrtten to {new_scale}")
        scale = new_scale

    # Create directory structure for the output
    obj_link_mesh_folder = out_dir / "shape"
    obj_link_mesh_folder.mkdir(exist_ok=True)
    obj_link_collision_mesh_folder = obj_link_mesh_folder / "collision"
    obj_link_collision_mesh_folder.mkdir(exist_ok=True)

    # Process collision meshes
    collision_info = []
    for i, collision_mesh in enumerate(collision_meshes):
        # Export collision mesh filename
        collision_filename = f"{obj_name}_base_link_collision_{i}.obj"

        # Scale collision mesh to unit bbox if needed
        bounding_box = collision_mesh.bounding_box.extents
        assert all(x > 0 for x in bounding_box), f"Invalid bounding box: {bounding_box}"

        collision_scale = 1.0 / bounding_box
        collision_scale_matrix = th.eye(4)
        collision_scale_matrix[:3, :3] = th.diag(th.as_tensor(collision_scale))

        # Create a copy to avoid modifying the original
        scaled_collision_mesh = collision_mesh.copy()
        scaled_collision_mesh.apply_transform(collision_scale_matrix.numpy())

        # Export collision mesh
        collision_path = obj_link_collision_mesh_folder / collision_filename
        scaled_collision_mesh.export(collision_path, file_type="obj")

        # Since we've already applied the transform, scale includes only the sizing adjustment
        collision_info.append({"filename": collision_path, "scale": 1.0 / collision_scale})

    # Generate URDF XML
    tree_root = ET.Element("robot")
    tree_root.attrib = {"name": mdl}

    # Create a base_link as the root
    base_link = ET.SubElement(tree_root, "link")
    base_link.attrib = {"name": "base_link"}

    rpy_str = " ".join(str(item) for item in rpy)

    # Add visual geometry
    visual_xml = ET.SubElement(base_link, "visual")
    visual_origin_xml = ET.SubElement(visual_xml, "origin")
    visual_origin_xml.attrib = {"xyz": "0 0 0", "rpy": rpy_str}
    visual_geometry_xml = ET.SubElement(visual_xml, "geometry")
    visual_mesh_xml = ET.SubElement(visual_geometry_xml, "mesh")
    visual_mesh_xml.attrib = {
        "filename": str(asset_path),
        "scale": f"{scale} {scale} {scale}",
    }

    # Add collision geometries
    for i, collision in enumerate(collision_info):
        collision_xml = ET.SubElement(base_link, "collision")
        collision_xml.attrib = {"name": f"base_link_collision_{i}"}
        collision_origin_xml = ET.SubElement(collision_xml, "origin")
        collision_origin_xml.attrib = {"xyz": "0 0 0", "rpy": rpy_str}  # Zero transform since already applied
        collision_geometry_xml = ET.SubElement(collision_xml, "geometry")
        collision_mesh_xml = ET.SubElement(collision_geometry_xml, "mesh")
        collision_mesh_xml.attrib = {
            "filename": str(collision["filename"]),
            "scale": " ".join(str(item) for item in scale * collision["scale"]),
        }

    # Save URDF file
    xmlstr = minidom.parseString(ET.tostring(tree_root)).toprettyxml(indent="   ")
    xmlio = io.StringIO(xmlstr)
    tree = ET.parse(xmlio)

    urdf_dir = out_dir / "urdf"
    urdf_dir.mkdir(exist_ok=True)
    urdf_path = urdf_dir / f"{mdl}.urdf"
    with open(urdf_path, "wb") as f:
        tree.write(f, xml_declaration=True)

    return str(urdf_path)

get_collision_approximation_for_urdf(urdf_path, collision_method='coacd', hull_count=32, coacd_links=None, convex_links=None, no_decompose_links=None, visual_only_links=None, ignore_links=None)

Computes collision approximation for all collision meshes (which are assumed to be non-convex) in the given URDF.

NOTE: This is an in-place operation! It will overwrite @urdf_path

Parameters:

Name Type Description Default
urdf_path str

Absolute path to the URDF to decompose

required
collision_method str

Default collision method to use. Valid options are: {"coacd", "convex"}

'coacd'
hull_count int

Maximum number of convex hulls to decompose individual visual meshes into. Only relevant if @collision_method is "coacd"

32
coacd_links None or list of str

If specified, links that should use CoACD to decompose collision meshes

None
convex_links None or list of str

If specified, links that should use convex hull to decompose collision meshes

None
no_decompose_links None or list of str

If specified, links that should not have any special collision decomposition applied. This will only use the convex hull

None
visual_only_links None or list of str

If specified, link names corresponding to links that should have no collision associated with them (so any pre-existing collisions will be removed!)

None
ignore_links None or list of str

If specified, link names corresponding to links that should be skipped during collision generation process

None
Source code in OmniGibson/omnigibson/utils/asset_conversion_utils.py
def get_collision_approximation_for_urdf(
    urdf_path,
    collision_method="coacd",
    hull_count=32,
    coacd_links=None,
    convex_links=None,
    no_decompose_links=None,
    visual_only_links=None,
    ignore_links=None,
):
    """
    Computes collision approximation for all collision meshes (which are assumed to be non-convex) in
    the given URDF.

    NOTE: This is an in-place operation! It will overwrite @urdf_path

    Args:
        urdf_path (str): Absolute path to the URDF to decompose
        collision_method (str): Default collision method to use. Valid options are: {"coacd", "convex"}
        hull_count (int): Maximum number of convex hulls to decompose individual visual meshes into.
            Only relevant if @collision_method is "coacd"
        coacd_links (None or list of str): If specified, links that should use CoACD to decompose collision meshes
        convex_links (None or list of str): If specified, links that should use convex hull to decompose collision meshes
        no_decompose_links (None or list of str): If specified, links that should not have any special collision
            decomposition applied. This will only use the convex hull
        visual_only_links (None or list of str): If specified, link names corresponding to links that should have
            no collision associated with them (so any pre-existing collisions will be removed!)
        ignore_links (None or list of str): If specified, link names corresponding to links that should be skipped
            during collision generation process
    """
    # Load URDF
    urdf_dir = os.path.dirname(urdf_path)
    tree = ET.parse(urdf_path)
    root = tree.getroot()

    # Next, iterate over each visual mesh and define collision meshes for them
    coacd_links = set() if coacd_links is None else set(coacd_links)
    convex_links = set() if convex_links is None else set(convex_links)
    no_decompose_links = set() if no_decompose_links is None else set(no_decompose_links)
    visual_only_links = set() if visual_only_links is None else set(visual_only_links)
    ignore_links = set() if ignore_links is None else set(ignore_links)
    col_mesh_rel_folder = "meshes/collision"
    col_mesh_folder = pathlib.Path(urdf_dir) / col_mesh_rel_folder
    col_mesh_folder.mkdir(exist_ok=True, parents=True)
    for link in root.findall("link"):
        link_name = link.attrib["name"]
        old_cols = link.findall("collision")
        # Completely skip this link if this a link to explicitly skip or we have no collision tags
        if link_name in ignore_links or len(old_cols) == 0:
            continue

        print(f"Generating collision approximation for link {link_name}...")
        generated_new_col = False
        idx = 0
        if link_name not in visual_only_links:
            for vis in link.findall("visual"):
                # Get origin
                origin = vis.find("origin")
                # Check all geometries
                geoms = vis.findall("geometry/*")
                # We should only have a single geom, so assert here
                assert len(geoms) == 1
                # Check whether we actually need to generate a collision approximation
                # No need if the geom type is not a mesh (i.e.: it's a primitive -- so we assume if a collision is already
                # specified, it's that same primitive)
                geom = geoms[0]
                if geom.tag != "mesh":
                    continue
                mesh_path = os.path.join(os.path.dirname(urdf_path), geom.attrib["filename"])
                tm = trimesh.load(mesh_path, force="mesh", process=False)

                if link_name in coacd_links:
                    method = "coacd"
                elif link_name in convex_links:
                    method = "convex"
                elif link_name in no_decompose_links:
                    # Output will just be ignored, so skip
                    continue
                else:
                    method = collision_method
                collision_meshes = generate_collision_meshes(
                    trimesh_mesh=tm,
                    method=method,
                    hull_count=hull_count,
                )
                # Save and merge precomputed collision mesh
                collision_filenames_and_scales = []
                for i, collision_mesh in enumerate(collision_meshes):
                    processed_collision_mesh = collision_mesh.copy()
                    processed_collision_mesh._cache.cache["vertex_normals"] = processed_collision_mesh.vertex_normals
                    collision_filename = f"{link_name}_col_{idx}.obj"

                    # OmniGibson requires unit-bbox collision meshes, so here we do that scaling
                    bounding_box = processed_collision_mesh.bounding_box.extents
                    assert all(
                        x > 0 for x in bounding_box
                    ), f"Bounding box extents are not all positive: {bounding_box}"
                    collision_scale = 1.0 / bounding_box
                    collision_scale_matrix = th.eye(4)
                    collision_scale_matrix[:3, :3] = th.diag(th.as_tensor(collision_scale))
                    processed_collision_mesh.apply_transform(collision_scale_matrix.numpy())
                    processed_collision_mesh.export(col_mesh_folder / collision_filename, file_type="obj")
                    collision_filenames_and_scales.append((collision_filename, 1 / collision_scale))

                    idx += 1

                for collision_filename, collision_scale in collision_filenames_and_scales:
                    collision_xml = ET.SubElement(link, "collision")
                    collision_xml.attrib = {"name": collision_filename.replace(".obj", "")}
                    # Add origin info if defined
                    if origin is not None:
                        collision_xml.append(deepcopy(origin))
                    collision_geometry_xml = ET.SubElement(collision_xml, "geometry")
                    collision_mesh_xml = ET.SubElement(collision_geometry_xml, "mesh")
                    collision_mesh_xml.attrib = {
                        "filename": os.path.join(col_mesh_rel_folder, collision_filename),
                        "scale": " ".join([str(item) for item in collision_scale]),
                    }

                if link_name not in no_decompose_links:
                    generated_new_col = True

        # If we generated a new set of collision meshes, remove the old ones
        if generated_new_col or link_name in visual_only_links:
            for col in old_cols:
                link.remove(col)

    # Save the URDF file
    _save_xmltree_as_urdf(
        root_element=root,
        name=os.path.splitext(os.path.basename(urdf_path))[0],
        dirpath=os.path.dirname(urdf_path),
        unique_urdf=False,
    )

import_obj_metadata(usd_path, obj_category, obj_model, dataset_root, force_asset_pipeline_materials=False)

Imports metadata for a given object model from the dataset. This metadata consist of information that is NOT included in the URDF file and instead included in the various JSON files shipped in iGibson and BEHAVIOR-1K datasets.

Parameters:

Name Type Description Default
usd_path str

Path to USD file

required
obj_category str

The category of the object.

required
obj_model str

The model name of the object.

required
dataset_root str

The root directory of the dataset.

required
force_asset_pipeline_materials bool

Flag to force the use of asset pipeline materials. Defaults to False.

False

Raises:

Type Description
ValueError

If the bounding box size is not found in the metadata.

Returns:

Type Description
bool

Success status of the conversion

Source code in OmniGibson/omnigibson/utils/asset_conversion_utils.py
def import_obj_metadata(usd_path, obj_category, obj_model, dataset_root, force_asset_pipeline_materials=False):
    """
    Imports metadata for a given object model from the dataset. This metadata consist of information
    that is NOT included in the URDF file and instead included in the various JSON files shipped in
    iGibson and BEHAVIOR-1K datasets.

    Args:
        usd_path (str): Path to USD file
        obj_category (str): The category of the object.
        obj_model (str): The model name of the object.
        dataset_root (str): The root directory of the dataset.
        force_asset_pipeline_materials (bool, optional): Flag to force the use of asset pipeline materials. Defaults to False.

    Raises:
        ValueError: If the bounding box size is not found in the metadata.

    Returns:
        bool: Success status of the conversion
    """
    usd_path = pathlib.Path(usd_path)
    usd_dir = usd_path.parent
    model_root_path = usd_dir.parent

    # Load model
    lazy.isaacsim.core.utils.stage.open_stage(str(usd_path))
    stage = lazy.isaacsim.core.utils.stage.get_current_stage()
    prim = stage.GetDefaultPrim()

    data = dict()
    for data_group in {"metadata", "mvbb_meta", "material_groups", "heights_per_link"}:
        data_path = model_root_path / f"misc/{data_group}.json"
        if data_path.exists():
            # Load data
            with open(data_path, "r") as f:
                data[data_group] = json.load(f)

    # If certain metadata doesn't exist, populate with some core info
    if "base_link_offset" not in data["metadata"]:
        data["metadata"]["base_link_offset"] = [0, 0, 0]
    if "bbox_size" not in data["metadata"]:
        raise ValueError("We cannot work without a bbox size.")

    # Pop bb and base link offset and meta links info
    base_link_offset = data["metadata"].pop("base_link_offset")
    default_bb = data["metadata"].pop("bbox_size")

    # Manually modify material groups info
    if "material_groups" in data:
        data["material_groups"] = {
            "groups": data["material_groups"][0],
            "links": data["material_groups"][1],
        }

    # Manually modify metadata
    if "openable_joint_ids" in data["metadata"]:
        data["metadata"]["openable_joint_ids"] = {
            str(pair[0]): pair[1] for pair in data["metadata"]["openable_joint_ids"]
        }

    # Grab light info if any
    meta_links = data["metadata"].get("meta_links", dict())

    log.debug("Process meta links")

    # Convert primitive meta links
    for link_name, link_metadata in meta_links.items():
        for meta_link_type, meta_link_infos in link_metadata.items():
            _generate_meshes_for_primitive_meta_links(stage, obj_model, link_name, meta_link_type, meta_link_infos)

    # Get all meta links, set them to guide purpose, and add some metadata
    # Here we want to include every link that has the meta__ prefix.
    # This includes meta links that get added into the URDF in earlier
    # stages.
    meta_link_prims = [
        p for p in prim.GetChildren() if p.GetName().startswith("meta__") and p.GetName().endswith("_link")
    ]
    for meta_prim in meta_link_prims:
        # Get meta link information
        unparsed_meta = meta_prim.GetName()[6:-5]  # remove meta__ and _link
        meta_parts = unparsed_meta.rsplit("_", 3)
        assert len(meta_parts) == 4, f"Invalid meta link name: {unparsed_meta}"
        link_name, meta_link_type, link_id, link_sub_id = meta_parts

        # Add the is_meta_link, meta_link_type, and meta_link_id attributes
        meta_prim.CreateAttribute("ig:isMetaLink", lazy.pxr.Sdf.ValueTypeNames.Bool)
        meta_prim.GetAttribute("ig:isMetaLink").Set(True)
        meta_prim.CreateAttribute("ig:metaLinkType", lazy.pxr.Sdf.ValueTypeNames.String)
        meta_prim.GetAttribute("ig:metaLinkType").Set(meta_link_type)
        meta_prim.CreateAttribute("ig:metaLinkId", lazy.pxr.Sdf.ValueTypeNames.String)
        meta_prim.GetAttribute("ig:metaLinkId").Set(link_id)
        meta_prim.CreateAttribute("ig:metaLinkSubId", lazy.pxr.Sdf.ValueTypeNames.Int)
        meta_prim.GetAttribute("ig:metaLinkSubId").Set(int(link_sub_id))

        # Set the purpose of the visual meshes to be guide
        visual_prim = meta_prim.GetChild("visuals")
        if visual_prim.IsValid():
            # If it's an imageable, set the purpose to guide
            if visual_prim.GetTypeName() == "Mesh":
                purpose_attr = lazy.pxr.UsdGeom.Imageable(visual_prim).CreatePurposeAttr()
                purpose_attr.Set(lazy.pxr.UsdGeom.Tokens.guide)
            for visual_mesh in visual_prim.GetChildren():
                if visual_mesh.GetTypeName() == "Mesh":
                    purpose_attr = lazy.pxr.UsdGeom.Imageable(visual_mesh).CreatePurposeAttr()
                    purpose_attr.Set(lazy.pxr.UsdGeom.Tokens.guide)

    log.debug("Done processing meta links")

    # Iterate over dict and replace any lists of dicts as dicts of dicts (with each dict being indexed by an integer)
    data = _recursively_replace_list_of_dict(data)

    log.debug("Done recursively replacing")

    # Create attributes for bb, offset, category, model and store values
    prim.CreateAttribute("ig:nativeBB", lazy.pxr.Sdf.ValueTypeNames.Vector3f)
    prim.CreateAttribute("ig:offsetBaseLink", lazy.pxr.Sdf.ValueTypeNames.Vector3f)
    prim.CreateAttribute("ig:category", lazy.pxr.Sdf.ValueTypeNames.String)
    prim.CreateAttribute("ig:model", lazy.pxr.Sdf.ValueTypeNames.String)
    prim.GetAttribute("ig:nativeBB").Set(lazy.pxr.Gf.Vec3f(*default_bb))
    prim.GetAttribute("ig:offsetBaseLink").Set(lazy.pxr.Gf.Vec3f(*base_link_offset))
    prim.GetAttribute("ig:category").Set(obj_category)
    prim.GetAttribute("ig:model").Set(obj_model)

    log.debug(f"data: {data}")

    # Store remaining data as metadata
    prim.SetCustomData(data)

    # Add material channels
    if force_asset_pipeline_materials:
        _force_asset_pipeline_materials(
            obj_prim=prim,
            obj_category=obj_category,
            obj_model=obj_model,
            usd_path=str(usd_path),
            dataset_root=dataset_root,
        )
    for link, link_tags in data["metadata"]["link_tags"].items():
        if "glass" in link_tags:
            _process_glass_link(prim.GetChild(link))

    # Rename model to be named <model> if not already named that
    old_prim_path = prim.GetPrimPath().pathString
    if old_prim_path.split("/")[-1] != obj_model:
        new_prim_path = "/".join(old_prim_path.split("/")[:-1]) + f"/{obj_model}"
        lazy.omni.kit.commands.execute("MovePrim", path_from=old_prim_path, path_to=new_prim_path)
        prim = stage.GetDefaultPrim()

    # Hacky way to avoid new prim being created at /World
    class DummyScene:
        prim_path = ""

    og.sim.render()

    mat_prims = find_all_prim_children_with_type(prim_type="Material", root_prim=prim)
    for i, mat_prim in enumerate(mat_prims):
        mat = MaterialPrim(mat_prim.GetPrimPath().pathString, f"mat{i}")
        mat.load(DummyScene)

    # Save stage
    stage.Save()

    # Return the root prim
    return prim

import_og_asset_from_urdf(category, model, dataset_root, urdf_path=None, collision_method='coacd', coacd_links=None, convex_links=None, no_decompose_links=None, visual_only_links=None, merge_fixed_joints=False, hull_count=32, overwrite=False, use_usda=False)

Imports an asset from URDF format into OmniGibson-compatible USD format. This will write the new USD (and copy the URDF if it does not already exist within @dataset_root) to @dataset_root

Parameters:

Name Type Description Default
category str

Category to assign to imported asset

required
model str

Model name to assign to imported asset

required
urdf_path None or str

If specified, external URDF that should be copied into the dataset first before converting into USD format. Otherwise, assumes that the urdf file already exists within @dataset_root dir

None
collision_method None or str

If specified, collision decomposition method to use to generate OmniGibson-compatible collision meshes. Valid options are {"coacd", "convex"}

'coacd'
coacd_links None or list of str

If specified, links that should use CoACD to decompose collision meshes

None
convex_links None or list of str

If specified, links that should use convex hull to decompose collision meshes

None
no_decompose_links None or list of str

If specified, links that should not have any special collision decomposition applied. This will only use the convex hull

None
visual_only_links None or list of str

If specified, links that should have no colliders associated with it

None
merge_fixed_joints bool

Whether to merge fixed joints or not

False
dataset_root str

Dataset root directory to use for writing imported USD file. Default is custom dataset path set from the global macros

required
hull_count int

Maximum number of convex hulls to decompose individual visual meshes into. Only relevant if @collision_method is "coacd"

32
overwrite bool

If set, will overwrite any pre-existing files

False
use_usda bool

If set, will write files to .usda files instead of .usd (bigger memory footprint, but human-readable)

False

Returns:

Type Description
3 - tuple
  • str: Absolute path to post-processed URDF file
  • str: Absolute path to generated USD file
  • Usd.Prim: Generated root USD prim (currently on active stage)
Source code in OmniGibson/omnigibson/utils/asset_conversion_utils.py
def import_og_asset_from_urdf(
    category,
    model,
    dataset_root,
    urdf_path=None,
    collision_method="coacd",
    coacd_links=None,
    convex_links=None,
    no_decompose_links=None,
    visual_only_links=None,
    merge_fixed_joints=False,
    hull_count=32,
    overwrite=False,
    use_usda=False,
):
    """
    Imports an asset from URDF format into OmniGibson-compatible USD format. This will write the new USD
    (and copy the URDF if it does not already exist within @dataset_root) to @dataset_root

    Args:
        category (str): Category to assign to imported asset
        model (str): Model name to assign to imported asset
        urdf_path (None or str): If specified, external URDF that should be copied into the dataset first before
            converting into USD format. Otherwise, assumes that the urdf file already exists within @dataset_root dir
        collision_method (None or str): If specified, collision decomposition method to use to generate
            OmniGibson-compatible collision meshes. Valid options are {"coacd", "convex"}
        coacd_links (None or list of str): If specified, links that should use CoACD to decompose collision meshes
        convex_links (None or list of str): If specified, links that should use convex hull to decompose collision meshes
        no_decompose_links (None or list of str): If specified, links that should not have any special collision
            decomposition applied. This will only use the convex hull
        visual_only_links (None or list of str): If specified, links that should have no colliders associated with it
        merge_fixed_joints (bool): Whether to merge fixed joints or not
        dataset_root (str): Dataset root directory to use for writing imported USD file. Default is custom dataset
            path set from the global macros
        hull_count (int): Maximum number of convex hulls to decompose individual visual meshes into.
            Only relevant if @collision_method is "coacd"
        overwrite (bool): If set, will overwrite any pre-existing files
        use_usda (bool): If set, will write files to .usda files instead of .usd
            (bigger memory footprint, but human-readable)

    Returns:
        3-tuple:
            - str: Absolute path to post-processed URDF file
            - str: Absolute path to generated USD file
            - Usd.Prim: Generated root USD prim (currently on active stage)
    """
    # Make sure all scaling is positive
    model_dir = os.path.join(dataset_root, "objects", category, model)
    os.makedirs(model_dir, exist_ok=overwrite)
    # urdf_path = make_asset_positive(urdf_fpath=urdf_path)

    # Update collisions if requested
    if collision_method is not None:
        print("Generating collision approximation for URDF...")
        get_collision_approximation_for_urdf(
            urdf_path=urdf_path,
            collision_method=collision_method,
            hull_count=hull_count,
            coacd_links=coacd_links,
            convex_links=convex_links,
            no_decompose_links=no_decompose_links,
            visual_only_links=visual_only_links,
        )

    # Generate metadata
    print("Recording object metadata from URDF...")
    record_obj_metadata_from_urdf(
        urdf_path=urdf_path,
        obj_dir=model_dir,
        joint_setting="zero",
        overwrite=overwrite,
    )

    # Convert to USD
    print("Converting obj URDF to USD...")
    og.launch()
    assert len(og.sim.scenes) == 0
    urdf_path, usd_path = convert_urdf_to_usd(
        urdf_path=urdf_path,
        obj_category=category,
        obj_model=model,
        dataset_root=dataset_root,
        use_omni_convex_decomp=False,  # We already pre-decomposed the values, so don' use omni convex decomp
        use_usda=use_usda,
        merge_fixed_joints=merge_fixed_joints,
    )

    prim = import_obj_metadata(usd_path=usd_path, obj_category=category, obj_model=model, dataset_root=dataset_root)
    print(
        f"\nConversion complete! Object has been successfully imported into OmniGibson-compatible USD, located at:\n\n{usd_path}\n"
    )

    return urdf_path, usd_path, prim

record_obj_metadata_from_urdf(urdf_path, obj_dir, joint_setting='zero', overwrite=False)

Records object metadata and writes it to misc/metadata.json within the object directory.

Parameters:

Name Type Description Default
urdf_path str

Path to object URDF

required
obj_dir str

Absolute path to the object's root directory

required
joint_setting str

Setting for joints when calculating canonical metadata. Valid options are {"low", "zero", "high"} (i.e.: lower joint limit, all 0 values, or upper joint limit)

'zero'
overwrite bool

Whether to overwrite any pre-existing data

False
Source code in OmniGibson/omnigibson/utils/asset_conversion_utils.py
def record_obj_metadata_from_urdf(urdf_path, obj_dir, joint_setting="zero", overwrite=False):
    """
    Records object metadata and writes it to misc/metadata.json within the object directory.

    Args:
        urdf_path (str): Path to object URDF
        obj_dir (str): Absolute path to the object's root directory
        joint_setting (str): Setting for joints when calculating canonical metadata. Valid options
            are {"low", "zero", "high"} (i.e.: lower joint limit, all 0 values, or upper joint limit)
        overwrite (bool): Whether to overwrite any pre-existing data
    """
    # Load the URDF file into urdfpy
    robot = URDF.load(urdf_path)

    # Do FK with everything at desired configuration
    if joint_setting == "zero":
        val = lambda jnt: 0.0
    elif joint_setting == "low":
        val = lambda jnt: jnt.limit.lower
    elif joint_setting == "high":
        val = lambda jnt: jnt.limit.upper
    else:
        raise ValueError(f"Got invalid joint_setting: {joint_setting}! Valid options are ['low', 'zero', 'high']")
    joint_cfg = {joint.name: val(joint) for joint in robot.joints if joint.joint_type in ("prismatic", "revolute")}
    vfk = robot.visual_trimesh_fk(cfg=joint_cfg)

    scene = trimesh.Scene()
    for mesh, transform in vfk.items():
        scene.add_geometry(geometry=mesh, transform=transform)

    # Base link offset is pos offset from robot root link -> overall AABB center
    # Since robot is placed at origin, this is simply the AABB centroid
    base_link_offset = scene.bounding_box.centroid

    # BBox size is simply the extent of the overall AABB
    bbox_size = scene.bounding_box.extents

    # Save metadata json
    out_metadata = {
        "meta_links": {},
        "link_tags": {},
        "object_parts": [],
        "base_link_offset": base_link_offset.tolist(),
        "bbox_size": bbox_size.tolist(),
        "orientations": [],
    }
    misc_dir = pathlib.Path(obj_dir) / "misc"
    misc_dir.mkdir(exist_ok=overwrite)
    with open(misc_dir / "metadata.json", "w") as f:
        json.dump(out_metadata, f)

simplify_convex_hull(tm, max_vertices=60, max_faces=128)

Simplifies a convex hull mesh by using quadric edge collapse to reduce the number of faces

Parameters:

Name Type Description Default
tm Trimesh

Trimesh mesh to simply. Should be convex hull

required
max_vertices int

Maximum number of vertices to generate

60
Source code in OmniGibson/omnigibson/utils/asset_conversion_utils.py
def simplify_convex_hull(tm, max_vertices=60, max_faces=128):
    """
    Simplifies a convex hull mesh by using quadric edge collapse to reduce the number of faces

    Args:
        tm (Trimesh): Trimesh mesh to simply. Should be convex hull
        max_vertices (int): Maximum number of vertices to generate
    """
    # If number of faces is less than or equal to @max_faces, simply return directly
    if len(tm.vertices) <= max_vertices:
        return tm

    # Use pymeshlab to reduce
    import pymeshlab  # We do this here because it's an optional dependency.

    ms = pymeshlab.MeshSet()
    ms.add_mesh(pymeshlab.Mesh(vertex_matrix=tm.vertices, face_matrix=tm.faces, v_normals_matrix=tm.vertex_normals))
    while len(ms.current_mesh().vertex_matrix()) > max_vertices:
        ms.apply_filter("meshing_decimation_quadric_edge_collapse", targetfacenum=max_faces)
        max_faces -= 2
    vertices_reduced = ms.current_mesh().vertex_matrix()
    faces_reduced = ms.current_mesh().face_matrix()
    vertex_normals_reduced = ms.current_mesh().vertex_normal_matrix()
    return trimesh.Trimesh(
        vertices=vertices_reduced,
        faces=faces_reduced,
        vertex_normals=vertex_normals_reduced,
    ).convex_hull