feat(sim): Support all simulators and opt asset storage size. (#40)
* feat(sim): Support all simulators and opt asset storage size.
This commit is contained in:
parent
1272b80926
commit
ee03a089b1
@ -4,6 +4,12 @@ All notable changes to this project will be documented in this file.
|
|||||||
|
|
||||||
The format is based on [Keep a Changelog](http://keepachangelog.com/en/1.0.0).
|
The format is based on [Keep a Changelog](http://keepachangelog.com/en/1.0.0).
|
||||||
|
|
||||||
|
|
||||||
|
## [0.1.5] - 2025-09-25
|
||||||
|
### Feature
|
||||||
|
- Support one-click import into all mainstream simulators([isaacsim](https://github.com/isaac-sim/IsaacSim), [mujoco](https://github.com/google-deepmind/mujoco), [genesis](https://github.com/Genesis-Embodied-AI/Genesis), [pybullet](https://github.com/bulletphysics/bullet3), [isaacgym](https://github.com/isaac-sim/IsaacGymEnvs), [sapien](https://github.com/haosulab/SAPIEN)) for assets generated by EmbodiedGen.
|
||||||
|
- Optimize the storage volume of EmbodiedGen generated assets.
|
||||||
|
|
||||||
## [0.1.4] - 2025-08-29
|
## [0.1.4] - 2025-08-29
|
||||||
### Feature
|
### Feature
|
||||||
- Supports importing the output of the EmbodiedGen Layout Generation module with a single `gym.make` command to create multiple parallel simulation environments and interactive 3D worlds.
|
- Supports importing the output of the EmbodiedGen Layout Generation module with a single `gym.make` command to create multiple parallel simulation environments and interactive 3D worlds.
|
||||||
|
|||||||
20
README.md
20
README.md
@ -23,6 +23,7 @@
|
|||||||
- [🌍 3D Scene Generation](#3d-scene-generation)
|
- [🌍 3D Scene Generation](#3d-scene-generation)
|
||||||
- [⚙️ Articulated Object Generation](#articulated-object-generation)
|
- [⚙️ Articulated Object Generation](#articulated-object-generation)
|
||||||
- [🏞️ Layout (Interactive 3D Worlds) Generation](#layout-generation)
|
- [🏞️ Layout (Interactive 3D Worlds) Generation](#layout-generation)
|
||||||
|
- [🎮 Any Simulators](#any-simulators)
|
||||||
|
|
||||||
## 🚀 Quick Start
|
## 🚀 Quick Start
|
||||||
|
|
||||||
@ -30,7 +31,7 @@
|
|||||||
```sh
|
```sh
|
||||||
git clone https://github.com/HorizonRobotics/EmbodiedGen.git
|
git clone https://github.com/HorizonRobotics/EmbodiedGen.git
|
||||||
cd EmbodiedGen
|
cd EmbodiedGen
|
||||||
git checkout v0.1.4
|
git checkout v0.1.5
|
||||||
git submodule update --init --recursive --progress
|
git submodule update --init --recursive --progress
|
||||||
conda create -n embodiedgen python=3.10.13 -y # recommended to use a new env.
|
conda create -n embodiedgen python=3.10.13 -y # recommended to use a new env.
|
||||||
conda activate embodiedgen
|
conda activate embodiedgen
|
||||||
@ -267,6 +268,23 @@ python embodied_gen/scripts/parallel_sim.py \
|
|||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
<h2 id="any-simulators">🎮 Any Simulators</h2>
|
||||||
|
|
||||||
|
Use EmbodiedGen-generated assets with correct physical collisions and consistent visual effects in any simulator
|
||||||
|
([isaacsim](https://github.com/isaac-sim/IsaacSim), [mujoco](https://github.com/google-deepmind/mujoco), [genesis](https://github.com/Genesis-Embodied-AI/Genesis), [pybullet](https://github.com/bulletphysics/bullet3), [isaacgym](https://github.com/isaac-sim/IsaacGymEnvs), [sapien](https://github.com/haosulab/SAPIEN)).
|
||||||
|
Example in `tests/test_examples/test_asset_converter.py`.
|
||||||
|
|
||||||
|
| Simulator | Conversion Class |
|
||||||
|
|-----------|------------------|
|
||||||
|
| [isaacsim](https://github.com/isaac-sim/IsaacSim) | MeshtoUSDConverter |
|
||||||
|
| [mujoco](https://github.com/google-deepmind/mujoco) | MeshtoMJCFConverter |
|
||||||
|
| [genesis](https://github.com/Genesis-Embodied-AI/Genesis) / [sapien](https://github.com/haosulab/SAPIEN) / [isaacgym](https://github.com/isaac-sim/IsaacGymEnvs) / [pybullet](https://github.com/bulletphysics/bullet3) | EmbodiedGen generated .urdf can be used directly |
|
||||||
|
|
||||||
|
|
||||||
|
<img src="apps/assets/simulators_collision.jpg" alt="simulators_collision" width="500">
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
## For Developer
|
## For Developer
|
||||||
```sh
|
```sh
|
||||||
pip install -e .[dev] && pre-commit install
|
pip install -e .[dev] && pre-commit install
|
||||||
|
|||||||
BIN
apps/assets/simulators_collision.jpg
Normal file
BIN
apps/assets/simulators_collision.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 926 KiB |
497
embodied_gen/data/asset_converter.py
Normal file
497
embodied_gen/data/asset_converter.py
Normal file
@ -0,0 +1,497 @@
|
|||||||
|
from __future__ import annotations
|
||||||
|
|
||||||
|
import logging
|
||||||
|
import os
|
||||||
|
import xml.etree.ElementTree as ET
|
||||||
|
from abc import ABC, abstractmethod
|
||||||
|
from dataclasses import dataclass
|
||||||
|
from shutil import copy
|
||||||
|
|
||||||
|
import trimesh
|
||||||
|
from scipy.spatial.transform import Rotation
|
||||||
|
|
||||||
|
logging.basicConfig(level=logging.INFO)
|
||||||
|
logger = logging.getLogger(__name__)
|
||||||
|
|
||||||
|
|
||||||
|
__all__ = [
|
||||||
|
"AssetConverterFactory",
|
||||||
|
"AssetType",
|
||||||
|
"MeshtoMJCFConverter",
|
||||||
|
"MeshtoUSDConverter",
|
||||||
|
"URDFtoUSDConverter",
|
||||||
|
]
|
||||||
|
|
||||||
|
|
||||||
|
@dataclass
|
||||||
|
class AssetType(str):
|
||||||
|
"""Asset type enumeration."""
|
||||||
|
|
||||||
|
MJCF = "mjcf"
|
||||||
|
USD = "usd"
|
||||||
|
URDF = "urdf"
|
||||||
|
MESH = "mesh"
|
||||||
|
|
||||||
|
|
||||||
|
class AssetConverterBase(ABC):
|
||||||
|
"""Converter abstract base class."""
|
||||||
|
|
||||||
|
@abstractmethod
|
||||||
|
def convert(self, urdf_path: str, output_path: str, **kwargs) -> str:
|
||||||
|
pass
|
||||||
|
|
||||||
|
def transform_mesh(
|
||||||
|
self, input_mesh: str, output_mesh: str, mesh_origin: ET.Element
|
||||||
|
) -> None:
|
||||||
|
"""Apply transform to the mesh based on the origin element in URDF."""
|
||||||
|
mesh = trimesh.load(input_mesh)
|
||||||
|
rpy = list(map(float, mesh_origin.get("rpy").split(" ")))
|
||||||
|
rotation = Rotation.from_euler("xyz", rpy, degrees=False)
|
||||||
|
offset = list(map(float, mesh_origin.get("xyz").split(" ")))
|
||||||
|
mesh.vertices = (mesh.vertices @ rotation.as_matrix().T) + offset
|
||||||
|
|
||||||
|
os.makedirs(os.path.dirname(output_mesh), exist_ok=True)
|
||||||
|
_ = mesh.export(output_mesh)
|
||||||
|
|
||||||
|
return
|
||||||
|
|
||||||
|
def __enter__(self):
|
||||||
|
return self
|
||||||
|
|
||||||
|
def __exit__(self, exc_type, exc_val, exc_tb):
|
||||||
|
return False
|
||||||
|
|
||||||
|
|
||||||
|
class MeshtoMJCFConverter(AssetConverterBase):
|
||||||
|
"""Convert URDF files into MJCF format."""
|
||||||
|
|
||||||
|
def __init__(
|
||||||
|
self,
|
||||||
|
**kwargs,
|
||||||
|
) -> None:
|
||||||
|
self.kwargs = kwargs
|
||||||
|
|
||||||
|
def _copy_asset_file(self, src: str, dst: str) -> None:
|
||||||
|
if os.path.exists(dst):
|
||||||
|
return
|
||||||
|
os.makedirs(os.path.dirname(dst), exist_ok=True)
|
||||||
|
copy(src, dst)
|
||||||
|
|
||||||
|
def add_geometry(
|
||||||
|
self,
|
||||||
|
mujoco_element: ET.Element,
|
||||||
|
link: ET.Element,
|
||||||
|
body: ET.Element,
|
||||||
|
tag: str,
|
||||||
|
input_dir: str,
|
||||||
|
output_dir: str,
|
||||||
|
mesh_name: str,
|
||||||
|
material: ET.Element | None = None,
|
||||||
|
is_collision: bool = False,
|
||||||
|
) -> None:
|
||||||
|
"""Add geometry to the MJCF body from the URDF link."""
|
||||||
|
element = link.find(tag)
|
||||||
|
geometry = element.find("geometry")
|
||||||
|
mesh = geometry.find("mesh")
|
||||||
|
filename = mesh.get("filename")
|
||||||
|
scale = mesh.get("scale", "1.0 1.0 1.0")
|
||||||
|
|
||||||
|
mesh_asset = ET.SubElement(
|
||||||
|
mujoco_element, "mesh", name=mesh_name, file=filename, scale=scale
|
||||||
|
)
|
||||||
|
geom = ET.SubElement(body, "geom", type="mesh", mesh=mesh_name)
|
||||||
|
|
||||||
|
self._copy_asset_file(
|
||||||
|
f"{input_dir}/{filename}",
|
||||||
|
f"{output_dir}/{filename}",
|
||||||
|
)
|
||||||
|
|
||||||
|
# Preprocess the mesh by applying rotation.
|
||||||
|
input_mesh = f"{input_dir}/{filename}"
|
||||||
|
output_mesh = f"{output_dir}/{filename}"
|
||||||
|
mesh_origin = element.find("origin")
|
||||||
|
if mesh_origin is not None:
|
||||||
|
self.transform_mesh(input_mesh, output_mesh, mesh_origin)
|
||||||
|
|
||||||
|
if material is not None:
|
||||||
|
geom.set("material", material.get("name"))
|
||||||
|
|
||||||
|
if is_collision:
|
||||||
|
geom.set("contype", "1")
|
||||||
|
geom.set("conaffinity", "1")
|
||||||
|
geom.set("rgba", "1 1 1 0")
|
||||||
|
|
||||||
|
def add_materials(
|
||||||
|
self,
|
||||||
|
mujoco_element: ET.Element,
|
||||||
|
link: ET.Element,
|
||||||
|
tag: str,
|
||||||
|
input_dir: str,
|
||||||
|
output_dir: str,
|
||||||
|
name: str,
|
||||||
|
reflectance: float = 0.2,
|
||||||
|
) -> ET.Element:
|
||||||
|
"""Add materials to the MJCF asset from the URDF link."""
|
||||||
|
element = link.find(tag)
|
||||||
|
geometry = element.find("geometry")
|
||||||
|
mesh = geometry.find("mesh")
|
||||||
|
filename = mesh.get("filename")
|
||||||
|
dirname = os.path.dirname(filename)
|
||||||
|
|
||||||
|
material = ET.SubElement(
|
||||||
|
mujoco_element,
|
||||||
|
"material",
|
||||||
|
name=f"material_{name}",
|
||||||
|
texture=f"texture_{name}",
|
||||||
|
reflectance=str(reflectance),
|
||||||
|
)
|
||||||
|
ET.SubElement(
|
||||||
|
mujoco_element,
|
||||||
|
"texture",
|
||||||
|
name=f"texture_{name}",
|
||||||
|
type="2d",
|
||||||
|
file=f"{dirname}/material_0.png",
|
||||||
|
)
|
||||||
|
|
||||||
|
self._copy_asset_file(
|
||||||
|
f"{input_dir}/{dirname}/material_0.png",
|
||||||
|
f"{output_dir}/{dirname}/material_0.png",
|
||||||
|
)
|
||||||
|
|
||||||
|
return material
|
||||||
|
|
||||||
|
def convert(self, urdf_path: str, mjcf_path: str):
|
||||||
|
"""Convert a URDF file to MJCF format."""
|
||||||
|
tree = ET.parse(urdf_path)
|
||||||
|
root = tree.getroot()
|
||||||
|
|
||||||
|
mujoco_struct = ET.Element("mujoco")
|
||||||
|
mujoco_struct.set("model", root.get("name"))
|
||||||
|
mujoco_asset = ET.SubElement(mujoco_struct, "asset")
|
||||||
|
mujoco_worldbody = ET.SubElement(mujoco_struct, "worldbody")
|
||||||
|
|
||||||
|
input_dir = os.path.dirname(urdf_path)
|
||||||
|
output_dir = os.path.dirname(mjcf_path)
|
||||||
|
os.makedirs(output_dir, exist_ok=True)
|
||||||
|
for idx, link in enumerate(root.findall("link")):
|
||||||
|
link_name = link.get("name", "unnamed_link")
|
||||||
|
body = ET.SubElement(mujoco_worldbody, "body", name=link_name)
|
||||||
|
|
||||||
|
material = self.add_materials(
|
||||||
|
mujoco_asset,
|
||||||
|
link,
|
||||||
|
"visual",
|
||||||
|
input_dir,
|
||||||
|
output_dir,
|
||||||
|
name=str(idx),
|
||||||
|
)
|
||||||
|
self.add_geometry(
|
||||||
|
mujoco_asset,
|
||||||
|
link,
|
||||||
|
body,
|
||||||
|
"visual",
|
||||||
|
input_dir,
|
||||||
|
output_dir,
|
||||||
|
f"visual_mesh_{idx}",
|
||||||
|
material,
|
||||||
|
)
|
||||||
|
self.add_geometry(
|
||||||
|
mujoco_asset,
|
||||||
|
link,
|
||||||
|
body,
|
||||||
|
"collision",
|
||||||
|
input_dir,
|
||||||
|
output_dir,
|
||||||
|
f"collision_mesh_{idx}",
|
||||||
|
is_collision=True,
|
||||||
|
)
|
||||||
|
|
||||||
|
tree = ET.ElementTree(mujoco_struct)
|
||||||
|
ET.indent(tree, space=" ", level=0)
|
||||||
|
|
||||||
|
tree.write(mjcf_path, encoding="utf-8", xml_declaration=True)
|
||||||
|
logger.info(f"Successfully converted {urdf_path} → {mjcf_path}")
|
||||||
|
|
||||||
|
|
||||||
|
class MeshtoUSDConverter(AssetConverterBase):
|
||||||
|
"""Convert Mesh file from URDF into USD format."""
|
||||||
|
|
||||||
|
DEFAULT_BIND_APIS = [
|
||||||
|
"MaterialBindingAPI",
|
||||||
|
"PhysicsMeshCollisionAPI",
|
||||||
|
"PhysicsCollisionAPI",
|
||||||
|
"PhysxCollisionAPI",
|
||||||
|
"PhysicsMassAPI",
|
||||||
|
"PhysicsRigidBodyAPI",
|
||||||
|
"PhysxRigidBodyAPI",
|
||||||
|
]
|
||||||
|
|
||||||
|
def __init__(
|
||||||
|
self,
|
||||||
|
force_usd_conversion: bool = True,
|
||||||
|
make_instanceable: bool = False,
|
||||||
|
simulation_app=None,
|
||||||
|
**kwargs,
|
||||||
|
):
|
||||||
|
self.usd_parms = dict(
|
||||||
|
force_usd_conversion=force_usd_conversion,
|
||||||
|
make_instanceable=make_instanceable,
|
||||||
|
**kwargs,
|
||||||
|
)
|
||||||
|
if simulation_app is not None:
|
||||||
|
self.simulation_app = simulation_app
|
||||||
|
|
||||||
|
def __enter__(self):
|
||||||
|
from isaaclab.app import AppLauncher
|
||||||
|
|
||||||
|
if not hasattr(self, "simulation_app"):
|
||||||
|
launch_args = dict(
|
||||||
|
headless=True,
|
||||||
|
no_splash=True,
|
||||||
|
fast_shutdown=True,
|
||||||
|
disable_gpu=True,
|
||||||
|
)
|
||||||
|
self.app_launcher = AppLauncher(launch_args)
|
||||||
|
self.simulation_app = self.app_launcher.app
|
||||||
|
|
||||||
|
return self
|
||||||
|
|
||||||
|
def __exit__(self, exc_type, exc_val, exc_tb):
|
||||||
|
# Close the simulation app if it was created here
|
||||||
|
if hasattr(self, "app_launcher"):
|
||||||
|
self.simulation_app.close()
|
||||||
|
|
||||||
|
if exc_val is not None:
|
||||||
|
logger.error(f"Exception occurred: {exc_val}.")
|
||||||
|
|
||||||
|
return False
|
||||||
|
|
||||||
|
def convert(self, urdf_path: str, output_file: str):
|
||||||
|
"""Convert a URDF file to USD and post-process collision meshes."""
|
||||||
|
from isaaclab.sim.converters import MeshConverter, MeshConverterCfg
|
||||||
|
from pxr import PhysxSchema, Sdf, Usd, UsdShade
|
||||||
|
|
||||||
|
tree = ET.parse(urdf_path)
|
||||||
|
root = tree.getroot()
|
||||||
|
mesh_file = root.find("link/visual/geometry/mesh").get("filename")
|
||||||
|
input_mesh = os.path.join(os.path.dirname(urdf_path), mesh_file)
|
||||||
|
output_dir = os.path.abspath(os.path.dirname(output_file))
|
||||||
|
output_mesh = f"{output_dir}/mesh/{os.path.basename(mesh_file)}"
|
||||||
|
mesh_origin = root.find("link/visual/origin")
|
||||||
|
if mesh_origin is not None:
|
||||||
|
self.transform_mesh(input_mesh, output_mesh, mesh_origin)
|
||||||
|
|
||||||
|
cfg = MeshConverterCfg(
|
||||||
|
asset_path=output_mesh,
|
||||||
|
usd_dir=output_dir,
|
||||||
|
usd_file_name=os.path.basename(output_file),
|
||||||
|
**self.usd_parms,
|
||||||
|
)
|
||||||
|
urdf_converter = MeshConverter(cfg)
|
||||||
|
usd_path = urdf_converter.usd_path
|
||||||
|
|
||||||
|
stage = Usd.Stage.Open(usd_path)
|
||||||
|
layer = stage.GetRootLayer()
|
||||||
|
with Usd.EditContext(stage, layer):
|
||||||
|
for prim in stage.Traverse():
|
||||||
|
# Change texture path to relative path.
|
||||||
|
if prim.GetName() == "material_0":
|
||||||
|
shader = UsdShade.Shader(prim).GetInput("diffuse_texture")
|
||||||
|
if shader.Get() is not None:
|
||||||
|
relative_path = shader.Get().path.replace(
|
||||||
|
f"{output_dir}/", ""
|
||||||
|
)
|
||||||
|
shader.Set(Sdf.AssetPath(relative_path))
|
||||||
|
|
||||||
|
# Add convex decomposition collision and set ShrinkWrap.
|
||||||
|
elif prim.GetName() == "mesh":
|
||||||
|
approx_attr = prim.GetAttribute("physics:approximation")
|
||||||
|
if not approx_attr:
|
||||||
|
approx_attr = prim.CreateAttribute(
|
||||||
|
"physics:approximation", Sdf.ValueTypeNames.Token
|
||||||
|
)
|
||||||
|
approx_attr.Set("convexDecomposition")
|
||||||
|
|
||||||
|
physx_conv_api = (
|
||||||
|
PhysxSchema.PhysxConvexDecompositionCollisionAPI.Apply(
|
||||||
|
prim
|
||||||
|
)
|
||||||
|
)
|
||||||
|
physx_conv_api.GetShrinkWrapAttr().Set(True)
|
||||||
|
|
||||||
|
api_schemas = prim.GetMetadata("apiSchemas")
|
||||||
|
if api_schemas is None:
|
||||||
|
api_schemas = Sdf.TokenListOp()
|
||||||
|
|
||||||
|
api_list = list(api_schemas.GetAddedOrExplicitItems())
|
||||||
|
for api in self.DEFAULT_BIND_APIS:
|
||||||
|
if api not in api_list:
|
||||||
|
api_list.append(api)
|
||||||
|
|
||||||
|
api_schemas.appendedItems = api_list
|
||||||
|
prim.SetMetadata("apiSchemas", api_schemas)
|
||||||
|
|
||||||
|
layer.Save()
|
||||||
|
logger.info(f"Successfully converted {urdf_path} → {usd_path}")
|
||||||
|
|
||||||
|
|
||||||
|
class URDFtoUSDConverter(MeshtoUSDConverter):
|
||||||
|
"""Convert URDF files into USD format.
|
||||||
|
|
||||||
|
Args:
|
||||||
|
fix_base (bool): Whether to fix the base link.
|
||||||
|
merge_fixed_joints (bool): Whether to merge fixed joints.
|
||||||
|
make_instanceable (bool): Whether to make prims instanceable.
|
||||||
|
force_usd_conversion (bool): Force conversion to USD.
|
||||||
|
collision_from_visuals (bool): Generate collisions from visuals if not provided.
|
||||||
|
"""
|
||||||
|
|
||||||
|
def __init__(
|
||||||
|
self,
|
||||||
|
fix_base: bool = False,
|
||||||
|
merge_fixed_joints: bool = False,
|
||||||
|
make_instanceable: bool = True,
|
||||||
|
force_usd_conversion: bool = True,
|
||||||
|
collision_from_visuals: bool = True,
|
||||||
|
joint_drive=None,
|
||||||
|
rotate_wxyz: tuple[float] | None = None,
|
||||||
|
simulation_app=None,
|
||||||
|
**kwargs,
|
||||||
|
):
|
||||||
|
self.usd_parms = dict(
|
||||||
|
fix_base=fix_base,
|
||||||
|
merge_fixed_joints=merge_fixed_joints,
|
||||||
|
make_instanceable=make_instanceable,
|
||||||
|
force_usd_conversion=force_usd_conversion,
|
||||||
|
collision_from_visuals=collision_from_visuals,
|
||||||
|
joint_drive=joint_drive,
|
||||||
|
**kwargs,
|
||||||
|
)
|
||||||
|
self.rotate_wxyz = rotate_wxyz
|
||||||
|
if simulation_app is not None:
|
||||||
|
self.simulation_app = simulation_app
|
||||||
|
|
||||||
|
def convert(self, urdf_path: str, output_file: str):
|
||||||
|
"""Convert a URDF file to USD and post-process collision meshes."""
|
||||||
|
from isaaclab.sim.converters import UrdfConverter, UrdfConverterCfg
|
||||||
|
from pxr import Gf, PhysxSchema, Sdf, Usd, UsdGeom
|
||||||
|
|
||||||
|
cfg = UrdfConverterCfg(
|
||||||
|
asset_path=urdf_path,
|
||||||
|
usd_dir=os.path.abspath(os.path.dirname(output_file)),
|
||||||
|
usd_file_name=os.path.basename(output_file),
|
||||||
|
**self.usd_parms,
|
||||||
|
)
|
||||||
|
|
||||||
|
urdf_converter = UrdfConverter(cfg)
|
||||||
|
usd_path = urdf_converter.usd_path
|
||||||
|
|
||||||
|
stage = Usd.Stage.Open(usd_path)
|
||||||
|
layer = stage.GetRootLayer()
|
||||||
|
with Usd.EditContext(stage, layer):
|
||||||
|
for prim in stage.Traverse():
|
||||||
|
if prim.GetName() == "collisions":
|
||||||
|
approx_attr = prim.GetAttribute("physics:approximation")
|
||||||
|
if not approx_attr:
|
||||||
|
approx_attr = prim.CreateAttribute(
|
||||||
|
"physics:approximation", Sdf.ValueTypeNames.Token
|
||||||
|
)
|
||||||
|
approx_attr.Set("convexDecomposition")
|
||||||
|
|
||||||
|
physx_conv_api = (
|
||||||
|
PhysxSchema.PhysxConvexDecompositionCollisionAPI.Apply(
|
||||||
|
prim
|
||||||
|
)
|
||||||
|
)
|
||||||
|
physx_conv_api.GetShrinkWrapAttr().Set(True)
|
||||||
|
|
||||||
|
api_schemas = prim.GetMetadata("apiSchemas")
|
||||||
|
if api_schemas is None:
|
||||||
|
api_schemas = Sdf.TokenListOp()
|
||||||
|
|
||||||
|
api_list = list(api_schemas.GetAddedOrExplicitItems())
|
||||||
|
for api in self.DEFAULT_BIND_APIS:
|
||||||
|
if api not in api_list:
|
||||||
|
api_list.append(api)
|
||||||
|
|
||||||
|
api_schemas.appendedItems = api_list
|
||||||
|
prim.SetMetadata("apiSchemas", api_schemas)
|
||||||
|
|
||||||
|
if self.rotate_wxyz is not None:
|
||||||
|
inner_prim = next(
|
||||||
|
p
|
||||||
|
for p in stage.GetDefaultPrim().GetChildren()
|
||||||
|
if p.IsA(UsdGeom.Xform)
|
||||||
|
)
|
||||||
|
xformable = UsdGeom.Xformable(inner_prim)
|
||||||
|
xformable.ClearXformOpOrder()
|
||||||
|
orient_op = xformable.AddOrientOp(UsdGeom.XformOp.PrecisionDouble)
|
||||||
|
orient_op.Set(Gf.Quatd(*self.rotate_wxyz))
|
||||||
|
|
||||||
|
layer.Save()
|
||||||
|
logger.info(f"Successfully converted {urdf_path} → {usd_path}")
|
||||||
|
|
||||||
|
|
||||||
|
class AssetConverterFactory:
|
||||||
|
"""Factory class for creating asset converters based on target and source types."""
|
||||||
|
|
||||||
|
@staticmethod
|
||||||
|
def create(
|
||||||
|
target_type: AssetType, source_type: AssetType = "urdf", **kwargs
|
||||||
|
) -> AssetConverterBase:
|
||||||
|
"""Create an asset converter instance based on target and source types."""
|
||||||
|
if target_type == AssetType.MJCF and source_type == AssetType.URDF:
|
||||||
|
converter = MeshtoMJCFConverter(**kwargs)
|
||||||
|
elif target_type == AssetType.USD and source_type == AssetType.URDF:
|
||||||
|
converter = URDFtoUSDConverter(**kwargs)
|
||||||
|
elif target_type == AssetType.USD and source_type == AssetType.MESH:
|
||||||
|
converter = MeshtoUSDConverter(**kwargs)
|
||||||
|
else:
|
||||||
|
raise ValueError(
|
||||||
|
f"Unsupported converter type: {source_type} -> {target_type}."
|
||||||
|
)
|
||||||
|
|
||||||
|
return converter
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == "__main__":
|
||||||
|
# target_asset_type = AssetType.MJCF
|
||||||
|
target_asset_type = AssetType.USD
|
||||||
|
|
||||||
|
urdf_paths = [
|
||||||
|
"outputs/embodiedgen_assets/demo_assets/remote_control/result/remote_control.urdf",
|
||||||
|
]
|
||||||
|
|
||||||
|
if target_asset_type == AssetType.MJCF:
|
||||||
|
output_files = [
|
||||||
|
"outputs/embodiedgen_assets/demo_assets/remote_control/mjcf/remote_control.mjcf",
|
||||||
|
]
|
||||||
|
asset_converter = AssetConverterFactory.create(
|
||||||
|
target_type=AssetType.MJCF,
|
||||||
|
source_type=AssetType.URDF,
|
||||||
|
)
|
||||||
|
|
||||||
|
elif target_asset_type == AssetType.USD:
|
||||||
|
output_files = [
|
||||||
|
"outputs/embodiedgen_assets/demo_assets/remote_control/usd/remote_control.usd",
|
||||||
|
]
|
||||||
|
asset_converter = AssetConverterFactory.create(
|
||||||
|
target_type=AssetType.USD,
|
||||||
|
source_type=AssetType.MESH,
|
||||||
|
)
|
||||||
|
|
||||||
|
with asset_converter:
|
||||||
|
for urdf_path, output_file in zip(urdf_paths, output_files):
|
||||||
|
asset_converter.convert(urdf_path, output_file)
|
||||||
|
|
||||||
|
# urdf_path = "outputs/embodiedgen_assets/demo_assets/remote_control/result/remote_control.urdf"
|
||||||
|
# output_file = "outputs/embodiedgen_assets/demo_assets/remote_control/usd/remote_control.usd"
|
||||||
|
|
||||||
|
# asset_converter = AssetConverterFactory.create(
|
||||||
|
# target_type=AssetType.USD,
|
||||||
|
# source_type=AssetType.URDF,
|
||||||
|
# rotate_wxyz=(0.7071, 0.7071, 0, 0), # rotate 90 deg around the X-axis
|
||||||
|
# )
|
||||||
|
|
||||||
|
# with asset_converter:
|
||||||
|
# asset_converter.convert(urdf_path, output_file)
|
||||||
@ -625,7 +625,7 @@ def parse_args():
|
|||||||
action="store_true",
|
action="store_true",
|
||||||
help="Disable saving delight image",
|
help="Disable saving delight image",
|
||||||
)
|
)
|
||||||
|
parser.add_argument("--n_max_faces", type=int, default=30000)
|
||||||
args, unknown = parser.parse_known_args()
|
args, unknown = parser.parse_known_args()
|
||||||
|
|
||||||
return args
|
return args
|
||||||
@ -687,6 +687,14 @@ def entrypoint(
|
|||||||
num_views=1000,
|
num_views=1000,
|
||||||
norm_mesh_ratio=0.5,
|
norm_mesh_ratio=0.5,
|
||||||
)
|
)
|
||||||
|
if len(mesh.faces) > args.n_max_faces:
|
||||||
|
mesh.vertices, mesh.faces = mesh_fixer(
|
||||||
|
filter_ratio=0.8,
|
||||||
|
max_hole_size=0.04,
|
||||||
|
resolution=1024,
|
||||||
|
num_views=1000,
|
||||||
|
norm_mesh_ratio=0.5,
|
||||||
|
)
|
||||||
# Restore scale.
|
# Restore scale.
|
||||||
mesh.vertices = mesh.vertices / scale
|
mesh.vertices = mesh.vertices / scale
|
||||||
mesh.vertices = mesh.vertices + center
|
mesh.vertices = mesh.vertices + center
|
||||||
|
|||||||
@ -196,7 +196,6 @@ class PickEmbodiedGen(BaseEnv):
|
|||||||
self.scene,
|
self.scene,
|
||||||
self.layouts[env_idx],
|
self.layouts[env_idx],
|
||||||
z_offset=self.objs_z_offset,
|
z_offset=self.objs_z_offset,
|
||||||
init_quat=self.init_quat,
|
|
||||||
env_idx=env_idx,
|
env_idx=env_idx,
|
||||||
)
|
)
|
||||||
self.env_actors[f"env{env_idx}"] = env_actors
|
self.env_actors[f"env{env_idx}"] = env_actors
|
||||||
|
|||||||
@ -39,6 +39,8 @@ __all__ = [
|
|||||||
"GaussianOperator",
|
"GaussianOperator",
|
||||||
]
|
]
|
||||||
|
|
||||||
|
SH_C0 = 0.2820947917738781
|
||||||
|
|
||||||
|
|
||||||
@dataclass
|
@dataclass
|
||||||
class RenderResult:
|
class RenderResult:
|
||||||
@ -210,9 +212,7 @@ class GaussianBase:
|
|||||||
device=device,
|
device=device,
|
||||||
)
|
)
|
||||||
|
|
||||||
def save_to_ply(
|
def save_to_ply(self, path: str, enable_mask: bool = False) -> None:
|
||||||
self, path: str, colors: torch.Tensor = None, enable_mask: bool = False
|
|
||||||
):
|
|
||||||
os.makedirs(os.path.dirname(path), exist_ok=True)
|
os.makedirs(os.path.dirname(path), exist_ok=True)
|
||||||
numpy_data = self.get_numpy_data()
|
numpy_data = self.get_numpy_data()
|
||||||
means = numpy_data["_means"]
|
means = numpy_data["_means"]
|
||||||
@ -249,7 +249,6 @@ class GaussianBase:
|
|||||||
shN = shN[~invalid_mask]
|
shN = shN[~invalid_mask]
|
||||||
|
|
||||||
num_points = means.shape[0]
|
num_points = means.shape[0]
|
||||||
|
|
||||||
with open(path, "wb") as f:
|
with open(path, "wb") as f:
|
||||||
# Write PLY header
|
# Write PLY header
|
||||||
f.write(b"ply\n")
|
f.write(b"ply\n")
|
||||||
@ -258,18 +257,11 @@ class GaussianBase:
|
|||||||
f.write(b"property float x\n")
|
f.write(b"property float x\n")
|
||||||
f.write(b"property float y\n")
|
f.write(b"property float y\n")
|
||||||
f.write(b"property float z\n")
|
f.write(b"property float z\n")
|
||||||
f.write(b"property float nx\n")
|
|
||||||
f.write(b"property float ny\n")
|
|
||||||
f.write(b"property float nz\n")
|
|
||||||
|
|
||||||
if colors is not None:
|
for i, data in enumerate([sh0, shN]):
|
||||||
for j in range(colors.shape[1]):
|
prefix = "f_dc" if i == 0 else "f_rest"
|
||||||
f.write(f"property float f_dc_{j}\n".encode())
|
for j in range(data.shape[1]):
|
||||||
else:
|
f.write(f"property float {prefix}_{j}\n".encode())
|
||||||
for i, data in enumerate([sh0, shN]):
|
|
||||||
prefix = "f_dc" if i == 0 else "f_rest"
|
|
||||||
for j in range(data.shape[1]):
|
|
||||||
f.write(f"property float {prefix}_{j}\n".encode())
|
|
||||||
|
|
||||||
f.write(b"property float opacity\n")
|
f.write(b"property float opacity\n")
|
||||||
|
|
||||||
@ -283,24 +275,19 @@ class GaussianBase:
|
|||||||
# Write vertex data
|
# Write vertex data
|
||||||
for i in range(num_points):
|
for i in range(num_points):
|
||||||
f.write(struct.pack("<fff", *means[i])) # x, y, z
|
f.write(struct.pack("<fff", *means[i])) # x, y, z
|
||||||
f.write(struct.pack("<fff", 0, 0, 0)) # nx, ny, nz (zeros)
|
|
||||||
|
|
||||||
if colors is not None:
|
for data in [sh0, shN]:
|
||||||
color = colors.detach().cpu().numpy()
|
for j in range(data.shape[1]):
|
||||||
for j in range(color.shape[1]):
|
f.write(struct.pack("<f", data[i, j]))
|
||||||
f_dc = (color[i, j] - 0.5) / 0.2820947917738781
|
|
||||||
f.write(struct.pack("<f", f_dc))
|
|
||||||
else:
|
|
||||||
for data in [sh0, shN]:
|
|
||||||
for j in range(data.shape[1]):
|
|
||||||
f.write(struct.pack("<f", data[i, j]))
|
|
||||||
|
|
||||||
f.write(struct.pack("<f", opacities[i])) # opacity
|
f.write(struct.pack("<f", opacities[i].item())) # opacity
|
||||||
|
|
||||||
for data in [scales, quats]:
|
for data in [scales, quats]:
|
||||||
for j in range(data.shape[1]):
|
for j in range(data.shape[1]):
|
||||||
f.write(struct.pack("<f", data[i, j]))
|
f.write(struct.pack("<f", data[i, j]))
|
||||||
|
|
||||||
|
return
|
||||||
|
|
||||||
|
|
||||||
@dataclass
|
@dataclass
|
||||||
class GaussianOperator(GaussianBase):
|
class GaussianOperator(GaussianBase):
|
||||||
@ -508,8 +495,8 @@ class GaussianOperator(GaussianBase):
|
|||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
input_gs = "outputs/test/debug.ply"
|
input_gs = "outputs/layouts_gens_demo/task_0000/background/gs_model.ply"
|
||||||
output_gs = "./debug_v3.ply"
|
output_gs = "./gs_model.ply"
|
||||||
gs_model: GaussianOperator = GaussianOperator.load_from_ply(input_gs)
|
gs_model: GaussianOperator = GaussianOperator.load_from_ply(input_gs)
|
||||||
|
|
||||||
# 绕 x 轴旋转 180°
|
# 绕 x 轴旋转 180°
|
||||||
|
|||||||
@ -60,7 +60,7 @@ def entrypoint(**kwargs):
|
|||||||
sim_cli(
|
sim_cli(
|
||||||
layout_path=out_layout_path,
|
layout_path=out_layout_path,
|
||||||
output_dir=output_dir,
|
output_dir=output_dir,
|
||||||
robot_name="franka" if args.insert_robot else None,
|
insert_robot=args.insert_robot,
|
||||||
)
|
)
|
||||||
|
|
||||||
logger.info(f"Layout placement completed in {output_dir}")
|
logger.info(f"Layout placement completed in {output_dir}")
|
||||||
|
|||||||
@ -76,7 +76,7 @@ class ParallelSimConfig:
|
|||||||
default_factory=lambda: [0.0, 0.0, 0.9]
|
default_factory=lambda: [0.0, 0.0, 0.9]
|
||||||
)
|
)
|
||||||
"""Camera target(look-at) point [x, y, z] in global coordiante system"""
|
"""Camera target(look-at) point [x, y, z] in global coordiante system"""
|
||||||
image_hw: list[int] = field(default_factory=lambda: [512, 512])
|
image_hw: list[int] = field(default_factory=lambda: [256, 256])
|
||||||
"""Rendered image height and width [height, width]"""
|
"""Rendered image height and width [height, width]"""
|
||||||
fovy_deg: float = 75
|
fovy_deg: float = 75
|
||||||
"""Camera vertical field of view in degrees"""
|
"""Camera vertical field of view in degrees"""
|
||||||
|
|||||||
@ -97,7 +97,6 @@ def entrypoint(**kwargs):
|
|||||||
scene_manager.scene,
|
scene_manager.scene,
|
||||||
cfg.layout_path,
|
cfg.layout_path,
|
||||||
cfg.z_offset,
|
cfg.z_offset,
|
||||||
cfg.init_quat,
|
|
||||||
)
|
)
|
||||||
agent = load_mani_skill_robot(
|
agent = load_mani_skill_robot(
|
||||||
scene_manager.scene, cfg.layout_path, cfg.control_freq
|
scene_manager.scene, cfg.layout_path, cfg.control_freq
|
||||||
|
|||||||
@ -285,10 +285,9 @@ def bfs_placement(
|
|||||||
# For manipulated and distractor objects, apply random rotation
|
# For manipulated and distractor objects, apply random rotation
|
||||||
angle_rad = np.random.uniform(0, 2 * np.pi)
|
angle_rad = np.random.uniform(0, 2 * np.pi)
|
||||||
object_quat = compute_axis_rotation_quat(
|
object_quat = compute_axis_rotation_quat(
|
||||||
axis="y", angle_rad=angle_rad
|
axis="z", angle_rad=angle_rad
|
||||||
)
|
)
|
||||||
object_quat_scipy = np.roll(object_quat, 1) # [w, x, y, z]
|
rotation = R.from_quat(object_quat).as_matrix()
|
||||||
rotation = R.from_quat(object_quat_scipy).as_matrix()
|
|
||||||
vertices = np.dot(mesh.vertices, rotation.T)
|
vertices = np.dot(mesh.vertices, rotation.T)
|
||||||
z1 = np.percentile(vertices[:, 1], 1)
|
z1 = np.percentile(vertices[:, 1], 1)
|
||||||
z2 = np.percentile(vertices[:, 1], 99)
|
z2 = np.percentile(vertices[:, 1], 99)
|
||||||
|
|||||||
@ -15,7 +15,6 @@
|
|||||||
# permissions and limitations under the License.
|
# permissions and limitations under the License.
|
||||||
|
|
||||||
import json
|
import json
|
||||||
import logging
|
|
||||||
import os
|
import os
|
||||||
import xml.etree.ElementTree as ET
|
import xml.etree.ElementTree as ET
|
||||||
from collections import defaultdict
|
from collections import defaultdict
|
||||||
@ -62,32 +61,48 @@ __all__ = [
|
|||||||
|
|
||||||
|
|
||||||
def load_actor_from_urdf(
|
def load_actor_from_urdf(
|
||||||
scene: ManiSkillScene | sapien.Scene,
|
scene: sapien.Scene | ManiSkillScene,
|
||||||
file_path: str,
|
file_path: str,
|
||||||
pose: sapien.Pose,
|
pose: sapien.Pose | None = None,
|
||||||
env_idx: int = None,
|
env_idx: int = None,
|
||||||
use_static: bool = False,
|
use_static: bool = False,
|
||||||
update_mass: bool = False,
|
update_mass: bool = False,
|
||||||
|
scale: float | np.ndarray = 1.0,
|
||||||
) -> sapien.pysapien.Entity:
|
) -> sapien.pysapien.Entity:
|
||||||
|
def _get_local_pose(origin_tag: ET.Element | None) -> sapien.Pose:
|
||||||
|
local_pose = sapien.Pose(p=[0, 0, 0], q=[1, 0, 0, 0])
|
||||||
|
if origin_tag is not None:
|
||||||
|
xyz = list(map(float, origin_tag.get("xyz", "0 0 0").split()))
|
||||||
|
rpy = list(map(float, origin_tag.get("rpy", "0 0 0").split()))
|
||||||
|
qx, qy, qz, qw = R.from_euler("xyz", rpy, degrees=False).as_quat()
|
||||||
|
local_pose = sapien.Pose(p=xyz, q=[qw, qx, qy, qz])
|
||||||
|
|
||||||
|
return local_pose
|
||||||
|
|
||||||
tree = ET.parse(file_path)
|
tree = ET.parse(file_path)
|
||||||
root = tree.getroot()
|
root = tree.getroot()
|
||||||
node_name = root.get("name")
|
node_name = root.get("name")
|
||||||
file_dir = os.path.dirname(file_path)
|
file_dir = os.path.dirname(file_path)
|
||||||
|
|
||||||
visual_mesh = root.find('.//visual/geometry/mesh')
|
visual_mesh = root.find(".//visual/geometry/mesh")
|
||||||
visual_file = visual_mesh.get("filename")
|
visual_file = visual_mesh.get("filename")
|
||||||
visual_scale = visual_mesh.get("scale", "1.0 1.0 1.0")
|
visual_scale = visual_mesh.get("scale", "1.0 1.0 1.0")
|
||||||
visual_scale = np.array([float(x) for x in visual_scale.split()])
|
visual_scale = np.array([float(x) for x in visual_scale.split()])
|
||||||
|
visual_scale *= np.array(scale)
|
||||||
|
|
||||||
collision_mesh = root.find('.//collision/geometry/mesh')
|
collision_mesh = root.find(".//collision/geometry/mesh")
|
||||||
collision_file = collision_mesh.get("filename")
|
collision_file = collision_mesh.get("filename")
|
||||||
collision_scale = collision_mesh.get("scale", "1.0 1.0 1.0")
|
collision_scale = collision_mesh.get("scale", "1.0 1.0 1.0")
|
||||||
collision_scale = np.array([float(x) for x in collision_scale.split()])
|
collision_scale = np.array([float(x) for x in collision_scale.split()])
|
||||||
|
collision_scale *= np.array(scale)
|
||||||
|
|
||||||
|
visual_pose = _get_local_pose(root.find(".//visual/origin"))
|
||||||
|
collision_pose = _get_local_pose(root.find(".//collision/origin"))
|
||||||
|
|
||||||
visual_file = os.path.join(file_dir, visual_file)
|
visual_file = os.path.join(file_dir, visual_file)
|
||||||
collision_file = os.path.join(file_dir, collision_file)
|
collision_file = os.path.join(file_dir, collision_file)
|
||||||
static_fric = root.find('.//collision/gazebo/mu1').text
|
static_fric = root.find(".//collision/gazebo/mu1").text
|
||||||
dynamic_fric = root.find('.//collision/gazebo/mu2').text
|
dynamic_fric = root.find(".//collision/gazebo/mu2").text
|
||||||
|
|
||||||
material = physx.PhysxMaterial(
|
material = physx.PhysxMaterial(
|
||||||
static_friction=np.clip(float(static_fric), 0.1, 0.7),
|
static_friction=np.clip(float(static_fric), 0.1, 0.7),
|
||||||
@ -106,17 +121,27 @@ def load_actor_from_urdf(
|
|||||||
# decomposition_params=dict(
|
# decomposition_params=dict(
|
||||||
# threshold=0.05, max_convex_hull=64, verbose=False
|
# threshold=0.05, max_convex_hull=64, verbose=False
|
||||||
# ),
|
# ),
|
||||||
|
pose=collision_pose,
|
||||||
)
|
)
|
||||||
|
|
||||||
builder.add_visual_from_file(visual_file, scale=visual_scale)
|
builder.add_visual_from_file(
|
||||||
|
visual_file,
|
||||||
|
scale=visual_scale,
|
||||||
|
pose=visual_pose,
|
||||||
|
)
|
||||||
|
if pose is None:
|
||||||
|
pose = sapien.Pose(p=[0, 0, 0], q=[1, 0, 0, 0])
|
||||||
|
|
||||||
builder.set_initial_pose(pose)
|
builder.set_initial_pose(pose)
|
||||||
if isinstance(scene, ManiSkillScene) and env_idx is not None:
|
if isinstance(scene, ManiSkillScene) and env_idx is not None:
|
||||||
builder.set_scene_idxs([env_idx])
|
builder.set_scene_idxs([env_idx])
|
||||||
|
|
||||||
actor = builder.build(name=f"{node_name}-{env_idx}")
|
actor = builder.build(
|
||||||
|
name=node_name if env_idx is None else f"{node_name}-{env_idx}"
|
||||||
|
)
|
||||||
|
|
||||||
if update_mass and hasattr(actor.components[1], "mass"):
|
if update_mass and hasattr(actor.components[1], "mass"):
|
||||||
node_mass = float(root.find('.//inertial/mass').get("value"))
|
node_mass = float(root.find(".//inertial/mass").get("value"))
|
||||||
actor.components[1].set_mass(node_mass)
|
actor.components[1].set_mass(node_mass)
|
||||||
|
|
||||||
return actor
|
return actor
|
||||||
|
|||||||
@ -1 +1 @@
|
|||||||
VERSION = "v0.1.4"
|
VERSION = "v0.1.5"
|
||||||
|
|||||||
@ -24,6 +24,7 @@ from xml.dom.minidom import parseString
|
|||||||
|
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import trimesh
|
import trimesh
|
||||||
|
from scipy.spatial.transform import Rotation
|
||||||
from embodied_gen.data.convex_decomposer import decompose_convex_mesh
|
from embodied_gen.data.convex_decomposer import decompose_convex_mesh
|
||||||
from embodied_gen.utils.gpt_clients import GPT_CLIENT, GPTclient
|
from embodied_gen.utils.gpt_clients import GPT_CLIENT, GPTclient
|
||||||
from embodied_gen.utils.process_media import render_asset3d
|
from embodied_gen.utils.process_media import render_asset3d
|
||||||
@ -40,11 +41,13 @@ URDF_TEMPLATE = """
|
|||||||
<robot name="template_robot">
|
<robot name="template_robot">
|
||||||
<link name="template_link">
|
<link name="template_link">
|
||||||
<visual>
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="mesh.obj" scale="1.0 1.0 1.0"/>
|
<mesh filename="mesh.obj" scale="1.0 1.0 1.0"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="mesh.obj" scale="1.0 1.0 1.0"/>
|
<mesh filename="mesh.obj" scale="1.0 1.0 1.0"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
@ -86,6 +89,7 @@ class URDFGenerator(object):
|
|||||||
render_dir: str = "urdf_renders",
|
render_dir: str = "urdf_renders",
|
||||||
render_view_num: int = 4,
|
render_view_num: int = 4,
|
||||||
decompose_convex: bool = False,
|
decompose_convex: bool = False,
|
||||||
|
rotate_xyzw: list[float] = (0.7071, 0, 0, 0.7071),
|
||||||
) -> None:
|
) -> None:
|
||||||
if mesh_file_list is None:
|
if mesh_file_list is None:
|
||||||
mesh_file_list = []
|
mesh_file_list = []
|
||||||
@ -160,6 +164,8 @@ class URDFGenerator(object):
|
|||||||
]
|
]
|
||||||
self.attrs_name = attrs_name
|
self.attrs_name = attrs_name
|
||||||
self.decompose_convex = decompose_convex
|
self.decompose_convex = decompose_convex
|
||||||
|
# Rotate 90 degrees around the X-axis from blender to align with simulators.
|
||||||
|
self.rotate_xyzw = rotate_xyzw
|
||||||
|
|
||||||
def parse_response(self, response: str) -> dict[str, any]:
|
def parse_response(self, response: str) -> dict[str, any]:
|
||||||
lines = response.split("\n")
|
lines = response.split("\n")
|
||||||
@ -251,6 +257,14 @@ class URDFGenerator(object):
|
|||||||
raise ValueError("URDF template is missing 'link' element.")
|
raise ValueError("URDF template is missing 'link' element.")
|
||||||
link.set("name", output_name)
|
link.set("name", output_name)
|
||||||
|
|
||||||
|
if self.rotate_xyzw is not None:
|
||||||
|
rpy = Rotation.from_quat(self.rotate_xyzw).as_euler(
|
||||||
|
"xyz", degrees=False
|
||||||
|
)
|
||||||
|
rpy = [str(round(num, 4)) for num in rpy]
|
||||||
|
link.find("visual/origin").set("rpy", " ".join(rpy))
|
||||||
|
link.find("collision/origin").set("rpy", " ".join(rpy))
|
||||||
|
|
||||||
# Update visual geometry
|
# Update visual geometry
|
||||||
visual = link.find("visual/geometry/mesh")
|
visual = link.find("visual/geometry/mesh")
|
||||||
if visual is not None:
|
if visual is not None:
|
||||||
@ -273,7 +287,11 @@ class URDFGenerator(object):
|
|||||||
decompose_convex_mesh(
|
decompose_convex_mesh(
|
||||||
mesh_output_path, output_path, **d_params
|
mesh_output_path, output_path, **d_params
|
||||||
)
|
)
|
||||||
collision_mesh = f"{self.output_mesh_dir}/{filename}"
|
obj_filename = filename.replace(".ply", ".obj")
|
||||||
|
trimesh.load(output_path).export(
|
||||||
|
f"{mesh_folder}/{obj_filename}"
|
||||||
|
)
|
||||||
|
collision_mesh = f"{self.output_mesh_dir}/{obj_filename}"
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
logger.warning(
|
logger.warning(
|
||||||
f"Convex decomposition failed for {output_path}, {e}."
|
f"Convex decomposition failed for {output_path}, {e}."
|
||||||
@ -436,6 +454,7 @@ class URDFGenerator(object):
|
|||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
|
# Rotate 90 degrees around the X-axis to align with simulators.
|
||||||
urdf_gen = URDFGenerator(GPT_CLIENT, render_view_num=4)
|
urdf_gen = URDFGenerator(GPT_CLIENT, render_view_num=4)
|
||||||
urdf_path = urdf_gen(
|
urdf_path = urdf_gen(
|
||||||
mesh_path="outputs/layout2/asset3d/marker/result/mesh/marker.obj",
|
mesh_path="outputs/layout2/asset3d/marker/result/mesh/marker.obj",
|
||||||
|
|||||||
@ -26,4 +26,6 @@ if [[ "$STAGE" == "extra" || "$STAGE" == "all" ]]; then
|
|||||||
bash "$SCRIPT_DIR/install/install_extra.sh"
|
bash "$SCRIPT_DIR/install/install_extra.sh"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
pip install triton==2.1.0 numpy==1.26.4
|
||||||
|
|
||||||
log_info "===== Installation completed successfully. ====="
|
log_info "===== Installation completed successfully. ====="
|
||||||
|
|||||||
@ -5,10 +5,10 @@ source "$SCRIPT_DIR/_utils.sh"
|
|||||||
|
|
||||||
PIP_INSTALL_PACKAGES=(
|
PIP_INSTALL_PACKAGES=(
|
||||||
"pip==22.3.1"
|
"pip==22.3.1"
|
||||||
"torch==2.4.0+cu118 torchvision==0.19.0+cu118 --index-url https://download.pytorch.org/whl/cu118"
|
"torch==2.4.0 torchvision==0.19.0 --index-url https://download.pytorch.org/whl/cu118"
|
||||||
"xformers==0.0.27.post2 --index-url https://download.pytorch.org/whl/cu118"
|
"xformers==0.0.27.post2 --index-url https://download.pytorch.org/whl/cu118"
|
||||||
"flash-attn==2.7.0.post2 --no-build-isolation"
|
|
||||||
"-r requirements.txt --use-deprecated=legacy-resolver"
|
"-r requirements.txt --use-deprecated=legacy-resolver"
|
||||||
|
"flash-attn==2.7.0.post2"
|
||||||
"utils3d@git+https://github.com/EasternJournalist/utils3d.git@9a4eb15"
|
"utils3d@git+https://github.com/EasternJournalist/utils3d.git@9a4eb15"
|
||||||
"clip@git+https://github.com/openai/CLIP.git"
|
"clip@git+https://github.com/openai/CLIP.git"
|
||||||
"segment-anything@git+https://github.com/facebookresearch/segment-anything.git@dca509f"
|
"segment-anything@git+https://github.com/facebookresearch/segment-anything.git@dca509f"
|
||||||
@ -32,5 +32,5 @@ pip install "$TMP_DIR/submodules/diff-gaussian-rasterization"
|
|||||||
rm -rf "$TMP_DIR"
|
rm -rf "$TMP_DIR"
|
||||||
|
|
||||||
try_install "Installing EmbodiedGen..." \
|
try_install "Installing EmbodiedGen..." \
|
||||||
"pip install triton==2.1.0 --no-deps && pip install -e ." \
|
"pip install -e .[dev]" \
|
||||||
"EmbodiedGen installation failed."
|
"EmbodiedGen installation failed."
|
||||||
|
|||||||
@ -9,6 +9,7 @@ PYTHON_PACKAGES_NODEPS=(
|
|||||||
)
|
)
|
||||||
|
|
||||||
PYTHON_PACKAGES=(
|
PYTHON_PACKAGES=(
|
||||||
|
"ninja"
|
||||||
"fused-ssim@git+https://github.com/rahul-goel/fused-ssim#egg=328dc98"
|
"fused-ssim@git+https://github.com/rahul-goel/fused-ssim#egg=328dc98"
|
||||||
"git+https://github.com/NVlabs/tiny-cuda-nn/#subdirectory=bindings/torch"
|
"git+https://github.com/NVlabs/tiny-cuda-nn/#subdirectory=bindings/torch"
|
||||||
"git+https://github.com/facebookresearch/pytorch3d.git@stable"
|
"git+https://github.com/facebookresearch/pytorch3d.git@stable"
|
||||||
@ -19,8 +20,6 @@ PYTHON_PACKAGES=(
|
|||||||
"icecream"
|
"icecream"
|
||||||
"open3d"
|
"open3d"
|
||||||
"pyequilib"
|
"pyequilib"
|
||||||
"numpy==1.26.4"
|
|
||||||
"triton==2.1.0"
|
|
||||||
)
|
)
|
||||||
|
|
||||||
for pkg in "${PYTHON_PACKAGES_NODEPS[@]}"; do
|
for pkg in "${PYTHON_PACKAGES_NODEPS[@]}"; do
|
||||||
|
|||||||
@ -7,7 +7,7 @@ packages = ["embodied_gen"]
|
|||||||
|
|
||||||
[project]
|
[project]
|
||||||
name = "embodied_gen"
|
name = "embodied_gen"
|
||||||
version = "v0.1.4"
|
version = "v0.1.5"
|
||||||
readme = "README.md"
|
readme = "README.md"
|
||||||
license = "Apache-2.0"
|
license = "Apache-2.0"
|
||||||
license-files = ["LICENSE", "NOTICE"]
|
license-files = ["LICENSE", "NOTICE"]
|
||||||
|
|||||||
@ -41,3 +41,5 @@ sapien==3.0.0b1
|
|||||||
coacd
|
coacd
|
||||||
mani_skill==3.0.0b21
|
mani_skill==3.0.0b21
|
||||||
typing_extensions==4.14.1
|
typing_extensions==4.14.1
|
||||||
|
ninja
|
||||||
|
packaging
|
||||||
58
tests/test_examples/test_asset_converter.py
Normal file
58
tests/test_examples/test_asset_converter.py
Normal file
@ -0,0 +1,58 @@
|
|||||||
|
import pytest
|
||||||
|
from huggingface_hub import snapshot_download
|
||||||
|
from embodied_gen.data.asset_converter import AssetConverterFactory, AssetType
|
||||||
|
|
||||||
|
|
||||||
|
@pytest.fixture(scope="session")
|
||||||
|
def data_dir(tmp_path_factory):
|
||||||
|
data_dir = tmp_path_factory.mktemp("EmbodiedGenData")
|
||||||
|
snapshot_download(
|
||||||
|
repo_id="HorizonRobotics/EmbodiedGenData",
|
||||||
|
repo_type="dataset",
|
||||||
|
local_dir=str(data_dir),
|
||||||
|
allow_patterns="demo_assets/remote_control/*",
|
||||||
|
local_dir_use_symlinks=False,
|
||||||
|
)
|
||||||
|
return data_dir
|
||||||
|
|
||||||
|
|
||||||
|
def test_MeshtoMJCFConverter(data_dir):
|
||||||
|
urdf_path = (
|
||||||
|
data_dir / "demo_assets/remote_control/result/remote_control.urdf"
|
||||||
|
)
|
||||||
|
assert urdf_path.exists(), f"URDF not found: {urdf_path}"
|
||||||
|
|
||||||
|
output_file = (
|
||||||
|
data_dir / "demo_assets/remote_control/mjcf/remote_control.mjcf"
|
||||||
|
)
|
||||||
|
asset_converter = AssetConverterFactory.create(
|
||||||
|
target_type=AssetType.MJCF,
|
||||||
|
source_type=AssetType.URDF,
|
||||||
|
)
|
||||||
|
|
||||||
|
with asset_converter:
|
||||||
|
asset_converter.convert(str(urdf_path), str(output_file))
|
||||||
|
|
||||||
|
assert output_file.exists(), f"Output not generated: {output_file}"
|
||||||
|
assert output_file.stat().st_size > 0
|
||||||
|
|
||||||
|
|
||||||
|
def test_MeshtoUSDConverter(data_dir):
|
||||||
|
urdf_path = (
|
||||||
|
data_dir / "demo_assets/remote_control/result/remote_control.urdf"
|
||||||
|
)
|
||||||
|
assert urdf_path.exists(), f"URDF not found: {urdf_path}"
|
||||||
|
|
||||||
|
output_file = (
|
||||||
|
data_dir / "demo_assets/remote_control/usd/remote_control.usd"
|
||||||
|
)
|
||||||
|
asset_converter = AssetConverterFactory.create(
|
||||||
|
target_type=AssetType.USD,
|
||||||
|
source_type=AssetType.MESH,
|
||||||
|
)
|
||||||
|
|
||||||
|
with asset_converter:
|
||||||
|
asset_converter.convert(str(urdf_path), str(output_file))
|
||||||
|
|
||||||
|
assert output_file.exists(), f"Output not generated: {output_file}"
|
||||||
|
assert output_file.stat().st_size > 0
|
||||||
25
tests/test_integration/test_pipeline.sh
Normal file
25
tests/test_integration/test_pipeline.sh
Normal file
@ -0,0 +1,25 @@
|
|||||||
|
export CUDA_VISIBLE_DEVICES=2
|
||||||
|
source outputs/env.sh
|
||||||
|
|
||||||
|
output_dir="outputs/test_integration"
|
||||||
|
|
||||||
|
rm -rf ${output_dir}
|
||||||
|
|
||||||
|
text3d-cli --prompts "small bronze figurine of a lion" \
|
||||||
|
--n_image_retry 2 --n_asset_retry 2 --n_pipe_retry 1 --seed_img 0 \
|
||||||
|
--output_root ${output_dir}/textto3d
|
||||||
|
|
||||||
|
texture-cli --mesh_path "apps/assets/example_texture/meshes/robot_text.obj" \
|
||||||
|
--prompt "举着牌子的写实风格机器人,大眼睛,牌子上写着“Hello”的文字" \
|
||||||
|
--output_root "${output_dir}/texture_gen" \
|
||||||
|
--seed 0
|
||||||
|
|
||||||
|
scene3d-cli --prompts "Art studio with easel and canvas" \
|
||||||
|
--output_dir ${output_dir}/bg_scenes/ \
|
||||||
|
--seed 0 --gs3d.max_steps 4000 \
|
||||||
|
--disable_pano_check
|
||||||
|
|
||||||
|
layout-cli --task_descs "Place the pen in the mug on the desk" \
|
||||||
|
--bg_list "outputs/bg_scenes/scene_list.txt" \
|
||||||
|
--output_root "${output_dir}/layouts_gen" --insert_robot
|
||||||
|
|
||||||
Loading…
x
Reference in New Issue
Block a user