diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 7c92e72..5a69727 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -15,7 +15,7 @@ repos: # code format according to black - repo: https://github.com/ambv/black - rev: 23.3.0 + rev: 24.2.0 hooks: - id: black diff --git a/experiments/run_env.py b/experiments/run_env.py index 57fb4b0..bd2319a 100644 --- a/experiments/run_env.py +++ b/experiments/run_env.py @@ -106,8 +106,7 @@ def main(args): if args.agent == "gello": gello_port = args.gello_port if gello_port is None: - # usb_ports = glob.glob("/dev/serial/by-id/*") - usb_ports = glob.glob("/dev/cu.usbserial*") + usb_ports = glob.glob("/dev/serial/by-id/*") print(f"Found {len(usb_ports)} ports") if len(usb_ports) > 0: gello_port = usb_ports[0] diff --git a/gello/agents/gello_agent.py b/gello/agents/gello_agent.py index 6f23564..fca60c3 100644 --- a/gello/agents/gello_agent.py +++ b/gello/agents/gello_agent.py @@ -90,7 +90,7 @@ PORT_CONFIG_MAP: Dict[str, DynamixelRobotConfig] = { gripper_config=(7, 20, -22), ), # Right UR - "/dev/cu.usbserial-FT7WBG6A": DynamixelRobotConfig( + "/dev/serial/by-id/usb-FTDI_USB__-__Serial_Converter_FT7WBG6A-if00-port0": DynamixelRobotConfig( joint_ids=(1, 2, 3, 4, 5, 6), joint_offsets=( np.pi + 0 * np.pi, diff --git a/requirements.txt b/requirements.txt index b7635ae..5ac85ad 100644 --- a/requirements.txt +++ b/requirements.txt @@ -5,7 +5,7 @@ pygame pyspacemouse PyQt6 pyquaternion -# pyrealsense2 +pyrealsense2 pure-python-adb quaternion tyro diff --git a/scripts/arm_blocks_play.py b/scripts/arm_blocks_play.py index 8a11e2c..851e85c 100644 --- a/scripts/arm_blocks_play.py +++ b/scripts/arm_blocks_play.py @@ -18,15 +18,15 @@ class Args: config = DynamixelRobotConfig( joint_ids=(1, 2, 3, 4, 5, 6), joint_offsets=( - np.pi + 0 * np.pi, - 2 * np.pi + np.pi / 2, - 2 * np.pi + np.pi / 2, - 2 * np.pi + np.pi / 2, - 1 * np.pi, - 3 * np.pi / 2, + -np.pi / 2, + 1 * np.pi / 2 + np.pi, + np.pi / 2 + 0 * np.pi, + 0 * np.pi + np.pi / 2, + np.pi - 2 * np.pi / 2, + -1 * np.pi / 2 + 2 * np.pi, ), joint_signs=(1, 1, -1, 1, 1, 1), - gripper_config=(7, 286, 248), + gripper_config=(7, 20, -22), ) @@ -40,7 +40,7 @@ def main(args: Args) -> None: action_space = env.action_spec() if args.use_gello: gello = config.make_robot( - port="/dev/cu.usbserial-FT7WBG6A", start_joints=reset_joints_left + port="/dev/cu.usbserial-FT7WBEIA", start_joints=reset_joints_left ) def policy(timestep) -> np.ndarray: