Skip to content

Commit ae34487

Browse files
committed
Fix dtype handling.
1 parent 5dbe448 commit ae34487

File tree

27 files changed

+171
-173
lines changed

27 files changed

+171
-173
lines changed

genesis/engine/entities/emitter.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -101,14 +101,15 @@ 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)
112+
pos = np.asarray(pos, dtype=gs.np_float)
112113
if droplet_length is None:
113114
# Use the speed to determine the length of the droplet in the emitting direction
114115
droplet_length = speed * self._solver.substep_dt * self._sim.substeps + self._acc_droplet_len
@@ -148,10 +149,10 @@ def emit(
148149
gs.raise_exception()
149150

150151
positions = gu.transform_by_trans_R(
151-
positions,
152+
positions.astype(gs.np_float, copy=False),
152153
pos,
153154
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)
155+
)
155156

156157
positions = np.tile(positions[np.newaxis], (self._sim._B, 1, 1))
157158

@@ -161,8 +162,7 @@ def emit(
161162
n_particles = positions.shape[1]
162163

163164
# 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))
165+
vels = np.tile((speed * direction).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: 12 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -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,

genesis/engine/entities/hybrid_entity.py

Lines changed: 11 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -144,7 +144,7 @@ def __init__(
144144

145145
# set muscle group
146146
mat_soft._n_groups = len(link_idcs)
147-
self._muscle_group_cache = muscle_group
147+
self._muscle_group_cache = muscle_group.astype(gs.np_int)
148148

149149
# set up info in taichi field
150150
if isinstance(mat_soft, gs.materials.MPM.Base):
@@ -154,10 +154,10 @@ def __init__(
154154
trans_local_to_global=gs.ti_vec3,
155155
quat_local_to_global=gs.ti_vec4,
156156
).field(shape=(mat_soft.n_groups,), needs_grad=False, layout=ti.Layout.SOA)
157-
part_soft_info.link_idx.from_numpy(np.array(link_idcs).astype(gs.np_int))
158-
part_soft_info.geom_idx.from_numpy(np.array(geom_idcs).astype(gs.np_int))
159-
part_soft_info.trans_local_to_global.from_numpy(np.array(trans_local_to_global).astype(gs.np_float))
160-
part_soft_info.quat_local_to_global.from_numpy(np.array(quat_local_to_global).astype(gs.np_float))
157+
part_soft_info.link_idx.from_numpy(np.asarray(link_idcs, dtype=gs.np_int))
158+
part_soft_info.geom_idx.from_numpy(np.asarray(geom_idcs, dtype=gs.np_int))
159+
part_soft_info.trans_local_to_global.from_numpy(np.asarray(trans_local_to_global, dtype=gs.np_float))
160+
part_soft_info.quat_local_to_global.from_numpy(np.asarray(quat_local_to_global, dtype=gs.np_float))
161161

162162
part_soft_init_positions = ti.field(dtype=gs.ti_vec3, shape=(part_soft.init_particles.shape[0],))
163163
part_soft_init_positions.from_torch(gs.Tensor(part_soft.init_particles))
@@ -352,7 +352,7 @@ def build(self):
352352
# can only be called here (at sim build)
353353
if not self.material.use_default_coupling and self._muscle_group_cache is not None:
354354
self._part_soft.set_muscle(
355-
muscle_group=gs.tensor(self._muscle_group_cache.astype(gs.np_int)),
355+
muscle_group=gs.tensor(self._muscle_group_cache),
356356
# no muscle direction as the soft body is actuated by rigid parts
357357
)
358358

@@ -618,7 +618,7 @@ def default_func_instantiate_rigid_from_soft(
618618
# add rigid entity
619619
mesh_center = (mesh.vertices.max(0) + mesh.vertices.min(0)) / 2.0
620620
offset = (graph_pos[src_node] - mesh_center) * morph.scale
621-
pos_rigid = morph.pos + offset.astype(gs.np_float)
621+
pos_rigid = morph.pos + offset.astype(gs.np_float, copy=False)
622622
quat_rigid = morph.quat
623623
scale_rigid = morph.scale
624624
morph_rigid = gs.morphs.URDF(
@@ -700,11 +700,10 @@ def default_func_instantiate_rigid_soft_association_from_soft(
700700
dist_to_p1 = np.linalg.norm(positions - p1, axis=-1)
701701
dist_to_line = np.sqrt(dist_to_p0**2 - ((positions_proj_on_line_t[:, None] * line_vec) ** 2).sum(-1))
702702

703-
dist_to_link = (
704-
dist_to_p0 * (positions_proj_on_line_t < 0).astype(float)
705-
+ dist_to_p1 * (positions_proj_on_line_t > 1).astype(float)
706-
+ dist_to_line * np.logical_and(positions_proj_on_line_t >= 0, positions_proj_on_line_t <= 1).astype(float)
707-
)
703+
is_clipped_low = positions_proj_on_line_t < 0.0
704+
is_clipped_high = positions_proj_on_line_t > 1.0
705+
is_valid = ~is_clipped_low & ~is_clipped_high
706+
dist_to_link = dist_to_p0 * is_clipped_low + dist_to_p1 * is_clipped_high + dist_to_line * is_valid
708707

709708
trans, quat = gu.transform_pos_quat_by_trans_quat(
710709
geom.init_pos, geom.init_quat, link.init_x_pos, link.init_x_quat

genesis/engine/entities/mpm_entity.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -368,7 +368,7 @@ def get_free(self):
368368
"""
369369
self._assert_active()
370370

371-
free = gs.zeros((self._n_particles,), dtype=int, requires_grad=False, scene=self._scene)
371+
free = gs.zeros((self._n_particles,), dtype=torch.bool, requires_grad=False, scene=self._scene)
372372
self.solver._kernel_get_free(
373373
self._particle_start,
374374
self._n_particles,

genesis/engine/entities/particle_entity.py

Lines changed: 39 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -176,18 +176,18 @@ def _kernel_add_vverts_to_solver(
176176
self.solver.vverts_info.support_idxs[i_vv][j] = support_idxs_local[i_vv_, j] + self._particle_start
177177

178178
kdtree = KDTree(self._particles)
179-
_, support_idxs = kdtree.query(self._vverts, k=self.solver._n_vvert_supports)
179+
_, support_idxs = kdtree.query(self._vverts, k=self.solver._n_vvert_supports).astype(gs.np_int, copy=False)
180180
support_idxs = np.clip(support_idxs, 0, len(self._particles) - 1)
181181
all_ps = self._particles[support_idxs]
182-
Ps = np.stack([all_ps[:, i, :] for i in range(self.solver._n_vvert_supports - 1)], axis=2) - np.expand_dims(
183-
all_ps[:, -1, :], axis=2
184-
)
182+
Ps = np.stack(
183+
[all_ps[:, i, :] for i in range(self.solver._n_vvert_supports - 1)], axis=2, dtype=gs.np_float
184+
) - np.expand_dims(all_ps[:, -1, :], axis=2)
185185

186186
_kernel_add_vverts_to_solver(
187-
vverts=self._vverts.astype(gs.np_float),
188-
particles=self._particles.astype(gs.np_float),
189-
P_invs=np.linalg.pinv(Ps).astype(gs.np_float),
190-
support_idxs_local=support_idxs.astype(gs.np_int),
187+
vverts=self._vverts,
188+
particles=self._particles,
189+
P_invs=np.linalg.pinv(Ps),
190+
support_idxs_local=support_idxs,
191191
)
192192

193193
def sample(self):
@@ -232,7 +232,9 @@ def sample(self):
232232
particles.append(particles_i)
233233

234234
elif isinstance(self._morph, (gs.options.morphs.Primitive, gs.options.morphs.Mesh)):
235-
particles = self._vmesh.particlize(self._particle_size, self.sampler)
235+
particles = self._vmesh.particlize(self._particle_size, self.sampler).astype(
236+
gs.np_float, order="C", copy=False
237+
)
236238

237239
elif isinstance(self._morph, gs.options.morphs.Nowhere):
238240
particles = pu.nowhere_particles(self._morph.n_particles)
@@ -244,14 +246,14 @@ def sample(self):
244246
gs.raise_exception("Entity has zero particles.")
245247

246248
if isinstance(self._morph, gs.options.morphs.Nowhere):
247-
origin = gu.nowhere().astype(gs.np_float)
248-
self._vverts = np.array([])
249-
self._vfaces = np.array([])
249+
origin = gu.nowhere()
250+
self._vverts = np.array([], dtype=gs.np_float)
251+
self._vfaces = np.array([], dtype=gs.np_float)
250252

251253
elif isinstance(self._morph, gs.options.morphs.MeshSet):
252254
for i in range(len(self._morph.files)):
253-
pos_i = np.array(self._morph.poss[i])
254-
quat_i = np.array(gu.euler_to_quat(self._morph.eulers[i]))
255+
pos_i, euler_i = map(np.asarray, (self._morph.poss[i], self._morph.eulers[i]))
256+
quat_i = gs.utils.geom.xyz_to_quat(euler_i, rpy=True, degrees=True)
255257
self._vmesh[i].apply_transform(gu.trans_quat_to_T(pos_i, quat_i))
256258

257259
# NOTE: particles are transformed already
@@ -260,7 +262,7 @@ def sample(self):
260262
self.mesh_set_group_ids = np.concatenate(
261263
[np.ones((v.shape[0],), dtype=gs.np_int) * i for i, v in enumerate(particles)]
262264
)
263-
particles = np.concatenate(particles)
265+
particles = np.concatenate(particles, dtype=gs.np_float)
264266
if not self._solver.boundary.is_inside(particles): # HACK no check
265267
gs.raise_exception(
266268
f"Entity has particles outside solver boundary. Note that for MPMSolver, boundary is slightly tighter than the specified domain due to safety padding.\n\nCurrent boundary:\n{self._solver.boundary}\n\nEntity to be added:\nmin: {particles.min(0)}\nmax: {particles.max(0)}\n"
@@ -277,35 +279,43 @@ def sample(self):
277279
vertex_normals=combined_vert_normals,
278280
)
279281
self._vmesh = mu.trimesh_to_mesh(combined_tmesh, 1, self._surface)
282+
280283
if self._need_skinning:
281-
self._vverts = np.array(self._vmesh.verts)
282-
self._vfaces = np.array(self._vmesh.faces)
284+
self._vverts = np.asarray(self._vmesh.verts, dtype=gs.np_float)
285+
self._vfaces = np.asarray(self._vmesh.faces, dtype=gs.np_float)
283286
else:
284-
self._vverts = np.array([])
285-
self._vfaces = np.array([])
287+
self._vverts = np.asarray([], dtype=gs.np_float)
288+
self._vfaces = np.asarray([], dtype=gs.np_float)
286289
origin = np.mean(self._morph.poss, dtype=gs.np_float)
287290

288291
else:
289292
# transform vmesh
290-
self._vmesh.apply_transform(gu.trans_quat_to_T(np.array(self._morph.pos), np.array(self._morph.quat)))
293+
pos, quat = map(np.asarray, (self._morph.pos, self._morph.quat))
294+
self._vmesh.apply_transform(gu.trans_quat_to_T(pos, quat))
291295
# transform particles
292-
origin = np.array(self._morph.pos, dtype=gs.np_float)
293-
particles = gu.transform_by_trans_quat(particles, np.array(self._morph.pos), np.array(self._morph.quat))
294-
# rotate
296+
particles = gu.transform_by_trans_quat(
297+
particles,
298+
np.asarray(self._morph.pos, dtype=gs.np_float),
299+
np.asarray(self._morph.quat, dtype=gs.np_float),
300+
)
295301

296302
if not self._solver.boundary.is_inside(particles):
297303
gs.raise_exception(
298-
f"Entity has particles outside solver boundary. Note that for MPMSolver, boundary is slightly tighter than the specified domain due to safety padding.\n\nCurrent boundary:\n{self._solver.boundary}\n\nEntity to be added:\nmin: {particles.min(0)}\nmax: {particles.max(0)}\n"
304+
"Entity has particles outside solver boundary. Note that for MPMSolver, boundary is slightly "
305+
"tighter than the specified domain due to safety padding.\n\n"
306+
"Current boundary:\n{self._solver.boundary}\n\nEntity to be added:\nmin: {particles.min(0)}\n"
307+
"max: {particles.max(0)}\n"
299308
)
300309

301310
if self._need_skinning:
302-
self._vverts = np.array(self._vmesh.verts)
303-
self._vfaces = np.array(self._vmesh.faces)
311+
self._vverts = np.asarray(self._vmesh.verts, dtype=gs.np_float)
312+
self._vfaces = np.asarray(self._vmesh.faces, dtype=gs.np_float)
304313
else:
305-
self._vverts = np.array([])
306-
self._vfaces = np.array([])
314+
self._vverts = np.asarray([], dtype=gs.np_float)
315+
self._vfaces = np.asarray([], dtype=gs.np_float)
316+
origin = np.array(self._morph.pos, dtype=gs.np_float)
307317

308-
self._particles = particles.astype(gs.np_float, order="C", copy=False)
318+
self._particles = particles
309319
self._init_particles_offset = gs.tensor(self._particles) - gs.tensor(origin)
310320
self._n_particles = len(self._particles)
311321

genesis/engine/entities/pbd_entity.py

Lines changed: 17 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -80,9 +80,9 @@ def sample(self):
8080
def _add_to_solver_(self):
8181
self._kernel_add_particles_edges_to_solver(
8282
f=self._scene.sim.cur_substep_local,
83-
particles=self._particles.astype(gs.np_float),
84-
edges=self._edges.astype(gs.np_int),
85-
edges_len_rest=self._edges_len_rest.astype(gs.np_float),
83+
particles=self._particles,
84+
edges=self._edges,
85+
edges_len_rest=self._edges_len_rest,
8686
mat_type=self._mat_type,
8787
active=True,
8888
)
@@ -331,16 +331,16 @@ def sample(self):
331331
gs.raise_exception("Input mesh has zero surface area.")
332332
self._mass = self._vmesh.area * self.material.rho
333333

334-
self._particles = np.array(self._mesh.verts)
335-
self._edges = np.array(self._mesh.get_unique_edges())
334+
self._particles = np.asarray(self._mesh.verts, dtype=gs.np_float)
335+
self._edges = np.asarray(self._mesh.get_unique_edges(), dtype=gs.np_int)
336336

337337
self._particle_mass = self._mass / len(self._particles)
338338

339339
# Inner edges are two diagonal edges of each quadrilateral formed by adjacent face pairs
340340
adjacency, inner_edges = trimesh.graph.face_adjacency(mesh=self._mesh.trimesh, return_edges=True)
341341
v3 = np.sum(self._mesh.faces[adjacency[:, 0]], axis=1) - inner_edges[:, 0] - inner_edges[:, 1]
342342
v4 = np.sum(self._mesh.faces[adjacency[:, 1]], axis=1) - inner_edges[:, 0] - inner_edges[:, 1]
343-
self._inner_edges = np.stack([inner_edges[:, 0], inner_edges[:, 1], v3, v4], axis=1)
343+
self._inner_edges = np.stack([inner_edges[:, 0], inner_edges[:, 1], v3, v4], axis=1, dtype=gs.np_int)
344344

345345
self._edges_len_rest = np.linalg.norm(
346346
self._particles[self._edges[:, 0]] - self._particles[self._edges[:, 1]], axis=1
@@ -359,8 +359,8 @@ def _add_to_solver_(self):
359359

360360
self._kernel_add_inner_edges_to_solver(
361361
f=self._scene.sim.cur_substep_local,
362-
inner_edges=self._inner_edges.astype(gs.np_int),
363-
inner_edges_len_rest=self._inner_edges_len_rest.astype(gs.np_float),
362+
inner_edges=self._inner_edges,
363+
inner_edges_len_rest=self._inner_edges_len_rest,
364364
)
365365

366366
@ti.kernel
@@ -469,34 +469,33 @@ def sample(self):
469469
self._mass = self._vmesh.volume * self.material.rho
470470

471471
tet_cfg = mu.generate_tetgen_config_from_morph(self.morph)
472-
self._particles, self._elems = self._mesh.tetrahedralize(tet_cfg)
472+
particles, elems = self._mesh.tetrahedralize(tet_cfg)
473+
self._particles = particles.astype(gs.np_float, copy=False)
474+
self._elems = elems.astype(gs.np_int, copy=False)
473475
self._edges = np.array(
474476
list(
475477
set(
476-
tuple(sorted([self._elems[i, j], self._elems[i, k]]))
477-
for i in range(self._elems.shape[0])
478+
tuple(sorted((self._elems[i, j], self._elems[i, k])))
479+
for i in range(len(self._elems))
478480
for j in range(4)
479481
for k in range(j + 1, 4)
480482
)
481-
)
483+
),
484+
dtype=gs.np_int,
482485
)
483486
self._particle_mass = self._mass / len(self._particles)
484487

485488
self._edges_len_rest = np.linalg.norm(
486489
self._particles[self._edges[:, 0]] - self._particles[self._edges[:, 1]], axis=1
487490
)
488491
self._elems_vol_rest = (
489-
np.linalg.det(self._particles[self._elems[:, 1:]] - self._particles[self._elems[:, 0:1]]) / 6.0
492+
np.linalg.det(self._particles[self._elems[:, 1:]] - self._particles[self._elems[:, :1]]) / 6.0
490493
)
491494
self._n_particles = len(self._particles)
492495

493496
def _add_to_solver_(self):
494497
super()._add_to_solver_()
495-
496-
self._kernel_add_elems_to_solver(
497-
elems=self._elems.astype(gs.np_int),
498-
elems_vol_rest=self._elems_vol_rest.astype(gs.np_float),
499-
)
498+
self._kernel_add_elems_to_solver(elems=self._elems, elems_vol_rest=self._elems_vol_rest)
500499

501500
@ti.kernel
502501
def _kernel_add_elems_to_solver(

genesis/engine/entities/rigid_entity/rigid_entity.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -272,7 +272,7 @@ def _load_mesh(self, morph, surface):
272272

273273
def _load_terrain(self, morph, surface):
274274
vmesh, mesh, self.terrain_hf = tu.parse_terrain(morph, surface)
275-
self.terrain_scale = np.array([morph.horizontal_scale, morph.vertical_scale])
275+
self.terrain_scale = np.array((morph.horizontal_scale, morph.vertical_scale), dtype=gs.np_float)
276276

277277
g_infos = []
278278
if morph.visualization:

0 commit comments

Comments
 (0)