Skip to content

Commit d05354d

Browse files
authored
[MISC] Minor cleanup and bug fixes. (#1398)
* Delay VTK import to mitigate import failure on Linux w/o X11. * Fix 'delete_weld_constraint'. * Fix 'test_convexify'. * Disable broken 'test_query' unit test. * Improve BVH query performance. * Use 'ti.u1' for boolean flags. * Fix dtype handling. * Avoid 'numpy.flatten' for efficiency. * Remove dead code 'RigidGeom.sdf_*' methods.
1 parent d386d0d commit d05354d

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

43 files changed

+400
-442
lines changed

examples/drone/hover_env.py

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -122,10 +122,11 @@ def _resample_commands(self, envs_idx):
122122
self.commands[envs_idx, 2] = gs_rand_float(*self.command_cfg["pos_z_range"], (len(envs_idx),), gs.device)
123123

124124
def _at_target(self):
125-
at_target = (
126-
(torch.norm(self.rel_pos, dim=1) < self.env_cfg["at_target_threshold"]).nonzero(as_tuple=False).flatten()
125+
return (
126+
(torch.norm(self.rel_pos, dim=1) < self.env_cfg["at_target_threshold"])
127+
.nonzero(as_tuple=False)
128+
.reshape((-1,))
127129
)
128-
return at_target
129130

130131
def step(self, actions):
131132
self.actions = torch.clip(actions, -self.env_cfg["clip_actions"], self.env_cfg["clip_actions"])
@@ -169,11 +170,11 @@ def step(self, actions):
169170
)
170171
self.reset_buf = (self.episode_length_buf > self.max_episode_length) | self.crash_condition
171172

172-
time_out_idx = (self.episode_length_buf > self.max_episode_length).nonzero(as_tuple=False).flatten()
173+
time_out_idx = (self.episode_length_buf > self.max_episode_length).nonzero(as_tuple=False).reshape((-1,))
173174
self.extras["time_outs"] = torch.zeros_like(self.reset_buf, device=gs.device, dtype=gs.tc_float)
174175
self.extras["time_outs"][time_out_idx] = 1.0
175176

176-
self.reset_idx(self.reset_buf.nonzero(as_tuple=False).flatten())
177+
self.reset_idx(self.reset_buf.nonzero(as_tuple=False).reshape((-1,)))
177178

178179
# compute reward
179180
self.rew_buf[:] = 0.0

examples/locomotion/go2_env.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -144,7 +144,7 @@ def step(self, actions):
144144
envs_idx = (
145145
(self.episode_length_buf % int(self.env_cfg["resampling_time_s"] / self.dt) == 0)
146146
.nonzero(as_tuple=False)
147-
.flatten()
147+
.reshape((-1,))
148148
)
149149
self._resample_commands(envs_idx)
150150

@@ -153,11 +153,11 @@ def step(self, actions):
153153
self.reset_buf |= torch.abs(self.base_euler[:, 1]) > self.env_cfg["termination_if_pitch_greater_than"]
154154
self.reset_buf |= torch.abs(self.base_euler[:, 0]) > self.env_cfg["termination_if_roll_greater_than"]
155155

156-
time_out_idx = (self.episode_length_buf > self.max_episode_length).nonzero(as_tuple=False).flatten()
156+
time_out_idx = (self.episode_length_buf > self.max_episode_length).nonzero(as_tuple=False).reshape((-1,))
157157
self.extras["time_outs"] = torch.zeros_like(self.reset_buf, device=gs.device, dtype=gs.tc_float)
158158
self.extras["time_outs"][time_out_idx] = 1.0
159159

160-
self.reset_idx(self.reset_buf.nonzero(as_tuple=False).flatten())
160+
self.reset_idx(self.reset_buf.nonzero(as_tuple=False).reshape((-1,)))
161161

162162
# compute reward
163163
self.rew_buf[:] = 0.0

genesis/engine/bvh.py

Lines changed: 22 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -160,7 +160,6 @@ class Node:
160160
# Whether an internal node has been visited during traversal
161161
self.internal_node_active = ti.field(ti.u1, shape=(self.n_batches, self.n_aabbs - 1))
162162
self.internal_node_ready = ti.field(ti.u1, shape=(self.n_batches, self.n_aabbs - 1))
163-
self.updated = ti.field(ti.u1, shape=())
164163

165164
# Query results, vec3 of batch id, self id, query id
166165
self.query_result = ti.field(gs.ti_ivec3, shape=(self.max_n_query_results))
@@ -281,11 +280,7 @@ def build_radix_tree(self):
281280

282281
# Parallel build for every internal node
283282
for i_b, i in ti.ndrange(self.n_batches, self.n_aabbs - 1):
284-
d = ti.select(
285-
self.delta(i, i + 1, i_b) > self.delta(i, i - 1, i_b),
286-
1,
287-
-1,
288-
)
283+
d = ti.select(self.delta(i, i + 1, i_b) > self.delta(i, i - 1, i_b), 1, -1)
289284

290285
delta_min = self.delta(i, i - d, i_b)
291286
l_max = ti.u32(2)
@@ -337,12 +332,12 @@ def compute_bounds(self):
337332
Starts from the leaf nodes and works upwards layer by layer.
338333
"""
339334
self._kernel_compute_bounds_init()
340-
while self.updated[None]:
341-
self._kernel_compute_bounds_one_layer()
335+
is_done = False
336+
while not is_done:
337+
is_done = self._kernel_compute_bounds_one_layer()
342338

343339
@ti.kernel
344340
def _kernel_compute_bounds_init(self):
345-
self.updated[None] = True
346341
self.internal_node_active.fill(False)
347342
self.internal_node_ready.fill(False)
348343

@@ -355,26 +350,26 @@ def _kernel_compute_bounds_init(self):
355350
self.internal_node_active[i_b, parent_idx] = True
356351

357352
@ti.kernel
358-
def _kernel_compute_bounds_one_layer(self):
359-
self.updated[None] = False
353+
def _kernel_compute_bounds_one_layer(self) -> ti.u1:
360354
for i_b, i in ti.ndrange(self.n_batches, self.n_aabbs - 1):
361-
if not self.internal_node_active[i_b, i]:
362-
continue
363-
left_bound = self.nodes[i_b, self.nodes[i_b, i].left].bound
364-
right_bound = self.nodes[i_b, self.nodes[i_b, i].right].bound
365-
self.nodes[i_b, i].bound.min = ti.min(left_bound.min, right_bound.min)
366-
self.nodes[i_b, i].bound.max = ti.max(left_bound.max, right_bound.max)
367-
parent_idx = self.nodes[i_b, i].parent
368-
if parent_idx != -1:
369-
self.internal_node_ready[i_b, parent_idx] = True
370-
self.internal_node_active[i_b, i] = False
371-
self.updated[None] = True
372-
355+
if self.internal_node_active[i_b, i]:
356+
left_bound = self.nodes[i_b, self.nodes[i_b, i].left].bound
357+
right_bound = self.nodes[i_b, self.nodes[i_b, i].right].bound
358+
self.nodes[i_b, i].bound.min = ti.min(left_bound.min, right_bound.min)
359+
self.nodes[i_b, i].bound.max = ti.max(left_bound.max, right_bound.max)
360+
parent_idx = self.nodes[i_b, i].parent
361+
if parent_idx != -1:
362+
self.internal_node_ready[i_b, parent_idx] = True
363+
self.internal_node_active[i_b, i] = False
364+
365+
is_done = True
373366
for i_b, i in ti.ndrange(self.n_batches, self.n_aabbs - 1):
374-
if not self.internal_node_ready[i_b, i]:
375-
continue
376-
self.internal_node_active[i_b, i] = True
377-
self.internal_node_ready[i_b, i] = False
367+
if self.internal_node_ready[i_b, i]:
368+
self.internal_node_active[i_b, i] = True
369+
is_done = False
370+
self.internal_node_ready.fill(False)
371+
372+
return is_done
378373

379374
@ti.kernel
380375
def query(self, aabbs: ti.template()):

genesis/engine/coupler.py

Lines changed: 9 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -694,7 +694,7 @@ def init_fem_fields(self):
694694
self.fem_pressure.from_numpy(fem_pressure_np)
695695
self.fem_pressure_gradient = ti.field(gs.ti_vec3, shape=(fem_solver._B, fem_solver.n_elements))
696696
self.fem_floor_contact_pair_type = ti.types.struct(
697-
active=gs.ti_int, # whether the contact pair is active
697+
active=ti.u1, # whether the contact pair is active
698698
batch_idx=gs.ti_int, # batch index
699699
geom_idx=gs.ti_int, # index of the FEM element
700700
intersection_code=gs.ti_int, # intersection code for the element
@@ -904,7 +904,7 @@ def fem_floor_detection(self, f: ti.i32):
904904
# Compute data for each contact pair
905905
for i_c in range(self.n_fem_floor_contact_pairs[None]):
906906
pair = self.fem_floor_contact_pairs[i_c]
907-
self.fem_floor_contact_pairs[i_c].active = 1 # mark the contact pair as active
907+
self.fem_floor_contact_pairs[i_c].active = True # mark the contact pair as active
908908
i_b = pair.batch_idx
909909
i_e = pair.geom_idx
910910
intersection_code = pair.intersection_code
@@ -956,7 +956,7 @@ def fem_floor_detection(self, f: ti.i32):
956956
rigid_g = self.fem_pressure_gradient[i_b, i_e].z
957957
# TODO A better way to handle corner cases where pressure and pressure gradient are ill defined
958958
if total_area < gs.EPS or rigid_g < gs.EPS:
959-
self.fem_floor_contact_pairs[i_c].active = 0
959+
self.fem_floor_contact_pairs[i_c].active = False
960960
continue
961961
g = self.default_deformable_g * rigid_g / (self.default_deformable_g + rigid_g) # harmonic average
962962
rigid_k = total_area * g
@@ -1004,7 +1004,7 @@ def compute_fem_floor_regularization(self, f: ti.i32):
10041004
fem_solver = self.fem_solver
10051005

10061006
for i_c in range(self.n_fem_floor_contact_pairs[None]):
1007-
if pairs[i_c].active == 0:
1007+
if not pairs[i_c].active:
10081008
continue
10091009
i_b = pairs[i_c].batch_idx
10101010
i_e = pairs[i_c].geom_idx
@@ -1103,7 +1103,7 @@ def compute_contact_gradient_hessian_diag_prec(self, f: ti.i32):
11031103
fem_solver = self.fem_solver
11041104

11051105
for i_c in range(self.n_fem_floor_contact_pairs[None]):
1106-
if pairs[i_c].active == 0:
1106+
if not pairs[i_c].active:
11071107
continue
11081108
i_b = pairs[i_c].batch_idx
11091109
i_e = pairs[i_c].geom_idx
@@ -1171,7 +1171,7 @@ def compute_contact_energy(self, f: ti.i32):
11711171
fem_solver = self.fem_solver
11721172

11731173
for i_c in range(self.n_fem_floor_contact_pairs[None]):
1174-
if pairs[i_c].active == 0:
1174+
if not pairs[i_c].active:
11751175
continue
11761176
i_b = pairs[i_c].batch_idx
11771177
if not self.batch_linesearch_active[i_b]:
@@ -1284,7 +1284,7 @@ def compute_Ap(self):
12841284

12851285
pairs = ti.static(self.fem_floor_contact_pairs)
12861286
for i_c in range(self.n_fem_floor_contact_pairs[None]):
1287-
if pairs[i_c].active == 0:
1287+
if not pairs[i_c].active:
12881288
continue
12891289
i_b = pairs[i_c].batch_idx
12901290
i_e = pairs[i_c].geom_idx
@@ -1444,20 +1444,18 @@ def compute_total_energy(self, f, energy):
14441444
for i_c in range(self.n_fem_floor_contact_pairs[None]):
14451445
pair = self.fem_floor_contact_pairs[i_c]
14461446
i_b = pair.batch_idx
1447-
if not self.batch_linesearch_active[i_b] or pair.active == 0:
1447+
if not self.batch_linesearch_active[i_b] or not pair.active:
14481448
continue
14491449
energy[i_b] += pair.energy
14501450

14511451
@ti.kernel
14521452
def init_linesearch(self, f: ti.i32):
14531453
fem_solver = self.fem_solver
1454-
dt = ti.static(self.sim._substep_dt)
1455-
dt2 = dt**2
14561454
for i_b in ti.ndrange(self._B):
14571455
self.batch_linesearch_active[i_b] = self.batch_active[i_b]
14581456
if not self.batch_linesearch_active[i_b]:
14591457
continue
1460-
self.linesearch_state[i_b].step_size = 1.0 / ti.static(self._linesearch_tau)
1458+
self.linesearch_state[i_b].step_size = 1.0 / self._linesearch_tau
14611459
self.linesearch_state[i_b].m = 0.0
14621460

14631461
# x_prev, m

genesis/engine/entities/emitter.py

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -101,14 +101,14 @@ def emit(
101101
else:
102102
gs.raise_exception(f"Unsupported nozzle shape: {droplet_shape}.")
103103

104+
direction = np.asarray(direction, dtype=gs.np_float)
104105
if np.linalg.norm(direction) < gs.EPS:
105106
gs.raise_exception("Zero-length direction.")
106107
else:
107108
direction = gu.normalize(direction)
108109

109110
p_size = self._solver.particle_size if p_size is None else p_size
110111

111-
pos = np.array(pos)
112112
if droplet_length is None:
113113
# Use the speed to determine the length of the droplet in the emitting direction
114114
droplet_length = speed * self._solver.substep_dt * self._sim.substeps + self._acc_droplet_len
@@ -148,10 +148,10 @@ def emit(
148148
gs.raise_exception()
149149

150150
positions = gu.transform_by_trans_R(
151-
positions,
152-
pos,
151+
positions.astype(gs.np_float, copy=False),
152+
np.asarray(pos, dtype=gs.np_float),
153153
gu.z_up_to_R(direction) @ gu.axis_angle_to_R(np.array([0.0, 0.0, 1.0], dtype=gs.np_float), theta),
154-
).astype(gs.np_float)
154+
)
155155

156156
positions = np.tile(positions[np.newaxis], (self._sim._B, 1, 1))
157157

@@ -161,8 +161,8 @@ def emit(
161161
n_particles = positions.shape[1]
162162

163163
# Expand vels with batch dimension
164-
vels = np.tile(direction * speed, (n_particles, 1)).astype(gs.np_float)
165-
vels = np.tile(vels[np.newaxis], (self._sim._B, 1, 1))
164+
vels = speed * direction
165+
vels = np.tile(vels.reshape((1, 1, -1)), (self._sim._B, n_particles, 1))
166166

167167
if n_particles > self._entity.n_particles:
168168
gs.logger.warning(

genesis/engine/entities/fem_entity.py

Lines changed: 17 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -8,12 +8,12 @@
88
import genesis.utils.element as eu
99
import genesis.utils.geom as gu
1010
import genesis.utils.mesh as mu
11+
from genesis.engine.coupler import SAPCoupler
1112
from genesis.engine.states.cache import QueriedStates
1213
from genesis.engine.states.entities import FEMEntityState
13-
from genesis.utils.misc import to_gs_tensor
14+
from genesis.utils.misc import to_gs_tensor, tensor_to_array
1415

1516
from .base_entity import Entity
16-
from genesis.engine.coupler import SAPCoupler
1717

1818

1919
@ti.data_oriented
@@ -62,28 +62,26 @@ def __init__(self, scene, solver, material, morph, surface, idx, v_start=0, el_s
6262
el2tri = np.array(
6363
[ # follow the order with correct normal
6464
[[v[0], v[2], v[1]], [v[1], v[2], v[3]], [v[0], v[1], v[3]], [v[0], v[3], v[2]]] for v in self.elems
65-
]
65+
],
66+
dtype=gs.np_int,
6667
)
67-
all_tri = el2tri.reshape(-1, 3)
68+
all_tri = el2tri.reshape((-1, 3))
6869
all_tri_sorted = np.sort(all_tri, axis=1)
6970
_, unique_idcs, cnt = np.unique(all_tri_sorted, axis=0, return_counts=True, return_index=True)
7071
unique_tri = all_tri[unique_idcs]
7172
surface_tri = unique_tri[cnt == 1]
7273

73-
self._surface_tri_np = surface_tri.astype(gs.np_int)
74+
self._surface_tri_np = surface_tri
7475
self._n_surfaces = len(self._surface_tri_np)
7576

7677
if self._n_surfaces > 0:
7778
self._n_surface_vertices = len(np.unique(self._surface_tri_np))
7879
else:
7980
self._n_surface_vertices = 0
8081

81-
tri2el = np.repeat(np.arange(self.elems.shape[0])[:, None], 4, axis=-1)
82-
all_el = tri2el.reshape(
83-
-1,
84-
)
85-
unique_el = all_el[unique_idcs]
86-
self._surface_el_np = unique_el[cnt == 1].astype(gs.np_int)
82+
tri2el = np.repeat(np.arange(self.elems.shape[0], dtype=gs.np_int)[:, np.newaxis], 4, axis=1)
83+
unique_el = tri2el.flat[unique_idcs]
84+
self._surface_el_np = unique_el[cnt == 1]
8785

8886
if isinstance(self.sim.coupler, SAPCoupler):
8987
self.compute_pressure_field()
@@ -259,7 +257,7 @@ def set_muscle(self, muscle_group=None, muscle_direction=None):
259257
if muscle_direction is not None:
260258
muscle_direction = to_gs_tensor(muscle_direction)
261259
assert muscle_direction.shape == (self.n_elements, 3)
262-
assert torch.allclose(muscle_direction.norm(dim=-1), torch.Tensor([1.0]).to(muscle_direction))
260+
assert ((1.0 - muscle_direction.norm(dim=-1)).abs() < gs.EPS).all()
263261

264262
self.set_muscle_direction(muscle_direction)
265263

@@ -308,8 +306,8 @@ def instantiate(self, verts, elems):
308306
Exception
309307
If no vertices are provided.
310308
"""
311-
verts = verts.astype(gs.np_float)
312-
elems = elems.astype(gs.np_int)
309+
verts = verts.astype(gs.np_float, copy=False)
310+
elems = elems.astype(gs.np_int, copy=False)
313311

314312
# rotate
315313
R = gu.quat_to_R(np.array(self.morph.quat, dtype=gs.np_float))
@@ -368,8 +366,8 @@ def _add_to_solver(self, in_backward=False):
368366
)
369367

370368
# Convert to appropriate numpy array types
371-
elems_np = self.elems.astype(gs.np_int)
372-
verts_numpy = self.init_positions.cpu().numpy().astype(gs.np_float)
369+
elems_np = self.elems.astype(gs.np_int, copy=False)
370+
verts_numpy = tensor_to_array(self.init_positions, dtype=gs.np_float)
373371

374372
self._solver._kernel_add_elements(
375373
f=self._sim.cur_substep_local,
@@ -401,8 +399,10 @@ def compute_pressure_field(self):
401399
TODO: Add margin support
402400
Drake's implementation of margin seems buggy.
403401
"""
404-
init_positions = self.init_positions.cpu().numpy()
402+
init_positions = tensor_to_array(self.init_positions)
405403
signed_distance, *_ = igl.signed_distance(init_positions, init_positions, self._surface_tri_np)
404+
signed_distance = signed_distance.astype(gs.np_float, copy=False)
405+
406406
unsigned_distance = np.abs(signed_distance)
407407
max_distance = np.max(unsigned_distance)
408408
if max_distance < gs.EPS:

0 commit comments

Comments
 (0)