Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
19 commits
Select commit Hold shift + click to select a range
e9c80c7
Improve IPC coupling: use trimesh for rigid bodies and add IPC-only mode
Roushelfy Nov 11, 2025
f01bb28
Refactor: unify IPC coupling API and update examples
Roushelfy Nov 13, 2025
cc1fd48
Merge branch 'main' into ipc-coupling-squashed
YilingQiao Nov 14, 2025
03d6fbb
black format
YilingQiao Nov 14, 2025
562c3fc
Merge branch 'ipc-coupling-squashed' into Roushelfy/ipc-coupling-squa…
Roushelfy Nov 14, 2025
04f6a3f
Merge branch 'main' of https://github.com/Genesis-Embodied-AI/Genesis…
Roushelfy Nov 14, 2025
239c60a
Merge branch 'ipc-coupling-squashed' of https://github.com/Roushelfy/…
Roushelfy Nov 14, 2025
373bae1
Merge pull request #1 from YilingQiao/Roushelfy/ipc-coupling-squashed
Roushelfy Nov 14, 2025
d617c9b
format
Roushelfy Nov 14, 2025
f95e79f
Merge branch 'main' into ipc-coupling-squashed
YilingQiao Nov 17, 2025
ceab965
contact proxy
Roushelfy Nov 18, 2025
23442d1
Add IPC contact force recording and improve transform synchronization
Roushelfy Nov 18, 2025
5e36037
Merge remote-tracking branch 'origin/main' into ipc-coupling-squashed
Roushelfy Nov 18, 2025
d70d942
Optimize IPCCoupler with Taichi kernels for better performance
Roushelfy Dec 3, 2025
0643af8
Merge origin/main into ipc-coupling-squashed
Roushelfy Dec 3, 2025
f41c0f2
Fix: Handle non-parallelized scenes in _get_genesis_link_transform
Roushelfy Dec 3, 2025
0c386ae
Fix: Divide IPC contact gradients by dt^2 to get actual force
Roushelfy Dec 3, 2025
f3b0e47
Optimize IPCCoupler with Taichi kernels
Roushelfy Dec 5, 2025
9538fae
Merge branch 'ipc-coupling-squashed' of https://github.com/Roushelfy/…
Roushelfy Dec 5, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -132,6 +132,7 @@ env.bak/
venv.bak/
.idea/
.vscode/
.claude/

# Spyder project settings
.spyderproject
Expand Down
627 changes: 459 additions & 168 deletions examples/IPC_Solver/genesis_ipc_motion_test.py

Large diffs are not rendered by default.

4 changes: 2 additions & 2 deletions examples/IPC_Solver/ipc_arm_cloth.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,6 @@ def build_scene(use_ipc=False, show_viewer=False, enable_ipc_gui=False):
ipc_constraint_strength=(1, 1), # (translation, rotation) strength ratios,
contact_friction_mu=0.8,
IPC_self_contact=False, # Disable rigid-rigid contact in IPC
two_way_coupling=True, # Enable two-way coupling (forces from IPC to Genesis rigid bodies)
enable_ipc_gui=enable_ipc_gui,
)
if use_ipc
Expand Down Expand Up @@ -110,8 +109,9 @@ def build_scene(use_ipc=False, show_viewer=False, enable_ipc_gui=False):
euler=(0, 0, 0),
),
)
scene.sim.coupler.set_ipc_link_filter(
scene.sim.coupler.set_link_ipc_coupling_type(
entity=entities["robot"],
coupling_type="both",
link_names=["left_finger", "right_finger"],
)

Expand Down
3 changes: 1 addition & 2 deletions examples/IPC_Solver/ipc_cloth.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,7 @@ def main():
contact_d_hat=0.01, # Contact barrier distance (10mm) - must be appropriate for mesh resolution
contact_friction_mu=0.3, # Friction coefficient
IPC_self_contact=False, # Disable rigid self-contact in IPC
two_way_coupling=True, # Enable two-way coupling (forces from IPC to Genesis rigid bodies)
disable_genesis_ground_contact=True, # Disable Genesis ground contact to avoid double contact handling
disable_genesis_contact=True, # Disable Genesis ground contact to avoid double contact handling
enable_ipc_gui=args.vis_ipc,
),
show_viewer=args.vis,
Expand Down
28 changes: 16 additions & 12 deletions examples/IPC_Solver/ipc_grasp.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,25 +14,27 @@ def main():
parser.add_argument("-v", "--vis", action="store_true", default=False)
args = parser.parse_args()

dt = 1e-2
dt = 1e-3

coupler_options = (
gs.options.IPCCouplerOptions(
dt=dt,
gravity=(0.0, 0.0, -9.8),
ipc_constraint_strength=(100, 100), # (translation, rotation) strength ratios,
ipc_constraint_strength=(3, 3), # (translation, rotation) strength ratios,
contact_friction_mu=0.8,
IPC_self_contact=False, # Disable rigid-rigid contact in IPC
two_way_coupling=True, # Enable two-way coupling (forces from IPC to Genesis rigid bodies)
use_contact_proxy=True,
enable_ipc_gui=args.vis_ipc,
)
if args.ipc
else None
)
args.vis = args.vis or args.vis_ipc

rigid_options = gs.options.RigidOptions(
enable_collision=False, # Disable rigid collision when using IPC
)
scene = gs.Scene(
sim_options=gs.options.SimOptions(dt=dt, gravity=(0.0, 0.0, -9.8)),
rigid_options=rigid_options,
coupler_options=coupler_options,
show_viewer=args.vis,
)
Expand All @@ -43,20 +45,22 @@ def main():
scene.add_entity(gs.morphs.Plane())

franka = scene.add_entity(
gs.morphs.MJCF(file="xml/franka_emika_panda/panda.xml"),
gs.morphs.MJCF(file="xml/franka_emika_panda/panda_non_overlap.xml"),
)

scene.sim.coupler.set_ipc_link_filter(
entity=franka,
link_names=["left_finger", "right_finger"],
)
if args.ipc:
scene.sim.coupler.set_link_ipc_coupling_type(
entity=franka,
coupling_type="both",
link_names=["left_finger", "right_finger"],
)

material = (
gs.materials.FEM.Elastic(E=5.0e3, nu=0.45, rho=1000.0, model="stable_neohookean")
if args.ipc
else gs.materials.Rigid()
)

# material = gs.materials.Rigid()
cube = scene.add_entity(
morph=gs.morphs.Box(pos=(0.65, 0.0, 0.03), size=(0.05, 0.05, 0.05)),
material=material,
Expand Down Expand Up @@ -88,7 +92,7 @@ def main():
new_kp[fingers_dof] = current_kp[fingers_dof] * 10
franka.set_dofs_kp(new_kp)

print(f"New kp: {franka.get_dofs_kp()}")
# print(f"New kp: {franka.get_dofs_kp()}")
# grasp
finder_pos = 0.0
for i in range(int(0.1 / dt)):
Expand Down
1 change: 0 additions & 1 deletion examples/IPC_Solver/ipc_twist_cloth_band.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,6 @@ def main():
ipc_constraint_strength=(1, 1), # (translation, rotation) strength ratios,
contact_friction_mu=0.5, # Higher friction to grip the band
IPC_self_contact=False,
two_way_coupling=True,
enable_ipc_gui=args.vis_ipc,
),
show_viewer=args.vis or args.vis_ipc,
Expand Down
283 changes: 283 additions & 0 deletions genesis/assets/xml/franka_emika_panda/panda_non_overlap.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,283 @@
<mujoco model="panda">
<compiler angle="radian" meshdir="assets" autolimits="true"/>

<option integrator="implicitfast"/>

<default>
<default class="panda">
<material specular="0.5" shininess="0.25"/>
<joint armature="0.1" damping="1" axis="0 0 1" range="-2.8973 2.8973"/>
<general dyntype="none" biastype="affine" ctrlrange="-2.8973 2.8973" forcerange="-87 87"/>
<default class="finger">
<joint axis="0 1 0" type="slide" range="0 0.04"/>
</default>

<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="collision">
<geom type="mesh" group="3"/>
<default class="fingertip_pad_collision_1">
<geom type="box" size="0.0085 0.004 0.0085" pos="0 0.0055 0.0445"/>
</default>
<default class="fingertip_pad_collision_2">
<geom type="box" size="0.003 0.0015 0.003" pos="0.0055 0.002 0.05"/>
</default>
<default class="fingertip_pad_collision_3">
<geom type="box" size="0.003 0.0015 0.003" pos="-0.0055 0.002 0.05"/>
</default>
<default class="fingertip_pad_collision_4">
<geom type="box" size="0.003 0.0015 0.0035" pos="0.0055 0.002 0.0395"/>
</default>
<default class="fingertip_pad_collision_5">
<geom type="box" size="0.003 0.0015 0.0035" pos="-0.0055 0.002 0.0395"/>
</default>
</default>
</default>
</default>

<asset>
<material class="panda" name="white" rgba="1 1 1 1"/>
<material class="panda" name="off_white" rgba="0.901961 0.921569 0.929412 1"/>
<material class="panda" name="black" rgba="0.25 0.25 0.25 1"/>
<material class="panda" name="green" rgba="0 1 0 1"/>
<material class="panda" name="light_blue" rgba="0.039216 0.541176 0.780392 1"/>

<!-- Collision meshes -->
<mesh name="link0_c" file="link0.stl"/>
<mesh name="link1_c" file="link1.stl"/>
<mesh name="link2_c" file="link2.stl"/>
<mesh name="link3_c" file="link3.stl"/>
<mesh name="link4_c" file="link4.stl"/>
<mesh name="link5_c0" file="link5_collision_0.obj"/>
<mesh name="link5_c1" file="link5_collision_1.obj"/>
<mesh name="link5_c2" file="link5_collision_2.obj"/>
<mesh name="link6_c" file="link6.stl"/>
<mesh name="link7_c" file="link7.stl"/>
<mesh name="hand_c" file="hand.stl"/>

<!-- Visual meshes -->
<mesh file="link0_0.obj"/>
<mesh file="link0_1.obj"/>
<mesh file="link0_2.obj"/>
<mesh file="link0_3.obj"/>
<mesh file="link0_4.obj"/>
<mesh file="link0_5.obj"/>
<mesh file="link0_7.obj"/>
<mesh file="link0_8.obj"/>
<mesh file="link0_9.obj"/>
<mesh file="link0_10.obj"/>
<mesh file="link0_11.obj"/>
<mesh file="link1.obj"/>
<mesh file="link2.obj"/>
<mesh file="link3_0.obj"/>
<mesh file="link3_1.obj"/>
<mesh file="link3_2.obj"/>
<mesh file="link3_3.obj"/>
<mesh file="link4_0.obj"/>
<mesh file="link4_1.obj"/>
<mesh file="link4_2.obj"/>
<mesh file="link4_3.obj"/>
<mesh file="link5_0.obj"/>
<mesh file="link5_1.obj"/>
<mesh file="link5_2.obj"/>
<mesh file="link6_0.obj"/>
<mesh file="link6_1.obj"/>
<mesh file="link6_2.obj"/>
<mesh file="link6_3.obj"/>
<mesh file="link6_4.obj"/>
<mesh file="link6_5.obj"/>
<mesh file="link6_6.obj"/>
<mesh file="link6_7.obj"/>
<mesh file="link6_8.obj"/>
<mesh file="link6_9.obj"/>
<mesh file="link6_10.obj"/>
<mesh file="link6_11.obj"/>
<mesh file="link6_12.obj"/>
<mesh file="link6_13.obj"/>
<mesh file="link6_14.obj"/>
<mesh file="link6_15.obj"/>
<mesh file="link6_16.obj"/>
<mesh file="link7_0.obj"/>
<mesh file="link7_1.obj"/>
<mesh file="link7_2.obj"/>
<mesh file="link7_3.obj"/>
<mesh file="link7_4.obj"/>
<mesh file="link7_5.obj"/>
<mesh file="link7_6.obj"/>
<mesh file="link7_7.obj"/>
<mesh file="hand_0.obj"/>
<mesh file="hand_1.obj"/>
<mesh file="hand_2.obj"/>
<mesh file="hand_3.obj"/>
<mesh file="hand_4.obj"/>
<mesh file="finger_0.obj"/>
<mesh file="finger_1.obj"/>
</asset>

<worldbody>
<light name="top" pos="0 0 2" mode="trackcom"/>
<body name="link0" childclass="panda">
<inertial mass="0.629769" pos="-0.041018 -0.00014 0.049974"
fullinertia="0.00315 0.00388 0.004285 8.2904e-7 0.00015 8.2299e-6"/>
<geom mesh="link0_0" material="off_white" class="visual"/>
<geom mesh="link0_1" material="black" class="visual"/>
<geom mesh="link0_2" material="off_white" class="visual"/>
<geom mesh="link0_3" material="black" class="visual"/>
<geom mesh="link0_4" material="off_white" class="visual"/>
<geom mesh="link0_5" material="black" class="visual"/>
<geom mesh="link0_7" material="white" class="visual"/>
<geom mesh="link0_8" material="white" class="visual"/>
<geom mesh="link0_9" material="black" class="visual"/>
<geom mesh="link0_10" material="off_white" class="visual"/>
<geom mesh="link0_11" material="white" class="visual"/>
<geom mesh="link0_c" class="collision"/>
<body name="link1" pos="0 0 0.333">
<inertial mass="4.970684" pos="0.003875 0.002081 -0.04762"
fullinertia="0.70337 0.70661 0.0091170 -0.00013900 0.0067720 0.019169"/>
<joint name="joint1"/>
<geom material="white" mesh="link1" class="visual"/>
<geom mesh="link1_c" class="collision"/>
<body name="link2" quat="1 -1 0 0">
<inertial mass="0.646926" pos="-0.003141 -0.02872 0.003495"
fullinertia="0.0079620 2.8110e-2 2.5995e-2 -3.925e-3 1.0254e-2 7.04e-4"/>
<joint name="joint2" range="-1.7628 1.7628"/>
<geom material="white" mesh="link2" class="visual"/>
<geom mesh="link2_c" class="collision"/>
<body name="link3" pos="0 -0.316 0" quat="1 1 0 0">
<joint name="joint3"/>
<inertial mass="3.228604" pos="2.7518e-2 3.9252e-2 -6.6502e-2"
fullinertia="3.7242e-2 3.6155e-2 1.083e-2 -4.761e-3 -1.1396e-2 -1.2805e-2"/>
<geom mesh="link3_0" material="white" class="visual"/>
<geom mesh="link3_1" material="white" class="visual"/>
<geom mesh="link3_2" material="white" class="visual"/>
<geom mesh="link3_3" material="black" class="visual"/>
<geom mesh="link3_c" class="collision"/>
<body name="link4" pos="0.0825 0 0" quat="1 1 0 0">
<inertial mass="3.587895" pos="-5.317e-2 1.04419e-1 2.7454e-2"
fullinertia="2.5853e-2 1.9552e-2 2.8323e-2 7.796e-3 -1.332e-3 8.641e-3"/>
<joint name="joint4" range="-3.0718 -0.0698"/>
<geom mesh="link4_0" material="white" class="visual"/>
<geom mesh="link4_1" material="white" class="visual"/>
<geom mesh="link4_2" material="black" class="visual"/>
<geom mesh="link4_3" material="white" class="visual"/>
<geom mesh="link4_c" class="collision"/>
<body name="link5" pos="-0.0825 0.384 0" quat="1 -1 0 0">
<inertial mass="1.225946" pos="-1.1953e-2 4.1065e-2 -3.8437e-2"
fullinertia="3.5549e-2 2.9474e-2 8.627e-3 -2.117e-3 -4.037e-3 2.29e-4"/>
<joint name="joint5"/>
<geom mesh="link5_0" material="black" class="visual"/>
<geom mesh="link5_1" material="white" class="visual"/>
<geom mesh="link5_2" material="white" class="visual"/>
<geom mesh="link5_c0" class="collision"/>
<geom mesh="link5_c1" class="collision"/>
<geom mesh="link5_c2" class="collision"/>
<body name="link6" quat="1 1 0 0">
<inertial mass="1.666555" pos="6.0149e-2 -1.4117e-2 -1.0517e-2"
fullinertia="1.964e-3 4.354e-3 5.433e-3 1.09e-4 -1.158e-3 3.41e-4"/>
<joint name="joint6" range="-0.0175 3.7525"/>
<geom mesh="link6_0" material="off_white" class="visual"/>
<geom mesh="link6_1" material="white" class="visual"/>
<geom mesh="link6_2" material="black" class="visual"/>
<geom mesh="link6_3" material="white" class="visual"/>
<geom mesh="link6_4" material="white" class="visual"/>
<geom mesh="link6_5" material="white" class="visual"/>
<geom mesh="link6_6" material="white" class="visual"/>
<geom mesh="link6_7" material="light_blue" class="visual"/>
<geom mesh="link6_8" material="light_blue" class="visual"/>
<geom mesh="link6_9" material="black" class="visual"/>
<geom mesh="link6_10" material="black" class="visual"/>
<geom mesh="link6_11" material="white" class="visual"/>
<geom mesh="link6_12" material="green" class="visual"/>
<geom mesh="link6_13" material="white" class="visual"/>
<geom mesh="link6_14" material="black" class="visual"/>
<geom mesh="link6_15" material="black" class="visual"/>
<geom mesh="link6_16" material="white" class="visual"/>
<geom mesh="link6_c" class="collision"/>
<body name="link7" pos="0.088 0 0" quat="1 1 0 0">
<inertial mass="7.35522e-01" pos="1.0517e-2 -4.252e-3 6.1597e-2"
fullinertia="1.2516e-2 1.0027e-2 4.815e-3 -4.28e-4 -1.196e-3 -7.41e-4"/>
<joint name="joint7"/>
<geom mesh="link7_0" material="white" class="visual"/>
<geom mesh="link7_1" material="black" class="visual"/>
<geom mesh="link7_2" material="black" class="visual"/>
<geom mesh="link7_3" material="black" class="visual"/>
<geom mesh="link7_4" material="black" class="visual"/>
<geom mesh="link7_5" material="black" class="visual"/>
<geom mesh="link7_6" material="black" class="visual"/>
<geom mesh="link7_7" material="white" class="visual"/>
<geom mesh="link7_c" class="collision"/>
<body name="hand" pos="0 0 0.107" quat="0.9238795 0 0 -0.3826834">
<inertial mass="0.73" pos="-0.01 0 0.03" diaginertia="0.001 0.0025 0.0017"/>
<geom mesh="hand_0" material="off_white" class="visual"/>
<geom mesh="hand_1" material="black" class="visual"/>
<geom mesh="hand_2" material="black" class="visual"/>
<geom mesh="hand_3" material="white" class="visual"/>
<geom mesh="hand_4" material="off_white" class="visual"/>
<geom mesh="hand_c" class="collision"/>
<body name="left_finger" pos="0 0 0.0584">
<inertial mass="0.015" pos="0 0 0" diaginertia="2.375e-6 2.375e-6 7.5e-7"/>
<joint name="finger_joint1" class="finger"/>
<geom mesh="finger_0" material="off_white" class="visual"/>
<geom mesh="finger_1" material="black" class="visual"/>
<geom mesh="finger_0" class="collision"/>
<geom class="fingertip_pad_collision_1"/>
<geom class="fingertip_pad_collision_2"/>
<geom class="fingertip_pad_collision_3"/>
<geom class="fingertip_pad_collision_4"/>
<geom class="fingertip_pad_collision_5"/>
</body>
<body name="right_finger" pos="0 0 0.0584" quat="0 0 0 1">
<inertial mass="0.015" pos="0 0 0" diaginertia="2.375e-6 2.375e-6 7.5e-7"/>
<joint name="finger_joint2" class="finger"/>
<geom mesh="finger_0" material="off_white" class="visual"/>
<geom mesh="finger_1" material="black" class="visual"/>
<geom mesh="finger_0" class="collision"/>
<geom class="fingertip_pad_collision_1"/>
<geom class="fingertip_pad_collision_2"/>
<geom class="fingertip_pad_collision_3"/>
<geom class="fingertip_pad_collision_4"/>
<geom class="fingertip_pad_collision_5"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>

<tendon>
<fixed name="split">
<joint joint="finger_joint1" coef="0.5"/>
<joint joint="finger_joint2" coef="0.5"/>
</fixed>
</tendon>

<equality>
<joint joint1="finger_joint1" joint2="finger_joint2" solimp="0.95 0.99 0.001" solref="0.005 1"/>
</equality>

<actuator>
<general class="panda" name="actuator1" joint="joint1" gainprm="4500" biasprm="0 -4500 -450"/>
<general class="panda" name="actuator2" joint="joint2" gainprm="4500" biasprm="0 -4500 -450"
ctrlrange="-1.7628 1.7628"/>
<general class="panda" name="actuator3" joint="joint3" gainprm="3500" biasprm="0 -3500 -350"/>
<general class="panda" name="actuator4" joint="joint4" gainprm="3500" biasprm="0 -3500 -350"
ctrlrange="-3.0718 -0.0698"/>
<general class="panda" name="actuator5" joint="joint5" gainprm="2000" biasprm="0 -2000 -200" forcerange="-12 12"/>
<general class="panda" name="actuator6" joint="joint6" gainprm="2000" biasprm="0 -2000 -200" forcerange="-12 12"
ctrlrange="-0.0175 3.7525"/>
<general class="panda" name="actuator7" joint="joint7" gainprm="2000" biasprm="0 -2000 -200" forcerange="-12 12"/>
<!-- Remap original ctrlrange (0, 0.04) to (0, 255): 0.04 * 100 / 255 = 0.01568627451 -->
<general class="panda" name="actuator8" tendon="split" forcerange="-100 100" ctrlrange="0 255"
gainprm="0.01568627451 0 0" biasprm="0 -100 -10"/>
</actuator>

<keyframe>
<key name="home" qpos="0 0 0 -1.57079 0 1.57079 -0.7853 0.04 0.04" ctrl="0 0 0 -1.57079 0 1.57079 -0.7853 255"/>
</keyframe>
</mujoco>
Loading