Skip to content

Commit e50b501

Browse files
AnisBduburcqa
authored andcommitted
Renaming and changing the behavior of parse_glb_zup.
1 parent 7b29170 commit e50b501

File tree

5 files changed

+139
-46
lines changed

5 files changed

+139
-46
lines changed

genesis/engine/mesh.py

Lines changed: 12 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,9 @@ def __init__(
5858
self._metadata = metadata or {}
5959
self._color = np.array([1.0, 1.0, 1.0, 1.0], dtype=gs.np_float)
6060

61+
# By default, all meshes are considered zup, unless the "FileMorph.file_meshes_are_zup" option was set to False.
62+
self._metadata["imported_as_zup"] = True
63+
6164
if self._surface.requires_uv(): # check uvs here
6265
if self._uvs is None:
6366
if "mesh_path" in metadata:
@@ -340,20 +343,19 @@ def from_morph_surface(cls, morph, surface=None):
340343
if isinstance(morph, gs.options.morphs.Mesh):
341344
if morph.is_format(gs.options.morphs.MESH_FORMATS):
342345
meshes = mu.parse_mesh_trimesh(morph.file, morph.group_by_material, morph.scale, surface)
346+
if not morph.file_meshes_are_zup:
347+
for mesh in meshes:
348+
mesh.convert_to_zup()
349+
gs.logger.debug(f"Converting the geometry of the '{morph.file}' file to zup.")
343350
elif morph.is_format(gs.options.morphs.GLTF_FORMATS):
344351
if morph.parse_glb_with_trimesh:
345352
meshes = mu.parse_mesh_trimesh(morph.file, morph.group_by_material, morph.scale, surface)
346353
else:
347354
meshes = gltf_utils.parse_mesh_glb(morph.file, morph.group_by_material, morph.scale, surface)
348-
if morph.parse_glb_with_zup:
349-
for mesh in meshes:
350-
mesh.convert_to_zup()
351-
else:
352-
gs.logger.warning(
353-
"GLTF is using y-up while Genesis uses z-up. Please set parse_glb_with_zup=True"
354-
" in morph options if you find the mesh is 90-degree rotated. We will set parse_glb_with_zup=True"
355-
" and rotate glb mesh by default later and gradually enforce this option."
356-
)
355+
# The GLF spec defines that all meshes are Yup, ignoring the FileMorph.file_meshes_are_zup option.
356+
for mesh in meshes:
357+
mesh.convert_to_zup()
358+
gs.logger.debug(f"Converting the GLTF geometry to zup '{morph.file}'")
357359
elif morph.is_format(gs.options.morphs.USD_FORMATS):
358360
import genesis.utils.usda as usda_utils
359361

@@ -403,6 +405,7 @@ def convert_to_zup(self):
403405
Convert the mesh to z-up.
404406
"""
405407
self._mesh.apply_transform(mu.Y_UP_TRANSFORM.T)
408+
self._metadata["imported_as_zup"] = False
406409

407410
def apply_transform(self, T):
408411
"""

genesis/options/morphs.py

Lines changed: 39 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -522,7 +522,12 @@ class FileMorph(Morph):
522522
coacd_options : CoacdOptions, optional
523523
Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
524524
parse_glb_with_zup : bool, optional
525-
Whether to use zup to load glb files. Defaults to False.
525+
This parameter is deprecated, see file_meshes_are_zup.
526+
file_meshes_are_zup : bool, optional
527+
Defines if the mesh files are expressed in a Z-up or Y-up coordinate system. If set to true, meshes are loaded
528+
as Z-up and no transforms are applied to the input data. If set to false, all meshes undergo a conversion step
529+
where the original coordinates are transformed as follows: (X, Y, Z) → (X, -Z, Y).
530+
This conversion always applies to GLTF/GLB files, as they are defined as Y-up by the standard. Defaults to true.
526531
visualization : bool, optional
527532
Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
528533
purposes. Defaults to True. `visualization` and `collision` cannot both be False.
@@ -549,7 +554,8 @@ class FileMorph(Morph):
549554
decompose_robot_error_threshold: float = float("inf")
550555
coacd_options: Optional[CoacdOptions] = None
551556
recompute_inertia: bool = False
552-
parse_glb_with_zup: bool = False
557+
parse_glb_with_zup: Optional[bool] = None
558+
file_meshes_are_zup: bool = True
553559
batch_fixed_verts: bool = False
554560

555561
def __init__(self, **data):
@@ -569,6 +575,13 @@ def __init__(self, **data):
569575
"'convexify' and 'decompose_(robot|object)_error_threshold' instead."
570576
)
571577

578+
if self.parse_glb_with_zup is not None:
579+
self.file_meshes_are_zup = not self.parse_glb_with_zup
580+
gs.logger.warning(
581+
"FileMorph option 'parse_glb_with_zup' is deprecated and will be removed in future release. Please use "
582+
"'file_meshes_are_zup'instead."
583+
)
584+
572585
# Make sure that this threshold is positive to avoid decomposition of convex and primitive shapes
573586
self.decompose_object_error_threshold = max(self.decompose_object_error_threshold, gs.EPS)
574587
self.decompose_robot_error_threshold = max(self.decompose_robot_error_threshold, gs.EPS)
@@ -668,7 +681,12 @@ class Mesh(FileMorph, TetGenMixin):
668681
parse_glb_with_trimesh : bool, optional
669682
Whether to use trimesh to load glb files. Defaults to False, in which case pygltflib will be used.
670683
parse_glb_with_zup : bool, optional
671-
Whether to use zup to load glb files. Defaults to False.
684+
This parameter is deprecated, see file_meshes_are_zup.
685+
file_meshes_are_zup : bool, optional
686+
Defines if the mesh files are expressed in a Z-up or Y-up coordinate system. If set to true, meshes are loaded
687+
as Z-up and no transforms are applied to the input data. If set to false, all meshes undergo a conversion step
688+
where the original coordinates are transformed as follows: (X, Y, Z) → (X, -Z, Y).
689+
This conversion always applies to GLTF/GLB files, as they are defined as Y-up by the standard. Defaults to true.
672690
fixed : bool, optional
673691
Whether the object should be fixed. Defaults to False. **This is only used for RigidEntity.**
674692
batch_fixed_verts : bool, optional
@@ -799,7 +817,12 @@ class MJCF(FileMorph):
799817
coacd_options : CoacdOptions, optional
800818
Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
801819
parse_glb_with_zup : bool, optional
802-
Whether to use zup to load glb files. Defaults to False.
820+
This parameter is deprecated, see file_meshes_are_zup.
821+
file_meshes_are_zup : bool, optional
822+
Defines if the mesh files are expressed in a Z-up or Y-up coordinate system. If set to true, meshes are loaded
823+
as Z-up and no transforms are applied to the input data. If set to false, all meshes undergo a conversion step
824+
where the original coordinates are transformed as follows: (X, Y, Z) → (X, -Z, Y).
825+
This conversion always applies to GLTF/GLB files, as they are defined as Y-up by the standard. Defaults to true.
803826
visualization : bool, optional
804827
Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
805828
purposes. Defaults to True. `visualization` and `collision` cannot both be False.
@@ -905,7 +928,12 @@ class URDF(FileMorph):
905928
coacd_options : CoacdOptions, optional
906929
Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
907930
parse_glb_with_zup : bool, optional
908-
Whether to use zup to load glb files. Defaults to False.
931+
This parameter is deprecated, see file_meshes_are_zup.
932+
file_meshes_are_zup : bool, optional
933+
Defines if the mesh files are expressed in a Z-up or Y-up coordinate system. If set to true, meshes are loaded
934+
as Z-up and no transforms are applied to the input data. If set to false, all meshes undergo a conversion step
935+
where the original coordinates are transformed as follows: (X, Y, Z) → (X, -Z, Y).
936+
This conversion always applies to GLTF/GLB files, as they are defined as Y-up by the standard. Defaults to true.
909937
visualization : bool, optional
910938
Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
911939
purposes. Defaults to True. `visualization` and `collision` cannot both be False.
@@ -1003,7 +1031,12 @@ class Drone(FileMorph):
10031031
coacd_options : CoacdOptions, optional
10041032
Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
10051033
parse_glb_with_zup : bool, optional
1006-
Whether to use zup to load glb files. Defaults to False.
1034+
This parameter is deprecated, see file_meshes_are_zup.
1035+
file_meshes_are_zup : bool, optional
1036+
Defines if the mesh files are expressed in a Z-up or Y-up coordinate system. If set to true, meshes are loaded
1037+
as Z-up and no transforms are applied to the input data. If set to false, all meshes undergo a conversion step
1038+
where the original coordinates are transformed as follows: (X, Y, Z) → (X, -Z, Y).
1039+
This conversion always applies to GLTF/GLB files, as they are defined as Y-up by the standard. Defaults to true.
10071040
visualization : bool, optional
10081041
Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
10091042
purposes. Defaults to True. `visualization` and `collision` cannot both be False.

genesis/utils/urdf.py

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -131,14 +131,14 @@ def parse_urdf(morph, surface):
131131
metadata={"mesh_path": mesh_path},
132132
)
133133

134+
# If the file is a gltf, we have to convert it to zup
134135
if mesh_path.lower().endswith(gs.morphs.GLTF_FORMATS):
135-
if morph.parse_glb_with_zup:
136-
mesh.convert_to_zup()
137-
else:
138-
gs.logger.warning(
139-
"This file contains GLTF mesh, which is using y-up while Genesis uses z-up. Please set "
140-
"'parse_glb_with_zup=True' in morph options if you find the mesh is 90-degree rotated. "
141-
)
136+
mesh.convert_to_zup()
137+
gs.logger.debug(f"Converting the GLTF geometry to zup '{morph.file}'")
138+
# If the file is a not a gltf, we convert to zup if the FileMorph.file_meshes_are_zup is true
139+
elif not morph.file_meshes_are_zup:
140+
mesh.convert_to_zup()
141+
gs.logger.debug(f"Converting the geometry of the '{morph.file}' file to zup.")
142142

143143
g_info = {"mesh" if geom_is_col else "vmesh": mesh}
144144
link_g_infos_.append(g_info)

tests/test_mesh.py

Lines changed: 80 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
import os
22
import platform
33
import sys
4+
from contextlib import nullcontext
45

56
import numpy as np
67
import pytest
@@ -350,55 +351,111 @@ def test_usd_bake(usd_file, show_viewer):
350351
show_viewer=show_viewer,
351352
show_FPS=False,
352353
)
353-
robot = scene.add_entity(
354+
scene.add_entity(
354355
gs.morphs.Mesh(
355356
file=usd_file,
356357
),
357358
)
358359

359360

360361
@pytest.mark.required
361-
def test_urdf_with_existing_glb(tmp_path, show_viewer):
362-
glb_file = "usd/sneaker_airforce.glb"
363-
asset_path = get_hf_dataset(pattern=glb_file)
364-
glb_path = os.path.join(asset_path, glb_file)
365-
362+
@pytest.mark.parametrize("mesh_file", ["yup_zup_coverage/cannon_z.glb", "yup_zup_coverage/cannon_y_-z.stl"])
363+
def test_urdf_yup(mesh_file, tmp_path):
364+
asset_path = get_hf_dataset(pattern=mesh_file)
366365
urdf_path = tmp_path / "model.urdf"
367366
urdf_path.write_text(
368367
f"""<robot name="shoe">
369368
<link name="base">
370369
<visual>
371-
<geometry><mesh filename="{glb_path}"/></geometry>
370+
<geometry><mesh filename="{os.path.join(asset_path, mesh_file)}"/></geometry>
372371
</visual>
373372
</link>
374373
</robot>
375374
"""
376375
)
377376

378-
scene = gs.Scene(
379-
show_viewer=show_viewer,
380-
show_FPS=False,
381-
)
382-
robot_urdf_yup = scene.add_entity(
377+
scene = gs.Scene()
378+
robot = scene.add_entity(
383379
gs.morphs.URDF(
384380
file=urdf_path,
381+
file_meshes_are_zup=False,
385382
),
386383
)
387-
robot_urdf_zup = scene.add_entity(
388-
gs.morphs.URDF(
389-
file=urdf_path,
390-
parse_glb_with_zup=True,
384+
mesh = robot.vgeoms[0].vmesh
385+
386+
with pytest.raises(AssertionError) if mesh_file == "yup_zup_coverage/cannon_z.glb" else nullcontext():
387+
assert_allclose(mesh.trimesh.center_mass, (-0.012, -0.142, 0.397), tol=0.002)
388+
389+
390+
@pytest.mark.required
391+
def test_obj_morphes_yup():
392+
scene = gs.Scene()
393+
394+
asset_path = get_hf_dataset(pattern="yup_zup_coverage/*")
395+
396+
glb_y = scene.add_entity(
397+
morph=gs.morphs.Mesh(
398+
file=f"{asset_path}/yup_zup_coverage/cannon_y.glb",
399+
convexify=False,
400+
fixed=True,
401+
file_meshes_are_zup=True,
391402
),
392403
)
393-
robot_mesh = scene.add_entity(
394-
gs.morphs.Mesh(
395-
file=glb_path,
396-
parse_glb_with_zup=True,
404+
glb_mesh_y = glb_y.vgeoms[0].vmesh
405+
glb_z = scene.add_entity(
406+
morph=gs.morphs.Mesh(
407+
file=f"{asset_path}/yup_zup_coverage/cannon_z.glb",
408+
convexify=False,
409+
fixed=True,
410+
file_meshes_are_zup=True,
411+
),
412+
)
413+
glb_mesh_z = glb_z.vgeoms[0].vmesh
414+
stl_y = scene.add_entity(
415+
morph=gs.morphs.Mesh(
416+
file=f"{asset_path}/yup_zup_coverage/cannon_y_-z.stl",
417+
convexify=False,
418+
fixed=True,
419+
file_meshes_are_zup=False,
420+
),
421+
)
422+
stl_mesh_y = stl_y.vgeoms[0].vmesh
423+
stl_z = scene.add_entity(
424+
morph=gs.morphs.Mesh(
425+
file=f"{asset_path}/yup_zup_coverage/cannon_z_y.stl",
426+
convexify=False,
427+
fixed=True,
397428
),
398429
)
399-
check_gs_meshes(robot_urdf_zup.vgeoms[0].vmesh, robot_mesh.vgeoms[0].vmesh, "robot")
400-
robot_urdf_yup.vgeoms[0].vmesh.convert_to_zup()
401-
check_gs_meshes(robot_urdf_yup.vgeoms[0].vmesh, robot_mesh.vgeoms[0].vmesh, "robot")
430+
stl_mesh_z = stl_z.vgeoms[0].vmesh
431+
obj_y = scene.add_entity(
432+
morph=gs.morphs.Mesh(
433+
file=f"{asset_path}/yup_zup_coverage/cannon_y_-z.obj",
434+
convexify=False,
435+
fixed=True,
436+
file_meshes_are_zup=False,
437+
),
438+
)
439+
obj_mesh_y = obj_y.vgeoms[0].vmesh
440+
obj_z = scene.add_entity(
441+
morph=gs.morphs.Mesh(
442+
file=f"{asset_path}/yup_zup_coverage/cannon_z_y.obj",
443+
convexify=False,
444+
fixed=True,
445+
),
446+
)
447+
obj_mesh_z = obj_z.vgeoms[0].vmesh
448+
449+
assert not glb_mesh_y.metadata["imported_as_zup"]
450+
assert not glb_mesh_z.metadata["imported_as_zup"]
451+
assert not stl_mesh_y.metadata["imported_as_zup"]
452+
assert stl_mesh_z.metadata["imported_as_zup"]
453+
assert not obj_mesh_y.metadata["imported_as_zup"]
454+
assert obj_mesh_z.metadata["imported_as_zup"]
455+
456+
for mesh in (glb_mesh_y, glb_mesh_z, stl_mesh_y, stl_mesh_z, obj_mesh_y, obj_mesh_z):
457+
with pytest.raises(AssertionError) if mesh is glb_mesh_z else nullcontext():
458+
assert_allclose(mesh.trimesh.center_mass, (-0.012, -0.142, 0.397), tol=0.002)
402459

403460

404461
@pytest.mark.required

tests/utils.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@
3535
REPOSITY_URL = "Genesis-Embodied-AI/Genesis"
3636
DEFAULT_BRANCH_NAME = "main"
3737

38-
HUGGINGFACE_ASSETS_REVISION = "701f78c1465f0a98f6540bae6c9daacaa551b7bf"
38+
HUGGINGFACE_ASSETS_REVISION = "c50bfe3e354e105b221ef4eb9a79504650709dd2"
3939
HUGGINGFACE_SNAPSHOT_REVISION = "17d79e7627479ef836524d14449e2fdc4282973d"
4040

4141
MESH_EXTENSIONS = (".mtl", *MESH_FORMATS, *GLTF_FORMATS, *USD_FORMATS)

0 commit comments

Comments
 (0)