@@ -183,71 +183,36 @@ def reset_scene():
183183 # entities["cube"].set_pos((random.uniform(0.2, 0.4), random.uniform(-0.2, 0.2), 0.05))
184184 # entities["cube"].set_quat(R.from_euler("z", random.uniform(0, np.pi * 2)).as_quat(scalar_first=True))
185185
186- # Define movement callbacks
187- def move_forward ():
188- target_pos [0 ][0 ] -= dpos
189-
190- def move_backward ():
191- target_pos [0 ][0 ] += dpos
192-
193- def move_left ():
194- target_pos [0 ][1 ] -= dpos
195-
196- def move_right ():
197- target_pos [0 ][1 ] += dpos
198-
199- def move_up ():
200- target_pos [0 ][2 ] += dpos
201-
202- def move_down ():
203- target_pos [0 ][2 ] -= dpos
204-
205- def yaw_left ():
206- target_R [0 ] = R .from_euler ("z" , drot ) * target_R [0 ]
207-
208- def yaw_right ():
209- target_R [0 ] = R .from_euler ("z" , - drot ) * target_R [0 ]
210-
211- def pitch_up ():
212- target_R [0 ] = R .from_euler ("y" , drot ) * target_R [0 ]
213-
214- def pitch_down ():
215- target_R [0 ] = R .from_euler ("y" , - drot ) * target_R [0 ]
216-
217- def roll_left ():
218- target_R [0 ] = R .from_euler ("x" , drot ) * target_R [0 ]
186+ # Register keybindings (only for interactive and record modes)
187+ if mode in ["interactive" , "record" ]:
219188
220- def roll_right ( ):
221- target_R [0 ] = R . from_euler ( "x" , - drot ) * target_R [ 0 ]
189+ def move ( dpos_delta : tuple [ float , float , float ] ):
190+ target_pos [0 ] += np . array ( dpos_delta , dtype = gs . np_float )
222191
223- def close_gripper ( ):
224- gripper_closed [0 ] = True
192+ def rotate ( axis : str , angle : float ):
193+ target_R [0 ] = R . from_euler ( axis , angle ) * target_R [ 0 ]
225194
226- def open_gripper ( ):
227- gripper_closed [0 ] = False
195+ def toggle_gripper ( close : bool = True ):
196+ gripper_closed [0 ] = close
228197
229- # Register keybindings (only for interactive and record modes)
230- if mode in ["interactive" , "record" ]:
231198 from pyglet .window import key
232199
233200 scene .viewer .register_keybinds (
234- (
235- Keybind (key_code = key .UP , key_action = KeyAction .HOLD , name = "move_forward" , callback = move_forward ),
236- Keybind (key_code = key .DOWN , key_action = KeyAction .HOLD , name = "move_backward" , callback = move_backward ),
237- Keybind (key_code = key .LEFT , key_action = KeyAction .HOLD , name = "move_left" , callback = move_left ),
238- Keybind (key_code = key .RIGHT , key_action = KeyAction .HOLD , name = "move_right" , callback = move_right ),
239- Keybind (key_code = key .N , key_action = KeyAction .HOLD , name = "move_up" , callback = move_up ),
240- Keybind (key_code = key .M , key_action = KeyAction .HOLD , name = "move_down" , callback = move_down ),
241- Keybind (key_code = key .J , key_action = KeyAction .HOLD , name = "yaw_left" , callback = yaw_left ),
242- Keybind (key_code = key .K , key_action = KeyAction .HOLD , name = "yaw_right" , callback = yaw_right ),
243- Keybind (key_code = key .I , key_action = KeyAction .HOLD , name = "pitch_up" , callback = pitch_up ),
244- Keybind (key_code = key .O , key_action = KeyAction .HOLD , name = "pitch_down" , callback = pitch_down ),
245- Keybind (key_code = key .L , key_action = KeyAction .HOLD , name = "roll_left" , callback = roll_left ),
246- Keybind (key_code = key .SEMICOLON , key_action = KeyAction .HOLD , name = "roll_right" , callback = roll_right ),
247- Keybind (key_code = key .U , key_action = KeyAction .HOLD , name = "reset_scene" , callback = reset_scene ),
248- Keybind (key_code = key .SPACE , key_action = KeyAction .PRESS , name = "close_gripper" , callback = close_gripper ),
249- Keybind (key_code = key .SPACE , key_action = KeyAction .RELEASE , name = "open_gripper" , callback = open_gripper ),
250- )
201+ Keybind (key .UP , KeyAction .HOLD , name = "move_forward" , callback = move , args = ((- dpos , 0 , 0 ),)),
202+ Keybind (key .DOWN , KeyAction .HOLD , name = "move_backward" , callback = move , args = ((dpos , 0 , 0 ),)),
203+ Keybind (key .LEFT , KeyAction .HOLD , name = "move_left" , callback = move , args = ((0 , - dpos , 0 ),)),
204+ Keybind (key .RIGHT , KeyAction .HOLD , name = "move_right" , callback = move , args = ((0 , dpos , 0 ),)),
205+ Keybind (key .N , KeyAction .HOLD , name = "move_up" , callback = move , args = ((0 , 0 , dpos ),)),
206+ Keybind (key .M , KeyAction .HOLD , name = "move_down" , callback = move , args = ((0 , 0 , - dpos ),)),
207+ Keybind (key .J , KeyAction .HOLD , name = "yaw_left" , callback = rotate , args = ("z" , drot )),
208+ Keybind (key .K , KeyAction .HOLD , name = "yaw_right" , callback = rotate , args = ("z" , - drot )),
209+ Keybind (key .I , KeyAction .HOLD , name = "pitch_up" , callback = rotate , args = ("y" , drot )),
210+ Keybind (key .O , KeyAction .HOLD , name = "pitch_down" , callback = rotate , args = ("y" , - drot )),
211+ Keybind (key .L , KeyAction .HOLD , name = "roll_left" , callback = rotate , args = ("x" , drot )),
212+ Keybind (key .SEMICOLON , KeyAction .HOLD , name = "roll_right" , callback = rotate , args = ("x" , - drot )),
213+ Keybind (key .U , KeyAction .HOLD , name = "reset_scene" , callback = reset_scene ),
214+ Keybind (key .SPACE , KeyAction .PRESS , name = "close_gripper" , callback = toggle_gripper , args = (True ,)),
215+ Keybind (key .SPACE , KeyAction .RELEASE , name = "open_gripper" , callback = toggle_gripper , args = (False ,)),
251216 )
252217
253218 # Load trajectory if in playback mode
0 commit comments