Skip to content

Commit d9c2a44

Browse files
authored
[MISC] Only enable GJK by default if gradient computation is required. (#1984)
* Increase default number of compile threads. * Do not disable self-collision in benchmarks anymore. * Only enable GJK by default if gradient computation is required.
1 parent f08f460 commit d9c2a44

File tree

6 files changed

+20
-14
lines changed

6 files changed

+20
-14
lines changed

genesis/__init__.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -214,6 +214,7 @@ def init(
214214
if ti_num_cpu_threads is not None:
215215
taichi_kwargs.update(
216216
cpu_max_num_threads=int(ti_num_cpu_threads),
217+
num_compile_threads=int(ti_num_cpu_threads),
217218
)
218219

219220
if seed is not None:

genesis/engine/scene.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -283,7 +283,9 @@ def _validate_options(
283283
gs.raise_exception(
284284
"`rigid_options.box_box_detection` cannot be True when `sim_options.requires_grad` is True."
285285
)
286-
if not rigid_options.use_gjk_collision and sim_options.requires_grad:
286+
if rigid_options.use_gjk_collision is None:
287+
rigid_options.use_gjk_collision = sim_options.requires_grad
288+
elif not rigid_options.use_gjk_collision and sim_options.requires_grad:
287289
gs.raise_exception(
288290
"`rigid_options.use_gjk_collision` cannot be False when `sim_options.requires_grad` is True."
289291
)

genesis/options/solvers.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -349,7 +349,8 @@ class RigidOptions(Options):
349349
max_dynamic_constraints : int, optional
350350
Maximum number of dynamic constraints (like suction cup). Defaults to 8.
351351
use_gjk_collision: bool, optional
352-
Whether to use GJK for collision detection instead of MPR. Defaults to True.
352+
Whether to use GJK for collision detection instead of MPR. More stable but much slower. Defaults to
353+
`sim_options.requires_grad`.
353354
354355
Warning
355356
-------
@@ -400,7 +401,7 @@ class RigidOptions(Options):
400401
enable_mujoco_compatibility: bool = False
401402

402403
# GJK collision detection
403-
use_gjk_collision: bool = True
404+
use_gjk_collision: Optional[bool] = None
404405

405406
def __init__(self, **data):
406407
super().__init__(**data)

tests/test_grad.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -140,7 +140,6 @@ def compute_dL_error(dL_dx, x_type):
140140
# stable way.
141141
@pytest.mark.required
142142
@pytest.mark.precision("64")
143-
@pytest.mark.parametrize("backend", [gs.cpu])
144143
def test_diff_solver(backend, monkeypatch):
145144
from genesis.engine.solvers.rigid.constraint_solver_decomp import func_init_solver, func_solve
146145
from genesis.engine.solvers.rigid.rigid_solver_decomp import kernel_step_1

tests/test_rigid_benchmarks.py

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -330,7 +330,6 @@ def anymal_c(solver, n_envs, gjk):
330330
rigid_options=gs.options.RigidOptions(
331331
**get_rigid_solver_options(
332332
dt=STEP_DT,
333-
enable_self_collision=False,
334333
**(dict(constraint_solver=solver) if solver is not None else {}),
335334
**(dict(use_gjk_collision=gjk) if gjk is not None else {}),
336335
)
@@ -403,7 +402,6 @@ def batched_franka(solver, n_envs, gjk):
403402
rigid_options=gs.options.RigidOptions(
404403
**get_rigid_solver_options(
405404
dt=STEP_DT,
406-
enable_self_collision=False,
407405
**(dict(constraint_solver=solver) if solver is not None else {}),
408406
**(dict(use_gjk_collision=gjk) if gjk is not None else {}),
409407
)
@@ -455,7 +453,6 @@ def random(solver, n_envs, gjk):
455453
rigid_options=gs.options.RigidOptions(
456454
**get_rigid_solver_options(
457455
dt=STEP_DT,
458-
enable_self_collision=False,
459456
**(dict(constraint_solver=solver) if solver is not None else {}),
460457
**(dict(use_gjk_collision=gjk) if gjk is not None else {}),
461458
)
@@ -626,10 +623,12 @@ def box_pyramid(solver, n_envs, n_cubes, enable_island, gjk, enable_mujoco_compa
626623
@pytest.mark.parametrize(
627624
"runnable, solver, gjk, n_envs, backend",
628625
[
626+
("anymal_c", None, True, 30000, gs.gpu),
629627
("anymal_c", gs.constraint_solver.CG, None, 30000, gs.gpu),
630628
("anymal_c", gs.constraint_solver.Newton, None, 30000, gs.gpu),
631629
("anymal_c", None, None, 0, gs.gpu),
632630
("anymal_c", None, None, 0, gs.cpu),
631+
("batched_franka", None, True, 30000, gs.gpu),
633632
("batched_franka", gs.constraint_solver.CG, None, 30000, gs.gpu),
634633
("batched_franka", gs.constraint_solver.Newton, None, 30000, gs.gpu),
635634
("batched_franka", None, None, 0, gs.gpu),

tests/test_rigid_physics.py

Lines changed: 11 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1756,8 +1756,8 @@ def test_set_dofs_frictionloss_physics(gs_sim, tol):
17561756
def test_frictionloss_advanced(show_viewer, tol):
17571757
scene = gs.Scene(
17581758
viewer_options=gs.options.ViewerOptions(
1759-
camera_pos=(1.0, 0.25, 0.75),
1760-
camera_lookat=(0.0, 0.0, 0.0),
1759+
camera_pos=(1.4, 0.7, 1.4),
1760+
camera_lookat=(0.6, 0.0, 0.0),
17611761
),
17621762
show_viewer=show_viewer,
17631763
show_FPS=False,
@@ -1768,21 +1768,25 @@ def test_frictionloss_advanced(show_viewer, tol):
17681768
morph=gs.morphs.MJCF(
17691769
file=f"{asset_path}/SO101/so101_new_calib.xml",
17701770
),
1771+
# vis_mode="collision",
17711772
)
17721773
box = scene.add_entity(
17731774
gs.morphs.Box(
1775+
pos=(0.1, 0.0, 0.6),
17741776
size=(0.025, 0.025, 0.025),
17751777
),
17761778
)
17771779
scene.build()
17781780

17791781
scene.reset()
1780-
box.set_pos(torch.tensor((0.1, 0.0, 1.0), dtype=gs.tc_float, device=gs.device))
1781-
for _ in range(200):
1782+
for _ in range(230):
17821783
scene.step()
17831784

17841785
assert_allclose(robot.get_contacts()["position"][:, 2].min(), 0.0, tol=1e-4)
1785-
# assert_allclose(robot.get_AABB()[2], 0.0, tol=1e-3)
1786+
assert_allclose(robot.get_AABB()[0, 2], 0.0, tol=2e-4)
1787+
box_pos = box.get_pos()
1788+
assert box_pos[0] > 0.6
1789+
assert_allclose(box_pos[1:], 0.0, tol=0.02)
17861790
assert_allclose(box.get_dofs_velocity(), 0.0, tol=tol)
17871791

17881792

@@ -3112,8 +3116,8 @@ def test_contype_conaffinity(show_viewer, tol):
31123116
scene.step()
31133117

31143118
assert_allclose(box1.get_pos(), (0.0, 0.0, 0.25), atol=5e-4)
3115-
assert_allclose(box2.get_pos(), (0.0, 0.0, 0.75), atol=1e-3)
3116-
assert_allclose(box2.get_pos(), box3.get_pos(), atol=1e-4)
3119+
assert_allclose(box2.get_pos(), (0.0, 0.0, 0.75), atol=2e-3)
3120+
assert_allclose(box2.get_pos(), box3.get_pos(), atol=2e-3)
31173121
assert_allclose(scene.rigid_solver.get_links_acc(slice(box4.link_start, box4.link_end)), GRAVITY, atol=tol)
31183122

31193123

0 commit comments

Comments
 (0)