From 0fb691bd220f9db164afa87fa3b0ddf28d80bed2 Mon Sep 17 00:00:00 2001 From: Xinjie Date: Thu, 2 Oct 2025 16:31:59 +0800 Subject: [PATCH] fix(sim): Fix .obj mesh compose issue. (#46) --- embodied_gen/data/convex_decomposer.py | 17 ++++++++++++----- embodied_gen/validators/urdf_convertor.py | 8 ++------ 2 files changed, 14 insertions(+), 11 deletions(-) diff --git a/embodied_gen/data/convex_decomposer.py b/embodied_gen/data/convex_decomposer.py index 57af815..f1c4e97 100644 --- a/embodied_gen/data/convex_decomposer.py +++ b/embodied_gen/data/convex_decomposer.py @@ -45,16 +45,23 @@ def decompose_convex_coacd( mesh = coacd.Mesh(mesh.vertices, mesh.faces) result = coacd.run_coacd(mesh, **params) - combined = sum([trimesh.Trimesh(*m) for m in result]) + + meshes = [] + for v, f in result: + meshes.append(trimesh.Trimesh(v, f)) # Compute collision_scale because convex decomposition usually makes the mesh larger. if auto_scale: - convex_mesh_shape = np.ptp(combined.vertices, axis=0) + all_mesh = sum([trimesh.Trimesh(*m) for m in result]) + convex_mesh_shape = np.ptp(all_mesh.vertices, axis=0) visual_mesh_shape = np.ptp(mesh.vertices, axis=0) - rescale = visual_mesh_shape / convex_mesh_shape - combined.vertices *= rescale + scale_factor *= visual_mesh_shape / convex_mesh_shape + + combined = trimesh.Scene() + for mesh_part in meshes: + mesh_part.vertices *= scale_factor + combined.add_geometry(mesh_part) - combined.vertices *= scale_factor combined.export(outfile) diff --git a/embodied_gen/validators/urdf_convertor.py b/embodied_gen/validators/urdf_convertor.py index 144f0df..7341ed7 100644 --- a/embodied_gen/validators/urdf_convertor.py +++ b/embodied_gen/validators/urdf_convertor.py @@ -282,16 +282,12 @@ class URDFGenerator(object): d_params = dict( threshold=0.05, max_convex_hull=100, verbose=False ) - filename = f"{os.path.splitext(obj_name)[0]}_collision.ply" + filename = f"{os.path.splitext(obj_name)[0]}_collision.obj" output_path = os.path.join(mesh_folder, filename) decompose_convex_mesh( mesh_output_path, output_path, **d_params ) - obj_filename = filename.replace(".ply", ".obj") - trimesh.load(output_path).export( - f"{mesh_folder}/{obj_filename}" - ) - collision_mesh = f"{self.output_mesh_dir}/{obj_filename}" + collision_mesh = f"{self.output_mesh_dir}/{filename}" except Exception as e: logger.warning( f"Convex decomposition failed for {output_path}, {e}."