|
| 1 | +""" |
| 2 | +Keyboard Controls: |
| 3 | +↑ - Move Forward (North) |
| 4 | +↓ - Move Backward (South) |
| 5 | +← - Move Left (West) |
| 6 | +→ - Move Right (East) |
| 7 | +n - Move Up |
| 8 | +m - Move Down |
| 9 | +j - Rotate Counterclockwise |
| 10 | +k - Rotate Clockwise |
| 11 | +u - Reset Scene |
| 12 | +space - Press to close gripper, release to open gripper |
| 13 | +esc - Quit |
| 14 | +""" |
| 15 | + |
| 16 | +import random |
| 17 | +import threading |
| 18 | + |
| 19 | +import genesis as gs |
| 20 | +import numpy as np |
| 21 | +from pynput import keyboard |
| 22 | +from scipy.spatial.transform import Rotation as R |
| 23 | + |
| 24 | + |
| 25 | +class KeyboardDevice: |
| 26 | + def __init__(self): |
| 27 | + self.pressed_keys = set() |
| 28 | + self.lock = threading.Lock() |
| 29 | + self.listener = keyboard.Listener(on_press=self.on_press, on_release=self.on_release) |
| 30 | + |
| 31 | + def start(self): |
| 32 | + self.listener.start() |
| 33 | + |
| 34 | + def stop(self): |
| 35 | + self.listener.stop() |
| 36 | + self.listener.join() |
| 37 | + |
| 38 | + def on_press(self, key: keyboard.Key): |
| 39 | + with self.lock: |
| 40 | + self.pressed_keys.add(key) |
| 41 | + |
| 42 | + def on_release(self, key: keyboard.Key): |
| 43 | + with self.lock: |
| 44 | + self.pressed_keys.discard(key) |
| 45 | + |
| 46 | + def get_cmd(self): |
| 47 | + return self.pressed_keys |
| 48 | + |
| 49 | + |
| 50 | +def build_scene(): |
| 51 | + ########################## init ########################## |
| 52 | + gs.init(seed=0, precision="32", logging_level="info", backend=gs.cpu) |
| 53 | + np.set_printoptions(precision=7, suppress=True) |
| 54 | + |
| 55 | + ########################## create a scene ########################## |
| 56 | + scene = gs.Scene( |
| 57 | + viewer_options=gs.options.ViewerOptions( |
| 58 | + camera_pos=(1.5, 0.0, 0.7), |
| 59 | + camera_lookat=(0.2, 0.0, 0.1), |
| 60 | + camera_fov=50, |
| 61 | + max_FPS=60, |
| 62 | + ), |
| 63 | + sim_options=gs.options.SimOptions( |
| 64 | + substeps=4, |
| 65 | + ), |
| 66 | + rigid_options=gs.options.RigidOptions( |
| 67 | + enable_joint_limit=True, |
| 68 | + enable_collision=True, |
| 69 | + gravity=(0, 0, -9.8), |
| 70 | + box_box_detection=True, |
| 71 | + constraint_timeconst=0.02, |
| 72 | + ), |
| 73 | + show_viewer=True, |
| 74 | + show_FPS=False, |
| 75 | + ) |
| 76 | + |
| 77 | + ########################## entities ########################## |
| 78 | + entities = dict() |
| 79 | + entities["plane"] = scene.add_entity( |
| 80 | + gs.morphs.Plane(), |
| 81 | + ) |
| 82 | + |
| 83 | + entities["robot"] = scene.add_entity( |
| 84 | + material=gs.materials.Rigid(gravity_compensation=1), |
| 85 | + morph=gs.morphs.MJCF( |
| 86 | + file="xml/franka_emika_panda/panda.xml", |
| 87 | + euler=(0, 0, 0), |
| 88 | + ), |
| 89 | + ) |
| 90 | + entities["cube"] = scene.add_entity( |
| 91 | + material=gs.materials.Rigid(rho=300), |
| 92 | + morph=gs.morphs.Box( |
| 93 | + pos=(0.5, 0.0, 0.07), |
| 94 | + size=(0.04, 0.04, 0.04), |
| 95 | + ), |
| 96 | + surface=gs.surfaces.Default(color=(0.5, 1, 0.5)), |
| 97 | + ) |
| 98 | + |
| 99 | + entities["target"] = scene.add_entity( |
| 100 | + gs.morphs.Mesh( |
| 101 | + file="meshes/axis.obj", |
| 102 | + scale=0.15, |
| 103 | + collision=False, |
| 104 | + ), |
| 105 | + surface=gs.surfaces.Default(color=(1, 0.5, 0.5, 1)), |
| 106 | + ) |
| 107 | + |
| 108 | + ########################## build ########################## |
| 109 | + scene.build() |
| 110 | + |
| 111 | + return scene, entities |
| 112 | + |
| 113 | + |
| 114 | +def run_sim(scene, entities, clients): |
| 115 | + robot = entities["robot"] |
| 116 | + target_entity = entities["target"] |
| 117 | + |
| 118 | + robot_init_pos = np.array([0.5, 0, 0.55]) |
| 119 | + robot_init_R = R.from_euler("y", np.pi) |
| 120 | + target_pos = robot_init_pos.copy() |
| 121 | + target_R = robot_init_R |
| 122 | + |
| 123 | + n_dofs = robot.n_dofs |
| 124 | + motors_dof = np.arange(n_dofs - 2) |
| 125 | + fingers_dof = np.arange(n_dofs - 2, n_dofs) |
| 126 | + ee_link = robot.get_link("hand") |
| 127 | + |
| 128 | + def reset_scene(): |
| 129 | + nonlocal target_pos, target_R |
| 130 | + target_pos = robot_init_pos.copy() |
| 131 | + target_R = robot_init_R |
| 132 | + target_quat = target_R.as_quat(scalar_first=True) |
| 133 | + target_entity.set_qpos(np.concatenate([target_pos, target_quat])) |
| 134 | + q = robot.inverse_kinematics(link=ee_link, pos=target_pos, quat=target_quat) |
| 135 | + robot.set_qpos(q[:-2], motors_dof) |
| 136 | + |
| 137 | + entities["cube"].set_pos((random.uniform(0.2, 0.4), random.uniform(-0.2, 0.2), 0.05)) |
| 138 | + entities["cube"].set_quat(R.from_euler("z", random.uniform(0, np.pi * 2)).as_quat(scalar_first=True)) |
| 139 | + |
| 140 | + print("\nKeyboard Controls:") |
| 141 | + print("↑\t- Move Forward (North)") |
| 142 | + print("↓\t- Move Backward (South)") |
| 143 | + print("←\t- Move Left (West)") |
| 144 | + print("→\t- Move Right (East)") |
| 145 | + print("n\t- Move Up") |
| 146 | + print("m\t- Move Down") |
| 147 | + print("j\t- Rotate Counterclockwise") |
| 148 | + print("k\t- Rotate Clockwise") |
| 149 | + print("u\t- Reset Scene") |
| 150 | + print("space\t- Press to close gripper, release to open gripper") |
| 151 | + print("esc\t- Quit") |
| 152 | + |
| 153 | + # reset scen before starting teleoperation |
| 154 | + reset_scene() |
| 155 | + |
| 156 | + # start teleoperation |
| 157 | + stop = False |
| 158 | + while not stop: |
| 159 | + pressed_keys = clients["keyboard"].pressed_keys.copy() |
| 160 | + |
| 161 | + # reset scene: |
| 162 | + reset_flag = False |
| 163 | + reset_flag |= keyboard.KeyCode.from_char("u") in pressed_keys |
| 164 | + if reset_flag: |
| 165 | + reset_scene() |
| 166 | + |
| 167 | + # stop teleoperation |
| 168 | + stop = keyboard.Key.esc in pressed_keys |
| 169 | + |
| 170 | + # get ee target pose |
| 171 | + is_close_gripper = False |
| 172 | + dpos = 0.002 |
| 173 | + drot = 0.01 |
| 174 | + for key in pressed_keys: |
| 175 | + if key == keyboard.Key.up: |
| 176 | + target_pos[0] -= dpos |
| 177 | + elif key == keyboard.Key.down: |
| 178 | + target_pos[0] += dpos |
| 179 | + elif key == keyboard.Key.right: |
| 180 | + target_pos[1] += dpos |
| 181 | + elif key == keyboard.Key.left: |
| 182 | + target_pos[1] -= dpos |
| 183 | + elif key == keyboard.KeyCode.from_char("n"): |
| 184 | + target_pos[2] += dpos |
| 185 | + elif key == keyboard.KeyCode.from_char("m"): |
| 186 | + target_pos[2] -= dpos |
| 187 | + elif key == keyboard.KeyCode.from_char("j"): |
| 188 | + target_R = R.from_euler("z", drot) * target_R |
| 189 | + elif key == keyboard.KeyCode.from_char("k"): |
| 190 | + target_R = R.from_euler("z", -drot) * target_R |
| 191 | + elif key == keyboard.Key.space: |
| 192 | + is_close_gripper = True |
| 193 | + |
| 194 | + # control arm |
| 195 | + target_quat = target_R.as_quat(scalar_first=True) |
| 196 | + target_entity.set_qpos(np.concatenate([target_pos, target_quat])) |
| 197 | + q, err = robot.inverse_kinematics(link=ee_link, pos=target_pos, quat=target_quat, return_error=True) |
| 198 | + robot.control_dofs_position(q[:-2], motors_dof) |
| 199 | + # control gripper |
| 200 | + if is_close_gripper: |
| 201 | + robot.control_dofs_force(np.array([-1.0, -1.0]), fingers_dof) |
| 202 | + else: |
| 203 | + robot.control_dofs_force(np.array([1.0, 1.0]), fingers_dof) |
| 204 | + |
| 205 | + scene.step() |
| 206 | + |
| 207 | + |
| 208 | +def main(): |
| 209 | + clients = dict() |
| 210 | + clients["keyboard"] = KeyboardDevice() |
| 211 | + clients["keyboard"].start() |
| 212 | + |
| 213 | + scene, entities = build_scene() |
| 214 | + run_sim(scene, entities, clients) |
| 215 | + |
| 216 | + |
| 217 | +if __name__ == "__main__": |
| 218 | + main() |
0 commit comments