Skip to content

Commit 5b97a61

Browse files
authored
Merge branch 'main' into yiling/250703_migrate_test
2 parents 5c2ce28 + 0782728 commit 5b97a61

File tree

16 files changed

+432
-116
lines changed

16 files changed

+432
-116
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]

examples/drone/hover_env.py

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,9 @@ def __init__(self, num_envs, env_cfg, obs_cfg, reward_cfg, command_cfg, show_vie
9090
# build scene
9191
self.scene.build(n_envs=num_envs)
9292

93+
# Set damping to a small value to avoid numerical instability
94+
self.drone.set_dofs_damping(torch.tensor([0.0, 0.0, 0.0, 1e-4, 1e-4, 1e-4]))
95+
9396
# prepare reward functions and multiply reward scales by dt
9497
self.reward_functions, self.episode_sums = dict(), dict()
9598
for name in self.reward_scales.keys():

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/entities/rigid_entity/rigid_geom.py

Lines changed: 10 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
import os
22
import pickle as pkl
3+
from typing import TYPE_CHECKING
34

45
import igl
56
import numpy as np
@@ -14,6 +15,12 @@
1415
from genesis.repr_base import RBC
1516
from genesis.utils.misc import tensor_to_array
1617

18+
if TYPE_CHECKING:
19+
from genesis.engine.materials.rigid import Rigid as RigidMaterial
20+
21+
from .rigid_entity import RigidEntity
22+
from .rigid_link import RigidLink
23+
1724

1825
@ti.data_oriented
1926
class RigidGeom(RBC):
@@ -42,9 +49,9 @@ def __init__(
4249
center_init=None,
4350
data=None,
4451
):
45-
self._link = link
46-
self._entity = link.entity
47-
self._material = link.entity.material
52+
self._link: "RigidLink" = link
53+
self._entity: "RigidEntity" = link.entity
54+
self._material: "RigidMaterial" = link.entity.material
4855
self._solver = link.entity.solver
4956
self._mesh = mesh
5057

genesis/engine/entities/rigid_entity/rigid_link.py

Lines changed: 16 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,7 @@
1+
from typing import TYPE_CHECKING
2+
13
import numpy as np
4+
from numpy.typing import ArrayLike
25
import taichi as ti
36
import torch
47

@@ -9,6 +12,9 @@
912

1013
from .rigid_geom import RigidGeom, RigidVisGeom
1114

15+
if TYPE_CHECKING:
16+
from .rigid_entity import RigidEntity
17+
1218

1319
@ti.data_oriented
1420
class RigidLink(RBC):
@@ -43,8 +49,8 @@ def __init__(
4349
invweight,
4450
visualize_contact,
4551
):
46-
self._name = name
47-
self._entity = entity
52+
self._name: str = name
53+
self._entity: "RigidEntity" = entity
4854
self._solver = entity.solver
4955
self._entity_idx_in_solver = entity.idx
5056

@@ -68,16 +74,18 @@ def __init__(
6874
self._vvert_start = vvert_start
6975
self._vface_start = vface_start
7076

71-
self._pos = pos
72-
self._quat = quat
73-
self._inertial_pos = inertial_pos
74-
self._inertial_quat = inertial_quat
77+
# Link position & rotation at creation time:
78+
self._pos: ArrayLike = pos
79+
self._quat: ArrayLike = quat
80+
# Link's center-of-mass position & principal axes frame rotation at creation time:
81+
self._inertial_pos: ArrayLike = inertial_pos
82+
self._inertial_quat: ArrayLike = inertial_quat
7583
self._inertial_mass = inertial_mass
7684
self._inertial_i = inertial_i
7785

7886
self._visualize_contact = visualize_contact
7987

80-
self._geoms = gs.List()
88+
self._geoms: list[RigidGeom] = gs.List()
8189
self._vgeoms = gs.List()
8290

8391
def _build(self):
@@ -99,7 +107,7 @@ def _build(self):
99107
is_fixed = False
100108
if self._root_idx is None:
101109
self._root_idx = gs.np_int(link.idx)
102-
self.is_fixed = gs.np_int(is_fixed)
110+
self.is_fixed: np.int32 = gs.np_int(is_fixed) # note: type inconsistent with is_built, is_free, is_leaf: bool
103111

104112
# inertial_mass and inertia_i
105113
if self._inertial_mass is None:

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

0 commit comments

Comments
 (0)