diff --git a/genesis/engine/entities/particle_entity.py b/genesis/engine/entities/particle_entity.py index 87e0acb114..8879a8c557 100644 --- a/genesis/engine/entities/particle_entity.py +++ b/genesis/engine/entities/particle_entity.py @@ -247,7 +247,8 @@ def sample(self): self._vfaces = np.array([], dtype=gs.np_float) elif isinstance(self._morph, gs.options.morphs.MeshSet): for i in range(len(self._morph.files)): - pos_i, euler_i = map(np.asarray, (self._morph.poss[i], self._morph.eulers[i])) + pos_i = np.asarray(self._morph.poss[i], dtype=gs.np_float) + euler_i = np.asarray(self._morph.eulers[i], dtype=gs.np_float) quat_i = gs.utils.geom.xyz_to_quat(euler_i, rpy=True, degrees=True) self._vmesh[i].apply_transform(gu.trans_quat_to_T(pos_i, quat_i)) @@ -284,7 +285,8 @@ def sample(self): origin = np.mean(self._morph.poss, dtype=gs.np_float) else: # transform vmesh - pos, quat = map(np.asarray, (self._morph.pos, self._morph.quat)) + pos = np.asarray(self._morph.pos, dtype=gs.np_float) + quat = np.asarray(self._morph.quat, dtype=gs.np_float) self._vmesh.apply_transform(gu.trans_quat_to_T(pos, quat)) # transform particles particles = gu.transform_by_trans_quat( diff --git a/genesis/engine/materials/MPM/elasto_plastic.py b/genesis/engine/materials/MPM/elasto_plastic.py index 51890bbf9c..f618f8cf8b 100644 --- a/genesis/engine/materials/MPM/elasto_plastic.py +++ b/genesis/engine/materials/MPM/elasto_plastic.py @@ -12,7 +12,8 @@ class ElastoPlastic(Base): Note ---- - Default yield ratio comes from the SNOW material in taichi's MPM implementation: https://github.com/taichi-dev/taichi_elements/blob/d19678869a28b09a32ef415b162e35dc929b792d/engine/mpm_solver.py#L434 + Default yield ratio comes from the SNOW material in taichi's MPM implementation: + https://github.com/taichi-dev/taichi_elements/blob/d19678869a28b09a32ef415b162e35dc929b792d/engine/mpm_solver.py#L434 Parameters ---------- diff --git a/genesis/options/surfaces.py b/genesis/options/surfaces.py index dfc357d940..9f857e26dc 100644 --- a/genesis/options/surfaces.py +++ b/genesis/options/surfaces.py @@ -13,12 +13,16 @@ class Surface(Options): """ Base class for all surfaces types in Genesis. - A ``Surface`` object encapsulates all visual information used for rendering an entity or its sub-components (links, geoms, etc.) - The surface contains different types textures: diffuse_texture, specular_texture, roughness_texture, metallic_texture, transmission_texture, normal_texture, and emissive_texture. Each one of them is a `gs.textures.Texture` object. + + A ``Surface`` object encapsulates all visual information used for rendering an entity or its sub-components (links, + geoms, ...). The surface contains different types textures: diffuse_texture, specular_texture, roughness_texture, + metallic_texture, transmission_texture, normal_texture, and emissive_texture. Each one of them is a + `gs.textures.Texture` object. Tip --- - If any of the textures only has single value (instead of a map), you can use the shortcut attribute (e.g., `color`, `roughness`, `metallic`, `emissive`) instead of creating a texture object. + If any of the textures only has single value (instead of a map), you can use the shortcut attribute (e.g., `color`, + `roughness`, `metallic`, `emissive`) instead of creating a texture object. Note ---- @@ -49,26 +53,26 @@ class Surface(Options): emissive_texture : gs.textures.Texture | None, optional Emissive texture of the surface. default_roughness : float, optional - Default roughness value when `roughness` is not set and the asset does not have a roughness texture. Defaults to 1.0. + Default roughness value when `roughness` is not set and the asset does not have a roughness texture. Defaults + to 1.0. vis_mode : str | None, optional - How the entity should be visualized. Possible values are ['visual', 'particle', 'collision', 'sdf', 'recon']. - + How the entity should be visualized, e.g. - 'visual': Render the entity's visual geometry. - 'collision': Render the entity's collision geometry. - 'particle': Render the entity's particle representation (if applicable). - 'sdf': Render the reconstructed surface mesh of the entity's sdf. - 'recon': Render the reconstructed surface mesh of the entity's particle representation. - smooth : bool, optional Whether to smooth face normals by interpolating vertex normals. double_sided : bool | None, optional - Whether to render both sides of the surface. Useful for non-watertight 2D objects. Defaults to True for Cloth material and False for others. + Whether to render both sides of the surface. Useful for non-watertight 2D objects. Defaults to True for Cloth + material and False for others. beam_angle : float The beam angle of emission. Defaults to 180.0. normal_diff_clamp : float, optional Controls the threshold for computing surface normals by interpolating vertex normals. recon_backend : str, optional - Backend for surface reconstruction. Possible values are ['splashsurf', 'openvdb']. + Backend for surface reconstruction. Possible values are ['splashsurf', 'openvdb']. Defaults to 'splashsurf'. generate_foam : bool, optional Whether to generate foam particles for visual effects for particle-based entities. foam_options : gs.options.FoamOptions, optional @@ -92,14 +96,12 @@ class Surface(Options): default_roughness: float = 1.0 - vis_mode: Optional[str] = None # ['visual', 'particle', 'collision', 'sdf', 'recon'] - smooth: bool = True # whether to smooth face normals by interpolating vertex normals - double_sided: Optional[bool] = ( - None # whether to render both sides of the surface. Defaults to True for Cloth material and False for others. - ) + vis_mode: Optional[str] = None + smooth: bool = True + double_sided: Optional[bool] = None beam_angle: float = 180 normal_diff_clamp: float = 180 - recon_backend: str = "splashsurf" # backend for surface recon + recon_backend: str = "splashsurf" generate_foam: bool = False foam_options: Optional[FoamOptions] = None diff --git a/genesis/utils/particle.py b/genesis/utils/particle.py index bf52484ae7..96e69b5553 100644 --- a/genesis/utils/particle.py +++ b/genesis/utils/particle.py @@ -6,6 +6,7 @@ import tempfile import igl +import pysplashsurf import numpy as np import trimesh @@ -347,48 +348,26 @@ def parse_args(backend): return trimesh.Trimesh(vertices, faces, process=False) elif "splashsurf" in backend: - if gs.platform != "Linux": - gs.raise_exception("Backend 'splashsurf' is only supported on Linux.") - - fd, xyz_path = tempfile.mkstemp(suffix=".xyz") - os.close(fd) - fd, obj_path = tempfile.mkstemp(suffix=".obj") - os.close(fd) - positions.astype(np.float32, copy=False).tofile(xyz_path) - # Suggested value is 1.4-1.6, but 1.0 seems more detailed - radius_scale = args_dict.get("rscale", 1.0) - smooth_iter = args_dict.get("smooth") - r = radius * radius_scale - - try: - command = ["splashsurf", "reconstruct", xyz_path, f"-r={r}", "-c=0.8", "-l=2.0", "-t=0.6", "-o", obj_path] - if smooth_iter is not None: - command += [ - "--mesh-cleanup=on", - "--mesh-smoothing-weights=on", - f"--mesh-smoothing-iters={int(smooth_iter)}", - "--normals=on", - "--normals-smoothing-iters=10", - ] - - result = subprocess.run(map(str, command), capture_output=True, text=True) - if result.stdout: - gs.logger.debug(result.stdout) - if result.stderr: - gs.logger.warning(result.stderr) - if os.path.getsize(obj_path) == 0: - raise OSError("Output OBJ file is empty.") - - # Read the generated OBJ file - mesh = trimesh.load_mesh(obj_path) - gs.logger.debug(f"[splashsurf]: reconstruct vertices: {mesh.vertices.shape}, {mesh.faces.shape}") - except OSError as e: - gs.raise_exception_from("Surface reconstruction failed.", e) - finally: - os.remove(xyz_path) - os.remove(obj_path) - + mesh_with_data, _ = pysplashsurf.reconstruction_pipeline( + positions, + particle_radius=radius * args_dict.get("rscale", 1.0), + smoothing_length=2.0, + cube_size=0.8, + iso_surface_threshold=0.6, + mesh_smoothing_weights=True, + mesh_smoothing_iters=int(args_dict.get("smooth", 25)), + normals_smoothing_iters=10, + mesh_cleanup=True, + compute_normals=True, + enable_multi_threading=True, + ) + mesh = trimesh.Trimesh( + vertices=mesh_with_data.mesh.vertices, + faces=mesh_with_data.mesh.triangles, + face_normals=mesh_with_data.get_point_attribute("normals"), + ) + gs.logger.debug(f"[splashsurf]: reconstruct vertices: {mesh.vertices.shape}, {mesh.faces.shape}") return mesh else: diff --git a/genesis/utils/path_planing.py b/genesis/utils/path_planing.py index 73b0bcf210..23b4bbc729 100644 --- a/genesis/utils/path_planing.py +++ b/genesis/utils/path_planing.py @@ -617,12 +617,11 @@ def plan( @ti.data_oriented class RRTConnect(PathPlanner): - def _init_rrt_connect_fields(self, goal_bias=0.1, max_nodes=4000, pos_tol=5e-3, max_step_size=0.05): + def _init_rrt_connect_fields(self, goal_bias=0.1, max_nodes=4000, max_step_size=0.05): self._is_rrt_connect_init = getattr(self, "_is_rrt_connect_init", False) if not self._is_rrt_connect_init: self._rrt_goal_bias = goal_bias self._rrt_max_nodes = max_nodes - self._rrt_pos_tol = pos_tol self._rrt_max_step_size = max_step_size self._rrt_start_configuration = ti.field( dtype=gs.ti_float, shape=self._solver._batch_shape(self._entity.n_qs) diff --git a/genesis/vis/rasterizer_context.py b/genesis/vis/rasterizer_context.py index d036aba3be..93a290a10a 100644 --- a/genesis/vis/rasterizer_context.py +++ b/genesis/vis/rasterizer_context.py @@ -489,7 +489,8 @@ def update_mpm(self, buffer_updates): if self.sim.mpm_solver.is_active(): idx = self.rendered_envs_idx[0] particles_all = self.sim.mpm_solver.particles_render.pos.to_numpy()[:, idx] - active_all = self.sim.mpm_solver.particles_render.active.to_numpy(dtype=np.bool_)[:, idx] + active_all = self.sim.mpm_solver.particles_render.active.to_numpy(dtype=gs.np_bool)[:, idx] + active_all = active_all.astype(dtype=np.bool_, copy=False) vverts_all = self.sim.mpm_solver.vverts_render.pos.to_numpy()[:, idx, :] for mpm_entity in self.sim.mpm_solver.entities: @@ -554,7 +555,8 @@ def update_sph(self, buffer_updates): if self.sim.sph_solver.is_active(): idx = self.rendered_envs_idx[0] particles_all = self.sim.sph_solver.particles_render.pos.to_numpy()[:, idx] - active_all = self.sim.sph_solver.particles_render.active.to_numpy(dtype=np.bool_)[:, idx] + active_all = self.sim.sph_solver.particles_render.active.to_numpy(dtype=gs.np_bool)[:, idx] + active_all = active_all.astype(dtype=np.bool_, copy=False) for sph_entity in self.sim.sph_solver.entities: if sph_entity.surface.vis_mode == "recon": @@ -630,7 +632,8 @@ def update_pbd(self, buffer_updates): idx = self.rendered_envs_idx[0] particles_all = self.sim.pbd_solver.particles_render.pos.to_numpy()[:, idx] particles_vel_all = self.sim.pbd_solver.particles_render.vel.to_numpy()[:, idx] - active_all = self.sim.pbd_solver.particles_render.active.to_numpy(dtype=np.bool_)[:, idx] + active_all = self.sim.pbd_solver.particles_render.active.to_numpy(dtype=gs.np_bool)[:, idx] + active_all = active_all.astype(dtype=np.bool_, copy=False) vverts_all = self.sim.pbd_solver.vverts_render.pos.to_numpy()[:, idx] for pbd_entity in self.sim.pbd_solver.entities: diff --git a/pyproject.toml b/pyproject.toml index de105929c1..04e4dc5f24 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -59,6 +59,8 @@ dependencies = [ "gs-madrona>=0.0.2; platform_system == 'Linux' and (platform_machine == 'x86_64' or platform_machine == 'AMD64')", # Used for mesh simplification "fast_simplification>=0.1.12", + # Surface reconstruction library for particle data from SPH simulations + "pysplashsurf", ] [project.optional-dependencies] diff --git a/tests/test_deformable_physics.py b/tests/test_deformable_physics.py index bea3c30368..25eb7eaedd 100644 --- a/tests/test_deformable_physics.py +++ b/tests/test_deformable_physics.py @@ -150,7 +150,6 @@ def test_deformable_parallel(show_viewer): ), surface=gs.surfaces.Default( color=(0.2, 0.6, 1.0, 1.0), - vis_mode="particle", ), ) mpm_cube = scene.add_entity( @@ -161,7 +160,6 @@ def test_deformable_parallel(show_viewer): ), surface=gs.surfaces.Default( color=(0.9, 0.8, 0.2, 1.0), - vis_mode="particle", ), ) diff --git a/tests/test_render.py b/tests/test_render.py index c69e71d640..1aca0f16d2 100644 --- a/tests/test_render.py +++ b/tests/test_render.py @@ -387,6 +387,31 @@ def test_point_cloud(show_viewer): assert_allclose(np.linalg.norm((0.0, 0.0, CAMERA_DIST) - point_cloud, axis=-1), SPHERE_RADIUS, atol=1e-2) +@pytest.mark.required +def test_splashsurf_surface_reconstruction(show_viewer): + scene = gs.Scene( + show_viewer=show_viewer, + ) + water = scene.add_entity( + material=gs.materials.SPH.Liquid(), + morph=gs.morphs.Box( + pos=(0.15, 0.15, 0.22), + size=(0.25, 0.25, 0.4), + ), + surface=gs.surfaces.Default( + color=(0.2, 0.6, 1.0, 1.0), + vis_mode="recon", + ), + ) + cam = scene.add_camera( + pos=(1.3, 1.3, 0.8), + lookat=(0.0, 0.0, 0.2), + GUI=show_viewer, + ) + scene.build() + cam.render(rgb=True, depth=False, segmentation=False, colorize_seg=False, normal=False) + + @pytest.mark.required def test_batched_mounted_camera_rendering(show_viewer, tol): scene = gs.Scene(