Skip to content

Commit cc1fd48

Browse files
authored
Merge branch 'main' into ipc-coupling-squashed
2 parents f01bb28 + 9f1a98a commit cc1fd48

33 files changed

+766
-290
lines changed

RELEASE.md

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,31 @@
11
# Genesis Release Note
22

3+
## 0.3.7
4+
5+
The performance of GsTaichi dynamic array mode has been greatly improved. Now it should be on par with fixed-size array mode (aka performance mode) for very large batch sizes, and up to 30% slower for non-batched simulations. This mode is still considered experimental and must be enabled manually by setting the env var 'GS_ENABLE_NDARRAY=1'. Just try it if you are tired of endlessly waiting for the simulation to compile!
6+
7+
### New Features
8+
9+
* Implement position-velocity controller. (@matthieuvigne) (#1948)
10+
11+
### Bug Fixes
12+
13+
* Fix missing option `diffuse_texture` to `Glass` surface. (@Kashu7100) (#1934)
14+
* Fix interactive viewer. (@YilingQiao) (#1931)
15+
* Fix external coupling forces from other solvers not affecting rigid bodies. (@SonSang) (#1941)
16+
* Fix silent process killing issue in MPM simulation by raising an exception. (@SonSang) (#1949)
17+
* Fix 'discrete_obstacles_terrain' being completely flat. (@jgillick) (#1972)
18+
19+
### Miscellaneous
20+
21+
* Added warning message about stable timestep for SPH solver. (@SonSang) (#1925)
22+
* Reduce memory usage due to diff constraint solver. (@YilingQiao) (#1930)
23+
* Faster non-batched simulation. (@duburcqa) (#1935)
24+
* Fix or silent dev warnings. (@duburcqa) (#1944)
25+
* Add caching to Rigid Link state getters to improve performance. (@duburcqa) (#1940, #1955)
26+
* Add support of Linux ARM. (@duburcqa) (#1961)
27+
* Add 'GS_PARA_LEVEL' env var to force kernel parallelization level. (@duburcqa) (#1968)
28+
329
## 0.3.6
430

531
A new experimental interface with the Incremental Potential Contact coupling solver [libuipc](https://github.com/spiriMirror/libuipc) has been introduced, mainly targeting cloth simulation.

examples/rigid/control_mesh.py

Lines changed: 4 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,5 @@
11
import argparse
22

3-
import numpy as np
4-
53
import genesis as gs
64

75

@@ -45,17 +43,13 @@ def main():
4543
scene.build()
4644

4745
dofs_idx = duck.base_joint.dofs_idx
46+
duck.set_dofs_kp((0.3,) * 6, dofs_idx)
47+
duck.set_dofs_kv((1.0,) * 6, dofs_idx)
4848

49-
duck.set_dofs_kv(
50-
np.array([1, 1, 1, 1, 1, 1]) * 50.0,
51-
dofs_idx,
52-
)
5349
pos = duck.get_dofs_position()
5450
pos[-1] = 1.0 # rotate around intrinsic z axis
55-
duck.control_dofs_position(
56-
pos,
57-
dofs_idx,
58-
)
51+
duck.control_dofs_position(pos, dofs_idx)
52+
5953
for i in range(1000):
6054
scene.step()
6155

Lines changed: 129 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,129 @@
1+
# This example compares the position control accuracy between 'control_dofs_position' and
2+
# 'control_dofs_position_velocity' when tracking a dynamic trajectory.
3+
# While both are equivalent in static, the former lacks the target velocity term of true PD controller in robotics,
4+
# making it underperform compared to 'control_dofs_position_velocity'.
5+
import argparse
6+
import math
7+
8+
import matplotlib.pyplot as plt
9+
10+
import genesis as gs
11+
12+
13+
def main():
14+
parser = argparse.ArgumentParser()
15+
parser.add_argument("-v", "--vis", action="store_true", default=False)
16+
parser.add_argument("-c", "--cpu", action="store_true", default=False)
17+
args = parser.parse_args()
18+
19+
########################## init ##########################
20+
gs.init(backend=gs.cpu if args.cpu else gs.gpu)
21+
22+
########################## create a scene ##########################
23+
scene = gs.Scene(
24+
viewer_options=gs.options.ViewerOptions(
25+
camera_pos=(0, -3.5, 2.5),
26+
camera_lookat=(0.0, 0.0, 0.5),
27+
camera_fov=30,
28+
max_FPS=None,
29+
),
30+
sim_options=gs.options.SimOptions(
31+
dt=0.005,
32+
),
33+
show_viewer=False,
34+
show_FPS=True,
35+
)
36+
37+
########################## entities ##########################
38+
plane = scene.add_entity(
39+
gs.morphs.Plane(),
40+
)
41+
franka = scene.add_entity(
42+
gs.morphs.MJCF(
43+
file="xml/franka_emika_panda/panda.xml",
44+
),
45+
)
46+
########################## build ##########################
47+
scene.build()
48+
49+
joints_name = (
50+
"joint1",
51+
"joint2",
52+
"joint3",
53+
"joint4",
54+
"joint5",
55+
"joint6",
56+
"joint7",
57+
"finger_joint1",
58+
"finger_joint2",
59+
)
60+
motors_dof_idx = [franka.get_joint(name).dofs_idx_local[0] for name in joints_name]
61+
62+
############ Optional: set control gains ############
63+
# set positional gains
64+
franka.set_dofs_kp(
65+
kp=[4500, 4500, 3500, 3500, 2000, 2000, 2000, 100, 100],
66+
dofs_idx_local=motors_dof_idx,
67+
)
68+
# set velocity gains
69+
franka.set_dofs_kv(
70+
kv=[450, 450, 350, 350, 200, 200, 200, 10, 10],
71+
dofs_idx_local=motors_dof_idx,
72+
)
73+
# set force range for safety
74+
franka.set_dofs_force_range(
75+
lower=[-87, -87, -87, -87, -12, -12, -12, -100, -100],
76+
upper=[87, 87, 87, 87, 12, 12, 12, 100, 100],
77+
dofs_idx_local=motors_dof_idx,
78+
)
79+
# Hard reset
80+
# Follow a sinusoid trajectory
81+
A = 0.5 # motion amplitude, rad
82+
f = 1.0 # motion frequency, Hz
83+
84+
# Use control_dofs_position
85+
pos_simulation_result = []
86+
franka.set_dofs_position([A, 0, 0, 0, 0, 0, 0, 0, 0], motors_dof_idx)
87+
t0 = scene.t
88+
while (t := (scene.t - t0) * scene.dt) < 2.0:
89+
target_position = A * (1 + math.sin(2 * math.pi * f * t))
90+
91+
current_position = float(franka.get_qpos()[0])
92+
pos_simulation_result.append([t, current_position, target_position])
93+
franka.control_dofs_position([target_position, 0, 0, 0, 0, 0, 0, 0, 0], motors_dof_idx)
94+
scene.step()
95+
96+
# Use control_dofs_position_velocity
97+
pos_vel_simulation_result = []
98+
franka.set_dofs_position([A, 0, 0, 0, 0, 0, 0, 0, 0], motors_dof_idx)
99+
t0 = scene.t
100+
while (t := (scene.t - t0) * scene.dt) < 2.0:
101+
target_position = A * (1 + math.sin(2 * math.pi * f * t))
102+
target_velocity = 2 * math.pi * f * A * math.cos(2 * math.pi * f * t)
103+
104+
current_position = float(franka.get_qpos()[0])
105+
pos_vel_simulation_result.append([t, current_position, target_position])
106+
franka.control_dofs_position_velocity(
107+
[target_position, 0, 0, 0, 0, 0, 0, 0, 0],
108+
[target_velocity, 0, 0, 0, 0, 0, 0, 0, 0],
109+
motors_dof_idx,
110+
)
111+
scene.step()
112+
113+
# Plot results
114+
pos_simulation_result = tuple(zip(*pos_simulation_result))
115+
pos_vel_simulation_result = tuple(zip(*pos_vel_simulation_result))
116+
117+
plt.plot(pos_simulation_result[0], pos_simulation_result[1], label="control_dofs_position")
118+
plt.plot(pos_vel_simulation_result[0], pos_vel_simulation_result[1], label="control_dofs_position_velocity")
119+
plt.plot(pos_vel_simulation_result[0], pos_vel_simulation_result[2], color="black", label="Target position")
120+
plt.xlabel("Time (s)")
121+
plt.ylabel("Joint position (rad)")
122+
plt.title("Comparison of joint position tracking with two different controllers")
123+
plt.grid()
124+
plt.legend()
125+
plt.show()
126+
127+
128+
if __name__ == "__main__":
129+
main()

genesis/__init__.py

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -118,8 +118,7 @@ def init(
118118

119119
# Configure GsTaichi fast cache and array type
120120
global use_ndarray, use_fastcache
121-
# is_ndarray_disabled = (os.environ.get("GS_ENABLE_NDARRAY") or ("0" if sys.platform == "darwin" else "1")) == "0"
122-
is_ndarray_disabled = os.environ.get("GS_ENABLE_NDARRAY", "0") == "0"
121+
is_ndarray_disabled = (os.environ.get("GS_ENABLE_NDARRAY") or ("0" if sys.platform == "darwin" else "1")) == "0"
123122
if use_ndarray is None:
124123
_use_ndarray = not (is_ndarray_disabled or performance_mode)
125124
else:

genesis/engine/couplers/legacy_coupler.py

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -190,6 +190,7 @@ def _func_collide_with_rigid_geom(
190190
normal_rigid = sdf_decomp.sdf_func_normal_world(
191191
geoms_state=geoms_state,
192192
geoms_info=geoms_info,
193+
rigid_global_info=rigid_global_info,
193194
collider_static_config=collider_static_config,
194195
sdf_info=sdf_info,
195196
pos_world=pos_world,
@@ -241,6 +242,7 @@ def _func_collide_with_rigid_geom_robust(
241242
normal_rigid = sdf_decomp.sdf_func_normal_world(
242243
geoms_state=geoms_state,
243244
geoms_info=geoms_info,
245+
rigid_global_info=rigid_global_info,
244246
collider_static_config=collider_static_config,
245247
sdf_info=sdf_info,
246248
pos_world=pos_world,
@@ -500,6 +502,7 @@ def mpm_surface_to_particle(
500502
geoms_state: array_class.GeomsState,
501503
geoms_info: array_class.GeomsInfo,
502504
sdf_info: array_class.SDFInfo,
505+
rigid_global_info: array_class.RigidGlobalInfo,
503506
collider_static_config: ti.template(),
504507
):
505508
for i_p, i_b in ti.ndrange(self.mpm_solver.n_particles, self.mpm_solver._B):
@@ -509,6 +512,7 @@ def mpm_surface_to_particle(
509512
sdf_normal = sdf_decomp.sdf_func_normal_world(
510513
geoms_state=geoms_state,
511514
geoms_info=geoms_info,
515+
rigid_global_info=rigid_global_info,
512516
collider_static_config=collider_static_config,
513517
sdf_info=sdf_info,
514518
pos_world=self.mpm_solver.particles[f, i_p, i_b].pos,
@@ -730,6 +734,7 @@ def kernel_pbd_rigid_collide(
730734
geoms_info: array_class.GeomsInfo,
731735
links_state: array_class.LinksState,
732736
sdf_info: array_class.SDFInfo,
737+
rigid_global_info: array_class.RigidGlobalInfo,
733738
collider_static_config: ti.template(),
734739
):
735740
for i_p, i_b in ti.ndrange(self.pbd_solver._n_particles, self.sph_solver._B):
@@ -753,6 +758,7 @@ def kernel_pbd_rigid_collide(
753758
geoms_info,
754759
links_state,
755760
sdf_info,
761+
rigid_global_info,
756762
collider_static_config,
757763
)
758764

@@ -856,6 +862,7 @@ def _func_pbd_collide_with_rigid_geom(
856862
geoms_info: array_class.GeomsInfo,
857863
links_state: array_class.LinksState,
858864
sdf_info: array_class.SDFInfo,
865+
rigid_global_info: array_class.RigidGlobalInfo,
859866
collider_static_config: ti.template(),
860867
):
861868
"""
@@ -879,6 +886,7 @@ def _func_pbd_collide_with_rigid_geom(
879886
contact_normal = sdf_decomp.sdf_func_normal_world(
880887
geoms_state=geoms_state,
881888
geoms_info=geoms_info,
889+
rigid_global_info=rigid_global_info,
882890
collider_static_config=collider_static_config,
883891
sdf_info=sdf_info,
884892
pos_world=pos_world,
@@ -926,6 +934,7 @@ def preprocess(self, f):
926934
self.rigid_solver.geoms_state,
927935
self.rigid_solver.geoms_info,
928936
self.rigid_solver.sdf._sdf_info,
937+
self.rigid_solver._rigid_global_info,
929938
self.rigid_solver.collider._collider_static_config,
930939
)
931940

@@ -963,6 +972,7 @@ def couple(self, f):
963972
geoms_info=self.rigid_solver.geoms_info,
964973
links_state=self.rigid_solver.links_state,
965974
sdf_info=self.rigid_solver.sdf._sdf_info,
975+
rigid_global_info=self.rigid_solver._rigid_global_info,
966976
collider_static_config=self.rigid_solver.collider._collider_static_config,
967977
)
968978

genesis/engine/couplers/sap_coupler.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -377,14 +377,14 @@ def rigid_update_volume_verts_pressure_gradient(
377377
i_g = self.rigid_volume_verts_geom_idx[i_v]
378378
pos = geoms_state.pos[i_g, i_b]
379379
quat = geoms_state.quat[i_g, i_b]
380-
R = gu.ti_quat_to_R(quat)
380+
R = gu.ti_quat_to_R(quat, gs.EPS)
381381
self.rigid_volume_verts[i_b, i_v] = R @ self.rigid_volume_verts_rest[i_v] + pos
382382

383383
for i_b, i_e in ti.ndrange(self._B, self.n_rigid_volume_elems):
384384
i_g = self.rigid_volume_elems_geom_idx[i_e]
385385
pos = geoms_state.pos[i_g, i_b]
386386
quat = geoms_state.quat[i_g, i_b]
387-
R = gu.ti_quat_to_R(quat)
387+
R = gu.ti_quat_to_R(quat, gs.EPS)
388388
self.rigid_pressure_gradient[i_b, i_e] = R @ self.rigid_pressure_gradient_rest[i_e]
389389

390390
@ti.kernel

genesis/engine/entities/hybrid_entity.py

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -309,6 +309,22 @@ def control_dofs_position(self, *args, **kwargs):
309309
"""
310310
return self._part_rigid.control_dofs_position(*args, **kwargs)
311311

312+
def control_dofs_position_velocity(self, *args, **kwargs):
313+
"""
314+
Apply position control to the rigid part of the hybrid entity.
315+
316+
Parameters
317+
----------
318+
*args, **kwargs
319+
Passed directly to the rigid entity's control_dofs_position method.
320+
321+
Returns
322+
-------
323+
gs.Tensor
324+
Control output for position adjustment of the rigid body's DOFs.
325+
"""
326+
return self._part_rigid.control_dofs_position_velocity(*args, **kwargs)
327+
312328
def control_dofs_velocity(self, *args, **kwargs):
313329
"""
314330
Apply velocity control to the rigid part of the hybrid entity.

0 commit comments

Comments
 (0)