Unverified Commit 64f810fa authored by jsmith-bdai's avatar jsmith-bdai Committed by GitHub

Add spawner functionality to allow direct loading of OBJ/STL/FBX assets (#138)

# Description

This PR enables users to convert meshes from OBJ, STL or FBX format to
USD with a few options:
- Asset instanceable
- Mass properties
- Rigid body properties
- Collision properties - including mesh approximation method

The layer hierarchy is as follows;
```
/World/
     [MESH_OBJECT_NAME] - Xform
         [INPUT_MESH_NAME]_xform - Xform
                /Looks/ - Material
                [MESH] - Mesh
```

Fixes #34. 

## Type of change

- New feature (non-breaking change which adds functionality)

## Screenshots

The screenshot below shows this with a duck example.


![image](https://github.com/isaac-orbit/orbit/assets/142246516/142afb96-7e35-427b-94a6-a066a2742b9b)

## Checklist
- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [x] I have made corresponding changes to the documentation
- [ ] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [ ] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file

---------
Signed-off-by: 's avatarjsmith-bdai <142246516+jsmith-bdai@users.noreply.github.com>
Co-authored-by: 's avatarMayank Mittal <mittalma@leggedrobotics.com>
parent d2ad4cf6
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.9.17" version = "0.9.18"
# Description # Description
title = "ORBIT framework for Robot Learning" title = "ORBIT framework for Robot Learning"
......
Changelog Changelog
--------- ---------
0.9.18 (2023-10-19)
~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Created :class:`omni.issac.orbit.sim.converters.asset_converter.AssetConverter` to serve as a base
class for all asset converters.
* Added :class:`omni.issac.orbit.sim.converters.mesh_converter.MeshConverter` to handle loading and conversion
of mesh files (OBJ, STL and FBX) into USD format.
* Added script `convert_mesh.py` to ``source/tools`` to allow users to convert a mesh to USD via command line arguments.
Changed
^^^^^^^
* Renamed the submodule :mod:`omni.isaac.orbit.sim.loaders` to :mod:`omni.isaac.orbit.sim.converters` to be more
general with the functionality of the module.
* Updated `check_instanceable.py` script to convert relative paths to absolute paths.
0.9.17 (2023-10-22) 0.9.17 (2023-10-22)
~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~
......
...@@ -631,20 +631,17 @@ class AppLauncher: ...@@ -631,20 +631,17 @@ class AppLauncher:
# enable isaac replicator extension # enable isaac replicator extension
# note: moved here since it requires to have the viewport extension to be enabled first. # note: moved here since it requires to have the viewport extension to be enabled first.
enable_extension("omni.replicator.isaac") enable_extension("omni.replicator.isaac")
# enable urdf importer
if int(isaacsim_version[2]) == 2022: # set the nucleus directory manually to the 2023.1.0 version
enable_extension("omni.isaac.urdf") # TODO: Remove this once the 2023.1.0 version is released
else: if int(isaacsim_version[2]) == 2023:
enable_extension("omni.importer.urdf")
# set the nucleus directory manually to the 2023.1.0 version
# TODO: Remove this once the 2023.1.0 version is released
carb_settings_iface.set_string( carb_settings_iface.set_string(
"/persistent/isaac/asset_root/default", "/persistent/isaac/asset_root/default",
"http://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/2023.1.0", "http://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/2023.1.0",
) )
carb_settings_iface.set_string( carb_settings_iface.set_string(
"/persistent/isaac/asset_root/nvidia", "/persistent/isaac/asset_root/nvidia",
"http://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/2023.1.0", "http://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets",
) )
def _update_globals(self): def _update_globals(self):
......
...@@ -9,7 +9,7 @@ These include: ...@@ -9,7 +9,7 @@ These include:
* Ability to spawn different objects and materials into Omniverse * Ability to spawn different objects and materials into Omniverse
* Define and modify various schemas on USD prims * Define and modify various schemas on USD prims
* Loaders to obtain USD file from other file formats (such as URDF) * Converters to obtain USD file from other file formats (such as URDF, OBJ, STL, FBX)
* Utility class to control the simulator * Utility class to control the simulator
.. note:: .. note::
...@@ -26,9 +26,7 @@ To make it convenient to use the module, we recommend importing the module as fo ...@@ -26,9 +26,7 @@ To make it convenient to use the module, we recommend importing the module as fo
""" """
from __future__ import annotations from .converters import * # noqa: F401, F403
from .loaders import * # noqa: F401, F403
from .schemas import * # noqa: F401, F403 from .schemas import * # noqa: F401, F403
from .simulation_cfg import PhysxCfg, SimulationCfg # noqa: F401, F403 from .simulation_cfg import PhysxCfg, SimulationCfg # noqa: F401, F403
from .simulation_context import SimulationContext # noqa: F401, F403 from .simulation_context import SimulationContext # noqa: F401, F403
......
# Copyright [2023] Boston Dynamics AI Institute, Inc.
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""A utility to convert various file types to a USD file.
In order to support direct loading of various file types into Omniverse, we provide a set of
converters that can convert the file into a USD file. The converters are implemented as
sub-classes of the :class:`AssetConverterBase` class.
The following converters are currently supported:
* :class:`UrdfConverter`: Converts a URDF file into a USD file.
* :class:`MeshConverter`: Converts a mesh file into a USD file. This supports OBJ, STL and FBX files.
"""
from __future__ import annotations
from .asset_converter_base import AssetConverterBase
from .asset_converter_base_cfg import AssetConverterBaseCfg
from .mesh_converter import MeshConverter
from .mesh_converter_cfg import MeshConverterCfg
from .urdf_converter import UrdfConverter
from .urdf_converter_cfg import UrdfConverterCfg
__all__ = [
"AssetConverterBase",
"AssetConverterBaseCfg",
"MeshConverter",
"MeshConverterCfg",
"UrdfConverter",
"UrdfConverterCfg",
]
...@@ -4,6 +4,9 @@ ...@@ -4,6 +4,9 @@
# #
# SPDX-License-Identifier: BSD-3-Clause # SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
import abc
import hashlib import hashlib
import json import json
import os import os
...@@ -11,80 +14,54 @@ import pathlib ...@@ -11,80 +14,54 @@ import pathlib
import random import random
from datetime import datetime from datetime import datetime
import omni.kit.commands from omni.isaac.orbit.sim.converters.asset_converter_base_cfg import AssetConverterBaseCfg
from omni.isaac.version import get_version
from omni.isaac.orbit.utils.assets import check_file_path from omni.isaac.orbit.utils.assets import check_file_path
from omni.isaac.orbit.utils.io import dump_yaml from omni.isaac.orbit.utils.io import dump_yaml
from .urdf_loader_cfg import UrdfLoaderCfg
# check if the urdf importer extension is available
# note: the urdf importer's name changed in 2023.1 onwards
isaacsim_version = get_version()
if int(isaacsim_version[2]) == 2022:
from omni.isaac.urdf import _urdf as omni_urdf
else:
from omni.importer.urdf import _urdf as omni_urdf
_DRIVE_TYPE = { class AssetConverterBase(abc.ABC):
"none": 0, """Base class for converting an asset file from different formats into USD format.
"position": 1,
"velocity": 2,
}
"""Mapping from drive type name to URDF importer drive number."""
_NORMALS_DIVISION = { This class provides a common interface for converting an asset file into USD. It does not
"catmullClark": 0, provide any implementation for the conversion. The derived classes must implement the
"loop": 1, :meth:`_convert_asset` method to provide the actual conversion.
"bilinear": 2,
"none": 3,
}
"""Mapping from normals division name to urdf importer normals division number."""
The file conversion is lazy if the output directory (:obj:`AssetConverterBaseCfg.usd_dir`) is provided.
In the lazy conversion, the USD file is re-generated only if:
class UrdfLoader: * The asset file is modified.
"""Loader for a URDF description file as an instanceable USD file. * The configuration parameters are modified.
* The USD file does not exist.
This class wraps around the ``omni.isaac.urdf_importer`` extension to provide a lazy implementation To override this behavior to force conversion, the flag :obj:`AssetConverterBaseCfg.force_usd_conversion`
for URDF to USD conversion. It stores the output USD file in an instanceable format since that is can be set to True.
what is typically used in all learning related applications.
The file conversion is lazy if the output usd directory, :obj:`UrdfLoaderCfg.usd_dir`, is provided. When no output directory is defined, lazy conversion is deactivated and the generated USD file is
In the lazy conversion, the USD file is only re-generated if the usd files do not exist or if they exist,
the provided configuration or the main urdf file is modified. To override this behavior, set
:obj:`UrdfLoaderCfg.force_usd_conversion` as True.
In the case that no USD directory is defined, lazy conversion is deactivated and the generated USD file is
stored in folder ``/tmp/Orbit/usd_{date}_{time}_{random}``, where the parameters in braces are generated stored in folder ``/tmp/Orbit/usd_{date}_{time}_{random}``, where the parameters in braces are generated
at runtime. The random identifiers help avoid a race condition where two simultaneously triggered conversions at runtime. The random identifiers help avoid a race condition where two simultaneously triggered conversions
try to use the same directory for reading/writing the generated files. try to use the same directory for reading/writing the generated files.
.. caution::
The current lazy conversion implementation does not automatically trigger USD generation if only the
mesh files used by the URDF are modified. To force generation, either set
:obj:`UrdfLoaderCfg.force_usd_conversion` to True or remove the USD folder.
.. note:: .. note::
Additionally, changes to the parameters :obj:`UrdfLoaderCfg.urdf_path`, :obj:`UrdfLoaderCfg.usd_dir`, and Changes to the parameters :obj:`AssetConverterBaseCfg.asset_path`, :obj:`AssetConverterBaseCfg.usd_dir`, and
:obj:`UrdfLoaderCfg.usd_file_name` are not considered as modifications in the configuration instance that :obj:`AssetConverterBaseCfg.usd_file_name` are not considered as modifications in the configuration instance that
trigger USD file re-generation. trigger USD file re-generation.
""" """
def __init__(self, cfg: UrdfLoaderCfg): def __init__(self, cfg: AssetConverterBaseCfg):
"""Initializes the class. """Initializes the class.
Args: Args:
cfg: The configuration instance for URDF to USD conversion. cfg: The configuration instance for converting an asset file to USD format.
Raises: Raises:
ValueError: When provided URDF file does not exist. ValueError: When provided asset file does not exist.
""" """
# check if the urdf file exists # check if the asset file exists
if not check_file_path(cfg.urdf_path): if not check_file_path(cfg.asset_path):
raise ValueError(f"The URDF path does not exist: ({cfg.urdf_path})!") raise ValueError(f"The asset path does not exist: {cfg.asset_path}")
# save the inputs
self.cfg = cfg
# resolve USD directory name # resolve USD directory name
if cfg.usd_dir is None: if cfg.usd_dir is None:
...@@ -94,14 +71,14 @@ class UrdfLoader: ...@@ -94,14 +71,14 @@ class UrdfLoader:
else: else:
self._usd_dir = cfg.usd_dir self._usd_dir = cfg.usd_dir
# resolve the file name from urdf file name if not provided # resolve the file name from asset file name if not provided
if cfg.usd_file_name is None: if cfg.usd_file_name is None:
usd_file_name = pathlib.PurePath(cfg.urdf_path).stem usd_file_name = pathlib.PurePath(cfg.asset_path).stem
else: else:
usd_file_name = cfg.usd_file_name usd_file_name = cfg.usd_file_name
# add USD extension if not provided # add USD extension if not provided
if not (usd_file_name.endswith(".usd") or usd_file_name.endswith(".usda")): if not (usd_file_name.endswith(".usd") or usd_file_name.endswith(".usda")):
self._usd_file_name = usd_file_name + ".usd" self._usd_file_name = usd_file_name + ".usda"
else: else:
self._usd_file_name = usd_file_name self._usd_file_name = usd_file_name
...@@ -109,32 +86,26 @@ class UrdfLoader: ...@@ -109,32 +86,26 @@ class UrdfLoader:
os.makedirs(self.usd_dir, exist_ok=True) os.makedirs(self.usd_dir, exist_ok=True)
# check if usd files exist # check if usd files exist
self._usd_file_exists = os.path.isfile(self.usd_path) self._usd_file_exists = os.path.isfile(self.usd_path)
# path to read/write urdf hash file # path to read/write asset hash file
dest_hash_path = f"{self.usd_dir}/.urdf_hash" self._dest_hash_path = os.path.join(self.usd_dir, ".asset_hash")
# convert urdf to hash # create asset hash to check if the asset has changed
urdf_hash = UrdfLoader._config_to_hash(cfg) self._asset_hash = self._config_to_hash(cfg)
# read the saved hash # read the saved hash
try: try:
with open(dest_hash_path) as f: with open(self._dest_hash_path) as f:
existing_urdf_hash = f.readline() existing_asset_hash = f.readline()
self._is_same_urdf = existing_urdf_hash == urdf_hash self._is_same_asset = existing_asset_hash == self._asset_hash
except FileNotFoundError: except FileNotFoundError:
self._is_same_urdf = False self._is_same_asset = False
# generate usd files # convert the asset to USD if the hash is different or USD file does not exist
if cfg.force_usd_conversion or not self._usd_file_exists or not self._is_same_urdf: if cfg.force_usd_conversion or not self._usd_file_exists or not self._is_same_asset:
# write the updated hash # write the updated hash
with open(dest_hash_path, "w") as f: with open(self._dest_hash_path, "w") as f:
f.write(urdf_hash) f.write(self._asset_hash)
# Convert urdf to an instantiable usd # convert the asset to USD
import_config = self._get_urdf_import_config(cfg) self._convert_asset(cfg)
omni.kit.commands.execute( # dump the configuration to a file
"URDFParseAndImportFile",
urdf_path=cfg.urdf_path,
import_config=import_config,
dest_path=self.usd_path,
)
# Dump the configuration to a file
dump_yaml(os.path.join(self.usd_dir, "config.yaml"), cfg.to_dict()) dump_yaml(os.path.join(self.usd_dir, "config.yaml"), cfg.to_dict())
""" """
...@@ -143,7 +114,7 @@ class UrdfLoader: ...@@ -143,7 +114,7 @@ class UrdfLoader:
@property @property
def usd_dir(self) -> str: def usd_dir(self) -> str:
"""The path to the directory where the generated USD files are stored.""" """The absolute path to the directory where the generated USD files are stored."""
return self._usd_dir return self._usd_dir
@property @property
...@@ -153,83 +124,53 @@ class UrdfLoader: ...@@ -153,83 +124,53 @@ class UrdfLoader:
@property @property
def usd_path(self) -> str: def usd_path(self) -> str:
"""The path to the generated USD file.""" """The absolute path to the generated USD file."""
return os.path.join(self.usd_dir, self.usd_file_name) return os.path.join(self.usd_dir, self.usd_file_name)
@property @property
def usd_instanceable_meshes_path(self) -> str: def usd_instanceable_meshes_path(self) -> str:
"""The path to the USD mesh file. """The relative path to the USD file with meshes.
This is a relative path with respect to the USD directory. This is to ensure that the mesh references The path is with respect to the USD directory :attr:`usd_dir`. This is to ensure that the
in the generated USD file are resolved relatively, which is important when the USD file is moved to mesh references in the generated USD file are resolved relatively. Otherwise, it becomes
a different location. difficult to move the USD asset to a different location.
""" """
return os.path.join(".", "Props", "instanceable_meshes.usd") return os.path.join(".", "Props", "instanceable_meshes.usda")
""" """
Private helpers. Implementation specifics.
""" """
def _get_urdf_import_config(self, cfg: UrdfLoaderCfg) -> omni_urdf.ImportConfig: @abc.abstractmethod
"""Set the settings into the import config.""" def _convert_asset(self, cfg: AssetConverterBaseCfg):
"""Converts the asset file to USD.
import_config = omni_urdf.ImportConfig()
Args:
# set the unit scaling factor, 1.0 means meters, 100.0 means cm cfg: The configuration instance for the input asset to USD conversion.
import_config.set_distance_scale(1.0) """
# set imported robot as default prim raise NotImplementedError()
import_config.set_make_default_prim(True)
# add a physics scene to the stage on import if none exists """
import_config.set_create_physics_scene(False) Private helpers.
"""
# -- instancing settings
# meshes will be placed in a separate usd file
import_config.set_make_instanceable(cfg.make_instanceable)
import_config.set_instanceable_usd_path(self.usd_instanceable_meshes_path)
# -- asset settings
# default density used for links, use 0 to auto-compute
import_config.set_density(cfg.link_density)
# import inertia tensor from urdf, if it is not specified in urdf it will import as identity
import_config.set_import_inertia_tensor(cfg.import_inertia_tensor)
# decompose a convex mesh into smaller pieces for a closer fit
import_config.set_convex_decomp(cfg.convex_decompose_mesh)
import_config.set_subdivision_scheme(_NORMALS_DIVISION["bilinear"])
# -- physics settings
# create fix joint for base link
import_config.set_fix_base(cfg.fix_base)
# consolidating links that are connected by fixed joints
import_config.set_merge_fixed_joints(cfg.merge_fixed_joints)
# self collisions between links in the articulation
import_config.set_self_collision(cfg.self_collision)
# default drive type used for joints
import_config.set_default_drive_type(_DRIVE_TYPE[cfg.default_drive_type])
# default proportional gains
import_config.set_default_drive_strength(cfg.default_drive_stiffness)
# default derivative gains
import_config.set_default_position_drive_damping(cfg.default_drive_damping)
return import_config
@staticmethod @staticmethod
def _config_to_hash(cfg: UrdfLoaderCfg) -> str: def _config_to_hash(cfg: AssetConverterBaseCfg) -> str:
"""Converts the configuration object and urdf file to an MD5 hash of a string. """Converts the configuration object and asset file to an MD5 hash of a string.
.. warning:: .. warning::
It only checks the main urdf file not the mesh files. It only checks the main asset file (:attr:`cfg.asset_path`).
Args: Args:
cfg: The urdf loader configuration object. config : The asset converter configuration object.
Returns: Returns:
An MD5 hash of a string. An MD5 hash of a string.
""" """
# convert ro dict and remove path related info # convert to dict and remove path related info
config_dic = cfg.to_dict() config_dic = cfg.to_dict()
_ = config_dic.pop("urdf_path") _ = config_dic.pop("asset_path")
_ = config_dic.pop("usd_dir") _ = config_dic.pop("usd_dir")
_ = config_dic.pop("usd_file_name") _ = config_dic.pop("usd_file_name")
# convert config dic to bytes # convert config dic to bytes
...@@ -238,12 +179,13 @@ class UrdfLoader: ...@@ -238,12 +179,13 @@ class UrdfLoader:
md5 = hashlib.md5() md5 = hashlib.md5()
md5.update(config_bytes) md5.update(config_bytes)
# read the urdf file to observe changes # read the asset file to observe changes
with open(cfg.urdf_path, "rb") as f: with open(cfg.asset_path, "rb") as f:
while True: while True:
# read 64kb chunks to avoid memory issues for the large files! # read 64kb chunks to avoid memory issues for the large files!
data = f.read(65536) data = f.read(65536)
if not data: if not data:
break break
md5.update(data) md5.update(data)
# return the hash
return md5.hexdigest() return md5.hexdigest()
# Copyright [2023] Boston Dynamics AI Institute, Inc.
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
from dataclasses import MISSING
from omni.isaac.orbit.utils import configclass
@configclass
class AssetConverterBaseCfg:
"""The base configuration class for asset converters."""
asset_path: str = MISSING
"""The absolute path to the asset file to convert into USD."""
usd_dir: str | None = None
"""The output directory path to store the generated USD file. Defaults to :obj:`None`.
If set to :obj:`None`, it is resolved as ``/tmp/Orbit/usd_{date}_{time}_{random}``, where
the parameters in braces are runtime generated.
"""
usd_file_name: str | None = None
"""The name of the generated usd file. Defaults to :obj:`None`.
If set to :obj:`None`, it is resolved from the asset file name. The extension of the asset file
is replaced with ``.usd``.
"""
force_usd_conversion: bool = False
"""Force the conversion of the asset file to usd. Defaults to False.
If True, then the USD file is always generated. It will overwrite the existing USD file if it exists.
"""
make_instanceable: bool = True
"""Make the generated USD file instanceable. Defaults to True.
Note:
Instancing helps reduce the memory footprint of the asset when multiple copies of the asset are
used in the scene. For more information, please check the USD documentation on
`scene-graph instancing <https://openusd.org/dev/api/_usd__page__scenegraph_instancing.html>`_.
"""
# Copyright [2023 Boston Dynamics AI Institute, Inc.
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
import asyncio
import os
import omni
import omni.kit.commands
import omni.usd
from omni.isaac.core.utils.extensions import enable_extension
from omni.isaac.version import get_version
from pxr import Gf, Usd, UsdGeom, UsdPhysics, UsdUtils
from omni.isaac.orbit.sim.converters.asset_converter_base import AssetConverterBase
from omni.isaac.orbit.sim.converters.mesh_converter_cfg import MeshConverterCfg
from omni.isaac.orbit.sim.schemas import schemas
from omni.isaac.orbit.sim.utils import export_prim_to_file
class MeshConverter(AssetConverterBase):
"""Converter for a mesh file in OBJ / STL / FBX format to a USD file.
This class wraps around the `omni.kit.asset_converter`_ extension to provide a lazy implementation
for mesh to USD conversion. It stores the output USD file in an instanceable format since that is
what is typically used in all learning related applications.
To make the asset instanceable, we must follow a certain structure dictated by how USD scene-graph
instancing and physics work. The rigid body component must be added to each instance and not the
referenced asset (i.e. the prototype prim itself). This is because the rigid body component defines
properties that are specific to each instance and cannot be shared under the referenced asset. For
more information, please check the `documentation <https://docs.omniverse.nvidia.com/extensions/latest/ext_physics/rigid-bodies.html#instancing-rigid-bodies>`_.
Due to the above, we follow the following structure:
* ``{prim_path}`` - The root prim that is an Xform with the rigid body and mass APIs if configured.
* ``{prim_path}/geometry`` - The prim that contains the mesh and optionally the materials if configured.
If instancing is enabled, this prim will be an instanceable reference to the prototype prim.
.. _omni.kit.asset_converter: https://docs.omniverse.nvidia.com/extensions/latest/ext_asset-converter.html
.. caution::
When converting STL files, Z-up convention is assumed, even though this is not the default for many CAD
export programs. Asset orientation convention can either be modified directly in the CAD program's export
process or an offset can be added within the config in Orbit.
"""
cfg: MeshConverterCfg
"""The configuration instance for mesh to USD conversion."""
def __init__(self, cfg: MeshConverterCfg):
"""Initializes the class.
Args:
cfg: The configuration instance for mesh to USD conversion.
"""
super().__init__(cfg=cfg)
"""
Implementation specific methods.
"""
def _convert_asset(self, cfg: MeshConverterCfg):
"""Generate USD from OBJ, STL or FBX.
It stores the asset in the following format:
/file_name (default prim)
|- /geometry <- Made instanceable if requested
|- /Looks
|- /mesh
Args:
cfg: The configuration for conversion of mesh to USD.
Raises:
RuntimeError: If the conversion using the Omniverse asset converter fails.
"""
# resolve mesh name and format
mesh_file_basename, mesh_file_format = os.path.basename(cfg.asset_path).split(".")
mesh_file_format = mesh_file_format.lower()
# Convert USD
status = asyncio.get_event_loop().run_until_complete(
self._convert_mesh_to_usd(in_file=cfg.asset_path, out_file=self.usd_path)
)
if not status:
raise RuntimeError(f"Failed to convert asset: {cfg.asset_path}! Please check the logs for more details.")
# Open converted USD stage
# note: This opens a new stage and does not use the stage created earlier by the user
# TODO: Fix this in Isaac 2023 using Usd.Stage.Open and update MovePrim commands to take in opened stage
isaacsim_major_version = int(get_version()[2])
if isaacsim_major_version == 2022:
omni.usd.get_context().open_stage(self.usd_path)
stage = omni.usd.get_context().get_stage()
# we do not need to cache as we use opened stage
stage_id = None
# no kwargs for 2022
stage_kwargs = {}
stage_or_context_kwargs = {}
else:
# create a new stage
stage = Usd.Stage.CreateNew(os.path.join(self.usd_dir, self.usd_instanceable_meshes_path))
# add USD to stage cache
stage_id = UsdUtils.StageCache.Get().Insert(stage)
# need to make kwargs for compatibility with 2022
stage_kwargs = {"stage": stage}
stage_or_context_kwargs = {"stage_or_context": stage}
# Set stage up-axis to Z
# note: later we need to rotate the mesh so that it is Z-up in the world
UsdGeom.SetStageUpAxis(stage, UsdGeom.Tokens.z)
# Move all meshes to underneath a new Xform so that we can make it instanceable later if requested
# Get the default prim (which is the root prim) -- "/World"
old_xform_prim = stage.GetDefaultPrim()
# Create a path called "/{mesh_file_basename}/geometry" and move the mesh to it
new_xform_prim = stage.DefinePrim(f"/{mesh_file_basename}", "Xform")
geom_undef_prim = stage.DefinePrim(f"{new_xform_prim.GetPath()}/geometry")
# Move Looks to underneath new Xform
omni.kit.commands.execute(
"MovePrim",
path_from=f"{old_xform_prim.GetPath()}/Looks",
path_to=f"{geom_undef_prim.GetPath()}/Looks",
destructive=True,
**stage_or_context_kwargs,
)
# Move all meshes to underneath new Xform
for child_mesh_prim in old_xform_prim.GetChildren():
# Get mesh prim path
old_child_mesh_prim_path = child_mesh_prim.GetPath().pathString
new_child_mesh_prim_path = f"{geom_undef_prim.GetPath()}/{old_child_mesh_prim_path.split('/')[-1]}"
# Move mesh to underneath new Xform
omni.kit.commands.execute(
"MovePrim",
path_from=old_child_mesh_prim_path,
path_to=new_child_mesh_prim_path,
destructive=True,
**stage_or_context_kwargs,
)
# Apply default Xform rotation to mesh
omni.kit.commands.execute(
"CreateDefaultXformOnPrimCommand",
prim_path=new_child_mesh_prim_path,
**stage_kwargs,
)
# Get new mesh prim
child_mesh_prim = stage.GetPrimAtPath(new_child_mesh_prim_path)
# Rotate mesh so that it is Z-up in the world
attr_rotate = child_mesh_prim.GetAttribute("xformOp:orient")
attr_rotate.Set(Gf.Quatd(0.5, 0.5, 0.5, 0.5))
# Apply collider properties to mesh
if cfg.collision_props is not None:
# -- Collision approximation to mesh
# TODO: https://github.com/isaac-orbit/orbit/issues/163 Move this to a new Schema
mesh_collision_api = UsdPhysics.MeshCollisionAPI.Apply(child_mesh_prim)
mesh_collision_api.GetApproximationAttr().Set(cfg.collision_approximation)
# -- Collider properties such as offset, scale, etc.
schemas.define_collision_properties(
prim_path=new_child_mesh_prim_path, cfg=cfg.collision_props, stage=stage
)
# Delete the old Xform and make the new Xform the default prim
stage.SetDefaultPrim(new_xform_prim)
omni.kit.commands.execute("DeletePrims", paths=[old_xform_prim.GetPath().pathString], stage=stage)
# Handle instanceable
# Create a new Xform prim that will be the prototype prim
if cfg.make_instanceable:
# Export Xform to a file so we can reference it from all instances
export_prim_to_file(
path=os.path.join(self.usd_dir, self.usd_instanceable_meshes_path),
source_prim_path=geom_undef_prim.GetPath(),
stage=stage,
)
# Delete the original prim that will now be a reference
geom_undef_prim_path = geom_undef_prim.GetPath().pathString
omni.kit.commands.execute("DeletePrims", paths=[geom_undef_prim_path], stage=stage)
# Update references to exported Xform and make it instanceable
geom_undef_prim = stage.DefinePrim(geom_undef_prim_path)
geom_undef_prim.GetReferences().AddReference(
self.usd_instanceable_meshes_path, primPath=geom_undef_prim_path
)
geom_undef_prim.SetInstanceable(True)
# Apply mass and rigid body properties after everything else
# Properties are applied to the top level prim to avoid the case where all instances of this
# asset unintentionally share the same rigid body properties
# apply mass properties
if cfg.mass_props is not None:
schemas.define_mass_properties(prim_path=new_xform_prim.GetPath(), cfg=cfg.mass_props, stage=stage)
# apply rigid body properties
if cfg.rigid_props is not None:
schemas.define_rigid_body_properties(prim_path=new_xform_prim.GetPath(), cfg=cfg.rigid_props, stage=stage)
# Save changes to USD stage
stage.Save()
if stage_id is not None:
UsdUtils.StageCache.Get().Erase(stage_id)
"""
Helper methods.
"""
@staticmethod
async def _convert_mesh_to_usd(in_file: str, out_file: str, load_materials: bool = True) -> bool:
"""Convert mesh from supported file types to USD.
This function uses the Omniverse Asset Converter extension to convert a mesh file to USD.
It is an asynchronous function and should be called using `asyncio.get_event_loop().run_until_complete()`.
The converted asset is stored in the USD format in the specified output file.
The USD file has Y-up axis and is scaled to meters.
The asset hierarchy is arranged as follows:
.. code-block:: none
/World (default prim)
|- /Looks
|- /Mesh
Args:
in_file: The file to convert.
out_file: The path to store the output file.
load_materials: Set to True to enable attaching materials defined in the input file
to the generated USD mesh. Defaults to True.
Returns:
True if the conversion succeeds.
"""
enable_extension("omni.kit.asset_converter")
enable_extension("omni.isaac.unit_converter")
import omni.kit.asset_converter
from omni.isaac.unit_converter.unit_conversion_utils import set_stage_meters_per_unit
# Create converter context
converter_context = omni.kit.asset_converter.AssetConverterContext()
# Set up converter settings
# Don't import/export materials
converter_context.ignore_materials = not load_materials
converter_context.ignore_animations = True
converter_context.ignore_camera = True
converter_context.ignore_light = True
# Merge all meshes into one
converter_context.merge_all_meshes = True
# Sets world units to meters, this will also scale asset if it's centimeters model.
# This does not work right now :(, so we need to scale the mesh manually
converter_context.use_meter_as_world_unit = True
converter_context.baking_scales = True
# Uses double precision for all transform ops.
converter_context.use_double_precision_to_usd_transform_op = True
# Create converter task
instance = omni.kit.asset_converter.get_instance()
task = instance.create_converter_task(in_file, out_file, None, converter_context)
# Start conversion task and wait for it to finish
success = True
while True:
success = await task.wait_until_finished()
if not success:
await asyncio.sleep(0.1)
else:
break
# Open converted USD stage
stage = Usd.Stage.Open(out_file)
# Set stage units to 1.0
set_stage_meters_per_unit(stage, 1.0)
# Save changes to USD stage
stage.Save()
return success
# Copyright [2023] Boston Dynamics AI Institute, Inc.
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
from omni.isaac.orbit.sim.converters.asset_converter_base_cfg import AssetConverterBaseCfg
from omni.isaac.orbit.sim.schemas import schemas_cfg
from omni.isaac.orbit.utils import configclass
@configclass
class MeshConverterCfg(AssetConverterBaseCfg):
"""The configuration class for MeshConverter."""
mass_props: schemas_cfg.MassPropertiesCfg = None
"""Mass properties to apply to the USD. Defaults to None.
Note:
If None, then no mass properties will be added.
"""
rigid_props: schemas_cfg.RigidBodyPropertiesCfg = None
"""Rigid body properties to apply to the USD. Defaults to None.
Note:
If None, then no rigid body properties will be added.
"""
collision_props: schemas_cfg.CollisionPropertiesCfg = None
"""Collision properties to apply to the USD. Defaults to None.
Note:
If None, then no collision properties will be added.
"""
collision_approximation: str = "convexDecomposition"
"""Collision approximation method to use. Defaults to "convexDecomposition".
Valid options are:
"convexDecomposition", "convexHull", "boundingCube",
"boundingSphere", "meshSimplification", or "none"
"none" causes no collision mesh to be added.
"""
# Copyright [2023] Boston Dynamics AI Institute, Inc.
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
import omni.kit.commands
from omni.isaac.core.utils.extensions import enable_extension
from omni.isaac.version import get_version
from .asset_converter_base import AssetConverterBase
from .urdf_converter_cfg import UrdfConverterCfg
_DRIVE_TYPE = {
"none": 0,
"position": 1,
"velocity": 2,
}
"""Mapping from drive type name to URDF importer drive number."""
_NORMALS_DIVISION = {
"catmullClark": 0,
"loop": 1,
"bilinear": 2,
"none": 3,
}
"""Mapping from normals division name to urdf importer normals division number."""
class UrdfConverter(AssetConverterBase):
"""Converter for a URDF description file to a USD file.
This class wraps around the `omni.isaac.urdf_importer`_ extension to provide a lazy implementation
for URDF to USD conversion. It stores the output USD file in an instanceable format since that is
what is typically used in all learning related applications.
.. caution::
The current lazy conversion implementation does not automatically trigger USD generation if
only the mesh files used by the URDF are modified. To force generation, either set
:obj:`AssetConverterBaseCfg.force_usd_conversion` to True or delete the output directory.
.. note::
From Isaac Sim 2023.1 onwards, the extension name changed from ``omni.isaac.urdf`` to
``omni.importer.urdf``. This converter class automatically detects the version of Isaac Sim
and uses the appropriate extension.
The new extension supports a custom XML tag``"dont_collapse"`` for joints. Setting this parameter
to true in the URDF joint tag prevents the child link from collapsing when the associated joint type
is "fixed".
.. _omni.isaac.urdf_importer: https://docs.omniverse.nvidia.com/isaacsim/latest/ext_omni_isaac_urdf.html
"""
cfg: UrdfConverterCfg
"""The configuration instance for URDF to USD conversion."""
def __init__(self, cfg: UrdfConverterCfg):
"""Initializes the class.
Args:
cfg: The configuration instance for URDF to USD conversion.
"""
super().__init__(cfg=cfg)
"""
Implementation specific methods.
"""
def _convert_asset(self, cfg: UrdfConverterCfg):
"""Calls underlying Omniverse command to convert URDF to USD.
Args:
cfg: The URDF conversion configuration.
"""
import_config = self._get_urdf_import_config(cfg)
omni.kit.commands.execute(
"URDFParseAndImportFile",
urdf_path=cfg.asset_path,
import_config=import_config,
dest_path=self.usd_path,
)
"""
Helper methods.
"""
def _get_urdf_import_config(self, cfg: UrdfConverterCfg) -> omni.importer.urdf.ImportConfig:
"""Create and fill URDF ImportConfig with desired settings
Args:
cfg: The URDF conversion configuration.
Returns:
The constructed ``ImportConfig`` object containing the desired settings.
"""
# check if the urdf importer extension is available
# note: the urdf importer's name changed in 2023.1 onwards
isaacsim_version = get_version()
if int(isaacsim_version[2]) == 2022:
enable_extension("omni.isaac.urdf")
from omni.isaac.urdf import _urdf as omni_urdf
else:
enable_extension("omni.importer.urdf")
from omni.importer.urdf import _urdf as omni_urdf
import_config = omni_urdf.ImportConfig()
# set the unit scaling factor, 1.0 means meters, 100.0 means cm
import_config.set_distance_scale(1.0)
# set imported robot as default prim
import_config.set_make_default_prim(True)
# add a physics scene to the stage on import if none exists
import_config.set_create_physics_scene(False)
# -- instancing settings
# meshes will be placed in a separate usd file
import_config.set_make_instanceable(cfg.make_instanceable)
import_config.set_instanceable_usd_path(self.usd_instanceable_meshes_path)
# -- asset settings
# default density used for links, use 0 to auto-compute
import_config.set_density(cfg.link_density)
# import inertia tensor from urdf, if it is not specified in urdf it will import as identity
import_config.set_import_inertia_tensor(cfg.import_inertia_tensor)
# decompose a convex mesh into smaller pieces for a closer fit
import_config.set_convex_decomp(cfg.convex_decompose_mesh)
import_config.set_subdivision_scheme(_NORMALS_DIVISION["bilinear"])
# -- physics settings
# create fix joint for base link
import_config.set_fix_base(cfg.fix_base)
# consolidating links that are connected by fixed joints
import_config.set_merge_fixed_joints(cfg.merge_fixed_joints)
# self collisions between links in the articulation
import_config.set_self_collision(cfg.self_collision)
# default drive type used for joints
import_config.set_default_drive_type(_DRIVE_TYPE[cfg.default_drive_type])
# default proportional gains
import_config.set_default_drive_strength(cfg.default_drive_stiffness)
# default derivative gains
import_config.set_default_position_drive_damping(cfg.default_drive_damping)
return import_config
...@@ -9,31 +9,13 @@ from __future__ import annotations ...@@ -9,31 +9,13 @@ from __future__ import annotations
from dataclasses import MISSING from dataclasses import MISSING
from typing_extensions import Literal from typing_extensions import Literal
from omni.isaac.orbit.sim.converters.asset_converter_base_cfg import AssetConverterBaseCfg
from omni.isaac.orbit.utils import configclass from omni.isaac.orbit.utils import configclass
@configclass @configclass
class UrdfLoaderCfg: class UrdfConverterCfg(AssetConverterBaseCfg):
"""The configuration class for UrdfLoader.""" """The configuration class for UrdfConverter."""
urdf_path: str = MISSING
"""The path to the urdf file (e.g. path/to/urdf/robot.urdf)."""
usd_dir: str | None = None
"""The output directory path to store the generated USD file. Defaults to :obj:`None`.
If set to :obj:`None`, it is resolved as ``/tmp/Orbit/usd_{date}_{time}_{random}``, where
the parameters in braces are runtime generated.
"""
usd_file_name: str | None = None
"""The name of the generated usd file. Defaults to :obj:`None`.
If set to :obj:`None`, it is resolved from the urdf file name.
"""
force_usd_conversion: bool = False
"""Force the conversion of the urdf file to usd. Defaults to False."""
link_density = 0.0 link_density = 0.0
"""Default density used for links. Defaults to 0. """Default density used for links. Defaults to 0.
...@@ -79,12 +61,3 @@ class UrdfLoaderCfg: ...@@ -79,12 +61,3 @@ class UrdfLoaderCfg:
If set to zero, the values parsed from the URDF joint tag ``"<dynamics><damping>"`` are used. If set to zero, the values parsed from the URDF joint tag ``"<dynamics><damping>"`` are used.
Otherwise, it is overridden by the configured value. Otherwise, it is overridden by the configured value.
""" """
make_instanceable: bool = True
"""Make the generated USD file instanceable. Defaults to True.
Note:
Instancing helps reduce the memory footprint of the asset when multiple copies of the asset are
used in the scene. For more information, please check the USD documentation on
`scene-graph instancing <https://openusd.org/dev/api/_usd__page__scenegraph_instancing.html>`_.
"""
# Copyright [2023] Boston Dynamics AI Institute, Inc.
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""A utility to load a URDF file and convert it to a USD file.
It wraps around the ``omni.isaac.urdf`` extension to convert a URDF file to a USD file
using a configurable set of parameters. Additionally, it also provides a convenient API
to cache the generated USD file based on the contents of the URDF file and the parameters
used to generate the USD file.
"""
from __future__ import annotations
from .urdf_loader import UrdfLoader
from .urdf_loader_cfg import UrdfLoaderCfg
__all__ = ["UrdfLoaderCfg", "UrdfLoader"]
...@@ -13,7 +13,7 @@ import omni.kit.commands ...@@ -13,7 +13,7 @@ import omni.kit.commands
from omni.isaac.version import get_version from omni.isaac.version import get_version
from pxr import Gf, Sdf, Usd from pxr import Gf, Sdf, Usd
from omni.isaac.orbit.sim import loaders, schemas from omni.isaac.orbit.sim import converters, schemas
from omni.isaac.orbit.sim.utils import bind_physics_material, bind_visual_material, clone from omni.isaac.orbit.sim.utils import bind_physics_material, bind_visual_material, clone
from omni.isaac.orbit.utils.assets import check_file_path from omni.isaac.orbit.utils.assets import check_file_path
...@@ -103,7 +103,7 @@ def spawn_from_urdf( ...@@ -103,7 +103,7 @@ def spawn_from_urdf(
) -> Usd.Prim: ) -> Usd.Prim:
"""Spawn an asset from a URDF file and override the settings with the given config. """Spawn an asset from a URDF file and override the settings with the given config.
It uses the :class:`UrdfLoader` class to create a USD file from URDF. This file is then imported It uses the :class:`UrdfConverter` class to create a USD file from URDF. This file is then imported
at the specified prim path. at the specified prim path.
In case a prim already exists at the given prim path, then the function does not create a new prim In case a prim already exists at the given prim path, then the function does not create a new prim
...@@ -131,7 +131,7 @@ def spawn_from_urdf( ...@@ -131,7 +131,7 @@ def spawn_from_urdf(
# spawn asset if it doesn't exist. # spawn asset if it doesn't exist.
if not prim_utils.is_prim_path_valid(prim_path): if not prim_utils.is_prim_path_valid(prim_path):
# urdf loader # urdf loader
urdf_loader = loaders.UrdfLoader(cfg) urdf_loader = converters.UrdfConverter(cfg)
# add prim as reference to stage # add prim as reference to stage
prim_utils.create_prim( prim_utils.create_prim(
prim_path, prim_path,
......
...@@ -8,7 +8,7 @@ from __future__ import annotations ...@@ -8,7 +8,7 @@ from __future__ import annotations
from dataclasses import MISSING from dataclasses import MISSING
from typing import Callable from typing import Callable
from omni.isaac.orbit.sim import loaders, schemas from omni.isaac.orbit.sim import converters, schemas
from omni.isaac.orbit.sim.spawners import materials from omni.isaac.orbit.sim.spawners import materials
from omni.isaac.orbit.sim.spawners.spawner_cfg import RigidObjectSpawnerCfg, SpawnerCfg from omni.isaac.orbit.sim.spawners.spawner_cfg import RigidObjectSpawnerCfg, SpawnerCfg
from omni.isaac.orbit.utils import configclass from omni.isaac.orbit.utils import configclass
...@@ -65,10 +65,10 @@ class UsdFileCfg(FileCfg): ...@@ -65,10 +65,10 @@ class UsdFileCfg(FileCfg):
@configclass @configclass
class UrdfFileCfg(FileCfg, loaders.UrdfLoaderCfg): class UrdfFileCfg(FileCfg, converters.UrdfConverterCfg):
"""URDF file to spawn asset from. """URDF file to spawn asset from.
It uses the :class:`UrdfLoader` class to create a USD file from URDF and spawns the imported It uses the :class:`UrdfConverter` class to create a USD file from URDF and spawns the imported
USD file. See :meth:`spawn_from_urdf` for more information. USD file. See :meth:`spawn_from_urdf` for more information.
.. note:: .. note::
......
...@@ -15,7 +15,7 @@ import omni.isaac.core.utils.stage as stage_utils ...@@ -15,7 +15,7 @@ import omni.isaac.core.utils.stage as stage_utils
import omni.kit.commands import omni.kit.commands
from omni.isaac.cloner import Cloner from omni.isaac.cloner import Cloner
from omni.isaac.version import get_version from omni.isaac.version import get_version
from pxr import PhysxSchema, Sdf, Semantics, Usd, UsdPhysics, UsdShade from pxr import PhysxSchema, Sdf, Semantics, Usd, UsdGeom, UsdPhysics, UsdShade
from omni.isaac.orbit.utils.string import to_camel_case from omni.isaac.orbit.utils.string import to_camel_case
...@@ -379,6 +379,59 @@ def bind_physics_material( ...@@ -379,6 +379,59 @@ def bind_physics_material(
return True return True
"""
Exporting.
"""
def export_prim_to_file(path: str, source_prim_path: str, target_prim_path: str = None, stage: Usd.Stage | None = None):
"""Exports a prim from a given stage to a USD file.
The function creates a new layer at the provided path and copies the prim to the layer.
It sets the copied prim as the default prim in the target layer. Additionally, it updates
the stage up-axis and meters-per-unit to match the current stage.
Args:
path: The filepath path to export the prim to.
source_prim_path: The prim path to export.
target_prim_path: The prim path to set as the default prim in the target layer.
Defaults to None, in which case the source prim path is used.
stage: The stage where the prim exists. Defaults to None, in which case the
current stage is used.
"""
# get current stage
if stage is None:
stage: Usd.Stage = omni.usd.get_context().get_stage()
# get root layer
source_layer = stage.GetRootLayer()
# only create a new layer if it doesn't exist already
target_layer = Sdf.Find(path)
if target_layer is None:
target_layer = Sdf.Layer.CreateNew(path)
# open the target stage
target_stage = Usd.Stage.Open(target_layer)
# update stage data
UsdGeom.SetStageUpAxis(target_stage, UsdGeom.GetStageUpAxis(stage))
UsdGeom.SetStageMetersPerUnit(target_stage, UsdGeom.GetStageMetersPerUnit(stage))
# specify the prim to copy
source_prim_path = Sdf.Path(source_prim_path)
if target_prim_path is None:
target_prim_path = source_prim_path
# copy the prim
Sdf.CreatePrimInLayer(target_layer, target_prim_path)
Sdf.CopySpec(source_layer, source_prim_path, target_layer, target_prim_path)
# set the default prim
target_layer.defaultPrim = Sdf.Path(target_prim_path).name
# resolve all paths relative to layer path
omni.usd.resolve_paths(source_layer.identifier, target_layer.identifier)
# save the stage
target_layer.Save()
""" """
USD Prim properties. USD Prim properties.
""" """
......
...@@ -33,7 +33,7 @@ from omni.isaac.orbit.utils.timer import Timer ...@@ -33,7 +33,7 @@ from omni.isaac.orbit.utils.timer import Timer
class TestUsdVisualizationMarkers(unittest.TestCase): class TestUsdVisualizationMarkers(unittest.TestCase):
"""Test fixture for the UrdfLoader class.""" """Test fixture for the VisualizationMarker class."""
def setUp(self): def setUp(self):
"""Create a blank new stage for each test.""" """Create a blank new stage for each test."""
......
# Copyright [2023] Boston Dynamics AI Institute, Inc.
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Launch Isaac Sim Simulator first."""
from omni.isaac.kit import SimulationApp
# launch omniverse app
config = {"headless": True}
simulation_app = SimulationApp(config)
"""Rest everything follows."""
import os
import traceback
import unittest
import carb
import omni
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.stage as stage_utils
from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.orbit_assets import ORBIT_ASSETS_DATA_DIR
from pxr import UsdGeom, UsdPhysics
from omni.isaac.orbit.sim.converters import MeshConverter, MeshConverterCfg
from omni.isaac.orbit.sim.schemas import schemas_cfg
class TestMeshConverter(unittest.TestCase):
"""Test fixture for the MeshConverter class."""
@classmethod
def setUpClass(cls):
"""Load assets for tests."""
# TODO: Clean this up: https://github.com/isaac-orbit/orbit/issues/166
assets_dir = os.path.join(ORBIT_ASSETS_DATA_DIR, "Samples/Tests/MeshConverter/duck")
# Create mapping of file endings to file paths that can be used by tests
cls.assets = {asset.split(".")[1]: os.path.join(assets_dir, asset) for asset in os.listdir(assets_dir)}
def setUp(self):
"""Create a blank new stage for each test."""
# Create a new stage
stage_utils.create_new_stage()
# Simulation time-step
self.dt = 0.01
# Load kit helper
self.sim = SimulationContext(physics_dt=self.dt, rendering_dt=self.dt, backend="numpy")
def tearDown(self) -> None:
"""Stops simulator after each test."""
# stop simulation
self.sim.stop()
# cleanup stage and context
self.sim.clear()
self.sim.clear_all_callbacks()
self.sim.clear_instance()
"""
Test fixtures.
"""
def test_no_change(self):
"""Call conversion twice on the same input asset. This should not generate a new USD file if the hash is the same."""
# create an initial USD file from asset
mesh_config = MeshConverterCfg(asset_path=self.assets["obj"])
mesh_converter = MeshConverter(mesh_config)
time_usd_file_created = os.stat(mesh_converter.usd_path).st_mtime_ns
# no change to config only define the usd directory
new_config = mesh_config
new_config.usd_dir = mesh_converter.usd_dir
# convert to usd but this time in the same directory as previous step
new_mesh_converter = MeshConverter(new_config)
new_time_usd_file_created = os.stat(new_mesh_converter.usd_path).st_mtime_ns
self.assertEqual(time_usd_file_created, new_time_usd_file_created)
def test_config_change(self):
"""Call conversion twice but change the config in the second call. This should generate a new USD file."""
# create an initial USD file from asset
mesh_config = MeshConverterCfg(asset_path=self.assets["obj"])
mesh_converter = MeshConverter(mesh_config)
time_usd_file_created = os.stat(mesh_converter.usd_path).st_mtime_ns
omni.usd.get_context().close_stage()
# change the config
new_config = mesh_config
new_config.make_instanceable = not mesh_config.make_instanceable
# define the usd directory
new_config.usd_dir = mesh_converter.usd_dir
# convert to usd but this time in the same directory as previous step
new_mesh_converter = MeshConverter(new_config)
new_time_usd_file_created = os.stat(new_mesh_converter.usd_path).st_mtime_ns
self.assertNotEqual(time_usd_file_created, new_time_usd_file_created)
def test_convert_obj(self):
"""Convert an OBJ file"""
mesh_config = MeshConverterCfg(asset_path=self.assets["obj"])
mesh_converter = MeshConverter(mesh_config)
# check that mesh conversion is successful
self._check_mesh_conversion(mesh_converter)
def test_convert_stl(self):
"""Convert an STL file"""
mesh_config = MeshConverterCfg(asset_path=self.assets["stl"])
mesh_converter = MeshConverter(mesh_config)
# check that mesh conversion is successful
self._check_mesh_conversion(mesh_converter)
def test_convert_fbx(self):
"""Convert an FBX file"""
mesh_config = MeshConverterCfg(asset_path=self.assets["fbx"])
mesh_converter = MeshConverter(mesh_config)
# check that mesh conversion is successful
self._check_mesh_conversion(mesh_converter)
def test_collider_no_approximation(self):
"""Convert an OBJ file using no approximation"""
collision_props = schemas_cfg.CollisionPropertiesCfg(collision_enabled=True)
mesh_config = MeshConverterCfg(
asset_path=self.assets["obj"],
collision_approximation="none",
collision_props=collision_props,
)
mesh_converter = MeshConverter(mesh_config)
# check that mesh conversion is successful
self._check_mesh_collider_settings(mesh_converter)
def test_collider_convex_hull(self):
"""Convert an OBJ file using convex hull approximation"""
collision_props = schemas_cfg.CollisionPropertiesCfg(collision_enabled=True)
mesh_config = MeshConverterCfg(
asset_path=self.assets["obj"],
collision_approximation="convexHull",
collision_props=collision_props,
)
mesh_converter = MeshConverter(mesh_config)
# check that mesh conversion is successful
self._check_mesh_collider_settings(mesh_converter)
def test_collider_mesh_simplification(self):
"""Convert an OBJ file using mesh simplification approximation"""
collision_props = schemas_cfg.CollisionPropertiesCfg(collision_enabled=True)
mesh_config = MeshConverterCfg(
asset_path=self.assets["obj"],
collision_approximation="meshSimplification",
collision_props=collision_props,
)
mesh_converter = MeshConverter(mesh_config)
# check that mesh conversion is successful
self._check_mesh_collider_settings(mesh_converter)
def test_collider_mesh_bounding_cube(self):
"""Convert an OBJ file using bounding cube approximation"""
collision_props = schemas_cfg.CollisionPropertiesCfg(collision_enabled=True)
mesh_config = MeshConverterCfg(
asset_path=self.assets["obj"],
collision_approximation="boundingCube",
collision_props=collision_props,
)
mesh_converter = MeshConverter(mesh_config)
# check that mesh conversion is successful
self._check_mesh_collider_settings(mesh_converter)
def test_collider_mesh_bounding_sphere(self):
"""Convert an OBJ file using bounding sphere"""
collision_props = schemas_cfg.CollisionPropertiesCfg(collision_enabled=True)
mesh_config = MeshConverterCfg(
asset_path=self.assets["obj"],
collision_approximation="boundingSphere",
collision_props=collision_props,
)
mesh_converter = MeshConverter(mesh_config)
# check that mesh conversion is successful
self._check_mesh_collider_settings(mesh_converter)
def test_collider_mesh_no_collision(self):
"""Convert an OBJ file using bounding sphere with collision disabled"""
collision_props = schemas_cfg.CollisionPropertiesCfg(collision_enabled=False)
mesh_config = MeshConverterCfg(
asset_path=self.assets["obj"],
collision_approximation="boundingSphere",
collision_props=collision_props,
)
mesh_converter = MeshConverter(mesh_config)
# check that mesh conversion is successful
self._check_mesh_collider_settings(mesh_converter)
"""
Helper functions.
"""
def _check_mesh_conversion(self, mesh_converter: MeshConverter):
"""Check that mesh is loadable and stage is valid."""
# Load the mesh
prim_path = "/World/Object"
prim_utils.create_prim(prim_path, usd_path=mesh_converter.usd_path)
# Check prim can be properly spawned
self.assertTrue(prim_utils.is_prim_path_valid(prim_path))
# Load a second time
prim_path = "/World/Object2"
prim_utils.create_prim(prim_path, usd_path=mesh_converter.usd_path)
# Check prim can be properly spawned
self.assertTrue(prim_utils.is_prim_path_valid(prim_path))
stage = omni.usd.get_context().get_stage()
# Check axis is z-up
axis = UsdGeom.GetStageUpAxis(stage)
self.assertEqual(axis, "Z")
# Check units is meters
units = UsdGeom.GetStageMetersPerUnit(stage)
self.assertEqual(units, 1.0)
def _check_mesh_collider_settings(self, mesh_converter: MeshConverter):
# Check prim can be properly spawned
prim_path = "/World/Object"
prim_utils.create_prim(prim_path, usd_path=mesh_converter.usd_path)
self.assertTrue(prim_utils.is_prim_path_valid(prim_path))
# Make uninstanceable to check collision settings
geom_prim = prim_utils.get_prim_at_path(prim_path + "/geometry")
# Check that instancing worked!
self.assertEqual(geom_prim.IsInstanceable(), mesh_converter.cfg.make_instanceable)
# Obtain mesh settings
geom_prim.SetInstanceable(False)
mesh_prim = prim_utils.get_prim_at_path(prim_path + "/geometry/mesh")
# Check collision settings
# -- if collision is enabled, check that API is present
exp_collision_enabled = (
mesh_converter.cfg.collision_props is not None and mesh_converter.cfg.collision_props.collision_enabled
)
collision_api = UsdPhysics.CollisionAPI(mesh_prim)
collision_enabled = collision_api.GetCollisionEnabledAttr().Get()
self.assertEqual(collision_enabled, exp_collision_enabled, "Collision enabled is not the same!")
# -- if collision is enabled, check that collision approximation is correct
if exp_collision_enabled:
exp_collision_approximation = mesh_converter.cfg.collision_approximation
mesh_collision_api = UsdPhysics.MeshCollisionAPI(mesh_prim)
collision_approximation = mesh_collision_api.GetApproximationAttr().Get()
self.assertEqual(
collision_approximation, exp_collision_approximation, "Collision approximation is not the same!"
)
if __name__ == "__main__":
try:
unittest.main()
except Exception as err:
carb.log_error(err)
carb.log_error(traceback.format_exc())
raise
finally:
# close sim app
simulation_app.close()
...@@ -69,7 +69,7 @@ class TestSpawningFromFiles(unittest.TestCase): ...@@ -69,7 +69,7 @@ class TestSpawningFromFiles(unittest.TestCase):
extension_path = get_extension_path_from_name("omni.importer.urdf") extension_path = get_extension_path_from_name("omni.importer.urdf")
# Spawn franka from URDF # Spawn franka from URDF
cfg = sim_utils.UrdfFileCfg( cfg = sim_utils.UrdfFileCfg(
urdf_path=f"{extension_path}/data/urdf/robots/franka_description/robots/panda_arm_hand.urdf", fix_base=True asset_path=f"{extension_path}/data/urdf/robots/franka_description/robots/panda_arm_hand.urdf", fix_base=True
) )
prim = cfg.func("/World/Franka", cfg) prim = cfg.func("/World/Franka", cfg)
# Check validity # Check validity
......
...@@ -29,75 +29,78 @@ from omni.isaac.core.simulation_context import SimulationContext ...@@ -29,75 +29,78 @@ from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.extensions import get_extension_path_from_name from omni.isaac.core.utils.extensions import get_extension_path_from_name
from omni.isaac.version import get_version from omni.isaac.version import get_version
from omni.isaac.orbit.sim.loaders import UrdfLoader, UrdfLoaderCfg from omni.isaac.orbit.sim.converters import UrdfConverter, UrdfConverterCfg
class TestUrdfLoader(unittest.TestCase): class TestUrdfConverter(unittest.TestCase):
"""Test fixture for the UrdfLoader class.""" """Test fixture for the UrdfConverter class."""
def setUp(self): def setUp(self):
"""Create a blank new stage for each test.""" """Create a blank new stage for each test."""
# Isaac Sim version
self.isaacsim_version_year = int(get_version()[2])
# retrieve path to urdf importer extension # retrieve path to urdf importer extension
if self.isaacsim_version_year == 2022: if self.isaacsim_version_year == 2022:
extension_path = get_extension_path_from_name("omni.isaac.urdf") extension_path = get_extension_path_from_name("omni.isaac.urdf")
else: else:
extension_path = get_extension_path_from_name("omni.importer.urdf") extension_path = get_extension_path_from_name("omni.importer.urdf")
# default configuration # default configuration
self.config = UrdfLoaderCfg( self.config = UrdfConverterCfg(
urdf_path=f"{extension_path}/data/urdf/robots/franka_description/robots/panda_arm_hand.urdf", fix_base=True asset_path=f"{extension_path}/data/urdf/robots/franka_description/robots/panda_arm_hand.urdf", fix_base=True
) )
# Simulation time-step # Simulation time-step
self.dt = 0.01 self.dt = 0.01
# Load kit helper # Load kit helper
self.sim = SimulationContext(physics_dt=self.dt, rendering_dt=self.dt, backend="numpy") self.sim = SimulationContext(physics_dt=self.dt, rendering_dt=self.dt, backend="numpy")
# Isaac Sim version
self.isaacsim_version_year = int(get_version()[2])
def tearDown(self) -> None: def tearDown(self) -> None:
"""Stops simulator after each test.""" """Stops simulator after each test."""
# stop simulation # stop simulation
self.sim.stop() self.sim.stop()
# cleanup stage and context
self.sim.clear() self.sim.clear()
self.sim.clear_all_callbacks()
self.sim.clear_instance()
def test_no_change(self): def test_no_change(self):
"""Call conversion twice. This should not generate a new USD file.""" """Call conversion twice. This should not generate a new USD file."""
urdf_loader = UrdfLoader(self.config) urdf_converter = UrdfConverter(self.config)
time_usd_file_created = os.stat(urdf_loader.usd_path).st_mtime_ns time_usd_file_created = os.stat(urdf_converter.usd_path).st_mtime_ns
# no change to config only define the usd directory # no change to config only define the usd directory
new_config = self.config new_config = self.config
new_config.usd_dir = urdf_loader.usd_dir new_config.usd_dir = urdf_converter.usd_dir
# convert to usd but this time in the same directory as previous step # convert to usd but this time in the same directory as previous step
new_urdf_loader = UrdfLoader(new_config) new_urdf_converter = UrdfConverter(new_config)
new_time_usd_file_created = os.stat(new_urdf_loader.usd_path).st_mtime_ns new_time_usd_file_created = os.stat(new_urdf_converter.usd_path).st_mtime_ns
self.assertEqual(time_usd_file_created, new_time_usd_file_created) self.assertEqual(time_usd_file_created, new_time_usd_file_created)
def test_config_change(self): def test_config_change(self):
"""Call conversion twice but change the config in the second call. This should generate a new USD file.""" """Call conversion twice but change the config in the second call. This should generate a new USD file."""
urdf_loader = UrdfLoader(self.config) urdf_converter = UrdfConverter(self.config)
time_usd_file_created = os.stat(urdf_loader.usd_path).st_mtime_ns time_usd_file_created = os.stat(urdf_converter.usd_path).st_mtime_ns
# change the config # change the config
new_config = self.config new_config = self.config
new_config.fix_base = not self.config.fix_base new_config.fix_base = not self.config.fix_base
# define the usd directory # define the usd directory
new_config.usd_dir = urdf_loader.usd_dir new_config.usd_dir = urdf_converter.usd_dir
# convert to usd but this time in the same directory as previous step # convert to usd but this time in the same directory as previous step
new_urdf_loader = UrdfLoader(new_config) new_urdf_converter = UrdfConverter(new_config)
new_time_usd_file_created = os.stat(new_urdf_loader.usd_path).st_mtime_ns new_time_usd_file_created = os.stat(new_urdf_converter.usd_path).st_mtime_ns
self.assertNotEqual(time_usd_file_created, new_time_usd_file_created) self.assertNotEqual(time_usd_file_created, new_time_usd_file_created)
def test_create_prim_from_usd(self): def test_create_prim_from_usd(self):
"""Call conversion and create a prim from it.""" """Call conversion and create a prim from it."""
urdf_loader = UrdfLoader(self.config) urdf_converter = UrdfConverter(self.config)
prim_path = "/World/Robot" prim_path = "/World/Robot"
prim_utils.create_prim(prim_path, usd_path=urdf_loader.usd_path) prim_utils.create_prim(prim_path, usd_path=urdf_converter.usd_path)
self.assertTrue(prim_utils.is_prim_path_valid(prim_path)) self.assertTrue(prim_utils.is_prim_path_valid(prim_path))
...@@ -106,7 +109,7 @@ class TestUrdfLoader(unittest.TestCase): ...@@ -106,7 +109,7 @@ class TestUrdfLoader(unittest.TestCase):
# Create directory to dump results # Create directory to dump results
test_dir = os.path.dirname(os.path.abspath(__file__)) test_dir = os.path.dirname(os.path.abspath(__file__))
output_dir = os.path.join(test_dir, "output", "urdf_loader") output_dir = os.path.join(test_dir, "output", "urdf_converter")
if not os.path.exists(output_dir): if not os.path.exists(output_dir):
os.makedirs(output_dir, exist_ok=True) os.makedirs(output_dir, exist_ok=True)
...@@ -115,10 +118,10 @@ class TestUrdfLoader(unittest.TestCase): ...@@ -115,10 +118,10 @@ class TestUrdfLoader(unittest.TestCase):
self.config.default_drive_stiffness = 400.0 self.config.default_drive_stiffness = 400.0
self.config.default_drive_damping = 40.0 self.config.default_drive_damping = 40.0
self.config.usd_dir = output_dir self.config.usd_dir = output_dir
urdf_loader = UrdfLoader(self.config) urdf_converter = UrdfConverter(self.config)
# check the drive type of the robot # check the drive type of the robot
prim_path = "/World/Robot" prim_path = "/World/Robot"
prim_utils.create_prim(prim_path, usd_path=urdf_loader.usd_path) prim_utils.create_prim(prim_path, usd_path=urdf_converter.usd_path)
# access the robot # access the robot
robot = ArticulationView(prim_path, reset_xform_properties=False) robot = ArticulationView(prim_path, reset_xform_properties=False)
......
...@@ -45,6 +45,7 @@ from __future__ import annotations ...@@ -45,6 +45,7 @@ from __future__ import annotations
import argparse import argparse
import contextlib import contextlib
import os
# omni-isaac-orbit # omni-isaac-orbit
from omni.isaac.kit import SimulationApp from omni.isaac.kit import SimulationApp
...@@ -100,8 +101,9 @@ def main(): ...@@ -100,8 +101,9 @@ def main():
prim_utils.define_prim("/World/envs/env_0") prim_utils.define_prim("/World/envs/env_0")
# Spawn things into stage # Spawn things into stage
prim_utils.create_prim("/World/Light", "DistantLight") prim_utils.create_prim("/World/Light", "DistantLight")
# Everything under the namespace "/World/envs/env_0" will be cloned # Everything under the namespace "/World/envs/env_0" will be cloned
prim_utils.create_prim("/World/envs/env_0/Asset", "Xform", usd_path=args_cli.input) prim_utils.create_prim("/World/envs/env_0/Asset", "Xform", usd_path=os.path.abspath(args_cli.usd_path))
# Clone the scene # Clone the scene
num_clones = args_cli.num_clones num_clones = args_cli.num_clones
......
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
Utility to convert a OBJ/STL/FBX into USD format.
The OBJ file format is a simple data-format that represents 3D geometry alone — namely, the position
of each vertex, the UV position of each texture coordinate vertex, vertex normals, and the faces that
make each polygon defined as a list of vertices, and texture vertices.
An STL file describes a raw, unstructured triangulated surface by the unit normal and vertices (ordered
by the right-hand rule) of the triangles using a three-dimensional Cartesian coordinate system.
FBX files are a type of 3D model file created using the Autodesk FBX software. They can be designed and
modified in various modeling applications, such as Maya, 3ds Max, and Blender. Moreover, FBX files typically
contain mesh, material, texture, and skeletal animation data.
Link: https://www.autodesk.com/products/fbx/overview
This script uses the asset converter extension from Isaac Sim (``omni.kit.asset_converter``) to convert a
OBJ/STL/FBX asset into USD format. It is designed as a convenience script for command-line use.
positional arguments:
input The path to the input mesh (.OBJ/.STL/.FBX) file.
output The path to store the USD file.
optional arguments:
-h, --help Show this help message and exit
--headless Force display off at all times. (default: False)
--make_instanceable, -i Make the asset instanceable for efficient cloning. (default: False)
--force_usd_conversion -f Convert the input file to USD even if the output file already exists.
--collision_approximation -c The method used for approximating collision mesh. Defaults to convexDecomposition. Set to \"none\" "
to not add a collision mesh to the converted mesh.
--mass -m The mass (in kg) to assign to the converted asset.
"""
"""Launch Isaac Sim Simulator first."""
import argparse
import contextlib
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser(description="Utility to convert a mesh file into USD format.")
parser.add_argument("input", type=str, help="The path to the input mesh file.")
parser.add_argument("output", type=str, help="The path to store the USD file.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument(
"--make_instanceable",
"-i",
action="store_true",
default=False,
help="Make the asset instanceable for efficient cloning.",
)
parser.add_argument(
"--force_usd_conversion",
"-f",
action="store_true",
default=False,
help="Convert the input file to USD even if the output file already exists.",
)
parser.add_argument(
"--collision_approximation",
"-c",
type=str,
default="convexDecomposition",
choices=["convexDecomposition", "convexHull", "none"],
help=(
'The method used for approximating collision mesh. Set to "none" '
"to not add a collision mesh to the converted mesh."
),
)
parser.add_argument(
"--mass",
"-m",
type=float,
default=None,
help="The mass (in kg) to assign to the converted asset. If not provided, then no mass is added.",
)
args_cli = parser.parse_args()
# launch omniverse app
simulation_app = AppLauncher(headless=args_cli.headless).app
"""Rest everything follows."""
import os
import omni.isaac.core.utils.stage as stage_utils
import omni.kit.app
from omni.isaac.orbit.sim.converters import MeshConverter, MeshConverterCfg
from omni.isaac.orbit.sim.schemas import schemas_cfg
from omni.isaac.orbit.utils.assets import check_file_path
from omni.isaac.orbit.utils.dict import print_dict
def main():
# check valid file path
mesh_path = args_cli.input
if not os.path.isabs(mesh_path):
mesh_path = os.path.abspath(mesh_path)
if not check_file_path(mesh_path):
raise ValueError(f"Invalid mesh file path: {mesh_path}")
# create destination path
dest_path = args_cli.output
if not os.path.isabs(dest_path):
dest_path = os.path.abspath(dest_path)
print(dest_path)
print(os.path.dirname(dest_path))
print(os.path.basename(dest_path))
# Mass properties
if args_cli.mass is not None:
mass_props = schemas_cfg.MassPropertiesCfg(mass=args_cli.mass)
rigid_props = schemas_cfg.RigidBodyPropertiesCfg()
else:
mass_props = None
rigid_props = None
# Collision properties
collision_props = schemas_cfg.CollisionPropertiesCfg(collision_enabled=args_cli.collision_approximation != "none")
# Create Mesh converter config
mesh_converter_cfg = MeshConverterCfg(
mass_props=mass_props,
rigid_props=rigid_props,
collision_props=collision_props,
asset_path=mesh_path,
force_usd_conversion=args_cli.force_usd_conversion,
usd_dir=os.path.dirname(dest_path),
usd_file_name=os.path.basename(dest_path),
make_instanceable=args_cli.make_instanceable,
collision_approximation=args_cli.collision_approximation,
)
# Print info
print("-" * 80)
print("-" * 80)
print(f"Input Mesh file: {mesh_path}")
print("Mesh importer config:")
print_dict(mesh_converter_cfg.to_dict(), nesting=0)
print("-" * 80)
print("-" * 80)
# Create Mesh converter and import the file
mesh_converter = MeshConverter(mesh_converter_cfg)
# print output
print("Mesh importer output:")
print(f"Generated USD file: {mesh_converter.usd_path}")
print("-" * 80)
print("-" * 80)
# Simulate scene (if not headless)
if not args_cli.headless:
# Open the stage with USD
stage_utils.open_stage(mesh_converter.usd_path)
# Reinitialize the simulation
app = omni.kit.app.get_app_interface()
# Run simulation
with contextlib.suppress(KeyboardInterrupt):
while True:
# perform step
app.update()
if __name__ == "__main__":
try:
main()
except Exception as e:
import traceback
import carb
carb.log_error(traceback.format_exc())
carb.log_error(e)
finally:
simulation_app.close()
...@@ -77,7 +77,7 @@ import carb ...@@ -77,7 +77,7 @@ import carb
import omni.isaac.core.utils.stage as stage_utils import omni.isaac.core.utils.stage as stage_utils
import omni.kit.app import omni.kit.app
from omni.isaac.orbit.sim.loaders import UrdfLoader, UrdfLoaderCfg from omni.isaac.orbit.sim.converters import UrdfConverter, UrdfConverterCfg
from omni.isaac.orbit.utils.assets import check_file_path from omni.isaac.orbit.utils.assets import check_file_path
from omni.isaac.orbit.utils.dict import print_dict from omni.isaac.orbit.utils.dict import print_dict
...@@ -94,9 +94,9 @@ def main(): ...@@ -94,9 +94,9 @@ def main():
if not os.path.isabs(dest_path): if not os.path.isabs(dest_path):
dest_path = os.path.abspath(dest_path) dest_path = os.path.abspath(dest_path)
# Create Urdf loader config # Create Urdf converter config
urdf_loader_cfg = UrdfLoaderCfg( urdf_converter_cfg = UrdfConverterCfg(
urdf_path=urdf_path, asset_path=urdf_path,
usd_dir=os.path.dirname(dest_path), usd_dir=os.path.dirname(dest_path),
usd_file_name=os.path.basename(dest_path), usd_file_name=os.path.basename(dest_path),
fix_base=args_cli.fix_base, fix_base=args_cli.fix_base,
...@@ -110,22 +110,22 @@ def main(): ...@@ -110,22 +110,22 @@ def main():
print("-" * 80) print("-" * 80)
print(f"Input URDF file: {urdf_path}") print(f"Input URDF file: {urdf_path}")
print("URDF importer config:") print("URDF importer config:")
print_dict(urdf_loader_cfg.to_dict(), nesting=0) print_dict(urdf_converter_cfg.to_dict(), nesting=0)
print("-" * 80) print("-" * 80)
print("-" * 80) print("-" * 80)
# Create Urdf loader and import the file # Create Urdf converter and import the file
urdf_loader = UrdfLoader(urdf_loader_cfg) urdf_converter = UrdfConverter(urdf_converter_cfg)
# print output # print output
print("URDF importer output:") print("URDF importer output:")
print(f"Generated USD file: {urdf_loader.usd_path}") print(f"Generated USD file: {urdf_converter.usd_path}")
print("-" * 80) print("-" * 80)
print("-" * 80) print("-" * 80)
# Simulate scene (if not headless) # Simulate scene (if not headless)
if not args_cli.headless: if not args_cli.headless:
# Open the stage with USD # Open the stage with USD
stage_utils.open_stage(urdf_loader.usd_path) stage_utils.open_stage(urdf_converter.usd_path)
# Reinitialize the simulation # Reinitialize the simulation
app = omni.kit.app.get_app_interface() app = omni.kit.app.get_app_interface()
# Run simulation # Run simulation
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment