feat(conversion): Add cvt_embodiedgen_asset_to_anysim interface. (#48)

This commit is contained in:
Xinjie 2025-10-30 20:00:32 +08:00 committed by GitHub
parent 54e5892607
commit 55dedc29ce
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194

View File

@ -21,6 +21,9 @@ __all__ = [
"MeshtoMJCFConverter", "MeshtoMJCFConverter",
"MeshtoUSDConverter", "MeshtoUSDConverter",
"URDFtoUSDConverter", "URDFtoUSDConverter",
"cvt_embodiedgen_asset_to_anysim",
"PhysicsUSDAdder",
"SimAssetMapper",
] ]
@ -34,6 +37,84 @@ class AssetType(str):
MESH = "mesh" MESH = "mesh"
class SimAssetMapper:
_mapping = dict(
ISAACSIM=AssetType.USD,
ISAACGYM=AssetType.URDF,
MUJOCO=AssetType.MJCF,
GENESIS=AssetType.MJCF,
SAPIEN=AssetType.URDF,
PYBULLET=AssetType.URDF,
)
@classmethod
def __class_getitem__(cls, key: str):
key = key.upper()
if key.startswith("SAPIEN"):
key = "SAPIEN"
return cls._mapping[key]
def cvt_embodiedgen_asset_to_anysim(
urdf_files: list[str],
target_type: AssetType,
source_type: AssetType,
**kwargs,
) -> dict[str, str]:
"""Convert URDF files generated by EmbodiedGen into the format required by all simulators.
Supported simulators include SAPIEN, Isaac Sim, MuJoCo, Isaac Gym, Genesis, and Pybullet.
Example:
dst_asset_path = cvt_embodiedgen_asset_to_anysim(
urdf_files,
target_type=SimAssetMapper[simulator_name],
source_type=AssetType.MESH,
)
Args:
urdf_files (List[str]): List of URDF file paths to be converted.
target_type (AssetType): The target asset type.
source_type (AssetType): The source asset type.
Returns:
Dict[str, str]: A dictionary mapping the original URDF file path to the converted asset file path.
"""
if isinstance(urdf_files, str):
urdf_files = [urdf_files]
# If the target type is URDF, no conversion is needed.
if target_type == AssetType.URDF:
return {key: key for key in urdf_files}
asset_converter = AssetConverterFactory.create(
target_type=target_type,
source_type=source_type,
**kwargs,
)
asset_paths = dict()
with asset_converter:
for urdf_file in urdf_files:
filename = os.path.basename(urdf_file).replace(".urdf", "")
asset_dir = os.path.dirname(urdf_file)
if target_type == AssetType.MJCF:
target_file = f"{asset_dir}/../mjcf/{filename}.xml"
elif target_type == AssetType.USD:
target_file = f"{asset_dir}/../usd/{filename}.usd"
else:
raise NotImplementedError(
f"Target type {target_type} not supported."
)
if not os.path.exists(target_file):
asset_converter.convert(urdf_file, target_file)
asset_paths[urdf_file] = target_file
return asset_paths
class AssetConverterBase(ABC): class AssetConverterBase(ABC):
"""Converter abstract base class.""" """Converter abstract base class."""
@ -222,6 +303,7 @@ class MeshtoMJCFConverter(AssetConverterBase):
output_dir, output_dir,
name=str(idx), name=str(idx),
) )
joint = ET.SubElement(body, "joint", attrib={"type": "free"})
self.add_geometry( self.add_geometry(
mujoco_asset, mujoco_asset,
link, link,
@ -357,24 +439,33 @@ class MeshtoUSDConverter(AssetConverterBase):
simulation_app=None, simulation_app=None,
**kwargs, **kwargs,
): ):
if simulation_app is not None:
self.simulation_app = simulation_app
if "exit_close" in kwargs:
self.exit_close = kwargs.pop("exit_close")
else:
self.exit_close = True
self.usd_parms = dict( self.usd_parms = dict(
force_usd_conversion=force_usd_conversion, force_usd_conversion=force_usd_conversion,
make_instanceable=make_instanceable, make_instanceable=make_instanceable,
**kwargs, **kwargs,
) )
if simulation_app is not None:
self.simulation_app = simulation_app
def __enter__(self): def __enter__(self):
from isaaclab.app import AppLauncher from isaaclab.app import AppLauncher
if not hasattr(self, "simulation_app"): if not hasattr(self, "simulation_app"):
launch_args = dict( if "launch_args" not in self.usd_parms:
headless=True, launch_args = dict(
no_splash=True, headless=True,
fast_shutdown=True, no_splash=True,
disable_gpu=True, fast_shutdown=True,
) disable_gpu=True,
)
else:
launch_args = self.usd_parms.pop("launch_args")
self.app_launcher = AppLauncher(launch_args) self.app_launcher = AppLauncher(launch_args)
self.simulation_app = self.app_launcher.app self.simulation_app = self.app_launcher.app
@ -382,7 +473,7 @@ class MeshtoUSDConverter(AssetConverterBase):
def __exit__(self, exc_type, exc_val, exc_tb): def __exit__(self, exc_type, exc_val, exc_tb):
# Close the simulation app if it was created here # Close the simulation app if it was created here
if hasattr(self, "app_launcher"): if hasattr(self, "app_launcher") and self.exit_close:
self.simulation_app.close() self.simulation_app.close()
if exc_val is not None: if exc_val is not None: