Skip to content

Commit 21338f1

Browse files
authored
[MISC] Add 'parse_glb_with_zup' option to all file-based Morph. (#1938)
1 parent bdad406 commit 21338f1

File tree

6 files changed

+47
-33
lines changed

6 files changed

+47
-33
lines changed

‎genesis/engine/mesh.py‎

Lines changed: 15 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -334,21 +334,19 @@ def from_morph_surface(cls, morph, surface=None):
334334
if morph.is_format(gs.options.morphs.MESH_FORMATS):
335335
meshes = mu.parse_mesh_trimesh(morph.file, morph.group_by_material, morph.scale, surface)
336336
elif morph.is_format(gs.options.morphs.GLTF_FORMATS):
337-
if not morph.parse_glb_with_zup:
337+
if morph.parse_glb_with_trimesh:
338+
meshes = mu.parse_mesh_trimesh(morph.file, morph.group_by_material, morph.scale, surface)
339+
else:
340+
meshes = gltf_utils.parse_mesh_glb(morph.file, morph.group_by_material, morph.scale, surface)
341+
if morph.parse_glb_with_zup:
342+
for mesh in meshes:
343+
mesh.convert_to_zup()
344+
else:
338345
gs.logger.warning(
339346
"GLTF is using y-up while Genesis uses z-up. Please set parse_glb_with_zup=True"
340347
" in morph options if you find the mesh is 90-degree rotated. We will set parse_glb_with_zup=True"
341348
" and rotate glb mesh by default later and gradually enforce this option."
342349
)
343-
if morph.parse_glb_with_trimesh:
344-
meshes = mu.parse_mesh_trimesh(morph.file, morph.group_by_material, morph.scale, surface)
345-
if morph.parse_glb_with_zup:
346-
for mesh in meshes:
347-
mesh.apply_transform(mu.Y_UP_TRANSFORM.T)
348-
else:
349-
meshes = gltf_utils.parse_mesh_glb(
350-
morph.file, morph.group_by_material, morph.scale, surface, morph.parse_glb_with_zup
351-
)
352350
elif morph.is_format(gs.options.morphs.USD_FORMATS):
353351
import genesis.utils.usda as usda_utils
354352

@@ -376,7 +374,7 @@ def from_morph_surface(cls, morph, surface=None):
376374
else:
377375
gs.raise_exception()
378376

379-
metadata = {"mesh_path": morph.file} if isinstance(morph, gs.options.morphs.FileMorph) else {}
377+
metadata = {}
380378
return cls.from_trimesh(tmesh, surface=surface, metadata=metadata)
381379

382380
def set_color(self, color):
@@ -395,6 +393,12 @@ def update_trimesh_visual(self):
395393
"""
396394
self._mesh.visual = mu.surface_uvs_to_trimesh_visual(self.surface, self.uvs, len(self.verts))
397395

396+
def convert_to_zup(self):
397+
"""
398+
Convert the mesh to z-up.
399+
"""
400+
self._mesh.apply_transform(mu.Y_UP_TRANSFORM.T)
401+
398402
def apply_transform(self, T):
399403
"""
400404
Apply a 4x4 transformation matrix (translation on the right column) to the mesh.

‎genesis/ext/urdfpy/utils.py‎

Lines changed: 1 addition & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -245,24 +245,14 @@ def load_meshes(filename):
245245
meshes = trimesh.load(filename, process=False)
246246

247247
if isinstance(meshes, trimesh.Scene):
248-
T = np.array([
249-
[ 1., 0., 0., 0.],
250-
[ 0., 0., -1., 0.],
251-
[ 0., 1., 0., 0.],
252-
[ 0., 0., 0., 1.]], dtype=np.float32,
253-
)
254248
# FIXME: Scene.dump() has bug that uses copy without include_cache=True,
255249
# it will lose the vertex normals.
256250
results = []
257-
is_glb = filename.endswith((".gltf", ".glb"))
258251
for node_name in meshes.graph.nodes_geometry:
259252
transform, geometry_name = meshes.graph[node_name]
260253
current = meshes.geometry[geometry_name].copy(include_cache=True)
261254
if isinstance(current, trimesh.Trimesh):
262-
if is_glb:
263-
current.apply_transform(T @ transform)
264-
else:
265-
current.apply_transform(transform)
255+
current.apply_transform(transform)
266256
current.metadata["name"] = geometry_name
267257
current.metadata["node"] = node_name
268258
results.append(current)

‎genesis/options/morphs.py‎

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -520,6 +520,8 @@ class FileMorph(Morph):
520520
0.0 to enforce decomposition, float("inf") to disable it completely. Defaults to float("inf").
521521
coacd_options : CoacdOptions, optional
522522
Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
523+
parse_glb_with_zup : bool, optional
524+
Whether to use zup to load glb files. Defaults to False.
523525
visualization : bool, optional
524526
Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
525527
purposes. Defaults to True. `visualization` and `collision` cannot both be False.
@@ -546,6 +548,7 @@ class FileMorph(Morph):
546548
decompose_robot_error_threshold: float = float("inf")
547549
coacd_options: Optional[CoacdOptions] = None
548550
recompute_inertia: bool = False
551+
parse_glb_with_zup: bool = False
549552
batch_fixed_verts: bool = False
550553

551554
def __init__(self, **data):
@@ -705,7 +708,6 @@ class Mesh(FileMorph, TetGenMixin):
705708
"""
706709

707710
parse_glb_with_trimesh: bool = False
708-
parse_glb_with_zup: bool = False
709711

710712
# Rigid specific
711713
fixed: bool = False
@@ -795,6 +797,8 @@ class MJCF(FileMorph):
795797
0.0 to enforce decomposition, float("inf") to disable it completely. Defaults to float("inf").
796798
coacd_options : CoacdOptions, optional
797799
Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
800+
parse_glb_with_zup : bool, optional
801+
Whether to use zup to load glb files. Defaults to False.
798802
visualization : bool, optional
799803
Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
800804
purposes. Defaults to True. `visualization` and `collision` cannot both be False.
@@ -899,6 +903,8 @@ class URDF(FileMorph):
899903
0.0 to enforce decomposition, float("inf") to disable it completely. Defaults to float("inf").
900904
coacd_options : CoacdOptions, optional
901905
Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
906+
parse_glb_with_zup : bool, optional
907+
Whether to use zup to load glb files. Defaults to False.
902908
visualization : bool, optional
903909
Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
904910
purposes. Defaults to True. `visualization` and `collision` cannot both be False.
@@ -995,6 +1001,8 @@ class Drone(FileMorph):
9951001
0.0 to enforce decomposition, float("inf") to disable it completely. Defaults to float("inf").
9961002
coacd_options : CoacdOptions, optional
9971003
Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
1004+
parse_glb_with_zup : bool, optional
1005+
Whether to use zup to load glb files. Defaults to False.
9981006
visualization : bool, optional
9991007
Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
10001008
purposes. Defaults to True. `visualization` and `collision` cannot both be False.

‎genesis/utils/gltf.py‎

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -290,7 +290,7 @@ def parse_glb_tree(glb, node_index):
290290
return mesh_list
291291

292292

293-
def parse_mesh_glb(path, group_by_material, scale, surface, convert_zup=False):
293+
def parse_mesh_glb(path, group_by_material, scale, surface):
294294
glb = pygltflib.GLTF2().load(path)
295295
assert glb is not None
296296
glb.convert_images(pygltflib.ImageFormat.DATAURI)
@@ -383,8 +383,6 @@ def parse_mesh_glb(path, group_by_material, scale, surface, convert_zup=False):
383383
if primitive.attributes.TEXCOORD_1:
384384
uvs = get_glb_data_from_accessor(glb, primitive.attributes.TEXCOORD_1).astype(np.float32)
385385

386-
if convert_zup:
387-
mesh_transform @= mu.Y_UP_TRANSFORM
388386
points, normals = mu.apply_transform(mesh_transform, points, normals)
389387
if normals is None:
390388
normals = trimesh.Trimesh(points, triangles, process=False).vertex_normals

‎genesis/utils/urdf.py‎

Lines changed: 11 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -114,17 +114,23 @@ def parse_urdf(morph, surface):
114114
if geom.geometry.geometry.scale is not None:
115115
scale *= geom.geometry.geometry.scale
116116

117+
mesh_path = urdfpy.utils.get_filename(os.path.dirname(path), geom.geometry.geometry.filename)
117118
mesh = gs.Mesh.from_trimesh(
118119
tmesh,
119120
scale=scale,
120121
surface=gs.surfaces.Collision() if geom_is_col else surface,
121-
metadata={
122-
"mesh_path": urdfpy.utils.get_filename(
123-
os.path.dirname(path), geom.geometry.geometry.filename
124-
)
125-
},
122+
metadata={"mesh_path": mesh_path},
126123
)
127124

125+
if mesh_path.lower().endswith(gs.morphs.GLTF_FORMATS):
126+
if morph.parse_glb_with_zup:
127+
mesh.convert_to_zup()
128+
else:
129+
gs.logger.warning(
130+
"This file contains GLTF mesh, which is using y-up while Genesis uses z-up. Please set "
131+
"'parse_glb_with_zup=True' in morph options if you find the mesh is 90-degree rotated. "
132+
)
133+
128134
if not geom_is_col and (morph.prioritize_urdf_material or not tmesh.visual.defined):
129135
if geom.material is not None and geom.material.color is not None:
130136
mesh.set_color(geom.material.color)

‎tests/test_mesh.py‎

Lines changed: 10 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -379,18 +379,26 @@ def test_urdf_with_existing_glb(tmp_path, show_viewer):
379379
show_viewer=show_viewer,
380380
show_FPS=False,
381381
)
382-
robot_urdf = scene.add_entity(
382+
robot_urdf_yup = scene.add_entity(
383383
gs.morphs.URDF(
384384
file=urdf_path,
385385
),
386386
)
387+
robot_urdf_zup = scene.add_entity(
388+
gs.morphs.URDF(
389+
file=urdf_path,
390+
parse_glb_with_zup=True,
391+
),
392+
)
387393
robot_mesh = scene.add_entity(
388394
gs.morphs.Mesh(
389395
file=glb_path,
390396
parse_glb_with_zup=True,
391397
),
392398
)
393-
check_gs_meshes(robot_urdf.vgeoms[0].vmesh, robot_mesh.vgeoms[0].vmesh, "robot")
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")
394402

395403

396404
@pytest.mark.required

0 commit comments

Comments
 (0)