Skip to content

Commit

Permalink
Use defaults for saving MJCF.
Browse files Browse the repository at this point in the history
  • Loading branch information
kevinzakka committed Sep 25, 2022
1 parent 09c0e71 commit 86320e2
Show file tree
Hide file tree
Showing 3 changed files with 54 additions and 61 deletions.
15 changes: 6 additions & 9 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -44,11 +44,9 @@ bash install_vhacd.sh
## Usage

```bash
usage: obj2mjcf [-h] --obj-dir STR [--obj-filter STR] [--save-mtl] [--save-mjcf] [--compile-model] [--verbose] [--vhacd-args.enable]
[--vhacd-args.max-output-convex-hulls INT] [--vhacd-args.voxel-resolution INT] [--vhacd-args.volume-error-percent FLOAT]
[--vhacd-args.max-recursion-depth INT] [--vhacd-args.disable-shrink-wrap] [--vhacd-args.fill-mode {FLOOD,SURFACE,RAYCAST}]
[--vhacd-args.max-hull-vert-count INT] [--vhacd-args.disable-async] [--vhacd-args.min-edge-length INT] [--vhacd-args.split-hull]
[--texture-args.resize-percent FLOAT]
usage: obj2mjcf [-h] --obj-dir STR [--obj-filter STR] [--save-mtl] [--save-mjcf] [--compile-model] [--verbose] [--vhacd-args.enable] [--vhacd-args.max-output-convex-hulls INT] [--vhacd-args.voxel-resolution INT]
[--vhacd-args.volume-error-percent FLOAT] [--vhacd-args.max-recursion-depth INT] [--vhacd-args.disable-shrink-wrap] [--vhacd-args.fill-mode {FLOOD,SURFACE,RAYCAST}] [--vhacd-args.max-hull-vert-count INT]
[--vhacd-args.disable-async] [--vhacd-args.min-edge-length INT] [--vhacd-args.split-hull] [--texture-resize-percent FLOAT] [--overwrite] [--add-free-joint]

A CLI for processing composite Wavefront OBJ files into a MuJoCo-conducive format.

Expand All @@ -63,7 +61,10 @@ optional arguments:
--save-mjcf save an example XML (MJCF) file
--compile-model compile the MJCF file to check for errors
--verbose print verbose output
--texture-resize-percent FLOAT
resize the texture to this percentage of the original size (default: 1.0)
--overwrite overwrite previous run output
--add-free-joint add a free joint to the root body

optional vhacd_args arguments:
arguments to pass to V-HACD
Expand All @@ -89,10 +90,6 @@ optional vhacd_args arguments:
minimum size of a voxel edge (default: 2)
--vhacd-args.split-hull
try to find optimal split plane location

optional texture_args arguments:
--texture-args.resize-percent FLOAT
resize the texture to this percentage of the original size (default: 1.0)
```

[OBJ]: https://en.wikipedia.org/wiki/Wavefront_.obj_file
Expand Down
2 changes: 1 addition & 1 deletion obj2mjcf/__init__.py
Original file line number Diff line number Diff line change
@@ -1 +1 @@
__version__ = "0.0.20"
__version__ = "0.0.21"
98 changes: 47 additions & 51 deletions obj2mjcf/_cli.py
Original file line number Diff line number Diff line change
Expand Up @@ -81,12 +81,6 @@ class VhacdArgs:
"""try to find optimal split plane location"""


@dataclass(frozen=True)
class TextureArgs:
resize_percent: float = 1.0
"""resize the texture to this percentage of the original size"""


@dataclass(frozen=True)
class Args:
obj_dir: str
Expand All @@ -104,9 +98,12 @@ class Args:
"""print verbose output"""
vhacd_args: VhacdArgs = field(default_factory=VhacdArgs)
"""arguments to pass to V-HACD"""
texture_args: TextureArgs = field(default_factory=TextureArgs)
texture_resize_percent: float = 1.0
"""resize the texture to this percentage of the original size"""
overwrite: bool = False
"""overwrite previous run output"""
add_free_joint: bool = False
"""add a free joint to the root body"""


@dataclass
Expand Down Expand Up @@ -161,13 +158,13 @@ def mjcf_specular(self) -> str:
return f"{Ks}"


def resize_texture(filename: Path, texture_args: TextureArgs) -> None:
def resize_texture(filename: Path, resize_percent) -> None:
"""Resize a texture to a percentage of its original size."""
if texture_args.resize_percent == 1.0:
if resize_percent == 1.0:
return
image = Image.open(filename)
new_width = int(image.size[0] * texture_args.resize_percent)
new_height = int(image.size[1] * texture_args.resize_percent)
new_width = int(image.size[0] * resize_percent)
new_height = int(image.size[1] * resize_percent)
logging.info(f"Resizing {filename} to {new_width}x{new_height}")
image = image.resize((new_width, new_height), Image.LANCZOS)
image.save(filename)
Expand Down Expand Up @@ -330,7 +327,7 @@ def process_obj(filename: Path, args: Args) -> None:
image.save(dst_filename)
texture_name = dst_filename.name
mtl.map_Kd = texture_name
resize_texture(dst_filename, args.texture_args)
resize_texture(dst_filename, args.texture_resize_percent)
logging.info("Done processing MTL file")

logging.info("Processing OBJ file with trimesh")
Expand Down Expand Up @@ -393,9 +390,25 @@ def process_obj(filename: Path, args: Args) -> None:

# Build an MJCF.
root = etree.Element("mujoco", model=filename.stem)
asset_elem = etree.SubElement(root, "asset")

# Add visual and collision default classes.
default_elem = etree.SubElement(root, "default")
visual_default_elem = etree.SubElement(default_elem, "default")
visual_default_elem.attrib["class"] = "visual"
etree.SubElement(
visual_default_elem,
"geom",
group="2",
type="mesh",
contype="0",
conaffinity="0",
)
collision_default_elem = etree.SubElement(default_elem, "default")
collision_default_elem.attrib["class"] = "collision"
etree.SubElement(collision_default_elem, "geom", group="3", type="mesh")

# Add assets.
asset_elem = etree.SubElement(root, "asset")
for material in mtls:
if material.map_Kd is not None:
# Create the texture asset.
Expand Down Expand Up @@ -428,48 +441,37 @@ def process_obj(filename: Path, args: Args) -> None:

worldbody_elem = etree.SubElement(root, "worldbody")
obj_body = etree.SubElement(worldbody_elem, "body", name=filename.stem)

visual_kwargs = dict(type="mesh", contype="0", conaffinity="0", group="2")
collision_kwargs = dict(type="mesh", group="3")
if args.add_free_joint:
etree.SubElement(obj_body, "freejoint")

# Add visual geoms.
if isinstance(mesh, trimesh.base.Trimesh):
meshname = Path(f"{filename.stem}.obj")
# Add the mesh to assets.
etree.SubElement(
asset_elem,
"mesh",
name=meshname.stem,
file=str(meshname),
)
etree.SubElement(asset_elem, "mesh", file=str(meshname))
# Add the geom to the worldbody.
if process_mtl:
etree.SubElement(
obj_body,
"geom",
material=material.name,
mesh=str(meshname.stem),
**visual_kwargs,
e_ = etree.SubElement(
obj_body, "geom", material=material.name, mesh=str(meshname.stem)
)
e_.attrib["class"] = "visual"
else:
etree.SubElement(obj_body, "geom", mesh=meshname.stem, **visual_kwargs)
e_ = etree.SubElement(obj_body, "geom", mesh=meshname.stem)
e_.attrib["class"] = "visual"
else:
for i, (name, geom) in enumerate(mesh.geometry.items()):
meshname = Path(f"{filename.stem}_{i}.obj")
# Add the mesh to assets.
etree.SubElement(
asset_elem,
"mesh",
name=meshname.stem,
file=str(meshname),
)
etree.SubElement(asset_elem, "mesh", file=str(meshname))
# Add the geom to the worldbody.
if process_mtl:
etree.SubElement(
obj_body, "geom", mesh=meshname.stem, material=name, **visual_kwargs
e_ = etree.SubElement(
obj_body, "geom", mesh=meshname.stem, material=name
)
e_.attrib["class"] = "visual"
else:
etree.SubElement(obj_body, "geom", mesh=meshname.stem, **visual_kwargs)
e_ = etree.SubElement(obj_body, "geom", mesh=meshname.stem)
e_.attrib["class"] = "visual"

# Add collision geoms.
if decomp_success:
Expand All @@ -480,26 +482,20 @@ def process_obj(filename: Path, args: Args) -> None:
collisions.sort(key=lambda x: int(x.stem.split("_")[-1]))

for collision in collisions:
etree.SubElement(
asset_elem, "mesh", name=collision.stem, file=collision.name
)
etree.SubElement(
obj_body,
"geom",
mesh=collision.stem,
**collision_kwargs,
)
etree.SubElement(asset_elem, "mesh", file=collision.name)
e_ = etree.SubElement(obj_body, "geom", mesh=collision.stem)
e_.attrib["class"] = "collision"
else:
# If no decomposed convex hulls were created, use the original mesh as the
# collision mesh.
if isinstance(mesh, trimesh.base.Trimesh):
etree.SubElement(obj_body, "geom", mesh=meshname.stem, **collision_kwargs)
e_ = etree.SubElement(obj_body, "geom", mesh=meshname.stem)
e_.attrib["class"] = "collision"
else:
for i, (name, geom) in enumerate(mesh.geometry.items()):
meshname = Path(f"{filename.stem}_{i}.obj")
etree.SubElement(
obj_body, "geom", mesh=meshname.stem, **collision_kwargs
)
e_ = etree.SubElement(obj_body, "geom", mesh=meshname.stem)
e_.attrib["class"] = "collision"

tree = etree.ElementTree(root)
etree.indent(tree, space=_XML_INDENTATION, level=0)
Expand Down

0 comments on commit 86320e2

Please sign in to comment.