Skip to content
Open
1 change: 0 additions & 1 deletion .github/workflows/examples.yml
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,6 @@ jobs:
run: |
pip install --upgrade pip setuptools wheel
pip install torch --index-url https://download.pytorch.org/whl/cpu
pip install -e '.[dev,usd]' pynput

- name: Get gstaichi version
id: gstaichi_version
Expand Down
241 changes: 104 additions & 137 deletions examples/IPC_Solver/ipc_arm_cloth.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,45 +14,19 @@
; - Roll Right (Rotate around X)
u - Reset Scene
space - Press to close gripper, release to open gripper
esc - Quit
"""

import threading
import argparse
import numpy as np
import csv
import os
from datetime import datetime
from pynput import keyboard
from scipy.spatial.transform import Rotation as R

import numpy as np
from huggingface_hub import snapshot_download

import genesis as gs


class KeyboardDevice:
def __init__(self):
self.pressed_keys = set()
self.lock = threading.Lock()
self.listener = keyboard.Listener(on_press=self.on_press, on_release=self.on_release)

def start(self):
self.listener.start()

def stop(self):
self.listener.stop()
self.listener.join()

def on_press(self, key: keyboard.Key):
with self.lock:
self.pressed_keys.add(key)

def on_release(self, key: keyboard.Key):
with self.lock:
self.pressed_keys.discard(key)

def get_cmd(self):
return self.pressed_keys
import genesis.utils.geom as gu
from genesis.vis.keybindings import Key, KeyAction, Keybind


def build_scene(use_ipc=False, show_viewer=False, enable_ipc_gui=False):
Expand Down Expand Up @@ -109,18 +83,12 @@ def build_scene(use_ipc=False, show_viewer=False, enable_ipc_gui=False):
euler=(0, 0, 0),
),
)
scene.sim.coupler.set_ipc_link_filter(
entity=entities["robot"],
link_names=["left_finger", "right_finger"],
)

material = (
gs.materials.FEM.Elastic(E=1.0e4, nu=0.45, rho=1000.0, model="stable_neohookean")
if use_ipc
else gs.materials.Rigid()
)

if use_ipc:
scene.sim.coupler.set_ipc_link_filter(
entity=entities["robot"],
link_names=["left_finger", "right_finger"],
)
cloth = scene.add_entity(
morph=gs.morphs.Mesh(
file="meshes/grid20x20.obj",
Expand Down Expand Up @@ -171,14 +139,15 @@ def build_scene(use_ipc=False, show_viewer=False, enable_ipc_gui=False):
return scene, entities


def run_sim(scene, entities, clients, mode="interactive", trajectory_file=None):
def run_sim(scene, entities, mode="interactive", trajectory_file=None):
robot = entities["robot"]
target_entity = entities["target"]
is_running = True

robot_init_pos = np.array([0.5, 0, 0.55])
robot_init_R = R.from_euler("y", np.pi)
robot_init_quat = gu.xyz_to_quat(np.array([0, np.pi, 0])) # Rotation around Y axis
target_pos = robot_init_pos.copy()
target_R = robot_init_R
target_quat = robot_init_quat.copy()

n_dofs = robot.n_dofs
motors_dof = np.arange(n_dofs - 2)
Expand All @@ -189,18 +158,63 @@ def run_sim(scene, entities, clients, mode="interactive", trajectory_file=None):
trajectory = []
recording = mode == "record"

# Gripper state (use list for mutability in closures)
gripper_closed = [False]

# Control parameters
dpos = 0.002
drot = 0.01

def reset_scene():
nonlocal target_pos, target_R
target_pos = robot_init_pos.copy()
target_R = robot_init_R
target_quat = target_R.as_quat(scalar_first=True)
target_pos[:] = robot_init_pos
target_quat[:] = robot_init_quat
target_entity.set_qpos(np.concatenate([target_pos, target_quat]))
q = robot.inverse_kinematics(link=ee_link, pos=target_pos, quat=target_quat)
robot.set_qpos(q[:-2], motors_dof)

# entities["cube"].set_pos((random.uniform(0.2, 0.4), random.uniform(-0.2, 0.2), 0.05))
# entities["cube"].set_quat(R.from_euler("z", random.uniform(0, np.pi * 2)).as_quat(scalar_first=True))

# Register keybindings (only for interactive and record modes)
if mode in ["interactive", "record"]:

def move(dpos_delta: tuple[float, float, float]):
target_pos[:] += np.array(dpos_delta, dtype=gs.np_float)

def rotate(axis: str, angle: float):
# Create rotation quaternion for the specified axis
euler = np.zeros(3)
axis_map = {"x": 0, "y": 1, "z": 2}
euler[axis_map[axis]] = angle
drot_quat = gu.xyz_to_quat(euler)
target_quat[:] = gu.transform_quat_by_quat(target_quat, drot_quat)

def toggle_gripper(close: bool = True):
gripper_closed[0] = close

def stop():
nonlocal is_running
is_running = False

scene.viewer.register_keybinds(
Keybind(Key.UP, KeyAction.HOLD, name="move_forward", callback=move, args=((-dpos, 0, 0),)),
Keybind(Key.DOWN, KeyAction.HOLD, name="move_backward", callback=move, args=((dpos, 0, 0),)),
Keybind(Key.LEFT, KeyAction.HOLD, name="move_left", callback=move, args=((0, -dpos, 0),)),
Keybind(Key.RIGHT, KeyAction.HOLD, name="move_right", callback=move, args=((0, dpos, 0),)),
Keybind(Key.N, KeyAction.HOLD, name="move_up", callback=move, args=((0, 0, dpos),)),
Keybind(Key.M, KeyAction.HOLD, name="move_down", callback=move, args=((0, 0, -dpos),)),
Keybind(Key.J, KeyAction.HOLD, name="yaw_left", callback=rotate, args=("z", drot)),
Keybind(Key.K, KeyAction.HOLD, name="yaw_right", callback=rotate, args=("z", -drot)),
Keybind(Key.I, KeyAction.HOLD, name="pitch_up", callback=rotate, args=("y", drot)),
Keybind(Key.O, KeyAction.HOLD, name="pitch_down", callback=rotate, args=("y", -drot)),
Keybind(Key.L, KeyAction.HOLD, name="roll_left", callback=rotate, args=("x", drot)),
Keybind(Key.SEMICOLON, KeyAction.HOLD, name="roll_right", callback=rotate, args=("x", -drot)),
Keybind(Key.U, KeyAction.HOLD, name="reset_scene", callback=reset_scene),
Keybind(Key.SPACE, KeyAction.PRESS, name="close_gripper", callback=toggle_gripper, args=(True,)),
Keybind(Key.SPACE, KeyAction.RELEASE, name="open_gripper", callback=toggle_gripper, args=(False,)),
Keybind(Key.ESCAPE, KeyAction.PRESS, name="quit", callback=stop),
)

# Load trajectory if in playback mode
if mode == "playback":
if not trajectory_file or not os.path.exists(trajectory_file):
Expand Down Expand Up @@ -232,7 +246,7 @@ def reset_scene():

print(f"\nMode: {mode.upper()}")
if mode == "record":
print("Recording trajectory... Press ESC to stop and save.")
print("Recording trajectory...")
elif mode == "playback":
print("Playing back trajectory...")

Expand All @@ -248,99 +262,56 @@ def reset_scene():
print("l/;\t- Roll Left/Right (Rotate around X axis)")
print("u\t- Reset Scene")
print("space\t- Press to close gripper, release to open gripper")
print("esc\t- Quit")
if mode in ["interactive", "record"]:
print("\nPlus all default viewer controls (press 'i' to see them)")

# reset scene before starting teleoperation
reset_scene()

# start teleoperation or playback
stop = False
step_count = 0

while not stop:
if mode == "playback":
# Playback mode: replay recorded trajectory
if step_count < len(trajectory):
step_data = trajectory[step_count]
target_pos = step_data["target_pos"]
target_R = R.from_quat(step_data["target_quat"])
is_close_gripper = step_data["gripper_closed"]
step_count += 1
print(f"\rPlayback step: {step_count}/{len(trajectory)}", end="")
# Check if user wants to stop playback
pressed_keys = clients["keyboard"].pressed_keys.copy()
stop = keyboard.Key.esc in pressed_keys
try:
while is_running:
if mode == "playback":
# Playback mode: replay recorded trajectory
if step_count < len(trajectory):
step_data = trajectory[step_count]
target_pos[:] = step_data["target_pos"]
target_quat[:] = step_data["target_quat"]
gripper_closed[0] = step_data["gripper_closed"]
step_count += 1
print(f"\rPlayback step: {step_count}/{len(trajectory)}", end="")
else:
print("\nPlayback finished!")
break
else:
print("\nPlayback finished!")
break
else:
# Interactive or recording mode
pressed_keys = clients["keyboard"].pressed_keys.copy()

# reset scene:
reset_flag = False
reset_flag |= keyboard.KeyCode.from_char("u") in pressed_keys
if reset_flag:
reset_scene()

# stop teleoperation
stop = keyboard.Key.esc in pressed_keys

# get ee target pose
is_close_gripper = False
dpos = 0.002
drot = 0.01
for key in pressed_keys:
if key == keyboard.Key.up:
target_pos[0] -= dpos
elif key == keyboard.Key.down:
target_pos[0] += dpos
elif key == keyboard.Key.right:
target_pos[1] += dpos
elif key == keyboard.Key.left:
target_pos[1] -= dpos
elif key == keyboard.KeyCode.from_char("n"):
target_pos[2] += dpos
elif key == keyboard.KeyCode.from_char("m"):
target_pos[2] -= dpos
elif key == keyboard.KeyCode.from_char("j"):
target_R = R.from_euler("z", drot) * target_R
elif key == keyboard.KeyCode.from_char("k"):
target_R = R.from_euler("z", -drot) * target_R
elif key == keyboard.KeyCode.from_char("i"):
target_R = R.from_euler("y", drot) * target_R
elif key == keyboard.KeyCode.from_char("o"):
target_R = R.from_euler("y", -drot) * target_R
elif key == keyboard.KeyCode.from_char("l"):
target_R = R.from_euler("x", drot) * target_R
elif key == keyboard.KeyCode.from_char(";"):
target_R = R.from_euler("x", -drot) * target_R
elif key == keyboard.Key.space:
is_close_gripper = True

# Record current state if recording
if recording:
step_data = {
"target_pos": target_pos.copy(),
"target_quat": target_R.as_quat(), # x,y,z,w format
"gripper_closed": is_close_gripper,
"step": step_count,
}
trajectory.append(step_data)

# control arm
target_quat = target_R.as_quat(scalar_first=True)
target_entity.set_qpos(np.concatenate([target_pos, target_quat]))
q, err = robot.inverse_kinematics(link=ee_link, pos=target_pos, quat=target_quat, return_error=True)
robot.control_dofs_position(q[:-2], motors_dof)
# control gripper
if is_close_gripper:
robot.control_dofs_force(np.array([-1.0, -1.0]), fingers_dof)
else:
robot.control_dofs_force(np.array([1.0, 1.0]), fingers_dof)
# Interactive or recording mode
# Movement is handled by keybinding callbacks
# Record current state if recording
if recording:
step_data = {
"target_pos": target_pos.copy(),
"target_quat": target_quat.copy(),
"gripper_closed": gripper_closed[0],
"step": step_count,
}
trajectory.append(step_data)

# control arm
target_entity.set_qpos(np.concatenate([target_pos, target_quat]))
q, err = robot.inverse_kinematics(link=ee_link, pos=target_pos, quat=target_quat, return_error=True)
robot.control_dofs_position(q[:-2], motors_dof)
# control gripper
if gripper_closed[0]:
robot.control_dofs_force(np.array([-1.0, -1.0]), fingers_dof)
else:
robot.control_dofs_force(np.array([1.0, 1.0]), fingers_dof)

scene.step()
step_count += 1
scene.step()
step_count += 1
except KeyboardInterrupt:
gs.logger.info("Simulation interrupted, exiting.")

# Save trajectory if recording
if recording and len(trajectory) > 0:
Expand Down Expand Up @@ -436,12 +407,8 @@ def main():
elif not os.path.isabs(trajectory_file):
trajectory_file = os.path.join(traj_dir, os.path.basename(trajectory_file))

clients = dict()
clients["keyboard"] = KeyboardDevice()
clients["keyboard"].start()

scene, entities = build_scene(use_ipc=args.ipc, show_viewer=args.vis, enable_ipc_gui=False)
run_sim(scene, entities, clients, mode=args.mode, trajectory_file=trajectory_file)
run_sim(scene, entities, mode=args.mode, trajectory_file=trajectory_file)


if __name__ == "__main__":
Expand Down
Loading