Skip to content
Merged
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
3 changes: 2 additions & 1 deletion .github/workflows/generic.yml
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ jobs:
TI_ENABLE_METAL: "0"
TI_ENABLE_OPENGL: "0"
TI_ENABLE_VULKAN: "0"
TI_DEBUG: "0"

runs-on: ${{ matrix.OS }}
if: github.event_name != 'release'
Expand Down Expand Up @@ -112,7 +113,7 @@ jobs:

- name: Run unit tests
run: |
pytest -v --logical --forked -m required ./tests
pytest -v --logical --dev --forked -m required ./tests

- name: Save Updated Taichi Kernel Cache
if: always()
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/production.yml
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ jobs:
bash -c "
pip install --extra-index-url https://pypi.nvidia.com/ omniverse-kit && \
pip install -e '.[dev,render,usd]' && \
pytest -v --forked ./tests
pytest -v --dev --forked ./tests
"

- name: Run benchmarks
Expand Down
4 changes: 2 additions & 2 deletions genesis/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -211,8 +211,8 @@ def init(
with redirect_stdout(_ti_outputs):
ti.init(
arch=ti_arch,
# debug is causing segfault on some machines
debug=False,
# Add a (hidden) mechanism to forceable disable taichi debug mode as it is still a bit experimental
debug=debug and backend == gs.cpu and (os.environ.get("TI_DEBUG") != "0"),
check_out_of_bound=debug,
# force_scalarize_matrix=True for speeding up kernel compilation
# Turning off 'force_scalarize_matrix' is causing numerical instabilities ('nan') on MacOS
Expand Down
2 changes: 1 addition & 1 deletion genesis/engine/couplers/legacy_coupler.py
Original file line number Diff line number Diff line change
Expand Up @@ -454,7 +454,7 @@ def fem_surface_force(self, f: ti.i32):
mpm_grid_I = mpm_base - self.mpm_solver.grid_offset + mpm_offset
mpm_grid_mass = self.mpm_solver.grid[f, mpm_grid_I, i_b].mass / self.mpm_solver.p_vol_scale

mpm_weight = ti.cast(1.0, gs.ti_float)
mpm_weight = gs.ti_float(1.0)
for d in ti.static(range(3)):
mpm_weight *= mpm_w[mpm_offset[d]][d]

Expand Down
2 changes: 1 addition & 1 deletion genesis/engine/entities/pbd_entity.py
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ def _kernel_add_particles_edges_to_solver(
self.solver.particles[i_p, i_b].dpos = ti.Vector.zero(gs.ti_float, 3)
self.solver.particles[i_p, i_b].free = True

self.solver.particles_ng[i_p, i_b].active = active
self.solver.particles_ng[i_p, i_b].active = ti.cast(active, gs.ti_bool)

for i_e_ in range(self.n_edges):
i_e = i_e_ + self._edge_start
Expand Down
15 changes: 8 additions & 7 deletions genesis/engine/entities/tool_entity/mesh.py
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ def sdf(self, f, pos_world, i_b):
def sdf_(self, pos_voxels):
# sdf value from voxels coordinate
base = ti.floor(pos_voxels, gs.ti_int)
signed_dist = ti.cast(0.0, gs.ti_float)
signed_dist = gs.ti_float(0.0)
if (base >= self.sdf_res - 1).any() or (base < 0).any():
signed_dist = 1.0
else:
Expand Down Expand Up @@ -117,7 +117,7 @@ def normal(self, f, pos_world, i_b):
@ti.func
def normal_(self, pos_voxels):
# since we are in voxels frame, delta can be a relatively big value
delta = ti.cast(1e-2, gs.ti_float)
delta = gs.ti_float(1e-2)
normal_vec = ti.Vector([0, 0, 0], dt=gs.ti_float)

for i in ti.static(range(3)):
Expand Down Expand Up @@ -146,15 +146,15 @@ def collide(self, f, pos_world, vel_mat, i_b):
signed_dist = self.sdf(f, pos_world, i_b)
# bigger coup_softness implies that the coupling influence extends further away from the object.
influence = ti.min(ti.exp(-signed_dist / max(gs.EPS, self.material.coup_softness)), 1)
if signed_dist <= 0 or influence > 0.1:
if signed_dist <= 0.0 or influence > 0.1:
vel_collider = self.vel_collider(f, pos_world, i_b)

# v w.r.t collider
rel_v = vel_mat - vel_collider
normal_vec = self.normal(f, pos_world, i_b)
normal_component = rel_v.dot(normal_vec)

if normal_component < 0:
if normal_component < 0.0:
# remove inward velocity
rel_v_t = rel_v - normal_component * normal_vec
rel_v_t_norm = rel_v_t.norm(gs.EPS)
Expand All @@ -165,9 +165,10 @@ def collide(self, f, pos_world, vel_mat, i_b):
)

# tangential component after friction
flag = ti.cast(normal_component < 0, gs.ti_float)
rel_v_t = rel_v_t_friction * flag + rel_v_t * (1 - flag)
vel_mat = vel_collider + rel_v_t * influence + rel_v * (1 - influence)
# FIXME: This formula could be simplified since flag = 1.0 systematically.
flag = ti.cast(normal_component < 0.0, gs.ti_float)
rel_v_t = rel_v_t_friction * flag + rel_v_t * (1.0 - flag)
vel_mat = vel_collider + rel_v_t * influence + rel_v * (1.0 - influence)

return vel_mat

Expand Down
4 changes: 2 additions & 2 deletions genesis/engine/solvers/fem_solver.py
Original file line number Diff line number Diff line change
Expand Up @@ -313,12 +313,12 @@ def _init_surface_info(self):
@ti.kernel
def compute_surface_vertices(self):
for i_v in range(self.n_vertices):
self.vertices_on_surface[i_v] = 0
self.vertices_on_surface[i_v] = False

for i_s in range(self.n_surfaces):
tri2v = self.surface[i_s].tri2v
for i in ti.static(range(3)):
self.vertices_on_surface[tri2v[i]] = 1
self.vertices_on_surface[tri2v[i]] = True

@ti.kernel
def compute_surface_elements(self):
Expand Down
12 changes: 6 additions & 6 deletions genesis/engine/solvers/mpm_solver.py
Original file line number Diff line number Diff line change
Expand Up @@ -383,7 +383,7 @@ def p2g(self, f: ti.i32):
w = [0.5 * (1.5 - fx) ** 2, 0.75 - (fx - 1) ** 2, 0.5 * (fx - 0.5) ** 2]
for offset in ti.static(ti.grouped(self.stencil_range())):
dpos = (offset.cast(gs.ti_float) - fx) * self._dx
weight = ti.cast(1.0, gs.ti_float)
weight = gs.ti_float(1.0)
for d in ti.static(range(3)):
weight *= w[offset[d]][d]

Expand Down Expand Up @@ -439,7 +439,7 @@ def g2p(self, f: ti.i32):
for offset in ti.static(ti.grouped(self.stencil_range())):
dpos = offset.cast(gs.ti_float) - fx
grid_vel = self.grid[f, base - self._grid_offset + offset, i_b].vel_out
weight = ti.cast(1.0, gs.ti_float)
weight = gs.ti_float(1.0)
for d in ti.static(range(3)):
weight *= w[offset[d]][d]

Expand Down Expand Up @@ -962,11 +962,11 @@ def set_state(self, f, state, envs_idx=None):
def _kernel_update_render_fields(self, f: ti.i32):
for i_p, i_b in ti.ndrange(self._n_particles, self._B):
if self.particles_ng[f, i_p, i_b].active:
self.particles_render[i_b, i_p].pos = self.particles[f, i_p, i_b].pos
self.particles_render[i_b, i_p].vel = self.particles[f, i_p, i_b].vel
self.particles_render[i_p, i_b].pos = self.particles[f, i_p, i_b].pos
self.particles_render[i_p, i_b].vel = self.particles[f, i_p, i_b].vel
else:
self.particles_render[i_b, i_p].pos = gu.ti_nowhere()
self.particles_render[i_b, i_p].active = self.particles_ng[f, i_p, i_b].active
self.particles_render[i_p, i_b].pos = gu.ti_nowhere()
self.particles_render[i_p, i_b].active = self.particles_ng[f, i_p, i_b].active

for i_v, i_b in ti.ndrange(self._n_vverts, self._B):
vvert_pos = ti.Vector.zero(gs.ti_float, 3)
Expand Down
12 changes: 6 additions & 6 deletions genesis/engine/solvers/rigid/rigid_solver_decomp.py
Original file line number Diff line number Diff line change
Expand Up @@ -5283,11 +5283,11 @@ def func_torque_and_passive_force(
joint_type = joints_info.type[I_j]

if joint_type != gs.JOINT_TYPE.FREE and joint_type != gs.JOINT_TYPE.FIXED:
dof_start = links_info.dof_start[I_l]
q_start = links_info.q_start[I_l]
q_end = links_info.q_end[I_l]
dof_start = links_info.dof_start[I_l]
dof_end = links_info.dof_end[I_l]

for j_d in range(q_end - q_start):
for j_d in range(dof_end - dof_start):
I_d = (
[dof_start + j_d, i_b]
if ti.static(static_rigid_sim_config.batch_dofs_info)
Expand All @@ -5313,11 +5313,11 @@ def func_torque_and_passive_force(
joint_type = joints_info.type[I_j]

if joint_type != gs.JOINT_TYPE.FREE and joint_type != gs.JOINT_TYPE.FIXED:
dof_start = links_info.dof_start[I_l]
q_start = links_info.q_start[I_l]
q_end = links_info.q_end[I_l]
dof_start = links_info.dof_start[I_l]
dof_end = links_info.dof_end[I_l]

for j_d in range(q_end - q_start):
for j_d in range(dof_end - dof_start):
I_d = (
[dof_start + j_d, i_b]
if ti.static(static_rigid_sim_config.batch_dofs_info)
Expand Down
2 changes: 1 addition & 1 deletion genesis/engine/solvers/sph_solver.py
Original file line number Diff line number Diff line change
Expand Up @@ -628,7 +628,7 @@ def _density_solve(self, f: ti.i32):

@ti.func
def cubic_kernel(self, r_norm):
res = ti.cast(0.0, gs.ti_float)
res = gs.ti_float(0.0)
h = self._support_radius
# value of cubic spline smoothing kernel
k = 1.0
Expand Down
3 changes: 2 additions & 1 deletion pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,8 @@ readme = "README.md"
requires-python = ">=3.10,<3.14"
dependencies = [
"psutil",
"taichi >= 1.7.2",
# Taichi debug mode has been fixed in 1.7.4
"taichi >= 1.7.4",
"pydantic >= 2.7.1",
"numpy >= 1.26.4",
"trimesh",
Expand Down
9 changes: 3 additions & 6 deletions tests/conftest.py
Original file line number Diff line number Diff line change
Expand Up @@ -148,6 +148,7 @@ def pytest_addoption(parser):
"--logical", action="store_true", default=False, help="Consider logical cores in default number of workers."
)
parser.addoption("--vis", action="store_true", default=False, help="Enable interactive viewer.")
parser.addoption("--dev", action="store_true", default=False, help="Enable genesis debug mode.")


@pytest.fixture(scope="session")
Expand Down Expand Up @@ -276,12 +277,8 @@ def initialize_genesis(request, backend, taichi_offline_cache):
from genesis.utils.misc import ALLOCATE_TENSOR_WARNING

logging_level = request.config.getoption("--log-cli-level")
if backend == gs.cpu:
precision = "64"
debug = True
else:
precision = "32"
debug = False
debug = request.config.getoption("--dev")
precision = "64" if backend == gs.cpu else "32"

try:
if not taichi_offline_cache:
Expand Down
4 changes: 2 additions & 2 deletions tests/test_render.py
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ def test_segmentation(segmentation_level, particle_mode):


@pytest.mark.required
@pytest.mark.flaky(reruns=3, condition=(sys.platform == "darwin"), reason="Flaky on MacOS with CPU-based OpenGL")
@pytest.mark.xfail(sys.platform == "darwin", reason="Flaky on MacOS with CPU-based OpenGL")
def test_batched_offscreen_rendering(tmp_path, show_viewer, tol):
scene = gs.Scene(
vis_options=gs.options.VisOptions(
Expand Down Expand Up @@ -275,7 +275,7 @@ def test_batched_offscreen_rendering(tmp_path, show_viewer, tol):


@pytest.mark.required
@pytest.mark.flaky(reruns=3, condition=(sys.platform == "darwin"), reason="Flaky on MacOS with CPU-based OpenGL")
@pytest.mark.xfail(sys.platform == "darwin", reason="Flaky on MacOS with CPU-based OpenGL")
def test_render_api(show_viewer):
scene = gs.Scene(
show_viewer=show_viewer,
Expand Down
2 changes: 1 addition & 1 deletion tests/test_rigid_physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -528,7 +528,7 @@ def test_rope_ball(gs_sim, mj_sim, gs_solver, tol):
gs_sim.rigid_solver.set_dofs_position(gs_sim.rigid_solver.get_dofs_position())

check_mujoco_model_consistency(gs_sim, mj_sim, tol=tol)
simulate_and_check_mujoco_consistency(gs_sim, mj_sim, num_steps=300, tol=5e-9)
simulate_and_check_mujoco_consistency(gs_sim, mj_sim, num_steps=300, tol=1e-8)


@pytest.mark.required
Expand Down
2 changes: 1 addition & 1 deletion tests/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,7 @@ def get_hf_dataset(

if not has_files:
raise HTTPError("No file downloaded.")
except HTTPError as e:
except (HTTPError, FileNotFoundError) as e:
num_trials += 1
if num_trials == num_retry:
raise
Expand Down