Skip to content

Commit 4ddf88f

Browse files
committed
Merge branch 'main' of https://github.com/Genesis-Embodied-AI/Genesis into dev_material
2 parents 9af6fdb + 69028c3 commit 4ddf88f

File tree

6 files changed

+105
-53
lines changed

6 files changed

+105
-53
lines changed

genesis/engine/mesh.py

Lines changed: 24 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -62,9 +62,12 @@ def __init__(
6262
self._metadata: dict[str, Any] = metadata or {}
6363
self._color = np.array([1.0, 1.0, 1.0, 1.0], dtype=gs.np_float)
6464

65-
# By default, all meshes are considered zup, unless the "FileMorph.file_meshes_are_zup" option was set to False.
65+
# By default, all meshes are considered zup, unless the "FileMorph.file_meshes_are_zup" option was set to False
6666
self._metadata.setdefault("imported_as_zup", True)
6767

68+
# By default, all meshes are considered having their original visual
69+
self._metadata.setdefault("is_visual_overwritten", False)
70+
6871
if not is_mesh_zup:
6972
if self._metadata["imported_as_zup"]:
7073
self._mesh.apply_transform(mu.Y_UP_TRANSFORM.T)
@@ -245,6 +248,7 @@ def from_trimesh(
245248
# Visual may not have uv, e.g. ColorVisuals
246249
uvs = None
247250

251+
metadata = metadata or {}
248252
must_update_surface = True
249253
roughness_factor = None
250254
color_image = None
@@ -287,14 +291,14 @@ def from_trimesh(
287291
else:
288292
# TODO: support vertex/face colors in luisa
289293
color_factor = tuple(np.array(visual.main_color, dtype=np.float32) / 255.0)
294+
elif surface.color is not None:
295+
color_factor = surface.color
296+
metadata["is_visual_overwritten"] = True
290297
elif (isinstance(visual, trimesh.visual.color.ColorVisuals) and visual.defined) or (
291298
isinstance(visual, trimesh.visual.color.VertexColor) and visual.vertex_colors.size > 0
292299
):
293-
# Color is already vertex-based. No need to create a new texture to keep the original one, unless a color
294-
# overwrite has been specified as surface-level.
295-
must_update_surface = surface.color is not None
296-
elif surface.color is not None:
297-
color_factor = surface.color
300+
# Color is already vertex-based. It is not only necessary to create a new visual.
301+
must_update_surface = False
298302
else:
299303
# use white color as default
300304
color_factor = (1.0, 1.0, 1.0, 1.0)
@@ -336,14 +340,20 @@ def from_attrs(
336340
if surface is None:
337341
surface = gs.surfaces.Default()
338342

343+
metadata = metadata or {}
344+
metadata["is_visual_overwritten"] = metadata.get("is_visual_overwritten", False) or (surface.color is not None)
345+
visual = mu.surface_uvs_to_trimesh_visual(surface, uvs, len(verts))
346+
347+
tmesh = trimesh.Trimesh(
348+
vertices=verts,
349+
faces=faces,
350+
vertex_normals=normals,
351+
visual=visual,
352+
process=False,
353+
)
354+
339355
return cls(
340-
mesh=trimesh.Trimesh(
341-
vertices=verts,
342-
faces=faces,
343-
vertex_normals=normals,
344-
visual=mu.surface_uvs_to_trimesh_visual(surface, uvs, len(verts)),
345-
process=False,
346-
),
356+
mesh=tmesh,
347357
surface=surface,
348358
uvs=uvs,
349359
scale=scale,
@@ -402,6 +412,7 @@ def update_trimesh_visual(self):
402412
Update the trimesh obj's visual attributes using its surface and uvs.
403413
"""
404414
self._mesh.visual = mu.surface_uvs_to_trimesh_visual(self.surface, self.uvs, len(self.verts))
415+
self._metadata["is_visual_overwritten"] = True
405416

406417
def apply_transform(self, T):
407418
"""

genesis/options/morphs.py

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
"""
77

88
import os
9-
from typing import Any, List, Optional, Sequence, Tuple, Union, Literal
9+
from typing import Any, List, Optional, Sequence, Tuple, Literal
1010
from pathlib import Path
1111

1212
import numpy as np
@@ -747,13 +747,17 @@ def __init__(self, **kwargs):
747747
"Specifying 'file_meshes_are_zup' for GLTF/GLB files is not supported. A rotation will be applied "
748748
"explicitly on the morph instead. Please consider fixing your asset to use Y-UP convention."
749749
)
750-
quat = (0.707, -0.707, 0.0, 0.0)
750+
y_up_quat = (1.0, -1.0, 0.0, 0.0)
751751
if self.quat is None:
752-
self.quat = quat
752+
self.quat = y_up_quat
753753
else:
754754
self.quat = gu.transform_quat_by_quat(
755-
np.array(quat, dtype=gs.np_float), np.array(self.quat, dtype=gs.np_float)
755+
np.array(y_up_quat, dtype=gs.np_float), np.array(self.quat, dtype=gs.np_float)
756756
)
757+
if self.scale is not None:
758+
scale = np.atleast_1d(np.array(self.scale))
759+
if scale.size == 3:
760+
self.scale = (scale[0], scale[2], scale[1])
757761
self.file_meshes_are_zup = False
758762
elif self.file_meshes_are_zup is None:
759763
self.file_meshes_are_zup = True

genesis/utils/urdf.py

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -117,6 +117,7 @@ def parse_urdf(morph, surface):
117117
scale *= geometry.scale
118118

119119
# Overwrite surface color by original color specified in URDF file only if necessary
120+
is_urdf_material = False
120121
if geom_is_col:
121122
geom_surface = gs.surfaces.Collision()
122123
elif (
@@ -125,6 +126,7 @@ def parse_urdf(morph, surface):
125126
and geom_prop.material.color is not None
126127
and (morph.prioritize_urdf_material or surface.color is None)
127128
):
129+
is_urdf_material = True
128130
geom_surface = surface.copy()
129131
geom_surface.color = geom_prop.material.color
130132
else:
@@ -145,6 +147,9 @@ def parse_urdf(morph, surface):
145147
is_mesh_zup=morph.file_meshes_are_zup,
146148
metadata={"mesh_path": mesh_path},
147149
)
150+
if is_urdf_material:
151+
# Material color defined in URDF are not considered as visual overwrite
152+
mesh.metadata["is_visual_overwritten"] = False
148153

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

genesis/vis/rasterizer_context.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -832,7 +832,7 @@ def draw_debug_frame(self, T, axis_length=1.0, origin_size=0.015, axis_radius=0.
832832

833833
def draw_debug_frames(self, poses, axis_length=1.0, origin_size=0.015, axis_radius=0.01):
834834
mesh = trimesh.creation.axis(origin_size=origin_size, axis_radius=axis_radius, axis_length=axis_length)
835-
node = pyrender.Mesh.from_trimesh(mesh, name=f"debug_frame_{gs.UID()}", is_marker=True)
835+
node = pyrender.Mesh.from_trimesh(mesh, name=f"debug_frame_{gs.UID()}", poses=poses, is_marker=True)
836836
self.add_external_node(node)
837837
return node
838838

tests/test_mesh.py

Lines changed: 41 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -153,16 +153,13 @@ def check_gs_surfaces(gs_surface1, gs_surface2, material_name):
153153
check_gs_textures(gs_surface1.emissive_texture, gs_surface2.emissive_texture, 0.0, material_name, "emissive")
154154

155155

156-
# ==================== Scaling Tests ====================
156+
# ==================== Scale Tests ====================
157157

158158

159159
@pytest.mark.required
160-
@pytest.mark.parametrize("scale", [(2.0, 3.0, 5.0), (2.0, 2.0, 2.0)])
161-
@pytest.mark.parametrize(
162-
"mesh_file, file_meshes_are_zup",
163-
[("meshes/camera/camera.glb", False), ("meshes/axis.obj", True)],
164-
)
165-
def test_morph_scaling(scale, mesh_file, file_meshes_are_zup, show_viewer, tmp_path):
160+
@pytest.mark.parametrize("scale", [(0.5, 2.0, 8.0), (2.0, 2.0, 2.0)])
161+
@pytest.mark.parametrize("mesh_file", ["meshes/camera/camera.glb", "meshes/axis.obj"])
162+
def test_morph_scale(scale, mesh_file, show_viewer, tmp_path):
166163
urdf_path = tmp_path / "model.urdf"
167164
urdf_path.write_text(
168165
f"""<robot name="cannon">
@@ -179,48 +176,72 @@ def test_morph_scaling(scale, mesh_file, file_meshes_are_zup, show_viewer, tmp_p
179176
obj_orig = scene.add_entity(
180177
morph=gs.morphs.Mesh(
181178
file=mesh_file,
179+
file_meshes_are_zup=False,
182180
pos=(0, 0, 1.0),
183-
scale=(1.0, 1.0, 1.0),
181+
scale=1.0,
184182
convexify=False,
185183
fixed=True,
186184
),
185+
surface=gs.surfaces.Default(
186+
color=(1.0, 0.0, 0.0, 1.0),
187+
),
187188
)
188-
mesh_orig = obj_orig.vgeoms[0].vmesh.trimesh
189+
for vgeom in obj_orig.vgeoms:
190+
mesh_orig = vgeom.vmesh.trimesh
191+
mesh_orig.apply_transform(mu.Y_UP_TRANSFORM)
192+
mesh_orig.apply_scale(scale)
193+
189194
obj_scaled = scene.add_entity(
190195
morph=gs.morphs.Mesh(
191196
file=mesh_file,
197+
file_meshes_are_zup=True,
192198
pos=(0, 0, 1.0),
193199
scale=scale,
194200
convexify=False,
195201
fixed=True,
196202
),
203+
surface=gs.surfaces.Default(
204+
color=(0.0, 1.0, 0.0, 1.0),
205+
),
197206
)
198-
mesh_scaled = obj_scaled.vgeoms[0].vmesh.trimesh
207+
assert obj_orig.n_vgeoms == obj_scaled.n_vgeoms
199208

200209
is_isotropic = np.unique(scale).size == 1
201210
with nullcontext() if is_isotropic else pytest.raises(gs.GenesisException):
202211
robot_scaled = scene.add_entity(
203212
gs.morphs.URDF(
204213
file=urdf_path,
214+
file_meshes_are_zup=True,
215+
pos=(0, 0, 1.0),
216+
scale=scale,
205217
convexify=False,
206218
fixed=True,
207-
scale=scale,
208-
file_meshes_are_zup=file_meshes_are_zup,
219+
),
220+
surface=gs.surfaces.Default(
221+
color=(0.0, 0.0, 1.0, 1.0),
209222
),
210223
)
211-
mesh_robot_scaled = robot_scaled.vgeoms[0].vmesh.trimesh
224+
assert robot_scaled.n_vgeoms == obj_scaled.n_vgeoms
212225

213-
if show_viewer:
214-
scene.build()
215226

216-
assert_allclose(mesh_orig.vertices * scale, mesh_scaled.vertices, tol=gs.EPS)
217-
if is_isotropic:
218-
assert_allclose(mesh_robot_scaled.vertices, mesh_scaled.vertices, tol=gs.EPS)
227+
for i_vg in range(obj_orig.n_vgeoms):
228+
mesh_orig = obj_orig.vgeoms[i_vg].vmesh.trimesh.copy()
229+
mesh_orig.apply_transform(gu.trans_quat_to_T(obj_orig.base_link.pos, obj_orig.base_link.quat))
230+
mesh_scaled = obj_scaled.vgeoms[i_vg].vmesh.trimesh.copy()
231+
mesh_scaled.apply_transform(gu.trans_quat_to_T(obj_scaled.base_link.pos, obj_scaled.base_link.quat))
232+
assert_allclose(mesh_orig.vertices, mesh_scaled.vertices, tol=gs.EPS)
233+
234+
if is_isotropic:
235+
mesh_robot_scaled = robot_scaled.vgeoms[i_vg].vmesh.trimesh.copy()
236+
mesh_robot_scaled.apply_transform(
237+
gu.trans_quat_to_T(robot_scaled.base_link.pos, robot_scaled.base_link.quat)
238+
)
239+
assert_allclose(mesh_robot_scaled.vertices, mesh_scaled.vertices, tol=gs.EPS)
219240

220241

221242
@pytest.mark.required
222243
@pytest.mark.parametrize("mesh_file", ["glb/combined_transform.glb", "yup_zup_coverage/cannon_y_-z.stl"])
223-
def test_urdf_scaling(mesh_file, tmp_path, show_viewer):
244+
def test_urdf_scale(mesh_file, tmp_path, show_viewer):
224245
SCALE_FACTOR = 2.0
225246

226247
asset_path = get_hf_dataset(pattern=mesh_file)
@@ -262,7 +283,7 @@ def test_urdf_scaling(mesh_file, tmp_path, show_viewer):
262283
assert_allclose(SCALE_FACTOR * mesh_1.extents, mesh_2.extents, tol=gs.EPS)
263284

264285

265-
# ==================== Coordinate System Tests ====================
286+
# ==================== Y-Up Coordinate Tests ====================
266287

267288

268289
@pytest.mark.required
@@ -647,19 +668,6 @@ def test_2_channels_luminance_alpha_textures(show_viewer):
647668
)
648669

649670

650-
@pytest.mark.required
651-
def test_plane_texture_path_preservation(show_viewer):
652-
"""Test that plane primitives preserve texture paths in metadata."""
653-
scene = gs.Scene(show_viewer=show_viewer, show_FPS=False)
654-
plane = scene.add_entity(gs.morphs.Plane())
655-
656-
# The texture path should be stored in metadata
657-
assert plane.vgeoms[0].vmesh.metadata["texture_path"] == "textures/checker.png"
658-
659-
660-
# ==================== Special Texture Format Tests ====================
661-
662-
663671
@pytest.mark.required
664672
@pytest.mark.parametrize(
665673
"n_channels, float_type",

tests/test_rigid_physics.py

Lines changed: 26 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2711,11 +2711,12 @@ def test_urdf_capsule(tmp_path, show_viewer, tol):
27112711
@pytest.mark.required
27122712
@pytest.mark.required
27132713
@pytest.mark.parametrize("overwrite", [False, True])
2714-
def test_urdf_color_overwrite(overwrite):
2715-
scene = gs.Scene()
2714+
def test_urdf_color_overwrite(overwrite, show_viewer):
2715+
scene = gs.Scene(show_viewer=show_viewer)
27162716
box = scene.add_entity(
27172717
gs.morphs.URDF(
27182718
file="genesis/assets/urdf/blue_box/model.urdf",
2719+
convexify=False,
27192720
),
27202721
surface=gs.surfaces.Default(
27212722
color=(1.0, 0.0, 0.0, 1.0) if overwrite else None,
@@ -2724,26 +2725,49 @@ def test_urdf_color_overwrite(overwrite):
27242725
axis = scene.add_entity(
27252726
gs.morphs.Mesh(
27262727
file="meshes/axis.obj",
2728+
convexify=False,
27272729
),
27282730
surface=gs.surfaces.Default(
27292731
color=(1.0, 0.0, 0.0, 1.0) if overwrite else None,
27302732
),
27312733
)
2734+
asset_path = get_hf_dataset(pattern="work_table.glb")
2735+
table = scene.add_entity(
2736+
gs.morphs.Mesh(
2737+
file=f"{asset_path}/work_table.glb",
2738+
convexify=False,
2739+
),
2740+
surface=gs.surfaces.Default(
2741+
color=(1.0, 0.0, 0.0, 1.0) if overwrite else None,
2742+
),
2743+
)
2744+
if show_viewer:
2745+
scene.build()
27322746
for vgeom in box.vgeoms:
2747+
assert vgeom.vmesh.metadata["is_visual_overwritten"] == overwrite
27332748
visual = vgeom.vmesh.trimesh.visual
27342749
assert visual.defined
27352750
color = np.unique(visual.vertex_colors, axis=0)
27362751
assert_array_equal(color, (255, 0, 0, 255) if overwrite else (0, 0, 255, 255))
27372752
for vgeom in axis.vgeoms:
2753+
assert vgeom.vmesh.metadata["is_visual_overwritten"] == overwrite
27382754
visual = vgeom.vmesh.trimesh.visual
27392755
assert visual.defined
27402756
color = np.unique(visual.vertex_colors, axis=0)
27412757
if overwrite:
27422758
assert_array_equal(color, (255, 0, 0, 255))
27432759
else:
27442760
assert_array_equal(color, [[0, 0, 178, 255], [0, 178, 0, 255], [178, 0, 0, 255], [255, 255, 255, 255]])
2761+
for vgeom in table.vgeoms:
2762+
assert vgeom.vmesh.metadata["is_visual_overwritten"] == overwrite
2763+
visual = vgeom.vmesh.trimesh.visual
2764+
assert visual.defined
2765+
if overwrite:
2766+
color = np.unique(visual.vertex_colors, axis=0)
2767+
assert_array_equal(color, (255, 0, 0, 255))
27452768
for entity in scene.entities:
27462769
for geom in entity.geoms:
2770+
assert geom.mesh.metadata["is_visual_overwritten"]
27472771
visual = geom.mesh.trimesh.visual
27482772
assert visual.defined
27492773
color = np.unique(visual.vertex_colors, axis=0)

0 commit comments

Comments
 (0)