Skip to content

Commit cd3b676

Browse files
committed
Merge remote-tracking branch 'origin/main' into pr/25/702_box_raycast
# Conflicts: # genesis/ext/pyrender/interaction/viewer_interaction.py
2 parents 7636ece + 6479cf6 commit cd3b676

20 files changed

+329
-55
lines changed

README.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
# Genesis
1919

2020
## 🔥 News
21+
- [2025-07-02] The development of Genesis is now officially supported by [Genesis AI](https://genesis-ai.company/).
2122
- [2025-01-09] We released a [detailed performance benchmarking and comparison report](https://github.com/zhouxian/genesis-speed-benchmark) on Genesis, together with all the test scripts.
2223
- [2025-01-08] Released v0.2.1 🎊 🎉
2324
- [2025-01-08] Created [Discord](https://discord.gg/nukCuhB47p) and [Wechat](https://drive.google.com/uc?export=view&id=1ZS9nnbQ-t1IwkzJlENBYqYIIOOZhXuBZ) group.

genesis/engine/coupler.py

Lines changed: 23 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
from typing import TYPE_CHECKING
2+
23
import numpy as np
34
import taichi as ti
45

@@ -83,14 +84,30 @@ def build(self) -> None:
8384
self._dx = 1 / 1024
8485
self._stencil_size = int(np.floor(self._dx / self.sph_solver.hash_grid_cell_size) + 2)
8586

86-
self.reset()
87+
self.reset(envs_idx=self.sim.scene._envs_idx)
8788

88-
def reset(self) -> None:
89+
def reset(self, envs_idx=None) -> None:
8990
if self._rigid_mpm and self.mpm_solver.enable_CPIC:
90-
self.mpm_rigid_normal.fill(0)
91+
if envs_idx is None:
92+
self.mpm_rigid_normal.fill(0)
93+
else:
94+
self._kernel_reset_mpm(envs_idx)
9195

9296
if self._rigid_sph:
93-
self.sph_rigid_normal.fill(0)
97+
if envs_idx is None:
98+
self.sph_rigid_normal.fill(0)
99+
else:
100+
self._kernel_reset_sph(envs_idx)
101+
102+
@ti.kernel
103+
def _kernel_reset_mpm(self, envs_idx: ti.types.ndarray()):
104+
for i_p, i_g, i_b_ in ti.ndrange(self.mpm_solver.n_particles, self.rigid_solver.n_geoms, envs_idx.shape[0]):
105+
self.mpm_rigid_normal[i_p, i_g, envs_idx[i_b_]] = 0.0
106+
107+
@ti.kernel
108+
def _kernel_reset_sph(self, envs_idx: ti.types.ndarray()):
109+
for i_p, i_g, i_b_ in ti.ndrange(self.sph_solver.n_particles, self.rigid_solver.n_geoms, envs_idx.shape[0]):
110+
self.sph_rigid_normal[i_p, i_g, envs_idx[i_b_]] = 0.0
94111

95112
@ti.func
96113
def _func_collide_with_rigid(self, f, pos_world, vel, mass, i_b):
@@ -200,7 +217,7 @@ def mpm_grid_op(self, f: ti.i32, t: ti.f32):
200217
vel_mpm = (1 / self.mpm_solver.grid[f, I, i_b].mass) * self.mpm_solver.grid[f, I, i_b].vel_in
201218

202219
# gravity
203-
vel_mpm += self.mpm_solver.substep_dt * self.mpm_solver._gravity[None]
220+
vel_mpm += self.mpm_solver.substep_dt * self.mpm_solver._gravity[i_b]
204221

205222
pos = (I + self.mpm_solver.grid_offset) * self.mpm_solver.dx
206223
mass_mpm = self.mpm_solver.grid[f, I, i_b].mass / self.mpm_solver._p_vol_scale
@@ -667,7 +684,7 @@ def build(self) -> None:
667684
self.init_pcg_fields()
668685
self.init_linesearch_fields()
669686

670-
def reset(self):
687+
def reset(self, envs_idx=None) -> None:
671688
pass
672689

673690
def init_fem_fields(self):

genesis/engine/scene.py

Lines changed: 11 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
from genesis.engine.force_fields import ForceField
1313
from genesis.engine.materials.base import Material
1414
from genesis.engine.entities import Emitter
15+
from genesis.engine.states.solvers import SimState
1516
from genesis.engine.simulator import Simulator
1617
from genesis.options import (
1718
AvatarOptions,
@@ -695,23 +696,27 @@ def _parallelize(
695696
self._para_level = gs.PARA_LEVEL.ALL
696697

697698
@gs.assert_built
698-
def reset(self, state: dict | None = None, envs_idx=None):
699+
def reset(self, state: SimState | None = None, envs_idx=None):
699700
"""
700701
Resets the scene to its initial state.
701702
702703
Parameters
703704
----------
704-
state : dict | None
705-
The state to reset the scene to. If None, the scene will be reset to its initial state. If this is given, the scene's registerered initial state will be updated to this state.
705+
state : SimState | None
706+
The state to reset the scene to. If None, the scene will be reset to its initial state.
707+
If this is given, the scene's registerered initial state will be updated to this state.
708+
envs_idx : None | array_like, optional
709+
The indices of the environments. If None, all environments will be considered. Defaults to None.
706710
"""
707-
gs.logger.info(f"Resetting Scene ~~~<{self._uid}>~~~.")
708-
self._reset(state, envs_idx)
711+
gs.logger.debug(f"Resetting Scene ~~~<{self._uid}>~~~.")
712+
self._reset(state, envs_idx=envs_idx)
709713

710-
def _reset(self, state=None, envs_idx=None):
714+
def _reset(self, state: SimState | None = None, *, envs_idx=None):
711715
if self._is_built:
712716
if state is None:
713717
state = self._init_state
714718
else:
719+
assert isinstance(state, SimState), "state must be a SimState object"
715720
self._init_state = state
716721
self._sim.reset(state, envs_idx)
717722
else:

genesis/engine/simulator.py

Lines changed: 9 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222

2323
from .coupler import Coupler, SAPCoupler
2424
from .entities import HybridEntity
25+
from .solvers.base_solver import Solver
2526
from .solvers import (
2627
AvatarSolver,
2728
FEMSolver,
@@ -205,12 +206,12 @@ def build(self):
205206
if isinstance(entity, HybridEntity):
206207
entity.build()
207208

208-
def reset(self, state, envs_idx=None):
209+
def reset(self, state: SimState, envs_idx=None):
209210
for solver, solver_state in zip(self._solvers, state):
210-
solver.set_state(0, solver_state, envs_idx)
211+
if solver.n_entities > 0:
212+
solver.set_state(0, solver_state, envs_idx)
211213

212-
# TODO: keeping as is for now, since coupler is currently for non-batched scenes
213-
self.coupler.reset()
214+
self.coupler.reset(envs_idx=envs_idx)
214215

215216
# TODO: keeping as is for now
216217
self.reset_grad()
@@ -395,6 +396,10 @@ def get_state(self):
395396

396397
return state
397398

399+
def set_gravity(self, gravity, envs_idx=None):
400+
for solver in self._solvers:
401+
solver.set_gravity(gravity, envs_idx)
402+
398403
# ------------------------------------------------------------------------------------
399404
# ----------------------------------- properties -------------------------------------
400405
# ------------------------------------------------------------------------------------

genesis/engine/solvers/base_solver.py

Lines changed: 22 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -21,13 +21,8 @@ def __init__(self, scene: "Scene", sim: "Simulator", options):
2121
self._scene = scene
2222
self._dt: float = options.dt
2323
self._substep_dt: float = options.dt / sim.substeps
24-
25-
if hasattr(options, "gravity"):
26-
self._gravity = ti.field(dtype=gs.ti_vec3, shape=())
27-
self._gravity.from_numpy(np.array(options.gravity, dtype=gs.np_float))
28-
else:
29-
self._gravity = None
30-
24+
self._init_gravity = getattr(options, "gravity", None)
25+
self._gravity = None
3126
self._entities: list[Entity] = gs.List()
3227

3328
# force fields
@@ -36,6 +31,26 @@ def __init__(self, scene: "Scene", sim: "Simulator", options):
3631
def _add_force_field(self, force_field):
3732
self._ffs.append(force_field)
3833

34+
def build(self):
35+
self._B = self._sim._B
36+
if self._init_gravity is not None:
37+
g_np = np.asarray(self._init_gravity, dtype=gs.np_float)
38+
g_np = np.repeat(g_np[None], self._B, axis=0)
39+
self._gravity = ti.Vector.field(3, dtype=gs.ti_float, shape=self._B)
40+
self._gravity.from_numpy(g_np)
41+
42+
@gs.assert_built
43+
def set_gravity(self, gravity, envs_idx=None):
44+
if self._gravity is None:
45+
return
46+
g = np.asarray(gravity, dtype=gs.np_float)
47+
if envs_idx is None:
48+
if g.ndim == 1:
49+
g = np.repeat(g[None], self._B, axis=0)
50+
self._gravity.from_numpy(g)
51+
else:
52+
self._gravity[envs_idx] = g
53+
3954
def dump_ckpt_to_numpy(self) -> dict[str, np.ndarray]:
4055
arrays: dict[str, np.ndarray] = {}
4156

genesis/engine/solvers/fem_solver.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -276,6 +276,7 @@ def reset_grad(self):
276276
entity.reset_grad()
277277

278278
def build(self):
279+
super().build()
279280
self.n_envs = self.sim.n_envs
280281
self._B = self.sim._B
281282

@@ -389,7 +390,7 @@ def apply_uniform_force(self, f: ti.i32):
389390
# however, this inevitably damp the gravity.
390391
self.elements_v[f + 1, i_v, i_b].vel *= ti.exp(-dt * self.damping)
391392
# Add gravity (avoiding damping on gravity)
392-
self.elements_v[f + 1, i_v, i_b].vel += dt * self._gravity[None]
393+
self.elements_v[f + 1, i_v, i_b].vel += dt * self._gravity[i_b]
393394

394395
@ti.kernel
395396
def compute_pos(self, f: ti.i32):
@@ -416,7 +417,7 @@ def init_pos_and_inertia(self, f: ti.i32):
416417
dt = self.substep_dt
417418
for i_v, i_b in ti.ndrange(self.n_vertices, self._B):
418419
self.elements_v_energy[i_b, i_v].inertia = (
419-
self.elements_v[f, i_v, i_b].pos + self.elements_v[f, i_v, i_b].vel * dt + self._gravity[None] * dt**2
420+
self.elements_v[f, i_v, i_b].pos + self.elements_v[f, i_v, i_b].vel * dt + self._gravity[i_b] * dt**2
420421
)
421422
self.elements_v[f + 1, i_v, i_b].pos = self.elements_v[f, i_v, i_b].pos
422423

genesis/engine/solvers/mpm_solver.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -196,6 +196,7 @@ def reset_grad(self):
196196
entity.reset_grad()
197197

198198
def build(self):
199+
super().build()
199200
# particles and entities
200201
self._B = self._sim._B
201202

genesis/engine/solvers/pbd_solver.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -208,6 +208,7 @@ def init_ckpt(self):
208208
self._ckpt = dict()
209209

210210
def build(self):
211+
super().build()
211212
self._B = self._sim._B
212213
self._n_particles = self.n_particles
213214
self._n_fluid_particles = self.n_fluid_particles
@@ -371,7 +372,7 @@ def _kernel_apply_external_force(self, f: ti.i32, t: ti.f32):
371372
for i_p, i_b in ti.ndrange(self._n_particles, self._B):
372373
if self.particles[i_p, i_b].free:
373374
# gravity
374-
self.particles[i_p, i_b].vel = self.particles[i_p, i_b].vel + self._gravity[None] * self._substep_dt
375+
self.particles[i_p, i_b].vel = self.particles[i_p, i_b].vel + self._gravity[i_b] * self._substep_dt
375376

376377
# external force fields
377378
acc = ti.Vector.zero(gs.ti_float, 3)

genesis/engine/solvers/rigid/collider_decomp.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2072,7 +2072,7 @@ def get_contacts(self, as_tensor: bool = True, to_torch: bool = True):
20722072
# Early return if already pre-computed
20732073
contacts_info = self._contacts_info_cache.get((as_tensor, to_torch))
20742074
if contacts_info is not None:
2075-
return contacts_info
2075+
return contacts_info.copy()
20762076

20772077
# Find out how much dynamic memory must be allocated
20782078
n_contacts = tuple(self.n_contacts.to_numpy())
@@ -2140,7 +2140,7 @@ def get_contacts(self, as_tensor: bool = True, to_torch: bool = True):
21402140
# Cache contact information before returning
21412141
self._contacts_info_cache[(as_tensor, to_torch)] = contacts_info
21422142

2143-
return contacts_info
2143+
return contacts_info.copy()
21442144

21452145
@ti.kernel
21462146
def _kernel_get_contacts(self, is_padded: ti.template(), iout: ti.types.ndarray(), fout: ti.types.ndarray()):

genesis/engine/solvers/rigid/rigid_solver_decomp.py

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -156,6 +156,7 @@ def add_entity(self, idx, material, morph, surface, visualize_contact) -> Entity
156156
return entity
157157

158158
def build(self):
159+
super().build()
159160
self.n_envs = self.sim.n_envs
160161
self._B = self.sim._B
161162
self._para_level = self.sim._para_level
@@ -2929,9 +2930,7 @@ def _func_update_acc(self, update_cacc: ti.template()):
29292930
i_p = self.links_info[I_l].parent_idx
29302931

29312932
if i_p == -1:
2932-
self.links_state[i_l, i_b].cdd_vel = -self._gravity[None] * (
2933-
1 - e_info.gravity_compensation
2934-
)
2933+
self.links_state[i_l, i_b].cdd_vel = -self._gravity[i_b] * (1 - e_info.gravity_compensation)
29352934
self.links_state[i_l, i_b].cdd_ang = ti.Vector.zero(gs.ti_float, 3)
29362935
if ti.static(update_cacc):
29372936
self.links_state[i_l, i_b].cacc_lin = ti.Vector.zero(gs.ti_float, 3)
@@ -2968,7 +2967,7 @@ def _func_update_acc(self, update_cacc: ti.template()):
29682967
i_p = self.links_info[I_l].parent_idx
29692968

29702969
if i_p == -1:
2971-
self.links_state[i_l, i_b].cdd_vel = -self._gravity[None] * (1 - e_info.gravity_compensation)
2970+
self.links_state[i_l, i_b].cdd_vel = -self._gravity[i_b] * (1 - e_info.gravity_compensation)
29722971
self.links_state[i_l, i_b].cdd_ang = ti.Vector.zero(gs.ti_float, 3)
29732972
if ti.static(update_cacc):
29742973
self.links_state[i_l, i_b].cacc_lin = ti.Vector.zero(gs.ti_float, 3)
@@ -4617,7 +4616,7 @@ def _kernel_get_links_acc(
46174616
# Mimick IMU accelerometer signal if requested
46184617
if mimick_imu:
46194618
# Subtract gravity
4620-
acc_classic_lin -= self._gravity[None]
4619+
acc_classic_lin -= self._gravity[i_b]
46214620

46224621
# Move the resulting linear acceleration in local links frame
46234622
acc_classic_lin = gu.ti_inv_transform_by_quat(acc_classic_lin, self.links_state[i_l, i_b].quat)

0 commit comments

Comments
 (0)