Skip to content

Commit a9c92f8

Browse files
authored
[BUG FIX] Various minor bug fixes. (#1368)
* Automatically kill irrelevant CI jobs. * Fix partially broken taichi stdout silencing. * Disable static_print in kernels because it does not work as intended. * More robust inverse kinematics unit test. * Get around MacOS Metal GPU taichi compiler bug (again!). * Fix taichi type cast warnings.
1 parent 6479cf6 commit a9c92f8

File tree

8 files changed

+90
-79
lines changed

8 files changed

+90
-79
lines changed

.github/workflows/generic-cpu.yml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,10 @@ on:
55
branches:
66
- main
77

8+
concurrency:
9+
group: ${{ github.workflow }}-${{ github.head_ref || github.ref }}
10+
cancel-in-progress: ${{ github.event_name == 'pull_request' }}
11+
812
jobs:
913
generic-cpu:
1014
strategy:

.github/workflows/linux-gpu.yml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,12 @@ on:
77
- main
88
pull_request:
99

10+
concurrency:
11+
# Cancel all workflows that are stil running if any when updating branches associated with PRs,
12+
# BUT don't do anything for workflows that are not triggered by PRs.
13+
group: ${{ github.workflow }}-${{ github.head_ref || github.ref }}
14+
cancel-in-progress: ${{ github.event_name == 'pull_request' }}
15+
1016
jobs:
1117
linux-gpu:
1218
runs-on: [self-hosted, coreweave]

genesis/__init__.py

Lines changed: 12 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -1,23 +1,19 @@
1-
# import taichi while suppressing its output
1+
import io
22
import os
33
import sys
44
import site
55
import atexit
66
import logging as _logging
77
import traceback
88
from platform import system
9-
from unittest.mock import patch
9+
from contextlib import redirect_stdout
1010

11+
# Import taichi while collecting its output without printing directly
12+
_ti_outputs = io.StringIO()
1113

12-
_ti_outputs = []
14+
os.environ.setdefault("TI_ENABLE_PYBUF", "0" if sys.stdout is sys.__stdout__ else "1")
1315

14-
15-
def fake_print(*args, **kwargs):
16-
output = "".join(args)
17-
_ti_outputs.append(output)
18-
19-
20-
with patch("builtins.print", fake_print):
16+
with redirect_stdout(_ti_outputs):
2117
import taichi as ti
2218

2319
try:
@@ -52,11 +48,9 @@ def init(
5248
logger_verbose_time=False,
5349
performance_mode: bool = False, # True: compilation up to 6x slower (GJK), but runs ~1-5% faster
5450
):
55-
# Consider Genesis as initialized right away
5651
global _initialized
5752
if _initialized:
5853
raise_exception("Genesis already initialized.")
59-
_initialized = True
6054

6155
# genesis._theme
6256
global _theme
@@ -193,7 +187,7 @@ def init(
193187
ti_arch = TI_ARCH[platform][gs_backend.cpu]
194188

195189
# init taichi
196-
with patch("builtins.print", fake_print):
190+
with redirect_stdout(_ti_outputs):
197191
ti.init(
198192
arch=ti_arch,
199193
# debug is causing segfault on some machines
@@ -227,9 +221,10 @@ def init(
227221
f"Running on ~~<[{device_name}]>~~ with backend ~~<{backend}>~~. Device memory: ~~<{total_mem:.2f}>~~ GB."
228222
)
229223

230-
for ti_output in _ti_outputs:
224+
for ti_output in _ti_outputs.getvalue().splitlines():
231225
logger.debug(ti_output)
232-
_ti_outputs.clear()
226+
_ti_outputs.truncate(0)
227+
_ti_outputs.seek(0)
233228

234229
global exit_callbacks
235230
exit_callbacks = []
@@ -238,6 +233,8 @@ def init(
238233
f"🚀 Genesis initialized. 🔖 version: ~~<{__version__}>~~, 🌱 seed: ~~<{seed}>~~, 📏 precision: '~~<{precision}>~~', 🐛 debug: ~~<{debug}>~~, 🎨 theme: '~~<{theme}>~~'."
239234
)
240235

236+
_initialized = True
237+
241238

242239
########################## init ##########################
243240
def destroy():

genesis/engine/bvh.py

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -343,38 +343,38 @@ def compute_bounds(self):
343343
@ti.kernel
344344
def _kernel_compute_bounds_init(self):
345345
self.updated[None] = True
346-
self.internal_node_active.fill(0)
347-
self.internal_node_ready.fill(0)
346+
self.internal_node_active.fill(False)
347+
self.internal_node_ready.fill(False)
348348

349349
for i_b, i in ti.ndrange(self.n_batches, self.n_aabbs):
350350
idx = ti.i32(self.morton_codes[i_b, i])
351351
self.nodes[i_b, i + self.n_aabbs - 1].bound.min = self.aabbs[i_b, idx].min
352352
self.nodes[i_b, i + self.n_aabbs - 1].bound.max = self.aabbs[i_b, idx].max
353353
parent_idx = self.nodes[i_b, i + self.n_aabbs - 1].parent
354354
if parent_idx != -1:
355-
self.internal_node_active[i_b, parent_idx] = 1
355+
self.internal_node_active[i_b, parent_idx] = True
356356

357357
@ti.kernel
358358
def _kernel_compute_bounds_one_layer(self):
359359
self.updated[None] = False
360360
for i_b, i in ti.ndrange(self.n_batches, self.n_aabbs - 1):
361-
if self.internal_node_active[i_b, i] == 0:
361+
if not self.internal_node_active[i_b, i]:
362362
continue
363363
left_bound = self.nodes[i_b, self.nodes[i_b, i].left].bound
364364
right_bound = self.nodes[i_b, self.nodes[i_b, i].right].bound
365365
self.nodes[i_b, i].bound.min = ti.min(left_bound.min, right_bound.min)
366366
self.nodes[i_b, i].bound.max = ti.max(left_bound.max, right_bound.max)
367367
parent_idx = self.nodes[i_b, i].parent
368368
if parent_idx != -1:
369-
self.internal_node_ready[i_b, parent_idx] = 1
370-
self.internal_node_active[i_b, i] = 0
369+
self.internal_node_ready[i_b, parent_idx] = True
370+
self.internal_node_active[i_b, i] = False
371371
self.updated[None] = True
372372

373373
for i_b, i in ti.ndrange(self.n_batches, self.n_aabbs - 1):
374-
if self.internal_node_ready[i_b, i] == 0:
374+
if not self.internal_node_ready[i_b, i]:
375375
continue
376-
self.internal_node_active[i_b, i] = 1
377-
self.internal_node_ready[i_b, i] = 0
376+
self.internal_node_active[i_b, i] = True
377+
self.internal_node_ready[i_b, i] = False
378378

379379
@ti.kernel
380380
def query(self, aabbs: ti.template()):

genesis/engine/solvers/rigid/collider_decomp.py

Lines changed: 23 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -153,6 +153,8 @@ def _init_collision_fields(self) -> None:
153153
self._max_collision_pairs = min(n_possible_pairs, self._solver._max_collision_pairs)
154154
self._max_contact_pairs = self._max_collision_pairs * self._n_contacts_per_pair
155155

156+
# FIXME: 'ti.static_print' cannot be used as it will be printed systematically, completely ignoring guard
157+
# condition, while 'print' is slowing down the kernel even if every called in practice...
156158
self._warn_msg_max_collision_pairs = (
157159
f"{colors.YELLOW}[Genesis] [00:00:00] [WARNING] Ignoring contact pair to avoid exceeding max "
158160
f"({self._max_contact_pairs}). Please increase the value of RigidSolver's option "
@@ -777,7 +779,7 @@ def _func_broad_phase(self):
777779
continue
778780

779781
if self.n_broad_pairs[i_b] == self._max_collision_pairs:
780-
ti.static_print(self._warn_msg_max_collision_pairs)
782+
# print(self._warn_msg_max_collision_pairs)
781783
break
782784
self.broad_collision_pairs[self.n_broad_pairs[i_b], i_b][0] = i_ga
783785
self.broad_collision_pairs[self.n_broad_pairs[i_b], i_b][1] = i_gb
@@ -887,22 +889,27 @@ def _func_narrow_phase_convex_vs_convex(self):
887889
i_ga = self.broad_collision_pairs[i_pair, i_b][0]
888890
i_gb = self.broad_collision_pairs[i_pair, i_b][1]
889891

892+
if self._solver.geoms_info[i_ga].type > self._solver.geoms_info[i_gb].type:
893+
i_ga, i_gb = i_gb, i_ga
894+
890895
if (
891896
self._solver.geoms_info[i_ga].is_convex
892897
and self._solver.geoms_info[i_gb].is_convex
893898
and not self._solver.geoms_info[i_gb].type == gs.GEOM_TYPE.TERRAIN
894-
and not (
895-
self._solver._enable_multi_contact
896-
and self._solver.geoms_info[i_ga].type == gs.GEOM_TYPE.PLANE
897-
and self._solver.geoms_info[i_gb].type == gs.GEOM_TYPE.BOX
898-
)
899899
and not (
900900
self._solver._box_box_detection
901901
and self._solver.geoms_info[i_ga].type == gs.GEOM_TYPE.BOX
902902
and self._solver.geoms_info[i_gb].type == gs.GEOM_TYPE.BOX
903903
)
904904
):
905-
self._func_convex_convex_contact(i_ga, i_gb, i_b)
905+
if ti.static(sys.platform == "darwin"):
906+
self._func_convex_convex_contact(i_ga, i_gb, i_b)
907+
else:
908+
if not (
909+
self._solver.geoms_info[i_ga].type == gs.GEOM_TYPE.PLANE
910+
and self._solver.geoms_info[i_gb].type == gs.GEOM_TYPE.BOX
911+
):
912+
self._func_convex_convex_contact(i_ga, i_gb, i_b)
906913

907914
@ti.kernel
908915
def _func_narrow_phase_convex_specializations(self):
@@ -915,15 +922,11 @@ def _func_narrow_phase_convex_specializations(self):
915922
if self._solver.geoms_info[i_ga].type > self._solver.geoms_info[i_gb].type:
916923
i_ga, i_gb = i_gb, i_ga
917924

918-
if (
919-
self._solver.geoms_info[i_ga].type == gs.GEOM_TYPE.PLANE
920-
and self._solver.geoms_info[i_gb].type == gs.GEOM_TYPE.BOX
921-
):
922-
if ti.static(sys.platform == "darwin"):
923-
# FIXME: It seems redundant, why don't we just call _func_plane_box_contact directly?
924-
# Anyway in this function, we will call _func_plane_box_contact.
925-
self._func_convex_convex_contact(i_ga, i_gb, i_b)
926-
else:
925+
if ti.static(sys.platform != "darwin"):
926+
if (
927+
self._solver.geoms_info[i_ga].type == gs.GEOM_TYPE.PLANE
928+
and self._solver.geoms_info[i_gb].type == gs.GEOM_TYPE.BOX
929+
):
927930
self._func_plane_box_contact(i_ga, i_gb, i_b)
928931

929932
if ti.static(self._solver._box_box_detection):
@@ -1110,7 +1113,10 @@ def _func_add_contact(self, i_ga, i_gb, normal, contact_pos, penetration, i_b):
11101113
i_col = self.n_contacts[i_b]
11111114

11121115
if i_col == self._max_contact_pairs:
1113-
ti.static_print(self._warn_msg_max_collision_pairs)
1116+
# FIXME: 'ti.static_print' cannot be used as it will be printed systematically, completely ignoring guard
1117+
# condition, while 'print' is slowing down the kernel even if every called in practice...
1118+
# print(self._warn_msg_max_collision_pairs)
1119+
pass
11141120
else:
11151121
ga_info = self._solver.geoms_info[i_ga]
11161122
gb_info = self._solver.geoms_info[i_gb]
@@ -1194,9 +1200,6 @@ def _func_contact_orthogonals(self, i_ga, i_gb, normal, i_b):
11941200

11951201
@ti.func
11961202
def _func_convex_convex_contact(self, i_ga, i_gb, i_b):
1197-
if self._solver.geoms_info[i_ga].type > self._solver.geoms_info[i_gb].type:
1198-
i_ga, i_gb = i_gb, i_ga
1199-
12001203
if (
12011204
self._solver.geoms_info[i_ga].type == gs.GEOM_TYPE.PLANE
12021205
and self._solver.geoms_info[i_gb].type == gs.GEOM_TYPE.BOX

tests/test_bvh.py

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,10 @@
1-
import taichi as ti
21
import torch
32
import numpy as np
4-
import genesis as gs
3+
import pytest
54

5+
import genesis as gs
66
from genesis.engine.bvh import LBVH, AABB
77

8-
import pytest
98
from .utils import assert_allclose
109

1110

@@ -37,18 +36,19 @@ def test_morton_code(lbvh):
3736
), f"Morton codes are not sorted: {morton_codes[i_b, i]} < {morton_codes[i_b, i - 1]}"
3837

3938

40-
@ti.kernel
41-
def expand_bits(lbvh: ti.template(), x: ti.template(), expanded_x: ti.template()):
42-
n_x = x.shape[0]
43-
for i in range(n_x):
44-
expanded_x[i] = lbvh.expand_bits(x[i])
45-
46-
4739
def test_expand_bits():
4840
"""
4941
Test the expand_bits function for LBVH.
5042
A 10-bit integer is expanded to a 30-bit integer by inserting two zeros before each bit.
5143
"""
44+
import taichi as ti
45+
46+
@ti.kernel
47+
def expand_bits(lbvh: ti.template(), x: ti.template(), expanded_x: ti.template()):
48+
n_x = x.shape[0]
49+
for i in range(n_x):
50+
expanded_x[i] = lbvh.expand_bits(x[i])
51+
5252
# random integer
5353
x_np = np.random.randint(0, 1024, (10,), dtype=np.uint32)
5454
x_ti = ti.field(ti.uint32, shape=x_np.shape)

tests/test_rigid_physics.py

Lines changed: 19 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414

1515
import genesis as gs
1616
import genesis.utils.geom as gu
17-
from genesis.utils.misc import tensor_to_array
17+
from genesis.utils.misc import tensor_to_array, get_assets_dir
1818

1919
from .utils import (
2020
get_hf_assets,
@@ -1404,14 +1404,14 @@ def move_cube(use_suction, mode, show_viewer):
14041404
# move to pre-grasp pose
14051405
qpos = franka.inverse_kinematics(
14061406
link=end_effector,
1407-
pos=np.array([0.65, 0.0, 0.25]),
1407+
pos=np.array([0.65, 0.0, 0.22]),
14081408
quat=np.array([0, 1, 0, 0]),
14091409
)
14101410
# gripper open pos
14111411
qpos[-2:] = 0.04
14121412
path = franka.plan_path(
14131413
qpos_goal=qpos,
1414-
num_waypoints=100, # 1s duration
1414+
num_waypoints=120, # 1s duration
14151415
resolution=0.05,
14161416
timeout=30.0,
14171417
)
@@ -1423,7 +1423,7 @@ def move_cube(use_suction, mode, show_viewer):
14231423
scene.step()
14241424

14251425
# Get more time to the robot to reach the last waypoint
1426-
for i in range(100):
1426+
for i in range(120):
14271427
scene.step()
14281428

14291429
# reach
@@ -1433,7 +1433,7 @@ def move_cube(use_suction, mode, show_viewer):
14331433
quat=np.array([0, 1, 0, 0]),
14341434
)
14351435
franka.control_dofs_position(qpos[:-2], motors_dof)
1436-
for i in range(50):
1436+
for i in range(60):
14371437
scene.step()
14381438

14391439
# grasp
@@ -1465,7 +1465,7 @@ def move_cube(use_suction, mode, show_viewer):
14651465
)
14661466
path = franka.plan_path(
14671467
qpos_goal=qpos,
1468-
num_waypoints=150,
1468+
num_waypoints=80,
14691469
resolution=0.05,
14701470
timeout=30.0,
14711471
)
@@ -1488,7 +1488,7 @@ def move_cube(use_suction, mode, show_viewer):
14881488
scene.step()
14891489
if i > 550:
14901490
qvel = cube.get_dofs_velocity()
1491-
assert_allclose(qvel, 0, atol=0.06)
1491+
assert_allclose(qvel, 0, atol=0.02)
14921492

14931493
qpos = cube.get_dofs_position()
14941494
assert_allclose(qpos[2], 0.075, atol=2e-3)
@@ -2715,28 +2715,29 @@ def must_cast(value):
27152715

27162716

27172717
@pytest.mark.parametrize("backend", [gs.cpu])
2718-
def test_mesh_to_heightfield(show_viewer):
2718+
def test_mesh_to_heightfield(tmp_path, show_viewer):
2719+
horizontal_scale = 2.0
2720+
path_terrain = os.path.join(get_assets_dir(), "meshes", "terrain_45.obj")
2721+
2722+
hf_terrain, xs, ys = gs.utils.terrain.mesh_to_heightfield(path_terrain, spacing=horizontal_scale, oversample=1)
2723+
2724+
# default heightfield starts at 0, 0, 0
2725+
# translate to the center of the mesh
2726+
translation = np.array([np.nanmin(xs), np.nanmin(ys), 0])
2727+
27192728
########################## create a scene ##########################
27202729
scene = gs.Scene(
2721-
show_viewer=show_viewer,
27222730
sim_options=gs.options.SimOptions(
27232731
gravity=(2, 0, -2),
27242732
),
27252733
viewer_options=gs.options.ViewerOptions(
27262734
camera_pos=(0, -50, 0),
27272735
camera_lookat=(0, 0, 0),
27282736
),
2737+
show_viewer=show_viewer,
2738+
show_FPS=False,
27292739
)
27302740

2731-
horizontal_scale = 2.0
2732-
gs_root = os.path.dirname(os.path.abspath(gs.__file__))
2733-
path_terrain = os.path.join(gs_root, "assets", "meshes", "terrain_45.obj")
2734-
hf_terrain, xs, ys = gs.utils.terrain.mesh_to_heightfield(path_terrain, spacing=horizontal_scale, oversample=1)
2735-
2736-
# default heightfield starts at 0, 0, 0
2737-
# translate to the center of the mesh
2738-
translation = np.array([np.nanmin(xs), np.nanmin(ys), 0])
2739-
27402741
terrain_heightfield = scene.add_entity(
27412742
morph=gs.morphs.Terrain(
27422743
horizontal_scale=horizontal_scale,
@@ -2746,15 +2747,13 @@ def test_mesh_to_heightfield(show_viewer):
27462747
),
27472748
vis_mode="collision",
27482749
)
2749-
27502750
ball = scene.add_entity(
27512751
gs.morphs.Sphere(
27522752
pos=(10, 15, 10),
27532753
radius=1,
27542754
),
27552755
vis_mode="collision",
27562756
)
2757-
27582757
scene.build()
27592758

27602759
for i in range(1000):

0 commit comments

Comments
 (0)