Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
26 changes: 15 additions & 11 deletions genesis/engine/mesh.py
Original file line number Diff line number Diff line change
Expand Up @@ -343,21 +343,19 @@ def from_morph_surface(cls, morph, surface=None):
if morph.is_format(gs.options.morphs.MESH_FORMATS):
meshes = mu.parse_mesh_trimesh(morph.file, morph.group_by_material, morph.scale, surface)
elif morph.is_format(gs.options.morphs.GLTF_FORMATS):
if not morph.parse_glb_with_zup:
if morph.parse_glb_with_trimesh:
meshes = mu.parse_mesh_trimesh(morph.file, morph.group_by_material, morph.scale, surface)
else:
meshes = gltf_utils.parse_mesh_glb(morph.file, morph.group_by_material, morph.scale, surface)
if morph.parse_glb_with_zup:
for mesh in meshes:
mesh.convert_to_zup()
else:
gs.logger.warning(
"GLTF is using y-up while Genesis uses z-up. Please set parse_glb_with_zup=True"
" in morph options if you find the mesh is 90-degree rotated. We will set parse_glb_with_zup=True"
" and rotate glb mesh by default later and gradually enforce this option."
)
if morph.parse_glb_with_trimesh:
meshes = mu.parse_mesh_trimesh(morph.file, morph.group_by_material, morph.scale, surface)
if morph.parse_glb_with_zup:
for mesh in meshes:
mesh.apply_transform(mu.Y_UP_TRANSFORM.T)
else:
meshes = gltf_utils.parse_mesh_glb(
morph.file, morph.group_by_material, morph.scale, surface, morph.parse_glb_with_zup
)
elif morph.is_format(gs.options.morphs.USD_FORMATS):
import genesis.utils.usda as usda_utils

Expand Down Expand Up @@ -385,7 +383,7 @@ def from_morph_surface(cls, morph, surface=None):
else:
gs.raise_exception()

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

def set_color(self, color):
Expand All @@ -404,6 +402,12 @@ def update_trimesh_visual(self):
"""
self._mesh.visual = mu.surface_uvs_to_trimesh_visual(self.surface, self.uvs, len(self.verts))

def convert_to_zup(self):
"""
Convert the mesh to z-up.
"""
self._mesh.apply_transform(mu.Y_UP_TRANSFORM.T)

def apply_transform(self, T):
"""
Apply a 4x4 transformation matrix (translation on the right column) to the mesh.
Expand Down
12 changes: 1 addition & 11 deletions genesis/ext/urdfpy/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -245,24 +245,14 @@ def load_meshes(filename):
meshes = trimesh.load(filename, process=False)

if isinstance(meshes, trimesh.Scene):
T = np.array([
[ 1., 0., 0., 0.],
[ 0., 0., -1., 0.],
[ 0., 1., 0., 0.],
[ 0., 0., 0., 1.]], dtype=np.float32,
)
# FIXME: Scene.dump() has bug that uses copy without include_cache=True,
# it will lose the vertex normals.
results = []
is_glb = filename.endswith((".gltf", ".glb"))
for node_name in meshes.graph.nodes_geometry:
transform, geometry_name = meshes.graph[node_name]
current = meshes.geometry[geometry_name].copy(include_cache=True)
if isinstance(current, trimesh.Trimesh):
if is_glb:
current.apply_transform(T @ transform)
else:
current.apply_transform(transform)
current.apply_transform(transform)
current.metadata["name"] = geometry_name
current.metadata["node"] = node_name
results.append(current)
Expand Down
10 changes: 9 additions & 1 deletion genesis/options/morphs.py
Original file line number Diff line number Diff line change
Expand Up @@ -503,6 +503,8 @@ class FileMorph(Morph):
0.0 to enforce decomposition, float("inf") to disable it completely. Defaults to float("inf").
coacd_options : CoacdOptions, optional
Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
parse_glb_with_zup : bool, optional
Whether to use zup to load glb files. Defaults to False.
visualization : bool, optional
Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
purposes. Defaults to True. `visualization` and `collision` cannot both be False.
Expand All @@ -526,6 +528,7 @@ class FileMorph(Morph):
decompose_robot_error_threshold: float = float("inf")
coacd_options: Optional[CoacdOptions] = None
recompute_inertia: bool = False
parse_glb_with_zup: bool = False

def __init__(self, **data):
super().__init__(**data)
Expand Down Expand Up @@ -681,7 +684,6 @@ class Mesh(FileMorph, TetGenMixin):
"""

parse_glb_with_trimesh: bool = False
parse_glb_with_zup: bool = False

# Rigid specific
fixed: bool = False
Expand Down Expand Up @@ -771,6 +773,8 @@ class MJCF(FileMorph):
0.0 to enforce decomposition, float("inf") to disable it completely. Defaults to float("inf").
coacd_options : CoacdOptions, optional
Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
parse_glb_with_zup : bool, optional
Whether to use zup to load glb files. Defaults to False. Mujoco currently does not support glb mesh.
visualization : bool, optional
Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
purposes. Defaults to True. `visualization` and `collision` cannot both be False.
Expand Down Expand Up @@ -872,6 +876,8 @@ class URDF(FileMorph):
0.0 to enforce decomposition, float("inf") to disable it completely. Defaults to float("inf").
coacd_options : CoacdOptions, optional
Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
parse_glb_with_zup : bool, optional
Whether to use zup to load glb files. Defaults to False.
visualization : bool, optional
Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
purposes. Defaults to True. `visualization` and `collision` cannot both be False.
Expand Down Expand Up @@ -965,6 +971,8 @@ class Drone(FileMorph):
0.0 to enforce decomposition, float("inf") to disable it completely. Defaults to float("inf").
coacd_options : CoacdOptions, optional
Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
parse_glb_with_zup : bool, optional
Whether to use zup to load glb files. Defaults to False.
visualization : bool, optional
Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
purposes. Defaults to True. `visualization` and `collision` cannot both be False.
Expand Down
4 changes: 1 addition & 3 deletions genesis/utils/gltf.py
Original file line number Diff line number Diff line change
Expand Up @@ -290,7 +290,7 @@ def parse_glb_tree(glb, node_index):
return mesh_list


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

if convert_zup:
mesh_transform @= mu.Y_UP_TRANSFORM
points, normals = mu.apply_transform(mesh_transform, points, normals)
if normals is None:
normals = trimesh.Trimesh(points, triangles, process=False).vertex_normals
Expand Down
18 changes: 13 additions & 5 deletions genesis/utils/urdf.py
Original file line number Diff line number Diff line change
Expand Up @@ -114,17 +114,25 @@ def parse_urdf(morph, surface):
if geom.geometry.geometry.scale is not None:
scale *= geom.geometry.geometry.scale

mesh_path = urdfpy.utils.get_filename(os.path.dirname(path), geom.geometry.geometry.filename)
mesh = gs.Mesh.from_trimesh(
tmesh,
scale=scale,
surface=gs.surfaces.Collision() if geom_is_col else surface,
metadata={
"mesh_path": urdfpy.utils.get_filename(
os.path.dirname(path), geom.geometry.geometry.filename
)
},
metadata={"mesh_path": mesh_path},
)

if mesh_path.lower().endswith(gs.morphs.GLTF_FORMATS):
if morph.parse_glb_with_zup:
mesh.convert_to_zup()
else:
gs.logger.warning(
"This URDF file contains GLTF mesh, which is using y-up while Genesis uses z-up."
" Please set parse_glb_with_zup=True in morph options if you find the mesh is"
" 90-degree rotated. We will set parse_glb_with_zup=True and rotate glb mesh by"
" default later and gradually enforce this option."
)

if not geom_is_col and (morph.prioritize_urdf_material or not tmesh.visual.defined):
if geom.material is not None and geom.material.color is not None:
mesh.set_color(geom.material.color)
Expand Down
12 changes: 10 additions & 2 deletions tests/test_mesh.py
Original file line number Diff line number Diff line change
Expand Up @@ -371,18 +371,26 @@ def test_urdf_with_existing_glb(tmp_path, show_viewer):
show_viewer=show_viewer,
show_FPS=False,
)
robot_urdf = scene.add_entity(
robot_urdf_yup = scene.add_entity(
gs.morphs.URDF(
file=urdf_path,
),
)
robot_urdf_zup = scene.add_entity(
gs.morphs.URDF(
file=urdf_path,
parse_glb_with_zup=True,
),
)
robot_mesh = scene.add_entity(
gs.morphs.Mesh(
file=glb_path,
parse_glb_with_zup=True,
),
)
check_gs_meshes(robot_urdf.vgeoms[0].vmesh, robot_mesh.vgeoms[0].vmesh, "robot")
check_gs_meshes(robot_urdf_zup.vgeoms[0].vmesh, robot_mesh.vgeoms[0].vmesh, "robot")
robot_urdf_yup.vgeoms[0].vmesh.convert_to_zup()
check_gs_meshes(robot_urdf_yup.vgeoms[0].vmesh, robot_mesh.vgeoms[0].vmesh, "robot")


@pytest.mark.required
Expand Down
Loading