Skip to content

Commit

Permalink
add doc; fix _func_update_all_verts; remove free_entities
Browse files Browse the repository at this point in the history
  • Loading branch information
ziyanx02 committed Feb 5, 2025
1 parent cf44336 commit 1f4f63c
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 15 deletions.
20 changes: 6 additions & 14 deletions genesis/engine/solvers/rigid/rigid_solver_decomp.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,6 @@ class RigidSolver(Solver):
def __init__(self, scene, sim, options):
super().__init__(scene, sim, options)

self._free_entities = gs.List()
self._fixed_entities = gs.List()

# options
self._enable_collision = options.enable_collision
self._enable_joint_limit = options.enable_joint_limit
Expand Down Expand Up @@ -93,10 +90,6 @@ def add_entity(self, idx, material, morph, surface, visualize_contact):
visualize_contact=visualize_contact,
)
self._entities.append(entity)
if entity.is_free:
self._free_entities.append(entity)
else:
self._fixed_entities.append(entity)

return entity

Expand Down Expand Up @@ -2228,16 +2221,15 @@ def _func_update_verts_for_geom(self, i_g, i_b):
@ti.func
def _func_update_all_verts(self):
ti.loop_config(serialize=self._para_level < gs.PARA_LEVEL.PARTIAL)
for i_v in range(self.n_verts):
for i_v, i_b in ti.ndrange(self.n_verts, self._B):
g_state = self.geoms_state[self.verts_info[i_v].geom_idx, i_b]
verts_state_idx = self.verts_info[i_v].verts_state_idx
if self.verts_info[i_v].is_free:
for i_b in range(self._B):
self.free_verts_state[verts_state_idx, i_b].pos = gu.ti_transform_by_trans_quat(
self.verts_info[i_v].init_pos, g_state.pos, g_state.quat
)
else:
self.free_verts_state[verts_state_idx].pos = gu.ti_transform_by_trans_quat(
self.free_verts_state[verts_state_idx, i_b].pos = gu.ti_transform_by_trans_quat(
self.verts_info[i_v].init_pos, g_state.pos, g_state.quat
)
elif i_b == 0:
self.fixed_verts_state[verts_state_idx].pos = gu.ti_transform_by_trans_quat(
self.verts_info[i_v].init_pos, g_state.pos, g_state.quat
)

Expand Down
3 changes: 2 additions & 1 deletion genesis/options/morphs.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,8 @@ class Morph(Options):
Whether the entity needs to be considered for collision checking. Defaults to True. `visualization` and `collision` cannot both be False. **This is only used for RigidEntity.**
requires_jac_and_IK : bool, optional
Whether this morph, if created as `RigidEntity`, requires jacobian and inverse kinematics. Defaults to False. **This is only used for RigidEntity.**
is_free : bool, optional
Whether the entity is free to move. Defaults to True. **This is only used for RigidEntity.**
"""

pos: tuple = (0.0, 0.0, 0.0)
Expand Down

0 comments on commit 1f4f63c

Please sign in to comment.