From 30b996dfbd97f05dbf757c4faa65bc5b245929b1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 5 May 2026 10:23:09 +0200 Subject: [PATCH 01/33] fix(docker): link script --- docker/README.md | 3 ++- docker/link-editable-source.sh | 25 ++++++++++--------------- 2 files changed, 12 insertions(+), 16 deletions(-) diff --git a/docker/README.md b/docker/README.md index 78bd0da4..35b4bd13 100644 --- a/docker/README.md +++ b/docker/README.md @@ -23,6 +23,7 @@ Notes: - `~/zed_models` is mounted into `/usr/local/zed/resources` to match the direct `docker run` setup. - `/dev/dri` is masked inside the container so host Mesa/AMD render nodes do not override the NVIDIA runtime devices. - NVIDIA PRIME/GLX environment variables are exported to bias OpenGL/EGL selection toward the NVIDIA stack when using X11 forwarding. -- Python source changes are picked up from the mounted repo, including `extensions/rcs_zed`. +- The simulator still bootstraps EGL for offscreen MuJoCo camera rendering; set `RCS_MUJOCO_DISABLE_EGL=1` only if you intentionally want to disable that path. +- Python source changes are picked up from the mounted repo. - If you change C++ code in `rcs` or `rcs_fr3`, rebuild the image. - For non-GPU hosts, comment out the GPU-related lines in `docker/compose/dev.yml`. diff --git a/docker/link-editable-source.sh b/docker/link-editable-source.sh index 0b1b967a..0a93db47 100644 --- a/docker/link-editable-source.sh +++ b/docker/link-editable-source.sh @@ -10,26 +10,21 @@ fi SITE_PACKAGES="$(python -c 'import sysconfig; print(sysconfig.get_paths()["purelib"])')" -link_mixed_package() { +link_compiled_package() { src_dir="$1" dst_dir="$2" - keep_dir_name="${3:-}" if [ ! -d "$src_dir" ] || [ ! -d "$dst_dir" ]; then return fi - # Replace only the Python sources from the mounted repo and keep compiled - # artifacts that were installed into site-packages during image build. - for path in "$src_dir"/* "$src_dir"/.[!.]* "$src_dir"/..?*; do - [ -e "$path" ] || continue - name="$(basename "$path")" - if [ -n "$keep_dir_name" ] && [ "$name" = "$keep_dir_name" ]; then - continue - fi - rm -rf "$dst_dir/$name" - cp -as "$path" "$dst_dir/$name" - done + tmp_keep="$(mktemp -d)" + find "$dst_dir" -maxdepth 1 \( -name '_core*.so' -o -name 'lib*.so*' \) -exec mv {} "$tmp_keep/" \; + rm -rf "$dst_dir" + mkdir -p "$dst_dir" + cp -as "$src_dir/." "$dst_dir/" + find "$tmp_keep" -maxdepth 1 -type f -exec mv {} "$dst_dir/" \; + rmdir "$tmp_keep" } link_pure_python_package() { @@ -44,8 +39,8 @@ link_pure_python_package() { ln -s "$src_dir" "$dst_dir" } -link_mixed_package "$REPO_ROOT/python/rcs" "$SITE_PACKAGES/rcs" "_core" -link_mixed_package "$REPO_ROOT/extensions/rcs_fr3/src/rcs_fr3" "$SITE_PACKAGES/rcs_fr3" "_core" +link_compiled_package "$REPO_ROOT/python/rcs" "$SITE_PACKAGES/rcs" +link_compiled_package "$REPO_ROOT/extensions/rcs_fr3/src/rcs_fr3" "$SITE_PACKAGES/rcs_fr3" link_pure_python_package "$REPO_ROOT/extensions/rcs_realsense/src/rcs_realsense" "$SITE_PACKAGES/rcs_realsense" link_pure_python_package "$REPO_ROOT/extensions/rcs_robotiq2f85/src/rcs_robotiq2f85" "$SITE_PACKAGES/rcs_robotiq2f85" link_pure_python_package "$REPO_ROOT/extensions/rcs_zed/src/rcs_zed" "$SITE_PACKAGES/rcs_zed" From fce0ff68741139518a07f30ee4abd066b820e9cd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 5 May 2026 10:29:43 +0200 Subject: [PATCH 02/33] feat: zed cli rgb snapshot --- extensions/rcs_zed/src/rcs_zed/__main__.py | 104 ++++++++++++++++----- 1 file changed, 81 insertions(+), 23 deletions(-) diff --git a/extensions/rcs_zed/src/rcs_zed/__main__.py b/extensions/rcs_zed/src/rcs_zed/__main__.py index cfe51fa5..8e2558f4 100644 --- a/extensions/rcs_zed/src/rcs_zed/__main__.py +++ b/extensions/rcs_zed/src/rcs_zed/__main__.py @@ -1,4 +1,6 @@ import logging +from pathlib import Path +from time import monotonic import cv2 import typer @@ -14,6 +16,36 @@ def _display_frame(window_name: str, frame): cv2.imshow(window_name, frame.camera.color.data[:, :, ::-1]) +def _resolve_serial(serial: str | None) -> str: + if serial is not None: + return serial + + try: + devices = ZEDCameraSet.enumerate_connected_devices() + except RuntimeError as exc: + msg = str(exc) + raise typer.BadParameter(msg) from exc + if len(devices) == 0: + msg = "No ZED devices connected." + raise typer.BadParameter(msg) + return next(iter(devices)) + + +def _create_rgb_camera(serial: str, width: int, height: int, fps: int) -> ZEDCameraSet: + return ZEDCameraSet( + cameras={ + "viewer": common.BaseCameraConfig( + identifier=serial, + resolution_width=width, + resolution_height=height, + frame_rate=fps, + ) + }, + enable_depth=False, + enable_imu=False, + ) + + @zed_app.command() def serials(): """Reads out the serial numbers and models of connected ZED devices via the SDK.""" @@ -39,29 +71,8 @@ def rgb_view( window_name: str = typer.Option("ZED RGB", help="OpenCV window title."), ): """Open a live RGB window using the RCS ZED camera interface.""" - if serial is None: - try: - devices = ZEDCameraSet.enumerate_connected_devices() - except RuntimeError as exc: - msg = str(exc) - raise typer.BadParameter(msg) from exc - if len(devices) == 0: - msg = "No ZED devices connected." - raise typer.BadParameter(msg) - serial = next(iter(devices)) - - camera = ZEDCameraSet( - cameras={ - "viewer": common.BaseCameraConfig( - identifier=serial, - resolution_width=width, - resolution_height=height, - frame_rate=fps, - ) - }, - enable_depth=False, - enable_imu=False, - ) + serial = _resolve_serial(serial) + camera = _create_rgb_camera(serial, width, height, fps) try: camera.open() @@ -81,6 +92,53 @@ def rgb_view( cv2.destroyAllWindows() +@zed_app.command("rgb-snapshot") +def rgb_snapshot( + serial: str | None = typer.Argument(None, help="Optional ZED serial number. Uses the first device if omitted."), + output: Path = typer.Option(Path("zed_latest.png"), "--output", "-o", help="PNG file to write."), + width: int = typer.Option(1280, help="Requested capture width."), + height: int = typer.Option(720, help="Requested capture height."), + fps: int = typer.Option(30, help="Requested capture frame rate."), + duration: float = typer.Option(1.0, "--duration", "-d", help="Seconds to read frames before saving."), +): + """Open a ZED camera briefly and save the latest RGB frame as a PNG.""" + if duration <= 0: + msg = "Duration must be greater than zero." + raise typer.BadParameter(msg) + if output.suffix.lower() != ".png": + msg = "Output path must end in .png." + raise typer.BadParameter(msg) + + serial = _resolve_serial(serial) + camera = _create_rgb_camera(serial, width, height, fps) + + try: + camera.open() + except Exception as exc: + msg = f"Could not start ZED camera {serial}: {exc}" + raise typer.BadParameter(msg) from exc + + latest_frame = None + frames_read = 0 + deadline = monotonic() + duration + try: + while latest_frame is None or monotonic() < deadline: + latest_frame = camera.poll_frame("viewer") + frames_read += 1 + finally: + camera.close() + + assert latest_frame is not None + output.parent.mkdir(parents=True, exist_ok=True) + image_bgr = latest_frame.camera.color.data[:, :, ::-1] + print(latest_frame.camera.color.intrinsics) + if not cv2.imwrite(str(output), image_bgr): + msg = f"Could not write PNG to {output}." + raise typer.BadParameter(msg) + + typer.echo(f"Saved {output} from ZED {serial} after reading {frames_read} frame(s).") + + def main(): zed_app() From 2f7fe19f9f9db6d1cc8e0373c676d85789f19cbb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 5 May 2026 18:56:24 +0200 Subject: [PATCH 03/33] fix(teleop): depth in cameras --- examples/teleop/franka.py | 2 +- extensions/rcs_fr3/src/rcs_fr3/creators.py | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/teleop/franka.py b/examples/teleop/franka.py index 2f0d6ede..3736d55b 100644 --- a/examples/teleop/franka.py +++ b/examples/teleop/franka.py @@ -117,7 +117,7 @@ def get_env(): for name, identifier in ZED_CAMERA_DICT.items() }, kwargs={ - "enable_depth": False, + "enable_depth": INCLUDE_DEPTH, "enable_imu": False, }, ) diff --git a/extensions/rcs_fr3/src/rcs_fr3/creators.py b/extensions/rcs_fr3/src/rcs_fr3/creators.py index 2225a577..e28401e4 100644 --- a/extensions/rcs_fr3/src/rcs_fr3/creators.py +++ b/extensions/rcs_fr3/src/rcs_fr3/creators.py @@ -203,7 +203,7 @@ def create_env(self, cfg: FR3HardwareEnvCreatorConfig) -> gym.Env: camera_set.start() camera_set.wait_for_frames() logger.info("CameraSet started") - env = CameraSetWrapper(env, camera_set) + env = CameraSetWrapper(env, camera_set, cfg.wrapper_cfg.include_depth) if cfg.relative_to != RelativeTo.NONE: env = RelativeActionSpace(env, max_mov=cfg.max_relative_movement, relative_to=cfg.relative_to) @@ -236,7 +236,7 @@ def create_env(self, cfg: FR3MultiHardwareEnvCreatorConfig) -> gym.Env: camera_set.start() camera_set.wait_for_frames() logger.info("CameraSet started") - env = CameraSetWrapper(env, camera_set) + env = CameraSetWrapper(env, camera_set, cfg.wrapper_cfg.include_depth) return CoverWrapper(env) def config(self) -> FR3MultiHardwareEnvCreatorConfig: From 9d44dc5e124d969b9d8a8ad54ded3a5dd1dd0088 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 5 May 2026 18:56:52 +0200 Subject: [PATCH 04/33] chore(quest): simplify right/left swapping logic --- python/rcs/operator/quest.py | 26 +++++++++++++------------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/python/rcs/operator/quest.py b/python/rcs/operator/quest.py index 322b870a..158850f0 100644 --- a/python/rcs/operator/quest.py +++ b/python/rcs/operator/quest.py @@ -128,6 +128,14 @@ def _reset_state(self): self._last_controller_pose[controller] = Pose() self._grp_pos[controller] = 1 + def _swap_controller_input(self, input_data: dict[str, Any]) -> dict[str, Any]: + if not self.config.switched_left_right: + return input_data + swapped = copy.copy(input_data) + swapped["left"] = input_data["right"] + swapped["right"] = input_data["left"] + return swapped + @staticmethod def _normalize_axis(value: bool | float | int) -> float: if isinstance(value, bool): @@ -139,13 +147,6 @@ def consume_commands(self) -> TeleopCommands: with self._cmd_lock: cmds = copy.copy(self._commands) self._commands = TeleopCommands() - if self.config.switched_left_right: - swapped_reset_origin_to_current = {} - if "left" in cmds.reset_origin_to_current: - swapped_reset_origin_to_current["right"] = cmds.reset_origin_to_current["left"] - if "right" in cmds.reset_origin_to_current: - swapped_reset_origin_to_current["left"] = cmds.reset_origin_to_current["right"] - cmds.reset_origin_to_current = swapped_reset_origin_to_current return cmds def reset_operator_state(self): @@ -176,11 +177,7 @@ def consume_action(self) -> dict[str, ArmWithGripper]: tquat=np.concatenate([transform.translation(), transform.rotation_q()]), gripper=np.array([self._grp_pos[controller]]), ) - return ( - {"left": transforms["right"], "right": transforms["left"]} - if self.config.switched_left_right - else transforms - ) + return transforms def set_camera(self, observation: dict) -> None: if not self.config.display_cameras: @@ -241,6 +238,8 @@ def run(self): logger.warning("[Quest Reader] packets arriving again") warning_raised = False + input_data = self._swap_controller_input(input_data) + # === Update Semantic Commands === with self._cmd_lock: if input_data[self._start_btn] and (self._prev_data is None or not self._prev_data[self._start_btn]): @@ -293,7 +292,8 @@ def run(self): gripper_axis = self._normalize_axis(input_data[controller][self._grp_btn[controller]]) # convert from IRIS to RCS gripper logic - self._grp_pos[controller] = 1.0 - gripper_axis + with self._resource_lock: + self._grp_pos[controller] = 1.0 - gripper_axis self._prev_data = input_data rate_limiter() From 4af54bbe3c193c60a6c05915751c651d5ded1fb4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 5 May 2026 18:58:28 +0200 Subject: [PATCH 05/33] impr(robotiq): physical reset only in constructor --- extensions/rcs_robotiq2f85/src/rcs_robotiq2f85/hw.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/extensions/rcs_robotiq2f85/src/rcs_robotiq2f85/hw.py b/extensions/rcs_robotiq2f85/src/rcs_robotiq2f85/hw.py index a5ed5736..4bb10d4e 100644 --- a/extensions/rcs_robotiq2f85/src/rcs_robotiq2f85/hw.py +++ b/extensions/rcs_robotiq2f85/src/rcs_robotiq2f85/hw.py @@ -42,7 +42,8 @@ class RobotiQ2F85Gripper(Gripper): def __init__(self, cfg: RobotiQ2F85GripperConfig): super().__init__() self._cfg: RobotiQ2F85GripperConfig = cfg - self.gripper = Robotiq2F85Driver(serial_number=cfg.serial_number) + self.gripper = Robotiq2F85Driver(serial_number=cfg.serial_number, ignore_read_frequency=True) + self.gripper.reset() def get_normalized_width(self) -> float: # value between 0 and 1 (0 is closed) @@ -61,7 +62,7 @@ def open(self) -> None: self.set_normalized_width(1.0) def reset(self) -> None: - self.gripper.reset() + self.open() def set_normalized_width(self, width: float, force: float = 0) -> None: """ From 2e7802192b2f5f714fa702ab4e6fa5619d3d6040 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 12 May 2026 11:55:05 +0200 Subject: [PATCH 06/33] feat: robotiq in teleop script --- .dockerignore | 2 ++ docker/Dockerfile | 3 +- examples/teleop/franka.py | 35 ++++++++++++++------- extensions/rcs_fr3/src/rcs_fr3/configs.py | 1 + python/tests/test_quest_operator.py | 38 ++++++++++++++++++++++- 5 files changed, 66 insertions(+), 13 deletions(-) diff --git a/.dockerignore b/.dockerignore index bdf319e7..8b767f67 100644 --- a/.dockerignore +++ b/.dockerignore @@ -1 +1,3 @@ **/build/ +real* +test* diff --git a/docker/Dockerfile b/docker/Dockerfile index 2b03ad71..b72bde92 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -53,7 +53,8 @@ RUN chmod +x /usr/local/bin/link-editable-source \ && uv pip install --no-build-isolation /opt/rcs-src/extensions/rcs_fr3 \ && uv pip install /opt/rcs-src/extensions/rcs_realsense \ && uv pip install /opt/rcs-src/extensions/rcs_robotiq2f85 \ - && uv pip install /opt/rcs-src/extensions/rcs_zed + && uv pip install /opt/rcs-src/extensions/rcs_zed \ + && uv pip install /opt/rcs-src/examples/teleop/SimPublisher WORKDIR /workspace/robot-control-stack diff --git a/examples/teleop/franka.py b/examples/teleop/franka.py index 3736d55b..f3951c98 100644 --- a/examples/teleop/franka.py +++ b/examples/teleop/franka.py @@ -26,22 +26,26 @@ "right": "0", } - -ROBOT_INSTANCE = RobotPlatform.SIMULATION -# ROBOT_INSTANCE = RobotPlatform.HARDWARE +# use `udevadm info -a -n /dev/ttyUSB0 | grep serial` +# to find out the serial numbers +ROBOTIQ_SERIAL = { + "left": "DAAQMPDC", + "right": "DAAQMJHX", +} RECORD_FPS = 30 # set camera dict to none disable cameras -# CAMERA_DICT = { -# "left_wrist": "230422272017", -# "right_wrist": "230422271040", -# "side": "243522070385", -# "bird_eye": "243522070364", -# } -CAMERA_DICT = None +CAMERA_DICT = { + "right_wrist": "230422272017", + "left_wrist": "230422271040", + # "side": "243522070385", + # "bird_eye": "243522070364", +} +# CAMERA_DICT = None ZED_CAMERA_DICT = { - "zed": "19928076", + "head": "19928076", } +# ZED_CAMERA_DICT = None MQ3_ADDR = "10.42.0.1" INCLUDE_DEPTH = False @@ -119,6 +123,7 @@ def get_env(): kwargs={ "enable_depth": INCLUDE_DEPTH, "enable_imu": False, + "include_right": True, }, ) if DIGIT_DICT is not None: @@ -137,11 +142,19 @@ def get_env(): hw_cfg.camera_cfgs = camera_cfgs or None hw_cfg.control_mode = config.operator_class.control_mode[0] hw_cfg.wrapper_cfg.include_depth = INCLUDE_DEPTH + hw_cfg.wrapper_cfg.binary_gripper = False + # hw_cfg.wrapper_cfg.binary_gripper = True hw_cfg.max_relative_movement = ( 0.5 if config.operator_class.control_mode[0] == ControlMode.JOINTS else (0.5, np.deg2rad(90)) ) hw_cfg.relative_to = config.operator_class.control_mode[1] hw_cfg.robot_to_shared_base_frame = robot2world + hw_cfg.robot_cfgs["left"].ignore_realtime = True + hw_cfg.robot_cfgs["right"].ignore_realtime = True + hw_cfg.robot_cfgs["left"].speed_factor = 0.3 + hw_cfg.robot_cfgs["right"].speed_factor = 0.3 + hw_cfg.gripper_cfgs["left"].serial_number = ROBOTIQ_SERIAL["left"] + hw_cfg.gripper_cfgs["right"].serial_number = ROBOTIQ_SERIAL["right"] env_rel = env_creator.create_env(hw_cfg) operator = GelloOperator(config) if isinstance(config, GelloConfig) else QuestOperator(config) else: diff --git a/extensions/rcs_fr3/src/rcs_fr3/configs.py b/extensions/rcs_fr3/src/rcs_fr3/configs.py index 3eaa8b0a..baf47eaf 100644 --- a/extensions/rcs_fr3/src/rcs_fr3/configs.py +++ b/extensions/rcs_fr3/src/rcs_fr3/configs.py @@ -152,6 +152,7 @@ def config(self) -> FR3MultiHardwareEnvCreatorConfig: class FrankaDuoEnv(DefaultFR3MultiHardwareEnv): + # use `udevadm info -a -n /dev/ttyUSB0 | grep serial` to find out the serial numbers left_gripper_serial_number = "DAAQMJHX" right_gripper_serial_number = "DAAQMPDC" diff --git a/python/tests/test_quest_operator.py b/python/tests/test_quest_operator.py index d5af2a78..55db719a 100644 --- a/python/tests/test_quest_operator.py +++ b/python/tests/test_quest_operator.py @@ -1,6 +1,9 @@ import threading from typing import Any, cast +import numpy as np + +from rcs._core.common import Pose from rcs.operator.interface import TeleopCommands from rcs.operator.quest import QuestOperator @@ -9,13 +12,46 @@ class _Config: switched_left_right = True +def test_swap_controller_input_swaps_left_and_right_packets(): + operator = QuestOperator.__new__(QuestOperator) + operator.config = cast(Any, _Config()) + + input_data = { + "left": {"hand_trigger": 0.1, "index_trigger": 0.2}, + "right": {"hand_trigger": 0.9, "index_trigger": 0.8}, + "A": True, + } + + swapped = QuestOperator._swap_controller_input(operator, input_data) + + assert swapped["left"] == input_data["right"] + assert swapped["right"] == input_data["left"] + assert swapped["A"] is True + + def test_consume_commands_swaps_both_reset_origin_keys(): operator = QuestOperator.__new__(QuestOperator) operator.config = cast(Any, _Config()) operator._cmd_lock = threading.Lock() - operator._commands = TeleopCommands(reset_origin_to_current={"left": True, "right": False}) + operator._commands = TeleopCommands(reset_origin_to_current={"right": True, "left": False}) cmds = QuestOperator.consume_commands(operator) assert cmds.reset_origin_to_current == {"right": True, "left": False} assert operator._commands.reset_origin_to_current == {} + + +def test_consume_action_swaps_gripper_with_controller(): + operator = QuestOperator.__new__(QuestOperator) + operator.config = cast(Any, _Config()) + operator._resource_lock = threading.Lock() + operator.controller_names = ["left", "right"] + operator._last_controller_pose = {key: Pose() for key in operator.controller_names} + operator._offset_pose = {key: Pose() for key in operator.controller_names} + operator._set_frame = {key: Pose() for key in operator.controller_names} + operator._grp_pos = {"left": 0.75, "right": 0.25} + + actions = QuestOperator.consume_action(operator) + + assert np.allclose(actions["left"]["gripper"], np.array([0.75])) + assert np.allclose(actions["right"]["gripper"], np.array([0.25])) From 7b1889110425fb8114b77f061ca86ac95db1281a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 12 May 2026 11:58:26 +0200 Subject: [PATCH 07/33] impr(gripper): improved change detection --- .../rcs_robotiq2f85/src/rcs_robotiq2f85/hw.py | 8 ++++--- python/rcs/envs/base.py | 21 +++++++++++++------ python/rcs/utils.py | 1 - 3 files changed, 20 insertions(+), 10 deletions(-) diff --git a/extensions/rcs_robotiq2f85/src/rcs_robotiq2f85/hw.py b/extensions/rcs_robotiq2f85/src/rcs_robotiq2f85/hw.py index 4bb10d4e..db4be1fa 100644 --- a/extensions/rcs_robotiq2f85/src/rcs_robotiq2f85/hw.py +++ b/extensions/rcs_robotiq2f85/src/rcs_robotiq2f85/hw.py @@ -42,12 +42,13 @@ class RobotiQ2F85Gripper(Gripper): def __init__(self, cfg: RobotiQ2F85GripperConfig): super().__init__() self._cfg: RobotiQ2F85GripperConfig = cfg - self.gripper = Robotiq2F85Driver(serial_number=cfg.serial_number, ignore_read_frequency=True) + self.gripper = Robotiq2F85Driver(serial_number=cfg.serial_number) + self._last_normalized_width = 1.0 self.gripper.reset() def get_normalized_width(self) -> float: - # value between 0 and 1 (0 is closed) - return self.gripper.opening / 85 + # Return the last commanded width to avoid a synchronous Modbus read on every env step. + return self._last_normalized_width def grasp(self) -> None: """ @@ -71,6 +72,7 @@ def set_normalized_width(self, width: float, force: float = 0) -> None: if not (0 <= width <= 1): msg = f"Width must be between 0 and 1, got {width}." raise ValueError(msg) + self._last_normalized_width = width abs_width = width * 85 self.gripper.go_to( opening=float(abs_width), diff --git a/python/rcs/envs/base.py b/python/rcs/envs/base.py index 71a210f0..7d12b336 100644 --- a/python/rcs/envs/base.py +++ b/python/rcs/envs/base.py @@ -935,6 +935,14 @@ def __init__(self, env, gripper: common.Gripper, binary: bool = True): self.gripper = gripper self._last_gripper_cmd = None + def _command_changed(self, gripper_action: np.ndarray) -> bool: + if self._last_gripper_cmd is None: + return True + last_action = np.asarray(self._last_gripper_cmd, dtype=np.float32) + if self.binary: + return not np.array_equal(gripper_action, last_action) + return not np.allclose(gripper_action, last_action, atol=1e-3, rtol=0.0) + def close(self): self.gripper.close() super().close() @@ -966,13 +974,14 @@ def action(self, action: dict[str, Any]) -> dict[str, Any]: gripper_action = [gripper_action] # type: ignore if self.binary: gripper_action = np.round(gripper_action) - gripper_action = np.clip(gripper_action, 0.0, 1.0) + gripper_action = np.clip(np.asarray(gripper_action, dtype=np.float32), 0.0, 1.0) - if self.binary: - self.gripper.grasp() if gripper_action == self.BINARY_GRIPPER_CLOSED else self.gripper.open() - else: - self.gripper.set_normalized_width(gripper_action[0]) - self._last_gripper_cmd = gripper_action + if self._command_changed(gripper_action): + if self.binary: + self.gripper.grasp() if gripper_action[0] < 0.5 else self.gripper.open() + else: + self.gripper.set_normalized_width(float(gripper_action[0])) + self._last_gripper_cmd = gripper_action.tolist() del action[self.gripper_key] return action diff --git a/python/rcs/utils.py b/python/rcs/utils.py index 9f9b7e7f..25ef2abb 100644 --- a/python/rcs/utils.py +++ b/python/rcs/utils.py @@ -27,7 +27,6 @@ def __call__(self): if self.t is None: self.t = perf_counter() self._last_print = self.t - sleep(1 / self.frame_rate) return sleep_time = 1 / self.frame_rate - (perf_counter() - self.t) if sleep_time > 0: From 785acb143c76697db27d7f5e299e45103f1526e7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 12 May 2026 11:59:23 +0200 Subject: [PATCH 08/33] feat(zed): add option to record both eyes --- extensions/rcs_zed/src/rcs_zed/camera.py | 156 +++++++++++++----- .../rcs_zed/tests/test_zed_extension.py | 58 ++++++- 2 files changed, 171 insertions(+), 43 deletions(-) diff --git a/extensions/rcs_zed/src/rcs_zed/camera.py b/extensions/rcs_zed/src/rcs_zed/camera.py index e9fd61dd..881a1368 100644 --- a/extensions/rcs_zed/src/rcs_zed/camera.py +++ b/extensions/rcs_zed/src/rcs_zed/camera.py @@ -30,6 +30,8 @@ class ZEDFrameBundle: color: np.ndarray timestamp: float color_intrinsics: np.ndarray[tuple[typing.Literal[3], typing.Literal[4]], np.dtype[np.float64]] + right_color: np.ndarray | None = None + right_color_intrinsics: np.ndarray[tuple[typing.Literal[3], typing.Literal[4]], np.dtype[np.float64]] | None = None depth: np.ndarray | None = None accel: np.ndarray | None = None gyro: np.ndarray | None = None @@ -47,12 +49,20 @@ def _intrinsics_matrix(fx: float, fy: float, cx: float, cy: float) -> np.ndarray class PyZEDCameraHandle: - def __init__(self, camera: typing.Any, device_info: ZEDDeviceInfo, color_intrinsics: np.ndarray): + def __init__( + self, + camera: typing.Any, + device_info: ZEDDeviceInfo, + color_intrinsics: np.ndarray, + right_color_intrinsics: np.ndarray | None = None, + ): self.camera = camera self.device_info = device_info self.color_intrinsics = color_intrinsics + self.right_color_intrinsics = right_color_intrinsics self.runtime_parameters = sl.RuntimeParameters() # type: ignore[union-attr] self.image_mat = sl.Mat() # type: ignore[union-attr] + self.right_image_mat = sl.Mat() # type: ignore[union-attr] self.depth_mat = sl.Mat() # type: ignore[union-attr] self.sensors_data = sl.SensorsData() # type: ignore[union-attr] @@ -69,7 +79,7 @@ def _timestamp_seconds(self) -> float: pass return time() - def grab_frame(self) -> ZEDFrameBundle: + def grab_frame(self, include_right: bool = False) -> ZEDFrameBundle: err = self.camera.grab(self.runtime_parameters) if err != sl.ERROR_CODE.SUCCESS: # type: ignore[union-attr] msg = f"Failed to grab ZED frame: {err}" @@ -82,6 +92,15 @@ def grab_frame(self) -> ZEDFrameBundle: raise RuntimeError(msg) color_rgb = color_raw[:, :, :3][:, :, ::-1] if color_raw.shape[2] == 4 else color_raw[:, :, ::-1] + right_color = None + if include_right: + self.camera.retrieve_image(self.right_image_mat, sl.VIEW.RIGHT) # type: ignore[union-attr] + right_raw = np.array(self.right_image_mat.get_data(), copy=True) + if right_raw.ndim != 3: + msg = f"Unexpected ZED right image shape {right_raw.shape}" + raise RuntimeError(msg) + right_color = right_raw[:, :, :3][:, :, ::-1] if right_raw.shape[2] == 4 else right_raw[:, :, ::-1] + depth = None if self.device_info.has_depth: self.camera.retrieve_measure(self.depth_mat, sl.MEASURE.DEPTH) # type: ignore[union-attr] @@ -105,6 +124,8 @@ def grab_frame(self) -> ZEDFrameBundle: return ZEDFrameBundle( color=color_rgb, + right_color=right_color, + right_color_intrinsics=self.right_color_intrinsics if right_color is not None else None, depth=depth, accel=accel, gyro=gyro, @@ -185,6 +206,7 @@ def open_camera( *, enable_depth: bool, enable_imu: bool, + include_right: bool, ) -> PyZEDCameraHandle: cls._require_sdk() assert sl is not None @@ -206,6 +228,7 @@ def open_camera( information = camera.get_camera_information() calibration = information.camera_configuration.calibration_parameters left_cam = calibration.left_cam + right_cam = calibration.right_cam info = ZEDDeviceInfo( serial=str(config.identifier), model=cls._model_to_string(information.camera_model), @@ -213,7 +236,15 @@ def open_camera( has_imu=enable_imu and cls._device_has_imu(information), ) intrinsics = _intrinsics_matrix(left_cam.fx, left_cam.fy, left_cam.cx, left_cam.cy) - return PyZEDCameraHandle(camera=camera, device_info=info, color_intrinsics=intrinsics) + right_intrinsics = None + if include_right: + right_intrinsics = _intrinsics_matrix(right_cam.fx, right_cam.fy, right_cam.cx, right_cam.cy) + return PyZEDCameraHandle( + camera=camera, + device_info=info, + color_intrinsics=intrinsics, + right_color_intrinsics=right_intrinsics, + ) def __init__( self, @@ -221,6 +252,7 @@ def __init__( calibration_strategy: dict[str, CalibrationStrategy] | None = None, enable_depth: bool = True, enable_imu: bool = True, + include_right: bool = False, ) -> None: self.cameras = cameras if calibration_strategy is None: @@ -228,12 +260,14 @@ def __init__( self.calibration_strategy = calibration_strategy self.enable_depth = enable_depth self.enable_imu = enable_imu + self.include_right = include_right self._logger = logging.getLogger(__name__) - self._camera_names = list(self.cameras.keys()) + self._camera_names = self._logical_camera_names() self._available_devices: dict[str, ZEDDeviceInfo] = {} self._enabled_devices: dict[str, PyZEDCameraHandle] = {} self._frame_buffer_lock: dict[str, threading.Lock] = {} self._frame_buffer: dict[str, list[Frame]] = {} + self._pending_right_bundles: dict[str, ZEDFrameBundle] = {} assert ( len({camera.resolution_width for camera in self.cameras.values()}) == 1 @@ -246,7 +280,63 @@ def camera_names(self) -> list[str]: return self._camera_names def config(self, camera_name) -> common.BaseCameraConfig: - return self.cameras[camera_name] + return self.cameras[self._physical_camera_name(camera_name)] + + @staticmethod + def _right_camera_name(camera_name: str) -> str: + return f"{camera_name}_right" + + def _physical_camera_name(self, camera_name: str) -> str: + if camera_name in self.cameras: + return camera_name + if self.include_right and camera_name.endswith("_right"): + physical_name = camera_name.removesuffix("_right") + if physical_name in self.cameras: + return physical_name + msg = f"Camera {camera_name} not found in the enabled devices" + raise AssertionError(msg) + + def _is_right_camera_name(self, camera_name: str) -> bool: + return camera_name not in self.cameras and self._physical_camera_name(camera_name) != camera_name + + def _logical_camera_names(self) -> list[str]: + names = list(self.cameras.keys()) + if self.include_right: + names.extend(self._right_camera_name(camera_name) for camera_name in self.cameras) + return names + + def _frame_from_bundle(self, camera_name: str, bundle: ZEDFrameBundle) -> Frame: + physical_name = self._physical_camera_name(camera_name) + extrinsics = self.calibration_strategy[physical_name].get_extrinsics() + is_right = self._is_right_camera_name(camera_name) + color_data = bundle.right_color if is_right else bundle.color + color_intrinsics = bundle.right_color_intrinsics if is_right else bundle.color_intrinsics + if color_data is None or color_intrinsics is None: + msg = f"Missing {'right' if is_right else 'left'} image data for {camera_name}" + raise RuntimeError(msg) + + color = DataFrame( + data=color_data, + timestamp=bundle.timestamp, + intrinsics=color_intrinsics, + extrinsics=extrinsics, + ) + depth = None + if not is_right and bundle.depth is not None: + depth = DataFrame( + data=bundle.depth, + timestamp=bundle.timestamp, + intrinsics=bundle.color_intrinsics, + extrinsics=extrinsics, + ) + + accel = DataFrame(data=bundle.accel, timestamp=bundle.timestamp) if bundle.accel is not None else None + gyro = DataFrame(data=bundle.gyro, timestamp=bundle.timestamp) if bundle.gyro is not None else None + return Frame( + camera=CameraFrame(color=color, depth=depth), + imu=IMUFrame(accel=accel, gyro=gyro) if (accel is not None or gyro is not None) else None, + avg_timestamp=bundle.timestamp, + ) def update_available_devices(self): self._available_devices = self.enumerate_connected_devices() @@ -256,6 +346,7 @@ def open(self): self._enabled_devices = {} self._frame_buffer = {} self._frame_buffer_lock = {} + self._pending_right_bundles = {} for camera_name, camera_cfg in self.cameras.items(): if camera_cfg.identifier not in self._available_devices: @@ -267,6 +358,7 @@ def open(self): camera_cfg, enable_depth=self.enable_depth and device_info.has_depth, enable_imu=self.enable_imu and device_info.has_imu, + include_right=self.include_right, ) self._enabled_devices[camera_name] = opened self._frame_buffer[camera_name] = [] @@ -274,44 +366,34 @@ def open(self): def poll_frame(self, camera_name: str) -> Frame: assert camera_name in self.camera_names, f"Camera {camera_name} not found in the enabled devices" - device = self._enabled_devices[camera_name] - bundle = device.grab_frame() - extrinsics = self.calibration_strategy[camera_name].get_extrinsics() - - color = DataFrame( - data=bundle.color, - timestamp=bundle.timestamp, - intrinsics=bundle.color_intrinsics, - extrinsics=extrinsics, - ) - depth = None - if bundle.depth is not None: - depth = DataFrame( - data=bundle.depth, - timestamp=bundle.timestamp, - intrinsics=bundle.color_intrinsics, - extrinsics=extrinsics, - ) - - accel = DataFrame(data=bundle.accel, timestamp=bundle.timestamp) if bundle.accel is not None else None - gyro = DataFrame(data=bundle.gyro, timestamp=bundle.timestamp) if bundle.gyro is not None else None - - frame = Frame( - camera=CameraFrame(color=color, depth=depth), - imu=IMUFrame(accel=accel, gyro=gyro) if (accel is not None or gyro is not None) else None, - avg_timestamp=bundle.timestamp, - ) - - with self._frame_buffer_lock[camera_name]: - if len(self._frame_buffer[camera_name]) >= self.CALIBRATION_FRAME_SIZE: - self._frame_buffer[camera_name].pop(0) - self._frame_buffer[camera_name].append(copy.deepcopy(frame)) + physical_name = self._physical_camera_name(camera_name) + device = self._enabled_devices[physical_name] + + if self._is_right_camera_name(camera_name): + bundle = self._pending_right_bundles.pop(physical_name, None) + if bundle is None: + bundle = device.grab_frame(include_right=True) + else: + bundle = device.grab_frame(include_right=self.include_right) + if self.include_right and bundle.right_color is not None: + self._pending_right_bundles[physical_name] = bundle + else: + self._pending_right_bundles.pop(physical_name, None) + + frame = self._frame_from_bundle(camera_name, bundle) + + if not self._is_right_camera_name(camera_name): + with self._frame_buffer_lock[physical_name]: + if len(self._frame_buffer[physical_name]) >= self.CALIBRATION_FRAME_SIZE: + self._frame_buffer[physical_name].pop(0) + self._frame_buffer[physical_name].append(copy.deepcopy(frame)) return frame def close(self): for device in self._enabled_devices.values(): device.close() self._enabled_devices = {} + self._pending_right_bundles = {} def calibrate(self) -> bool: for camera_name in self.cameras: diff --git a/extensions/rcs_zed/tests/test_zed_extension.py b/extensions/rcs_zed/tests/test_zed_extension.py index 32e8294f..cb17acec 100644 --- a/extensions/rcs_zed/tests/test_zed_extension.py +++ b/extensions/rcs_zed/tests/test_zed_extension.py @@ -20,8 +20,10 @@ def __init__(self, device_info: ZEDDeviceInfo, color_intrinsics: np.ndarray, fra self.color_intrinsics = color_intrinsics self._frame_bundle = frame_bundle self.closed = False + self.grab_calls: list[bool] = [] - def grab_frame(self) -> ZEDFrameBundle: + def grab_frame(self, include_right: bool = False) -> ZEDFrameBundle: + self.grab_calls.append(include_right) return self._frame_bundle def close(self): @@ -31,7 +33,7 @@ def close(self): class PatchZedState(TypedDict): devices: dict[str, ZEDDeviceInfo] opened: dict[str, FakeOpenedZEDCamera] - open_calls: list[tuple[str, bool, bool]] + open_calls: list[tuple[str, bool, bool, bool]] @pytest.fixture() @@ -41,8 +43,8 @@ def patch_zed(monkeypatch) -> PatchZedState: def fake_enumerate(_cls): return state["devices"] - def fake_open(_cls, config: common.BaseCameraConfig, *, enable_depth: bool, enable_imu: bool): - state["open_calls"].append((config.identifier, enable_depth, enable_imu)) + def fake_open(_cls, config: common.BaseCameraConfig, *, enable_depth: bool, enable_imu: bool, include_right: bool): + state["open_calls"].append((config.identifier, enable_depth, enable_imu, include_right)) return state["opened"][config.identifier] monkeypatch.setattr(ZEDCameraSet, "enumerate_connected_devices", classmethod(fake_enumerate)) @@ -78,7 +80,7 @@ def test_zed_frame_mapping_depth_scaling_and_imu_downgrade(patch_zed): frame = camera_set.poll_frame("wrist") assert frame.camera.color.intrinsics is not None - assert patch_zed["open_calls"] == [("123", True, False)] + assert patch_zed["open_calls"] == [("123", True, False, False)] assert np.array_equal(frame.camera.color.data, color) assert np.array_equal(frame.camera.depth.data, depth) # type: ignore[union-attr] assert np.array_equal(frame.camera.color.intrinsics, intrinsics) @@ -113,7 +115,51 @@ def test_zed_enumeration_and_multi_camera_open(patch_zed): }, ) camera_set.open() - assert patch_zed["open_calls"] == [("111", True, False), ("222", True, True)] + assert patch_zed["open_calls"] == [("111", True, False, False), ("222", True, True, False)] camera_set.close() assert opened["111"].closed assert opened["222"].closed + + +def test_zed_include_right_adds_logical_right_camera_without_double_grab(patch_zed): + left_intrinsics = np.array([[100.0, 0.0, 10.0, 0.0], [0.0, 110.0, 20.0, 0.0], [0.0, 0.0, 1.0, 0.0]]) + right_intrinsics = np.array([[120.0, 0.0, 12.0, 0.0], [0.0, 130.0, 22.0, 0.0], [0.0, 0.0, 1.0, 0.0]]) + left_color = np.arange(27, dtype=np.uint8).reshape(3, 3, 3) + right_color = np.arange(27, 54, dtype=np.uint8).reshape(3, 3, 3) + frame_bundle = ZEDFrameBundle( + color=left_color, + right_color=right_color, + timestamp=12.5, + color_intrinsics=left_intrinsics, + right_color_intrinsics=right_intrinsics, + ) + device_info = ZEDDeviceInfo(serial="123", model="ZED Mini", has_depth=True, has_imu=False) + opened = FakeOpenedZEDCamera(device_info=device_info, color_intrinsics=left_intrinsics, frame_bundle=frame_bundle) + patch_zed["devices"] = {"123": device_info} + patch_zed["opened"] = {"123": opened} + + camera_set = ZEDCameraSet( + cameras={ + "wrist": common.BaseCameraConfig( + identifier="123", resolution_width=1280, resolution_height=720, frame_rate=30 + ) + }, + include_right=True, + ) + + assert camera_set.camera_names == ["wrist", "wrist_right"] + assert camera_set.config("wrist_right").identifier == "123" + + camera_set.open() + assert patch_zed["open_calls"] == [("123", True, False, True)] + left_frame = camera_set.poll_frame("wrist") + right_frame = camera_set.poll_frame("wrist_right") + + assert opened.grab_calls == [True] + assert np.array_equal(left_frame.camera.color.data, left_color) + assert np.array_equal(right_frame.camera.color.data, right_color) + assert np.array_equal(left_frame.camera.color.intrinsics, left_intrinsics) + assert np.array_equal(right_frame.camera.color.intrinsics, right_intrinsics) + assert left_frame.avg_timestamp == right_frame.avg_timestamp == 12.5 + assert left_frame.camera.depth is None + assert right_frame.camera.depth is None From 07a8d3d4e5542e205ba584eec438994365bfd3e0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Fri, 8 May 2026 16:57:31 +0200 Subject: [PATCH 09/33] feat(inference): add initial inference loop script --- examples/inference/README.md | 0 examples/inference/franka.py | 236 ++++++++++++++++++++++++++++ examples/inference/requirements.txt | 1 + 3 files changed, 237 insertions(+) create mode 100644 examples/inference/README.md create mode 100644 examples/inference/franka.py create mode 100644 examples/inference/requirements.txt diff --git a/examples/inference/README.md b/examples/inference/README.md new file mode 100644 index 00000000..e69de29b diff --git a/examples/inference/franka.py b/examples/inference/franka.py new file mode 100644 index 00000000..8ac52572 --- /dev/null +++ b/examples/inference/franka.py @@ -0,0 +1,236 @@ +from dataclasses import dataclass +import datetime +import logging +from typing import Any + +import numpy as np +from rcs._core.common import BaseCameraConfig, RobotPlatform +from rcs._core.sim import SimConfig +from rcs.envs.base import ControlMode, RelativeTo +from rcs.envs.configs import EmptyWorldFR3Duo +import gymnasium as gym + +import rcs +from rcs.envs.tasks import PickTaskConfig +from vlagents.client import RemoteAgent +from vlagents.policies import Act, Obs + +logger = logging.getLogger(__name__) + + +ROBOT2IP = { + "right": "192.168.102.1", + "left": "192.168.101.1", +} +ROBOT2ID = { + "left": "1", + "right": "0", +} + + +ROBOT_INSTANCE = RobotPlatform.SIMULATION +# ROBOT_INSTANCE = RobotPlatform.HARDWARE + +# set camera dict to none disable cameras +# CAMERA_DICT = { +# "left_wrist": "230422272017", +# "right_wrist": "230422271040", +# "side": "243522070385", +# "bird_eye": "243522070364", +# } +CAMERA_DICT = None +ZED_CAMERA_DICT = { + "zed": "19928076", +} +INCLUDE_DEPTH = False + + +# DIGIT_DICT = { +# "digit_right_left": "D21182", +# "digit_right_right": "D21193" +# } +DIGIT_DICT = None + + +DATASET_PATH = "test_iris" +INSTRUCTION = "pick up cube" +RECORD_FPS = 30 +CONTROL_MODE = ControlMode.JOINTS +RELATIVETO = RelativeTo.NONE +DEBUG = True +VIDEO_PATH = "videos" +MODEL = "pi05" +IP = "" +PORT = 20997 + + +robot2world = { + "right": rcs.common.Pose( + translation=np.array([0, 0, 0]), rpy_vector=np.array([0.89360858, -0.17453293, 0.46425758]) + ), + "left": rcs.common.Pose( + translation=np.array([0, 0, 0]), rpy_vector=np.array([-0.89360858, -0.17453293, -0.46425758]) + ), +} + +@dataclass +class InferenceConfig: + vlagents_host: str + vlagents_port: int + vlagents_model: str + instruction: str + robot_keys: list[str] + jpeg_encoding: bool = True + on_same_machine: bool = False + +class ModelInference: + def __init__(self, env: gym.Env, cfg: InferenceConfig): + self.env = env + self.gripper_state = 1 + self._cfg = cfg + self.remote_agent = RemoteAgent(cfg.vlagents_host, cfg.vlagents_port, cfg.vlagents_model, cfg.on_same_machine, cfg.jpeg_encoding) + + + def obs_rcs2agents(self, obs: dict, info: dict | None = None) -> Obs: + cameras = {} + for frame in obs["frames"]: + cameras[frame] = obs["frames"][frame]["rgb"]["data"] + state = [] + for robot in self._cfg.robot_keys: + # TODO: currently hardcoded for joints + state.append(obs[robot]["joints"]) + state.append(obs[robot]["gripper"]) + + return Obs(cameras=None, gripper=None, info=info, state=np.concatenate(state)) + + def action_agents2rcs(self, action: Act) -> dict[str, Any]: + act = {} + for idx, robot in enumerate(self._cfg.robot_keys): + # TODO: this is currently hard coded for franka joints + act[robot] = {} + act[robot]["joints"] = action.action[idx*8:idx*8+7] + act[robot]["gripper"] = action.action[idx*8+7] + return act + + + def loop(self): + obs, _ = self.env.reset() + + obs_dict = self.obs_rcs2agents(obs) + + self.remote_agent.reset(obs_dict, instruction=self._cfg.instruction) + + while True: + action = self.remote_agent.act(obs_dict) + if action.done: + logger.info("done issued by agent, shutting down") + break + obs, _, _, _, info = self.env.step(self.action_agents2rcs(action)) + + obs_dict = self.obs_rcs2agents(obs) + + +def get_env(): + if ROBOT_INSTANCE == RobotPlatform.HARDWARE: + from rcs_fr3.configs import FrankaDuoEnv + from rcs_fr3.creators import HardwareCameraCreatorConfig + + env_creator = FrankaDuoEnv() + env_creator.left_ip = ROBOT2IP["left"] + env_creator.right_ip = ROBOT2IP["right"] + hw_cfg = env_creator.config() + camera_cfgs: dict[str, HardwareCameraCreatorConfig] = {} + if CAMERA_DICT is not None: + camera_cfgs["realsense"] = HardwareCameraCreatorConfig( + camera_type_id="realsense", + camera_cfgs={ + name: BaseCameraConfig( + identifier=identifier, + resolution_width=1280, + resolution_height=720, + frame_rate=30, + ) + for name, identifier in CAMERA_DICT.items() + }, + ) + if ZED_CAMERA_DICT is not None: + camera_cfgs["zed"] = HardwareCameraCreatorConfig( + camera_type_id="zed", + camera_cfgs={ + name: BaseCameraConfig( + identifier=identifier, + resolution_width=1280, + resolution_height=720, + frame_rate=30, + ) + for name, identifier in ZED_CAMERA_DICT.items() + }, + kwargs={ + "enable_depth": False, + "enable_imu": False, + }, + ) + if DIGIT_DICT is not None: + camera_cfgs["digit"] = HardwareCameraCreatorConfig( + camera_type_id="digit", + camera_cfgs={ + name: BaseCameraConfig( + identifier=identifier, + resolution_width=320, + resolution_height=240, + frame_rate=30, + ) + for name, identifier in DIGIT_DICT.items() + }, + ) + hw_cfg.camera_cfgs = camera_cfgs or None + hw_cfg.control_mode = CONTROL_MODE + hw_cfg.wrapper_cfg.include_depth = INCLUDE_DEPTH + hw_cfg.max_relative_movement = ( + 0.5 if CONTROL_MODE == ControlMode.JOINTS else (0.5, np.deg2rad(90)) + ) + hw_cfg.relative_to = RELATIVETO + hw_cfg.robot_to_shared_base_frame = robot2world + env_rel = env_creator.create_env(hw_cfg) + else: + # FR3 + + scene = EmptyWorldFR3Duo() + sim_cfg_data = scene.config() + sim_cfg_data.sim_cfg = SimConfig( + async_control=True, realtime=True, frequency=RECORD_FPS, max_convergence_steps=500 + ) + sim_cfg_data.relative_to = RelativeTo.CONFIGURED_ORIGIN + sim_cfg_data.wrapper_cfg.include_depth = INCLUDE_DEPTH + if sim_cfg_data.root_frame_objects is None: + sim_cfg_data.root_frame_objects = {} + sim_cfg_data.task_cfg = PickTaskConfig(robot_name="right") + + env_rel = scene.create_env(sim_cfg_data) + + return env_rel + + +def main(): + env_rel = get_env() + env_rel.reset() + + VIDEO_PATH.mkdir(parents=True, exist_ok=True) + timestamp = str(datetime.now().strftime("%Y-%m-%d_%H-%M-%S")) + + + camera_set = env_rel.get_wrapper_attr("camera_set") + camera_set.record_video(VIDEO_PATH, timestamp) + + # env = RHCWrapper(env, exec_horizon=1) + + cfg = InferenceConfig(IP, PORT, MODEL, INSTRUCTION, jpeg_encoding=True, on_same_machine=True, robot_keys=["left", "right"]) + controller = ModelInference(env_rel, cfg) + input("robot is about to be controlled by AI, press enter to start") + with env_rel: + controller.loop() + + + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/examples/inference/requirements.txt b/examples/inference/requirements.txt new file mode 100644 index 00000000..cb843744 --- /dev/null +++ b/examples/inference/requirements.txt @@ -0,0 +1 @@ +vlagents @ git+https://github.com/RobotControlStack/vlagents.git@lerobot \ No newline at end of file From f36b8e1a0e4c14f416f10e08374347c28370655c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Thu, 14 May 2026 14:42:39 +0200 Subject: [PATCH 10/33] style: format inference franka script --- examples/inference/franka.py | 34 +++++++++++++++++----------------- 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/examples/inference/franka.py b/examples/inference/franka.py index 8ac52572..bbd0c053 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -1,17 +1,17 @@ -from dataclasses import dataclass import datetime import logging +from dataclasses import dataclass from typing import Any +import gymnasium as gym import numpy as np from rcs._core.common import BaseCameraConfig, RobotPlatform from rcs._core.sim import SimConfig from rcs.envs.base import ControlMode, RelativeTo from rcs.envs.configs import EmptyWorldFR3Duo -import gymnasium as gym +from rcs.envs.tasks import PickTaskConfig import rcs -from rcs.envs.tasks import PickTaskConfig from vlagents.client import RemoteAgent from vlagents.policies import Act, Obs @@ -73,6 +73,7 @@ ), } + @dataclass class InferenceConfig: vlagents_host: str @@ -83,13 +84,15 @@ class InferenceConfig: jpeg_encoding: bool = True on_same_machine: bool = False + class ModelInference: def __init__(self, env: gym.Env, cfg: InferenceConfig): self.env = env self.gripper_state = 1 self._cfg = cfg - self.remote_agent = RemoteAgent(cfg.vlagents_host, cfg.vlagents_port, cfg.vlagents_model, cfg.on_same_machine, cfg.jpeg_encoding) - + self.remote_agent = RemoteAgent( + cfg.vlagents_host, cfg.vlagents_port, cfg.vlagents_model, cfg.on_same_machine, cfg.jpeg_encoding + ) def obs_rcs2agents(self, obs: dict, info: dict | None = None) -> Obs: cameras = {} @@ -108,11 +111,10 @@ def action_agents2rcs(self, action: Act) -> dict[str, Any]: for idx, robot in enumerate(self._cfg.robot_keys): # TODO: this is currently hard coded for franka joints act[robot] = {} - act[robot]["joints"] = action.action[idx*8:idx*8+7] - act[robot]["gripper"] = action.action[idx*8+7] + act[robot]["joints"] = action.action[idx * 8 : idx * 8 + 7] + act[robot]["gripper"] = action.action[idx * 8 + 7] return act - def loop(self): obs, _ = self.env.reset() @@ -186,9 +188,7 @@ def get_env(): hw_cfg.camera_cfgs = camera_cfgs or None hw_cfg.control_mode = CONTROL_MODE hw_cfg.wrapper_cfg.include_depth = INCLUDE_DEPTH - hw_cfg.max_relative_movement = ( - 0.5 if CONTROL_MODE == ControlMode.JOINTS else (0.5, np.deg2rad(90)) - ) + hw_cfg.max_relative_movement = 0.5 if CONTROL_MODE == ControlMode.JOINTS else (0.5, np.deg2rad(90)) hw_cfg.relative_to = RELATIVETO hw_cfg.robot_to_shared_base_frame = robot2world env_rel = env_creator.create_env(hw_cfg) @@ -212,25 +212,25 @@ def get_env(): def main(): - env_rel = get_env() + env_rel = get_env() env_rel.reset() VIDEO_PATH.mkdir(parents=True, exist_ok=True) - timestamp = str(datetime.now().strftime("%Y-%m-%d_%H-%M-%S")) - + timestamp = str(datetime.now().strftime("%Y-%m-%d_%H-%M-%S")) camera_set = env_rel.get_wrapper_attr("camera_set") camera_set.record_video(VIDEO_PATH, timestamp) # env = RHCWrapper(env, exec_horizon=1) - cfg = InferenceConfig(IP, PORT, MODEL, INSTRUCTION, jpeg_encoding=True, on_same_machine=True, robot_keys=["left", "right"]) + cfg = InferenceConfig( + IP, PORT, MODEL, INSTRUCTION, jpeg_encoding=True, on_same_machine=True, robot_keys=["left", "right"] + ) controller = ModelInference(env_rel, cfg) input("robot is about to be controlled by AI, press enter to start") with env_rel: controller.loop() - if __name__ == "__main__": - main() \ No newline at end of file + main() From 844d78b8f5ea6fd35b9bad7e06abc3f4a9f159af Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Thu, 14 May 2026 19:22:37 +0200 Subject: [PATCH 11/33] fix(franka): inference script after testing Co-authored-by: Copilot --- docker/Dockerfile | 4 +- docker/link-editable-source.sh | 1 + examples/inference/franka.py | 67 +++++++++++++++++++++------------- 3 files changed, 46 insertions(+), 26 deletions(-) diff --git a/docker/Dockerfile b/docker/Dockerfile index b72bde92..9c88e253 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -54,7 +54,9 @@ RUN chmod +x /usr/local/bin/link-editable-source \ && uv pip install /opt/rcs-src/extensions/rcs_realsense \ && uv pip install /opt/rcs-src/extensions/rcs_robotiq2f85 \ && uv pip install /opt/rcs-src/extensions/rcs_zed \ - && uv pip install /opt/rcs-src/examples/teleop/SimPublisher + && uv pip install /opt/rcs-src/examples/teleop/SimPublisher \ + && uv pip install /opt/rcs-src/2f85-python-driver \ + && uv pip install /opt/rcs-src/vlagents WORKDIR /workspace/robot-control-stack diff --git a/docker/link-editable-source.sh b/docker/link-editable-source.sh index 0a93db47..02bf007e 100644 --- a/docker/link-editable-source.sh +++ b/docker/link-editable-source.sh @@ -44,3 +44,4 @@ link_compiled_package "$REPO_ROOT/extensions/rcs_fr3/src/rcs_fr3" "$SITE_PACKAGE link_pure_python_package "$REPO_ROOT/extensions/rcs_realsense/src/rcs_realsense" "$SITE_PACKAGES/rcs_realsense" link_pure_python_package "$REPO_ROOT/extensions/rcs_robotiq2f85/src/rcs_robotiq2f85" "$SITE_PACKAGES/rcs_robotiq2f85" link_pure_python_package "$REPO_ROOT/extensions/rcs_zed/src/rcs_zed" "$SITE_PACKAGES/rcs_zed" +link_pure_python_package "$REPO_ROOT/vlagents" "$SITE_PACKAGES/vlagents" diff --git a/examples/inference/franka.py b/examples/inference/franka.py index bbd0c053..37bb8bae 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -1,8 +1,13 @@ +import copy import datetime import logging from dataclasses import dataclass +from pathlib import Path +from time import sleep from typing import Any +from rcs.utils import SimpleFrameRate + import gymnasium as gym import numpy as np from rcs._core.common import BaseCameraConfig, RobotPlatform @@ -28,22 +33,26 @@ } -ROBOT_INSTANCE = RobotPlatform.SIMULATION -# ROBOT_INSTANCE = RobotPlatform.HARDWARE +# ROBOT_INSTANCE = RobotPlatform.SIMULATION +ROBOT_INSTANCE = RobotPlatform.HARDWARE # set camera dict to none disable cameras -# CAMERA_DICT = { -# "left_wrist": "230422272017", -# "right_wrist": "230422271040", -# "side": "243522070385", -# "bird_eye": "243522070364", -# } -CAMERA_DICT = None +CAMERA_DICT = { + "left_wrist": "230422272017", + "right_wrist": "230422271040", + # "side": "243522070385", + # "bird_eye": "243522070364", +} +# CAMERA_DICT = None ZED_CAMERA_DICT = { - "zed": "19928076", + "head": "19928076", } INCLUDE_DEPTH = False +ROBOTIQ_SERIAL = { + "left": "DAAQMPDC", + "right": "DAAQMJHX", +} # DIGIT_DICT = { # "digit_right_left": "D21182", @@ -52,16 +61,15 @@ DIGIT_DICT = None -DATASET_PATH = "test_iris" -INSTRUCTION = "pick up cube" +INSTRUCTION = "pick up the black cube with the right arm and place it into the black bowl; pick up the white cube with the left arm and place it into the white bowl" RECORD_FPS = 30 CONTROL_MODE = ControlMode.JOINTS RELATIVETO = RelativeTo.NONE DEBUG = True VIDEO_PATH = "videos" -MODEL = "pi05" -IP = "" -PORT = 20997 +MODEL = "lerobot" +IP = "172.29.5.16" +PORT = 20000 robot2world = { @@ -93,6 +101,7 @@ def __init__(self, env: gym.Env, cfg: InferenceConfig): self.remote_agent = RemoteAgent( cfg.vlagents_host, cfg.vlagents_port, cfg.vlagents_model, cfg.on_same_machine, cfg.jpeg_encoding ) + self.frame_rate = SimpleFrameRate(RECORD_FPS) def obs_rcs2agents(self, obs: dict, info: dict | None = None) -> Obs: cameras = {} @@ -104,7 +113,7 @@ def obs_rcs2agents(self, obs: dict, info: dict | None = None) -> Obs: state.append(obs[robot]["joints"]) state.append(obs[robot]["gripper"]) - return Obs(cameras=None, gripper=None, info=info, state=np.concatenate(state)) + return Obs(cameras=cameras, gripper=None, info=info, state=np.concatenate(state)) def action_agents2rcs(self, action: Act) -> dict[str, Any]: act = {} @@ -112,7 +121,7 @@ def action_agents2rcs(self, action: Act) -> dict[str, Any]: # TODO: this is currently hard coded for franka joints act[robot] = {} act[robot]["joints"] = action.action[idx * 8 : idx * 8 + 7] - act[robot]["gripper"] = action.action[idx * 8 + 7] + act[robot]["gripper"] = action.action[idx * 8 + 7 : idx * 8 + 8] return act def loop(self): @@ -120,16 +129,18 @@ def loop(self): obs_dict = self.obs_rcs2agents(obs) - self.remote_agent.reset(obs_dict, instruction=self._cfg.instruction) + self.remote_agent.reset(copy.deepcopy(obs_dict), instruction=self._cfg.instruction) while True: - action = self.remote_agent.act(obs_dict) + action = self.remote_agent.act(copy.deepcopy(obs_dict)) if action.done: logger.info("done issued by agent, shutting down") break - obs, _, _, _, info = self.env.step(self.action_agents2rcs(action)) + a = self.action_agents2rcs(action) + obs, _, _, _, info = self.env.step(a) obs_dict = self.obs_rcs2agents(obs) + self.frame_rate() def get_env(): @@ -191,6 +202,12 @@ def get_env(): hw_cfg.max_relative_movement = 0.5 if CONTROL_MODE == ControlMode.JOINTS else (0.5, np.deg2rad(90)) hw_cfg.relative_to = RELATIVETO hw_cfg.robot_to_shared_base_frame = robot2world + hw_cfg.robot_cfgs["left"].ignore_realtime = True + hw_cfg.robot_cfgs["right"].ignore_realtime = True + hw_cfg.robot_cfgs["left"].speed_factor = 0.3 + hw_cfg.robot_cfgs["right"].speed_factor = 0.3 + hw_cfg.gripper_cfgs["left"].serial_number = ROBOTIQ_SERIAL["left"] + hw_cfg.gripper_cfgs["right"].serial_number = ROBOTIQ_SERIAL["right"] env_rel = env_creator.create_env(hw_cfg) else: # FR3 @@ -215,16 +232,16 @@ def main(): env_rel = get_env() env_rel.reset() - VIDEO_PATH.mkdir(parents=True, exist_ok=True) - timestamp = str(datetime.now().strftime("%Y-%m-%d_%H-%M-%S")) + # Path(VIDEO_PATH).mkdir(parents=True, exist_ok=True) + # timestamp = str(datetime.datetime.now().strftime("%Y-%m-%d_%H-%M-%S")) - camera_set = env_rel.get_wrapper_attr("camera_set") - camera_set.record_video(VIDEO_PATH, timestamp) + # camera_set = env_rel.get_wrapper_attr("camera_set") + # camera_set.record_video(Path(VIDEO_PATH), timestamp) # env = RHCWrapper(env, exec_horizon=1) cfg = InferenceConfig( - IP, PORT, MODEL, INSTRUCTION, jpeg_encoding=True, on_same_machine=True, robot_keys=["left", "right"] + IP, PORT, MODEL, INSTRUCTION, jpeg_encoding=True, on_same_machine=False, robot_keys=["left", "right"] ) controller = ModelInference(env_rel, cfg) input("robot is about to be controlled by AI, press enter to start") From ac4836f08c1255e41866da07689b5d4484b14b24 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Mon, 18 May 2026 14:17:53 +0200 Subject: [PATCH 12/33] feat: sim inference --- examples/inference/franka.py | 19 ++++++++++++++----- 1 file changed, 14 insertions(+), 5 deletions(-) diff --git a/examples/inference/franka.py b/examples/inference/franka.py index 37bb8bae..93ff6f18 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -5,6 +5,7 @@ from pathlib import Path from time import sleep from typing import Any +from PIL import Image from rcs.utils import SimpleFrameRate @@ -17,6 +18,7 @@ from rcs.envs.tasks import PickTaskConfig import rcs +from rcs_duobench.tasks.bin_sort import BinSortEnvConfig from vlagents.client import RemoteAgent from vlagents.policies import Act, Obs @@ -107,6 +109,8 @@ def obs_rcs2agents(self, obs: dict, info: dict | None = None) -> Obs: cameras = {} for frame in obs["frames"]: cameras[frame] = obs["frames"][frame]["rgb"]["data"] + cameras[frame] = np.array(Image.fromarray(cameras[frame]).resize((224, 224), Image.Resampling.LANCZOS)) + state = [] for robot in self._cfg.robot_keys: # TODO: currently hardcoded for joints @@ -212,16 +216,21 @@ def get_env(): else: # FR3 - scene = EmptyWorldFR3Duo() + scene = BinSortEnvConfig() sim_cfg_data = scene.config() sim_cfg_data.sim_cfg = SimConfig( - async_control=True, realtime=True, frequency=RECORD_FPS, max_convergence_steps=500 + async_control=True, realtime=False, frequency=RECORD_FPS, max_convergence_steps=500 ) sim_cfg_data.relative_to = RelativeTo.CONFIGURED_ORIGIN sim_cfg_data.wrapper_cfg.include_depth = INCLUDE_DEPTH - if sim_cfg_data.root_frame_objects is None: - sim_cfg_data.root_frame_objects = {} - sim_cfg_data.task_cfg = PickTaskConfig(robot_name="right") + sim_cfg_data.control_mode = ControlMode.JOINTS + sim_cfg_data.relative_to = RELATIVETO + sim_cfg_data.wrapper_cfg.binary_gripper = True + + + # if sim_cfg_data.root_frame_objects is None: + # sim_cfg_data.root_frame_objects = {} + # sim_cfg_data.task_cfg = PickTaskConfig(robot_name="right") env_rel = scene.create_env(sim_cfg_data) From fc401e64df87c7caa01c448b00fb845403728850 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Mon, 18 May 2026 15:06:25 +0200 Subject: [PATCH 13/33] fix: patch always open gripper observation --- examples/inference/franka.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/examples/inference/franka.py b/examples/inference/franka.py index 93ff6f18..fd1acdb7 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -142,6 +142,8 @@ def loop(self): break a = self.action_agents2rcs(action) obs, _, _, _, info = self.env.step(a) + # print(obs["left"]["joints"], obs["left"]["gripper"], obs["right"]["joints"], obs["right"]["gripper"]) + obs["left"]["gripper"] = obs["right"]["gripper"] = 1.0 obs_dict = self.obs_rcs2agents(obs) self.frame_rate() From f9c0c9a53a8bf0242a0baf64c42e907e3819be22 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 19 May 2026 10:31:20 +0200 Subject: [PATCH 14/33] feat: reconnect and keyboard control --- examples/inference/franka.py | 143 ++++++++++++++++++++++++++++------- 1 file changed, 115 insertions(+), 28 deletions(-) diff --git a/examples/inference/franka.py b/examples/inference/franka.py index fd1acdb7..1d29ca13 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -1,11 +1,13 @@ import copy import datetime +import json import logging -from dataclasses import dataclass +from dataclasses import asdict, dataclass, field from pathlib import Path from time import sleep from typing import Any from PIL import Image +import threading from rcs.utils import SimpleFrameRate @@ -22,6 +24,8 @@ from vlagents.client import RemoteAgent from vlagents.policies import Act, Obs +from pynput import keyboard + logger = logging.getLogger(__name__) @@ -35,8 +39,8 @@ } -# ROBOT_INSTANCE = RobotPlatform.SIMULATION -ROBOT_INSTANCE = RobotPlatform.HARDWARE +ROBOT_INSTANCE = RobotPlatform.SIMULATION +# ROBOT_INSTANCE = RobotPlatform.HARDWARE # set camera dict to none disable cameras CAMERA_DICT = { @@ -64,14 +68,14 @@ INSTRUCTION = "pick up the black cube with the right arm and place it into the black bowl; pick up the white cube with the left arm and place it into the white bowl" -RECORD_FPS = 30 +FPS = 30 CONTROL_MODE = ControlMode.JOINTS RELATIVETO = RelativeTo.NONE -DEBUG = True -VIDEO_PATH = "videos" +RECORD_PATH = "inference_recordings" MODEL = "lerobot" -IP = "172.29.5.16" +IP = "localhost" PORT = 20000 +CONFIG_PATH = Path(__file__).with_suffix(".json") robot2world = { @@ -86,13 +90,23 @@ @dataclass class InferenceConfig: - vlagents_host: str - vlagents_port: int - vlagents_model: str - instruction: str - robot_keys: list[str] + vlagents_host: str = IP + vlagents_port: int = PORT + vlagents_model: str = MODEL + instruction: str = INSTRUCTION + robot_keys: list[str] = field(default_factory=lambda: ["left", "right"]) jpeg_encoding: bool = True on_same_machine: bool = False + fps: int = FPS + record_path: str = RECORD_PATH + + +def load_inference_config() -> InferenceConfig: + if not CONFIG_PATH.exists(): + CONFIG_PATH.write_text(json.dumps(asdict(InferenceConfig()), indent=2) + "\n") + return InferenceConfig() + return InferenceConfig(**json.loads(CONFIG_PATH.read_text())) + class ModelInference: @@ -100,10 +114,33 @@ def __init__(self, env: gym.Env, cfg: InferenceConfig): self.env = env self.gripper_state = 1 self._cfg = cfg + self._episode_running = False + self._start_requested = False + self._stop_requested = False + self._reload_requested = False + self._cmd_lock = threading.Lock() self.remote_agent = RemoteAgent( cfg.vlagents_host, cfg.vlagents_port, cfg.vlagents_model, cfg.on_same_machine, cfg.jpeg_encoding ) - self.frame_rate = SimpleFrameRate(RECORD_FPS) + self.frame_rate = SimpleFrameRate(self._cfg.fps) + self._listener = keyboard.Listener(on_press=self._on_press) + self._listener.start() + + def _on_press(self, key): + try: + if not hasattr(key, "char"): + return + if key.char == "e": + with self._cmd_lock: + self._start_requested = True + elif key.char == "q": + with self._cmd_lock: + self._stop_requested = True + elif key.char == "o": + with self._cmd_lock: + self._reload_requested = True + except AttributeError: + pass def obs_rcs2agents(self, obs: dict, info: dict | None = None) -> Obs: cameras = {} @@ -130,26 +167,78 @@ def action_agents2rcs(self, action: Act) -> dict[str, Any]: def loop(self): obs, _ = self.env.reset() - obs_dict = self.obs_rcs2agents(obs) - - self.remote_agent.reset(copy.deepcopy(obs_dict), instruction=self._cfg.instruction) + logger.info("waiting for 'e' to start an episode, 'q' to stop and reset, and 'o' to reload config") while True: + with self._cmd_lock: + start_requested = self._start_requested + stop_requested = self._stop_requested + reload_requested = self._reload_requested + self._start_requested = False + self._stop_requested = False + self._reload_requested = False + + if reload_requested: + self._cfg = load_inference_config() + try: + self.remote_agent.reconnect( + host=self._cfg.vlagents_host, + port=self._cfg.vlagents_port, + model=self._cfg.vlagents_model, + on_same_machine=self._cfg.on_same_machine, + jpeg_encoding=self._cfg.jpeg_encoding, + ) + logger.info( + "reloaded config from %s with host=%s port=%s model=%s", + CONFIG_PATH, + self._cfg.vlagents_host, + self._cfg.vlagents_port, + self._cfg.vlagents_model, + ) + except Exception: + logger.exception("failed to reconnect after reloading %s", CONFIG_PATH) + obs, _ = self.env.reset() + obs_dict = self.obs_rcs2agents(obs) + self._episode_running = False + + if stop_requested: + if self._episode_running: + logger.info("stopping episode and resetting environment") + obs, _ = self.env.reset() + obs_dict = self.obs_rcs2agents(obs) + self._episode_running = False + + if not self._episode_running: + try: + self.remote_agent.ensure_connected() + except Exception: + sleep(0.5) + continue + if start_requested: + logger.info("starting episode") + self.remote_agent.reset(copy.deepcopy(obs_dict), instruction=self._cfg.instruction) + self._episode_running = True + else: + sleep(0.05) + continue + action = self.remote_agent.act(copy.deepcopy(obs_dict)) if action.done: - logger.info("done issued by agent, shutting down") - break + logger.info("done issued by agent, resetting environment") + obs, _ = self.env.reset() + obs_dict = self.obs_rcs2agents(obs) + self._episode_running = False + continue a = self.action_agents2rcs(action) obs, _, _, _, info = self.env.step(a) # print(obs["left"]["joints"], obs["left"]["gripper"], obs["right"]["joints"], obs["right"]["gripper"]) - obs["left"]["gripper"] = obs["right"]["gripper"] = 1.0 obs_dict = self.obs_rcs2agents(obs) self.frame_rate() -def get_env(): +def get_env(cfg: InferenceConfig) -> gym.Env: if ROBOT_INSTANCE == RobotPlatform.HARDWARE: from rcs_fr3.configs import FrankaDuoEnv from rcs_fr3.creators import HardwareCameraCreatorConfig @@ -210,8 +299,8 @@ def get_env(): hw_cfg.robot_to_shared_base_frame = robot2world hw_cfg.robot_cfgs["left"].ignore_realtime = True hw_cfg.robot_cfgs["right"].ignore_realtime = True - hw_cfg.robot_cfgs["left"].speed_factor = 0.3 - hw_cfg.robot_cfgs["right"].speed_factor = 0.3 + hw_cfg.robot_cfgs["left"].speed_factor = 0.1 + hw_cfg.robot_cfgs["right"].speed_factor = 0.1 hw_cfg.gripper_cfgs["left"].serial_number = ROBOTIQ_SERIAL["left"] hw_cfg.gripper_cfgs["right"].serial_number = ROBOTIQ_SERIAL["right"] env_rel = env_creator.create_env(hw_cfg) @@ -221,7 +310,7 @@ def get_env(): scene = BinSortEnvConfig() sim_cfg_data = scene.config() sim_cfg_data.sim_cfg = SimConfig( - async_control=True, realtime=False, frequency=RECORD_FPS, max_convergence_steps=500 + async_control=True, realtime=False, frequency=cfg.fps, max_convergence_steps=500 ) sim_cfg_data.relative_to = RelativeTo.CONFIGURED_ORIGIN sim_cfg_data.wrapper_cfg.include_depth = INCLUDE_DEPTH @@ -240,7 +329,7 @@ def get_env(): def main(): - env_rel = get_env() + env_rel = get_env(cfg) env_rel.reset() # Path(VIDEO_PATH).mkdir(parents=True, exist_ok=True) @@ -251,11 +340,9 @@ def main(): # env = RHCWrapper(env, exec_horizon=1) - cfg = InferenceConfig( - IP, PORT, MODEL, INSTRUCTION, jpeg_encoding=True, on_same_machine=False, robot_keys=["left", "right"] - ) + cfg = load_inference_config() controller = ModelInference(env_rel, cfg) - input("robot is about to be controlled by AI, press enter to start") + input("robot is about to be controlled by AI, press enter to enable keyboard control") with env_rel: controller.loop() From e945ccb022195cd193f5fc8c91c3b62757d1d3b9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 19 May 2026 10:31:44 +0200 Subject: [PATCH 15/33] feat: optionally record --- examples/inference/franka.py | 31 ++++++++++++++++++++++++++----- 1 file changed, 26 insertions(+), 5 deletions(-) diff --git a/examples/inference/franka.py b/examples/inference/franka.py index 1d29ca13..e00a1ab5 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -17,6 +17,7 @@ from rcs._core.sim import SimConfig from rcs.envs.base import ControlMode, RelativeTo from rcs.envs.configs import EmptyWorldFR3Duo +from rcs.envs.storage_wrapper import StorageWrapper from rcs.envs.tasks import PickTaskConfig import rcs @@ -116,6 +117,7 @@ def __init__(self, env: gym.Env, cfg: InferenceConfig): self._cfg = cfg self._episode_running = False self._start_requested = False + self._record_requested = False self._stop_requested = False self._reload_requested = False self._cmd_lock = threading.Lock() @@ -133,6 +135,9 @@ def _on_press(self, key): if key.char == "e": with self._cmd_lock: self._start_requested = True + elif key.char == "r": + with self._cmd_lock: + self._record_requested = True elif key.char == "q": with self._cmd_lock: self._stop_requested = True @@ -168,14 +173,16 @@ def action_agents2rcs(self, action: Act) -> dict[str, Any]: def loop(self): obs, _ = self.env.reset() obs_dict = self.obs_rcs2agents(obs) - logger.info("waiting for 'e' to start an episode, 'q' to stop and reset, and 'o' to reload config") + logger.info("waiting for 'e' to start, 'r' to start and record, 'q' to stop and reset, and 'o' to reload config") while True: with self._cmd_lock: start_requested = self._start_requested + record_requested = self._record_requested stop_requested = self._stop_requested reload_requested = self._reload_requested self._start_requested = False + self._record_requested = False self._stop_requested = False self._reload_requested = False @@ -198,6 +205,9 @@ def loop(self): ) except Exception: logger.exception("failed to reconnect after reloading %s", CONFIG_PATH) + if isinstance(self.env, StorageWrapper): + self.env.base_dir = self._cfg.record_path + self.env.set_instruction(self._cfg.instruction) obs, _ = self.env.reset() obs_dict = self.obs_rcs2agents(obs) self._episode_running = False @@ -215,8 +225,12 @@ def loop(self): except Exception: sleep(0.5) continue - if start_requested: - logger.info("starting episode") + if start_requested or record_requested: + if isinstance(self.env, StorageWrapper): + self.env.set_instruction(self._cfg.instruction) + if record_requested: + self.env.start_record() + logger.info("starting episode%s", " with recording" if record_requested else "") self.remote_agent.reset(copy.deepcopy(obs_dict), instruction=self._cfg.instruction) self._episode_running = True else: @@ -325,10 +339,18 @@ def get_env(cfg: InferenceConfig) -> gym.Env: env_rel = scene.create_env(sim_cfg_data) - return env_rel + return StorageWrapper( + env_rel, + cfg.record_path, + cfg.instruction, + batch_size=32, + max_rows_per_group=2, + max_rows_per_file=10, + ) def main(): + cfg = load_inference_config() env_rel = get_env(cfg) env_rel.reset() @@ -340,7 +362,6 @@ def main(): # env = RHCWrapper(env, exec_horizon=1) - cfg = load_inference_config() controller = ModelInference(env_rel, cfg) input("robot is about to be controlled by AI, press enter to enable keyboard control") with env_rel: From 2081f007a0eb284dcaf78f9d46da2f77d0963c64 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 19 May 2026 11:06:17 +0200 Subject: [PATCH 16/33] feat: added mp4 video converter from recording --- python/rcs/__main__.py | 23 +++++++++ python/rcs/utils.py | 108 +++++++++++++++++++++++++++++++++++++++++ 2 files changed, 131 insertions(+) diff --git a/python/rcs/__main__.py b/python/rcs/__main__.py index 32dd98a4..4f97eae0 100644 --- a/python/rcs/__main__.py +++ b/python/rcs/__main__.py @@ -21,6 +21,7 @@ run_conversion, ) from rcs.sim.replayer import replay as replay_dataset +from rcs.utils import export_episode_videos app = typer.Typer() @@ -195,5 +196,27 @@ def lerobot_convert( ) +@app.command("episode-videos") +def episode_videos( + dataset: Annotated[ + Path, + typer.Argument( + exists=True, + help="Parquet dataset file or directory with parquet parts.", + ), + ], + output: Annotated[ + Path, + typer.Argument( + exists=False, + help="Output directory for episode mp4 files.", + ), + ], + fps: Annotated[int, typer.Option(help="Video frames per second.")] = DEFAULT_FPS, + n: Annotated[int, typer.Option(help="Maximum number of episodes to export. -1 means all.")] = -1, +): + export_episode_videos(dataset=dataset, output=output, fps=fps, n=n) + + if __name__ == "__main__": app() diff --git a/python/rcs/utils.py b/python/rcs/utils.py index 25ef2abb..b2f97cd3 100644 --- a/python/rcs/utils.py +++ b/python/rcs/utils.py @@ -1,6 +1,15 @@ +import datetime import logging +import math +import subprocess +from pathlib import Path from time import perf_counter, sleep +import duckdb +import numpy as np +import torch +from torchvision.io import decode_jpeg + logger = logging.getLogger(__name__) logger.setLevel(logging.INFO) @@ -44,3 +53,102 @@ def __enter__(self): def __exit__(self, *args): pass + + +def _write_mp4(frames: list[np.ndarray], output_path: Path, fps: int) -> None: + if not frames: + return + + height, width = frames[0].shape[:2] + process = subprocess.Popen( + [ + "ffmpeg", + "-y", + "-f", + "rawvideo", + "-pix_fmt", + "rgb24", + "-s", + f"{width}x{height}", + "-r", + str(fps), + "-i", + "-", + "-an", + "-vf", + "pad=ceil(iw/2)*2:ceil(ih/2)*2", + "-c:v", + "libx264", + "-pix_fmt", + "yuv420p", + "-movflags", + "+faststart", + str(output_path), + ], + stdin=subprocess.PIPE, + stdout=subprocess.DEVNULL, + stderr=subprocess.DEVNULL, + ) + assert process.stdin is not None + for frame in frames: + process.stdin.write(np.ascontiguousarray(frame).astype(np.uint8).tobytes()) + process.stdin.close() + process.wait() + + +def export_episode_videos( + dataset: str | Path, + output: str | Path, + fps: int = 30, + n: int = -1, +) -> None: + dataset = Path(dataset) + output = Path(output) + output.mkdir(parents=True, exist_ok=True) + + source = str(dataset / "*.parquet") if dataset.is_dir() else str(dataset) + source_escaped = source.replace("'", "''") + conn = duckdb.connect() + relation = conn.sql(f"SELECT * FROM read_parquet('{source_escaped}')") + frame_struct = relation.select("obs.frames").types[0] + camera_names = [name for name, _ in frame_struct.children] + + uuids = conn.execute(f"SELECT DISTINCT uuid FROM read_parquet('{source_escaped}') ORDER BY uuid").fetchall() + for index, (episode_id,) in enumerate(uuids): + if n != -1 and index >= n: + break + + image_selects = ", ".join(f"obs.frames.{camera}.rgb.data AS {camera}" for camera in camera_names) + not_null_checks = " ".join(f"AND obs.frames.{camera}.rgb.data IS NOT NULL" for camera in camera_names) + rows = conn.execute( + f""" + SELECT timestamp, {image_selects} + FROM read_parquet('{source_escaped}') + WHERE uuid = ? + {not_null_checks} + ORDER BY step + """, + [episode_id], + ).fetchall() + if not rows: + continue + + timestamp = datetime.datetime.fromtimestamp(float(rows[0][0])).strftime("%Y-%m-%d-%H-%M-%S") + frames = [] + cols = math.ceil(math.sqrt(len(camera_names))) + rows_per_frame = math.ceil(len(camera_names) / cols) + + for row in rows: + decoded = [ + decode_jpeg(torch.frombuffer(bytearray(image_bytes), dtype=torch.uint8)).permute(1, 2, 0).cpu().numpy() + for image_bytes in row[1:] + ] + height, width = decoded[0].shape[:2] + tiled = np.zeros((rows_per_frame * height, cols * width, 3), dtype=np.uint8) + for camera_index, image in enumerate(decoded): + top = (camera_index // cols) * height + left = (camera_index % cols) * width + tiled[top : top + height, left : left + width] = image + frames.append(tiled) + + _write_mp4(frames, output / f"{timestamp}.mp4", fps=fps) From 1c7a9cb157b1fa9d4e7e1815c5bc8631b9423e40 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 19 May 2026 11:32:12 +0200 Subject: [PATCH 17/33] feat(mp4): added joint display --- python/rcs/utils.py | 73 +++++++++++++++++++++++++++++++++++++++++---- 1 file changed, 67 insertions(+), 6 deletions(-) diff --git a/python/rcs/utils.py b/python/rcs/utils.py index b2f97cd3..d061ba81 100644 --- a/python/rcs/utils.py +++ b/python/rcs/utils.py @@ -1,13 +1,18 @@ import datetime import logging import math +import os import subprocess from pathlib import Path from time import perf_counter, sleep import duckdb +os.environ.setdefault("MPLCONFIGDIR", "/tmp/matplotlib") +import matplotlib +matplotlib.use("Agg") import numpy as np import torch +from matplotlib import pyplot as plt from torchvision.io import decode_jpeg logger = logging.getLogger(__name__) @@ -96,6 +101,43 @@ def _write_mp4(frames: list[np.ndarray], output_path: Path, fps: int) -> None: process.wait() +def _render_action_panel( + joint_history: dict[str, np.ndarray], + gripper_history: dict[str, np.ndarray], + step: int, + height: int, + width: int, +) -> np.ndarray: + fig, axes = plt.subplots( + len(joint_history), + 1, + figsize=(width / 100, height / 100), + dpi=100, + squeeze=False, + ) + x = np.arange(len(next(iter(joint_history.values())))) + for axis, robot_key in zip(axes[:, 0], joint_history, strict=True): + joints = joint_history[robot_key] + for joint_idx in range(joints.shape[1]): + axis.plot(x, joints[:, joint_idx], linewidth=1) + axis.axvline(step, color="tab:red", linewidth=2) + axis.set_xlim(0, max(len(x) - 1, 1)) + axis.set_title(robot_key) + axis.set_xlabel("step") + axis.set_ylabel("joint") + + gripper_axis = axis.twinx() + gripper_axis.plot(x, gripper_history[robot_key], color="black", linestyle="--", linewidth=2) + gripper_axis.set_ylabel("gripper") + gripper_axis.set_ylim(-0.1, 1.1) + + fig.tight_layout() + fig.canvas.draw() + image = np.asarray(fig.canvas.buffer_rgba())[..., :3].copy() + plt.close(fig) + return image + + def export_episode_videos( dataset: str | Path, output: str | Path, @@ -112,6 +154,7 @@ def export_episode_videos( relation = conn.sql(f"SELECT * FROM read_parquet('{source_escaped}')") frame_struct = relation.select("obs.frames").types[0] camera_names = [name for name, _ in frame_struct.children] + robot_names = [name for name, _ in relation.select("obs").types[0].children if name != "frames"] uuids = conn.execute(f"SELECT DISTINCT uuid FROM read_parquet('{source_escaped}') ORDER BY uuid").fetchall() for index, (episode_id,) in enumerate(uuids): @@ -119,10 +162,19 @@ def export_episode_videos( break image_selects = ", ".join(f"obs.frames.{camera}.rgb.data AS {camera}" for camera in camera_names) + state_selects = ", ".join( + [ + *(f"obs.{robot}.joints AS joints_{robot}" for robot in robot_names), + *( + f"COALESCE(CAST(action.{robot}.gripper[1] AS DOUBLE), obs.{robot}.gripper[1]) AS gripper_{robot}" + for robot in robot_names + ), + ] + ) not_null_checks = " ".join(f"AND obs.frames.{camera}.rgb.data IS NOT NULL" for camera in camera_names) rows = conn.execute( f""" - SELECT timestamp, {image_selects} + SELECT timestamp, {image_selects}, {state_selects} FROM read_parquet('{source_escaped}') WHERE uuid = ? {not_null_checks} @@ -135,15 +187,24 @@ def export_episode_videos( timestamp = datetime.datetime.fromtimestamp(float(rows[0][0])).strftime("%Y-%m-%d-%H-%M-%S") frames = [] - cols = math.ceil(math.sqrt(len(camera_names))) - rows_per_frame = math.ceil(len(camera_names) / cols) - - for row in rows: + joint_history = { + robot: np.asarray([row[1 + len(camera_names) + robot_idx] for row in rows], dtype=np.float32) + for robot_idx, robot in enumerate(robot_names) + } + gripper_history = { + robot: np.asarray([row[1 + len(camera_names) + len(robot_names) + robot_idx] for row in rows], dtype=np.float32) + for robot_idx, robot in enumerate(robot_names) + } + cols = math.ceil(math.sqrt(len(camera_names) + 1)) + rows_per_frame = math.ceil((len(camera_names) + 1) / cols) + + for step_idx, row in enumerate(rows): decoded = [ decode_jpeg(torch.frombuffer(bytearray(image_bytes), dtype=torch.uint8)).permute(1, 2, 0).cpu().numpy() - for image_bytes in row[1:] + for image_bytes in row[1 : 1 + len(camera_names)] ] height, width = decoded[0].shape[:2] + decoded.append(_render_action_panel(joint_history, gripper_history, step_idx, height, width)) tiled = np.zeros((rows_per_frame * height, cols * width, 3), dtype=np.uint8) for camera_index, image in enumerate(decoded): top = (camera_index // cols) * height From d2e35b7c3ace8a5d110bd66646fe1730739e9371 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 19 May 2026 13:45:45 +0200 Subject: [PATCH 18/33] fix: printing and sim sleep --- examples/inference/franka.py | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/examples/inference/franka.py b/examples/inference/franka.py index e00a1ab5..2bd7d41e 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -78,6 +78,11 @@ PORT = 20000 CONFIG_PATH = Path(__file__).with_suffix(".json") +logging.basicConfig( + format="%(asctime)s - %(name)s - %(levelname)s - %(message)s", + level=logging.INFO, +) + robot2world = { "right": rcs.common.Pose( @@ -249,7 +254,9 @@ def loop(self): # print(obs["left"]["joints"], obs["left"]["gripper"], obs["right"]["joints"], obs["right"]["gripper"]) obs_dict = self.obs_rcs2agents(obs) - self.frame_rate() + + if ROBOT_INSTANCE == RobotPlatform.HARDWARE: + self.frame_rate() def get_env(cfg: InferenceConfig) -> gym.Env: From 82f1ace01eaa2f37df007f01ce627d8255b17823 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 19 May 2026 14:26:06 +0200 Subject: [PATCH 19/33] feat: action chunking optionally in inference script --- examples/inference/franka.py | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/examples/inference/franka.py b/examples/inference/franka.py index 2bd7d41e..1cfe009c 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -105,6 +105,7 @@ class InferenceConfig: on_same_machine: bool = False fps: int = FPS record_path: str = RECORD_PATH + n_action_steps: int | None = None def load_inference_config() -> InferenceConfig: @@ -132,6 +133,7 @@ def __init__(self, env: gym.Env, cfg: InferenceConfig): self.frame_rate = SimpleFrameRate(self._cfg.fps) self._listener = keyboard.Listener(on_press=self._on_press) self._listener.start() + self._action_buffer = [] def _on_press(self, key): try: @@ -166,6 +168,18 @@ def obs_rcs2agents(self, obs: dict, info: dict | None = None) -> Obs: return Obs(cameras=cameras, gripper=None, info=info, state=np.concatenate(state)) + def act(self, obs_dict) -> None: + done = False + if self._cfg.n_action_steps is None: + return self.remote_agent.act(obs_dict) + if len(self._action_buffer) == 0: + action = self.remote_agent.act(obs_dict) + selected_action = action.action[:self._cfg.n_action_steps] + self._action_buffer = selected_action.tolist() + done = action.done + act = self._action_buffer.pop(0) + return Act(action=act, done=done) + def action_agents2rcs(self, action: Act) -> dict[str, Any]: act = {} for idx, robot in enumerate(self._cfg.robot_keys): @@ -242,7 +256,7 @@ def loop(self): sleep(0.05) continue - action = self.remote_agent.act(copy.deepcopy(obs_dict)) + action = self.act(copy.deepcopy(obs_dict)) if action.done: logger.info("done issued by agent, resetting environment") obs, _ = self.env.reset() @@ -370,7 +384,6 @@ def main(): # env = RHCWrapper(env, exec_horizon=1) controller = ModelInference(env_rel, cfg) - input("robot is about to be controlled by AI, press enter to enable keyboard control") with env_rel: controller.loop() From ce16d0a454c837eeb824b7958e7a9a076bc1183a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 19 May 2026 14:31:03 +0200 Subject: [PATCH 20/33] feat: support for relative actions --- examples/inference/franka.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/examples/inference/franka.py b/examples/inference/franka.py index 1cfe009c..319578db 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -177,6 +177,9 @@ def act(self, obs_dict) -> None: selected_action = action.action[:self._cfg.n_action_steps] self._action_buffer = selected_action.tolist() done = action.done + if RELATIVETO == RelativeTo.CONFIGURED_ORIGIN: + for robot in self.env.get_wrapper_attr("envs"): + self.env.get_wrapper_attr("envs")[robot].get_wrapper_attr("set_origin_to_current")() act = self._action_buffer.pop(0) return Act(action=act, done=done) From 80f36578b9bb7c0ff64480df9f94b1927d15d443 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 19 May 2026 16:12:10 +0200 Subject: [PATCH 21/33] feat: inference add success button --- examples/inference/franka.py | 23 ++++++++++++++++++++++- 1 file changed, 22 insertions(+), 1 deletion(-) diff --git a/examples/inference/franka.py b/examples/inference/franka.py index 319578db..2d014905 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -124,6 +124,7 @@ def __init__(self, env: gym.Env, cfg: InferenceConfig): self._episode_running = False self._start_requested = False self._record_requested = False + self._success_requested = False self._stop_requested = False self._reload_requested = False self._cmd_lock = threading.Lock() @@ -145,6 +146,9 @@ def _on_press(self, key): elif key.char == "r": with self._cmd_lock: self._record_requested = True + elif key.char == "s": + with self._cmd_lock: + self._success_requested = True elif key.char == "q": with self._cmd_lock: self._stop_requested = True @@ -195,16 +199,20 @@ def action_agents2rcs(self, action: Act) -> dict[str, Any]: def loop(self): obs, _ = self.env.reset() obs_dict = self.obs_rcs2agents(obs) - logger.info("waiting for 'e' to start, 'r' to start and record, 'q' to stop and reset, and 'o' to reload config") + logger.info( + "waiting for 'e' to start, 'r' to start and record, 's' for success and reset, 'q' to stop and reset, and 'o' to reload config" + ) while True: with self._cmd_lock: start_requested = self._start_requested record_requested = self._record_requested + success_requested = self._success_requested stop_requested = self._stop_requested reload_requested = self._reload_requested self._start_requested = False self._record_requested = False + self._success_requested = False self._stop_requested = False self._reload_requested = False @@ -232,6 +240,16 @@ def loop(self): self.env.set_instruction(self._cfg.instruction) obs, _ = self.env.reset() obs_dict = self.obs_rcs2agents(obs) + self._action_buffer = [] + self._episode_running = False + + if success_requested: + if self._episode_running: + logger.info("marking episode successful and resetting environment") + self.env.get_wrapper_attr("success")() + obs, _ = self.env.reset() + obs_dict = self.obs_rcs2agents(obs) + self._action_buffer = [] self._episode_running = False if stop_requested: @@ -239,6 +257,7 @@ def loop(self): logger.info("stopping episode and resetting environment") obs, _ = self.env.reset() obs_dict = self.obs_rcs2agents(obs) + self._action_buffer = [] self._episode_running = False if not self._episode_running: @@ -264,6 +283,7 @@ def loop(self): logger.info("done issued by agent, resetting environment") obs, _ = self.env.reset() obs_dict = self.obs_rcs2agents(obs) + self._action_buffer = [] self._episode_running = False continue a = self.action_agents2rcs(action) @@ -370,6 +390,7 @@ def get_env(cfg: InferenceConfig) -> gym.Env: batch_size=32, max_rows_per_group=2, max_rows_per_file=10, + allow_wrapper_instruction=False ) From 74a5b7602ec909bd628f96f1f6fe4a28806e9bc2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 19 May 2026 16:12:47 +0200 Subject: [PATCH 22/33] fix(storage wrapper): flush keeps last to avoid success problems --- python/rcs/envs/storage_wrapper.py | 17 +++++++++++------ 1 file changed, 11 insertions(+), 6 deletions(-) diff --git a/python/rcs/envs/storage_wrapper.py b/python/rcs/envs/storage_wrapper.py index 497a1f03..58929bf3 100644 --- a/python/rcs/envs/storage_wrapper.py +++ b/python/rcs/envs/storage_wrapper.py @@ -182,15 +182,18 @@ def _writer_worker(self): ), ) - def _flush(self): + def _flush(self, keep_last: bool = False): + rows = self.buffer[:-1] if keep_last else self.buffer + if len(rows) == 0: + return if self.schema is None: - temp_batch = pa.RecordBatch.from_pylist(self.buffer) + temp_batch = pa.RecordBatch.from_pylist(rows) self.schema = temp_batch.schema - self.buffer[-1]["success"] = self._success - batch = pa.RecordBatch.from_pylist(self.buffer, schema=self.schema) + rows[-1]["success"] = self._success + batch = pa.RecordBatch.from_pylist(rows, schema=self.schema) self.queue.put(batch) - self.buffer.clear() + self.buffer = self.buffer[-1:] if keep_last else [] def _flatten_arrays(self, d: dict[str, Any]): # NOTE: list / tuples of arrays not supported @@ -284,7 +287,9 @@ def step(self, action): self.step_cnt += 1 if len(self.buffer) == self.batch_size: - self._flush() + # Keep the most recent row in memory so a success() right before reset() + # can still mark the episode as successful even if the batch boundary was hit. + self._flush(keep_last=True) return obs_original, reward, terminated, truncated, info From 6d795ae5287cdacd5e30889f7fe4a64155b8b9fb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 19 May 2026 16:13:08 +0200 Subject: [PATCH 23/33] fix(mp4): shows joint actions if available --- python/rcs/utils.py | 28 +++++++++++++++++++++++----- 1 file changed, 23 insertions(+), 5 deletions(-) diff --git a/python/rcs/utils.py b/python/rcs/utils.py index d061ba81..1571233c 100644 --- a/python/rcs/utils.py +++ b/python/rcs/utils.py @@ -153,8 +153,13 @@ def export_episode_videos( conn = duckdb.connect() relation = conn.sql(f"SELECT * FROM read_parquet('{source_escaped}')") frame_struct = relation.select("obs.frames").types[0] + action_struct = relation.select("action").types[0] camera_names = [name for name, _ in frame_struct.children] robot_names = [name for name, _ in relation.select("obs").types[0].children if name != "frames"] + action_fields_by_robot = { + robot: {field_name for field_name, _ in robot_struct.children} + for robot, robot_struct in action_struct.children + } uuids = conn.execute(f"SELECT DISTINCT uuid FROM read_parquet('{source_escaped}') ORDER BY uuid").fetchall() for index, (episode_id,) in enumerate(uuids): @@ -162,13 +167,26 @@ def export_episode_videos( break image_selects = ", ".join(f"obs.frames.{camera}.rgb.data AS {camera}" for camera in camera_names) + joint_selects = ", ".join( + ( + f"COALESCE(action.{robot}.joints, obs.{robot}.joints) AS joints_{robot}" + if "joints" in action_fields_by_robot.get(robot, set()) + else f"obs.{robot}.joints AS joints_{robot}" + ) + for robot in robot_names + ) + gripper_selects = ", ".join( + ( + f"COALESCE(CAST(action.{robot}.gripper[1] AS DOUBLE), obs.{robot}.gripper[1]) AS gripper_{robot}" + if "gripper" in action_fields_by_robot.get(robot, set()) + else f"obs.{robot}.gripper[1] AS gripper_{robot}" + ) + for robot in robot_names + ) state_selects = ", ".join( [ - *(f"obs.{robot}.joints AS joints_{robot}" for robot in robot_names), - *( - f"COALESCE(CAST(action.{robot}.gripper[1] AS DOUBLE), obs.{robot}.gripper[1]) AS gripper_{robot}" - for robot in robot_names - ), + joint_selects, + gripper_selects, ] ) not_null_checks = " ".join(f"AND obs.frames.{camera}.rgb.data IS NOT NULL" for camera in camera_names) From 8bc34f2abb7cda935f7a36283a6c301ca4b78e01 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 19 May 2026 20:54:23 +0200 Subject: [PATCH 24/33] fix(fr3): torque discontinuity while reset --- extensions/rcs_fr3/src/hw/Franka.cpp | 13 ++++++++----- extensions/rcs_fr3/src/hw/Franka.h | 1 + 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/extensions/rcs_fr3/src/hw/Franka.cpp b/extensions/rcs_fr3/src/hw/Franka.cpp index 1fbb140d..4d0eb285 100644 --- a/extensions/rcs_fr3/src/hw/Franka.cpp +++ b/extensions/rcs_fr3/src/hw/Franka.cpp @@ -220,6 +220,11 @@ void Franka::check_for_background_errors() { } } +void Franka::clear_background_error() { + std::lock_guard lock(this->exception_mutex); + this->background_exception = nullptr; +} + void Franka::osc_set_cartesian_position( const common::Pose& desired_pose_EE_in_base_frame) { this->check_for_background_errors(); @@ -335,8 +340,7 @@ void Franka::osc() { // torques handler if (this->running_controller.load() == Controller::none) { - franka::Torques zero_torques{{0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}}; - return franka::MotionFinished(zero_torques); + return franka::MotionFinished(franka::Torques(robot_state.tau_J_d)); } // TO BE replaced // if (!this->control_thread_running && dq.maxCoeff() < 0.0001) { @@ -541,9 +545,7 @@ void Franka::joint_controller() { // torques handler if (this->running_controller.load() == Controller::none) { - // TODO: test if this also works when the robot is moving - franka::Torques zero_torques{{0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}}; - return franka::MotionFinished(zero_torques); + return franka::MotionFinished(franka::Torques(robot_state.tau_J_d)); } common::Vector7d desired_q; @@ -667,6 +669,7 @@ void Franka::automatic_error_recovery() { void Franka::reset() { this->stop_control_thread(); this->automatic_error_recovery(); + this->clear_background_error(); } void Franka::wait_milliseconds(int milliseconds) { diff --git a/extensions/rcs_fr3/src/hw/Franka.h b/extensions/rcs_fr3/src/hw/Franka.h index 6054b924..9601d343 100644 --- a/extensions/rcs_fr3/src/hw/Franka.h +++ b/extensions/rcs_fr3/src/hw/Franka.h @@ -93,6 +93,7 @@ class Franka : public common::Robot { void joint_controller(); void zero_torque_controller(); void check_for_background_errors(); + void clear_background_error(); public: Franka(const FrankaConfig& cfg, From 8eaa1a756925992d21a109c752cc90c9a54599f6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 19 May 2026 21:17:20 +0200 Subject: [PATCH 25/33] fix(hw camera): stop camera before stop polling thread --- python/rcs/camera/hw.py | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/python/rcs/camera/hw.py b/python/rcs/camera/hw.py index 460f26f7..da8dc8d9 100644 --- a/python/rcs/camera/hw.py +++ b/python/rcs/camera/hw.py @@ -179,15 +179,19 @@ def get_timestamp_frames(self, ts: datetime) -> FrameSet | None: def stop(self): """Stops the polling of the cameras.""" self.running = False - assert self._thread is not None - self._thread.join() - self._thread = None + if self._thread is not None: + self._thread.join() + self._thread = None def close(self): - if self.running and self._thread is not None: + if self.running: + self.running = False + for camera in self.cameras: + camera.close() self.stop() - for camera in self.cameras: - camera.close() + else: + for camera in self.cameras: + camera.close() self.stop_video() def start(self, warm_up: bool = True): From 26f549f0c7420f331b1983280c707e4330141895 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Tue, 19 May 2026 21:39:57 +0200 Subject: [PATCH 26/33] feat: using input instead of pynput --- examples/inference/franka.py | 114 ++++++++++++++++++++--------------- 1 file changed, 67 insertions(+), 47 deletions(-) diff --git a/examples/inference/franka.py b/examples/inference/franka.py index 2d014905..9ad6b1af 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -1,13 +1,14 @@ import copy -import datetime import json import logging +import threading from dataclasses import asdict, dataclass, field from pathlib import Path +from queue import Empty, Queue from time import sleep from typing import Any + from PIL import Image -import threading from rcs.utils import SimpleFrameRate @@ -25,8 +26,6 @@ from vlagents.client import RemoteAgent from vlagents.policies import Act, Obs -from pynput import keyboard - logger = logging.getLogger(__name__) @@ -122,41 +121,45 @@ def __init__(self, env: gym.Env, cfg: InferenceConfig): self.gripper_state = 1 self._cfg = cfg self._episode_running = False - self._start_requested = False - self._record_requested = False - self._success_requested = False - self._stop_requested = False - self._reload_requested = False - self._cmd_lock = threading.Lock() + self._command_queue: Queue[str] = Queue() + self._shutdown_requested = threading.Event() self.remote_agent = RemoteAgent( cfg.vlagents_host, cfg.vlagents_port, cfg.vlagents_model, cfg.on_same_machine, cfg.jpeg_encoding ) self.frame_rate = SimpleFrameRate(self._cfg.fps) - self._listener = keyboard.Listener(on_press=self._on_press) - self._listener.start() self._action_buffer = [] - def _on_press(self, key): - try: - if not hasattr(key, "char"): - return - if key.char == "e": - with self._cmd_lock: - self._start_requested = True - elif key.char == "r": - with self._cmd_lock: - self._record_requested = True - elif key.char == "s": - with self._cmd_lock: - self._success_requested = True - elif key.char == "q": - with self._cmd_lock: - self._stop_requested = True - elif key.char == "o": - with self._cmd_lock: - self._reload_requested = True - except AttributeError: - pass + def submit_command(self, command: str) -> None: + self._command_queue.put(command) + + def request_shutdown(self) -> None: + self._shutdown_requested.set() + + def _drain_commands(self) -> tuple[bool, bool, bool, bool, bool]: + start_requested = False + record_requested = False + success_requested = False + stop_requested = False + reload_requested = False + + while True: + try: + command = self._command_queue.get_nowait() + except Empty: + break + + if command == "e": + start_requested = True + elif command == "r": + record_requested = True + elif command == "s": + success_requested = True + elif command == "q": + stop_requested = True + elif command == "o": + reload_requested = True + + return start_requested, record_requested, success_requested, stop_requested, reload_requested def obs_rcs2agents(self, obs: dict, info: dict | None = None) -> Obs: cameras = {} @@ -200,21 +203,13 @@ def loop(self): obs, _ = self.env.reset() obs_dict = self.obs_rcs2agents(obs) logger.info( - "waiting for 'e' to start, 'r' to start and record, 's' for success and reset, 'q' to stop and reset, and 'o' to reload config" + "waiting for input: 'e' to start, 'r' to start and record, 's' for success and reset, 'q' to stop and reset, and 'o' to reload config" ) - while True: - with self._cmd_lock: - start_requested = self._start_requested - record_requested = self._record_requested - success_requested = self._success_requested - stop_requested = self._stop_requested - reload_requested = self._reload_requested - self._start_requested = False - self._record_requested = False - self._success_requested = False - self._stop_requested = False - self._reload_requested = False + while not self._shutdown_requested.is_set(): + start_requested, record_requested, success_requested, stop_requested, reload_requested = ( + self._drain_commands() + ) if reload_requested: self._cfg = load_inference_config() @@ -296,6 +291,28 @@ def loop(self): self.frame_rate() +def command_loop(controller: ModelInference) -> None: + prompt = "Command [e=start, r=record, s=success/reset, q=stop/reset, o=reload, x=exit]: " + while True: + try: + command = input(prompt).strip().lower() + except EOFError: + command = "x" + except KeyboardInterrupt: + print() + command = "x" + + if not command: + continue + if command == "x": + controller.request_shutdown() + return + if command in {"e", "r", "s", "q", "o"}: + controller.submit_command(command) + continue + logger.info("unknown command %r", command) + + def get_env(cfg: InferenceConfig) -> gym.Env: if ROBOT_INSTANCE == RobotPlatform.HARDWARE: from rcs_fr3.configs import FrankaDuoEnv @@ -409,7 +426,10 @@ def main(): controller = ModelInference(env_rel, cfg) with env_rel: - controller.loop() + worker = threading.Thread(target=controller.loop, name="model-inference", daemon=True) + worker.start() + command_loop(controller) + worker.join() if __name__ == "__main__": From fe4b3533694aaaa0b9adec9a49cf7af133c067ee Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Wed, 20 May 2026 08:38:17 +0200 Subject: [PATCH 27/33] feat: add limited absolute action wrapper --- python/rcs/envs/base.py | 88 +++++++++++++++++++++++++++++++++++++++++ 1 file changed, 88 insertions(+) diff --git a/python/rcs/envs/base.py b/python/rcs/envs/base.py index cfe392f6..40d1dbeb 100644 --- a/python/rcs/envs/base.py +++ b/python/rcs/envs/base.py @@ -593,6 +593,94 @@ class RelativeTo(Enum): CONFIGURED_ORIGIN = auto() NONE = auto() +class LimitedAbsoluteAction(ActObsInfoWrapper): + ABSOLUTE_ACTION_KEY = "limited_absolute_action" + + def __init__( + self, + env, + max_mov: float | tuple[float, float] | None = None, + ): + super().__init__(env) + self.joints_key = get_space_keys(LimitedJointsRelDictType)[0] + self.trpy_key = get_space_keys(LimitedTRPYRelDictType)[0] + self.tquat_key = get_space_keys(LimitedTQuatRelDictType)[0] + self._absolute_action: common.Pose | VecType | None = None + self.max_mov = max_mov + + def _get_current(self) -> np.ndarray: + if self.get_wrapper_attr("get_control_mode")() == ControlMode.JOINTS: + return self._robot.get_joint_position() + else: + return self._robot.get_cartesian_position() + + def action(self, action: dict[str, Any]) -> dict[str, Any]: + if self.max_mov is None: + return action + if self.get_wrapper_attr("get_control_mode")() == ControlMode.JOINTS: + assert isinstance(self.max_mov, float) + low, high = self._robot.get_config().joint_limits + curr = self._get_current() + delta = action[self.joints_key] - curr + limited_delta = np.clip(delta, -self.max_mov, self.max_mov) + clipped_joints = np.clip(curr + limited_delta, low, high) + action.update(JointsDictType(joints=clipped_joints)) + self._absolute_action = clipped_joints + + elif self.get_wrapper_attr("get_control_mode")() == ControlMode.CARTESIAN_TRPY: + assert isinstance(self.max_mov, tuple) + curr = cast(common.Pose, self._get_current()) + pose_space = cast(gym.spaces.Box, get_space(TRPYDictType).spaces[self.trpy_key]) + target_pose = common.Pose( + translation=action[self.trpy_key][:3], + rpy_vector=action[self.trpy_key][3:], + ) + pose_delta = common.Pose( + translation=target_pose.translation() - curr.translation(), # type: ignore + rpy_vector=(target_pose * curr.inverse()).rotation_rpy().as_vector(), + ) + limited_delta = pose_delta.limit_translation_length(self.max_mov[0]).limit_rotation_angle(self.max_mov[1]) + clipped_pose = np.concatenate( + [ + np.clip(curr.translation() + limited_delta.translation(), pose_space.low[:3], pose_space.high[:3]), + (limited_delta * curr).rotation_rpy().as_vector(), + ] + ) + action.update(TRPYDictType(xyzrpy=clipped_pose)) + self._absolute_action = clipped_pose + + elif self.get_wrapper_attr("get_control_mode")() == ControlMode.CARTESIAN_TQuat: + assert isinstance(self.max_mov, tuple) + curr = cast(common.Pose, self._get_current()) + pose_space = cast(gym.spaces.Box, get_space(TQuatDictType).spaces[self.tquat_key]) + target_pose = common.Pose( + translation=action[self.tquat_key][:3], + quaternion=action[self.tquat_key][3:], + ) + pose_delta = target_pose * curr.inverse() + limited_delta = pose_delta.limit_translation_length(self.max_mov[0]).limit_rotation_angle(self.max_mov[1]) + clipped_pose = np.concatenate( + [ + np.clip(curr.translation() + limited_delta.translation(), pose_space.low[:3], pose_space.high[:3]), + (limited_delta * curr).rotation_q(), + ] + ) + action.update(TQuatDictType(tquat=clipped_pose)) # type: ignore + self._absolute_action = clipped_pose + else: + msg = "Control mode not recognized!" + raise ValueError(msg) + return action + + def observation(self, observation: dict, info: dict[str, Any]) -> tuple[dict[str, Any], dict[str, Any]]: + if self._absolute_action is not None: + info[self.ABSOLUTE_ACTION_KEY] = ( + list(self._absolute_action.translation()) + list(self._absolute_action.rotation_q()) + if isinstance(self._absolute_action, common.Pose) + else self._absolute_action + ) + return observation, info + class RelativeActionSpace(ActObsInfoWrapper): DEFAULT_MAX_CART_MOV = 0.5 From 0aa68c9dd6f4f770fecf22141549cb63cf5f5d17 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Wed, 20 May 2026 07:56:43 +0200 Subject: [PATCH 28/33] feat: add limited absolute actions to inference script --- examples/inference/franka.py | 7 ++++++- extensions/rcs_fr3/src/rcs_fr3/creators.py | 3 +++ python/rcs/envs/scenes.py | 3 +++ 3 files changed, 12 insertions(+), 1 deletion(-) diff --git a/examples/inference/franka.py b/examples/inference/franka.py index 9ad6b1af..2c2ed6ad 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -76,6 +76,8 @@ IP = "localhost" PORT = 20000 CONFIG_PATH = Path(__file__).with_suffix(".json") +MAX_REL_MOV_JOINTS = np.deg2rad(0.5) +MAX_REL_MOV_CART = (0.5, np.deg2rad(90)) logging.basicConfig( format="%(asctime)s - %(name)s - %(levelname)s - %(message)s", @@ -105,6 +107,8 @@ class InferenceConfig: fps: int = FPS record_path: str = RECORD_PATH n_action_steps: int | None = None + max_rel_mov_joints: float = MAX_REL_MOV_JOINTS + max_rel_mov_cart: tuple[float, float] = MAX_REL_MOV_CART def load_inference_config() -> InferenceConfig: @@ -369,7 +373,7 @@ def get_env(cfg: InferenceConfig) -> gym.Env: hw_cfg.camera_cfgs = camera_cfgs or None hw_cfg.control_mode = CONTROL_MODE hw_cfg.wrapper_cfg.include_depth = INCLUDE_DEPTH - hw_cfg.max_relative_movement = 0.5 if CONTROL_MODE == ControlMode.JOINTS else (0.5, np.deg2rad(90)) + hw_cfg.max_relative_movement = cfg.max_rel_mov_joints if CONTROL_MODE == ControlMode.JOINTS else cfg.max_rel_mov_cart hw_cfg.relative_to = RELATIVETO hw_cfg.robot_to_shared_base_frame = robot2world hw_cfg.robot_cfgs["left"].ignore_realtime = True @@ -392,6 +396,7 @@ def get_env(cfg: InferenceConfig) -> gym.Env: sim_cfg_data.control_mode = ControlMode.JOINTS sim_cfg_data.relative_to = RELATIVETO sim_cfg_data.wrapper_cfg.binary_gripper = True + sim_cfg_data.max_relative_movement = cfg.max_rel_mov_joints if CONTROL_MODE == ControlMode.JOINTS else cfg.max_rel_mov_cart # if sim_cfg_data.root_frame_objects is None: diff --git a/extensions/rcs_fr3/src/rcs_fr3/creators.py b/extensions/rcs_fr3/src/rcs_fr3/creators.py index e28401e4..01386503 100644 --- a/extensions/rcs_fr3/src/rcs_fr3/creators.py +++ b/extensions/rcs_fr3/src/rcs_fr3/creators.py @@ -15,6 +15,7 @@ GripperWrapper, HandWrapper, HardwareEnv, + LimitedAbsoluteAction, MultiRobotWrapper, RelativeActionSpace, RelativeTo, @@ -207,6 +208,8 @@ def create_env(self, cfg: FR3HardwareEnvCreatorConfig) -> gym.Env: if cfg.relative_to != RelativeTo.NONE: env = RelativeActionSpace(env, max_mov=cfg.max_relative_movement, relative_to=cfg.relative_to) + else: + env = LimitedAbsoluteAction(env, max_mov=cfg.max_relative_movement) return CoverWrapper(env) def config(self) -> FR3HardwareEnvCreatorConfig: diff --git a/python/rcs/envs/scenes.py b/python/rcs/envs/scenes.py index ef281673..6cedeae3 100644 --- a/python/rcs/envs/scenes.py +++ b/python/rcs/envs/scenes.py @@ -14,6 +14,7 @@ ControlMode, CoverWrapper, GripperWrapper, + LimitedAbsoluteAction, MultiRobotWrapper, RelativeActionSpace, RelativeTo, @@ -363,6 +364,8 @@ def create_env_from_model(self, cfg: SimEnvCreatorConfig, mjmodel: MjModel) -> g env = RelativeActionSpace( env, max_mov=prefixed_cfg.max_relative_movement, relative_to=prefixed_cfg.relative_to ) + else: + env = LimitedAbsoluteAction(env, max_mov=cfg.max_relative_movement) envs[robot_name] = env env = MultiRobotWrapper(envs, prefixed_cfg.robot_to_shared_base_frame) From bb40618775be10d47d40dda455651e0278b117b9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Thu, 21 May 2026 13:36:18 +0200 Subject: [PATCH 29/33] stash: latest version Co-authored-by: Copilot --- .dockerignore | 7 + docker/Dockerfile | 3 +- examples/inference/franka.json | 20 + examples/inference/franka.py | 11 +- examples/teleop/inspect_parquet_duckdb.ipynb | 506 ++++++++++++++----- extensions/rcs_fr3/src/hw/Franka.cpp | 10 +- python/rcs/envs/base.py | 14 +- python/rcs/envs/storage_wrapper.py | 2 +- python/rcs/lerobot_joint_converter.py | 8 +- python/rcs/utils.py | 142 +++++- 10 files changed, 579 insertions(+), 144 deletions(-) create mode 100644 examples/inference/franka.json diff --git a/.dockerignore b/.dockerignore index 8b767f67..fb730c5f 100644 --- a/.dockerignore +++ b/.dockerignore @@ -1,3 +1,10 @@ **/build/ real* test* +sim* +transfer_cube +single_pick* +ball_maze +candy +*.parquet +*venv* diff --git a/docker/Dockerfile b/docker/Dockerfile index 9c88e253..7770f522 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -56,7 +56,8 @@ RUN chmod +x /usr/local/bin/link-editable-source \ && uv pip install /opt/rcs-src/extensions/rcs_zed \ && uv pip install /opt/rcs-src/examples/teleop/SimPublisher \ && uv pip install /opt/rcs-src/2f85-python-driver \ - && uv pip install /opt/rcs-src/vlagents + && uv pip install /opt/rcs-src/vlagents \ + && uv pip install /opt/rcs-src/rcs_duobench WORKDIR /workspace/robot-control-stack diff --git a/examples/inference/franka.json b/examples/inference/franka.json new file mode 100644 index 00000000..7dac17c1 --- /dev/null +++ b/examples/inference/franka.json @@ -0,0 +1,20 @@ +{ + "vlagents_host": "localhost", + "vlagents_port": 20000, + "vlagents_model": "lerobot", + "instruction": "open the box with the right arm and place the cube inside the box with the left arm", + "robot_keys": [ + "left", + "right" + ], + "jpeg_encoding": true, + "on_same_machine": false, + "fps": 30, + "record_path": "inference_recordings_hinge_chest_duobench_act_hinge_chest_real_2026-05-18_21-55-00", + "n_action_steps": 100, + "max_rel_mov_joints": 0.08726646259971647, + "max_rel_mov_cart": [ + 0.5, + 1.5707963267948966 + ] +} diff --git a/examples/inference/franka.py b/examples/inference/franka.py index 2c2ed6ad..20c04173 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -22,7 +22,7 @@ from rcs.envs.tasks import PickTaskConfig import rcs -from rcs_duobench.tasks.bin_sort import BinSortEnvConfig +# from rcs_duobench.tasks.bin_sort import BinSortEnvConfig from vlagents.client import RemoteAgent from vlagents.policies import Act, Obs @@ -39,8 +39,8 @@ } -ROBOT_INSTANCE = RobotPlatform.SIMULATION -# ROBOT_INSTANCE = RobotPlatform.HARDWARE +# ROBOT_INSTANCE = RobotPlatform.SIMULATION +ROBOT_INSTANCE = RobotPlatform.HARDWARE # set camera dict to none disable cameras CAMERA_DICT = { @@ -71,6 +71,7 @@ FPS = 30 CONTROL_MODE = ControlMode.JOINTS RELATIVETO = RelativeTo.NONE +# RELATIVETO = RelativeTo.CONFIGURED_ORIGIN RECORD_PATH = "inference_recordings" MODEL = "lerobot" IP = "localhost" @@ -373,6 +374,7 @@ def get_env(cfg: InferenceConfig) -> gym.Env: hw_cfg.camera_cfgs = camera_cfgs or None hw_cfg.control_mode = CONTROL_MODE hw_cfg.wrapper_cfg.include_depth = INCLUDE_DEPTH + hw_cfg.wrapper_cfg.binary_gripper = True hw_cfg.max_relative_movement = cfg.max_rel_mov_joints if CONTROL_MODE == ControlMode.JOINTS else cfg.max_rel_mov_cart hw_cfg.relative_to = RELATIVETO hw_cfg.robot_to_shared_base_frame = robot2world @@ -386,12 +388,11 @@ def get_env(cfg: InferenceConfig) -> gym.Env: else: # FR3 - scene = BinSortEnvConfig() + # scene = BinSortEnvConfig() sim_cfg_data = scene.config() sim_cfg_data.sim_cfg = SimConfig( async_control=True, realtime=False, frequency=cfg.fps, max_convergence_steps=500 ) - sim_cfg_data.relative_to = RelativeTo.CONFIGURED_ORIGIN sim_cfg_data.wrapper_cfg.include_depth = INCLUDE_DEPTH sim_cfg_data.control_mode = ControlMode.JOINTS sim_cfg_data.relative_to = RELATIVETO diff --git a/examples/teleop/inspect_parquet_duckdb.ipynb b/examples/teleop/inspect_parquet_duckdb.ipynb index 87c24370..31a5bf5d 100644 --- a/examples/teleop/inspect_parquet_duckdb.ipynb +++ b/examples/teleop/inspect_parquet_duckdb.ipynb @@ -2,68 +2,169 @@ "cells": [ { "cell_type": "code", - "execution_count": 1, + "execution_count": null, "id": "85351314", "metadata": {}, "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Collecting duckdb\n", + " Downloading duckdb-1.5.3-cp312-cp312-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl.metadata (4.2 kB)\n", + "Downloading duckdb-1.5.3-cp312-cp312-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl (21.5 MB)\n", + "\u001b[2K \u001b[90m━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━\u001b[0m \u001b[32m21.5/21.5 MB\u001b[0m \u001b[31m103.8 MB/s\u001b[0m eta \u001b[36m0:00:00\u001b[0m00:01\u001b[0m\n", + "\u001b[?25hInstalling collected packages: duckdb\n", + "Successfully installed duckdb-1.5.3\n" + ] + }, { "data": { "text/plain": [ - "(┌─────────────┬──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┬─────────┬─────────┬─────────┬─────────┐\n", - " │ column_name │ column_type │ null │ key │ default │ extra │\n", - " │ varchar │ varchar │ varchar │ varchar │ varchar │ varchar │\n", - " ├─────────────┼──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┼─────────┼─────────┼─────────┼─────────┤\n", - " │ obs │ STRUCT(\"left\" STRUCT(tquat DOUBLE[], joints DOUBLE[], xyzrpy DOUBLE[], gripper DOUBLE[]), \"right\" STRUCT(tquat DOUBLE[], joints DOUBLE[], xyzrpy DOUBLE[], gripper DOUBLE[]), frames STRUCT(head STRUCT(rgb STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[]), depth STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[])), left_wrist STRUCT(rgb STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[]), depth STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[])), right_wrist STRUCT(rgb STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[]), depth STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[])))) │ YES │ NULL │ NULL │ NULL │\n", - " │ info │ STRUCT(\"left\" STRUCT(collision BOOLEAN, ik_success BOOLEAN, is_sim_converged BOOLEAN, gripper_width DOUBLE, is_grasped BOOLEAN, terminated BOOLEAN, truncated BOOLEAN), \"right\" STRUCT(collision BOOLEAN, ik_success BOOLEAN, is_sim_converged BOOLEAN, gripper_width DOUBLE, is_grasped BOOLEAN, terminated BOOLEAN, truncated BOOLEAN), camera_available BOOLEAN, frame_timestamp DOUBLE, is_grasped BOOLEAN, success BOOLEAN) │ YES │ NULL │ NULL │ NULL │\n", - " │ reward │ DOUBLE │ YES │ NULL │ NULL │ NULL │\n", - " │ step │ BIGINT │ YES │ NULL │ NULL │ NULL │\n", - " │ uuid │ VARCHAR │ YES │ NULL │ NULL │ NULL │\n", - " │ success │ BOOLEAN │ YES │ NULL │ NULL │ NULL │\n", - " │ action │ STRUCT(\"left\" STRUCT(tquat DOUBLE[], gripper BIGINT[]), \"right\" STRUCT(tquat DOUBLE[], gripper BIGINT[])) │ YES │ NULL │ NULL │ NULL │\n", - " │ instruction │ VARCHAR │ YES │ NULL │ NULL │ NULL │\n", - " │ timestamp │ DOUBLE │ YES │ NULL │ NULL │ NULL │\n", - " │ head │ STRUCT(rgb STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[]), depth STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[])) │ YES │ NULL │ NULL │ NULL │\n", - " │ left_wrist │ STRUCT(rgb STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[]), depth STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[])) │ YES │ NULL │ NULL │ NULL │\n", - " │ right_wrist │ STRUCT(rgb STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[]), depth STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[])) │ YES │ NULL │ NULL │ NULL │\n", - " └─────────────┴──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┴─────────┴─────────┴─────────┴─────────┘\n", - " 12 rows 6 columns,\n", + "(┌─────────────┬───────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┬─────────┬─────────┬─────────┬─────────┐\n", + " │ column_name │ column_type │ null │ key │ default │ extra │\n", + " │ varchar │ varchar │ varchar │ varchar │ varchar │ varchar │\n", + " ├─────────────┼───────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┼─────────┼─────────┼─────────┼─────────┤\n", + " │ obs │ STRUCT(\"left\" STRUCT(tquat DOUBLE[], joints DOUBLE[], xyzrpy DOUBLE[], robot_state STRUCT(EE_T_K DOUBLE[], F_T_EE DOUBLE[], F_T_NE DOUBLE[], F_x_Cee DOUBLE[], F_x_Cload DOUBLE[], F_x_Ctotal DOUBLE[], I_ee DOUBLE[], I_load DOUBLE[], I_total DOUBLE[], K_F_ext_hat_K DOUBLE[], NE_T_EE DOUBLE[], O_F_ext_hat_K DOUBLE[], O_T_EE DOUBLE[], O_T_EE_c DOUBLE[], O_T_EE_d DOUBLE[], O_dP_EE_c DOUBLE[], O_dP_EE_d DOUBLE[], O_ddP_EE_c DOUBLE[], O_ddP_O DOUBLE[], cartesian_collision DOUBLE[], cartesian_contact DOUBLE[], control_command_success_rate DOUBLE, ddelbow_c DOUBLE[], ddq_d DOUBLE[], delbow_c DOUBLE[], dq DOUBLE[], dq_d DOUBLE[], dtau_J DOUBLE[], dtheta DOUBLE[], elbow DOUBLE[], elbow_c DOUBLE[], elbow_d DOUBLE[], joint_collision DOUBLE[], joint_contact DOUBLE[], m_ee DOUBLE, m_load DOUBLE, m_total DOUBLE, q DOUBLE[], q_d DOUBLE[], tau_J DOUBLE[], tau_J_d DOUBLE[], tau_ext_hat_filtered DOUBLE[], theta DOUBLE[]), gripper DOUBLE[]), \"right\" STRUCT(tquat DOUBLE[], joints DOUBLE[], xyzrpy DOUBLE[], robot_state STRUCT(EE_T_K DOUBLE[], F_T_EE DOUBLE[], F_T_NE DOUBLE[], F_x_Cee DOUBLE[], F_x_Cload DOUBLE[], F_x_Ctotal DOUBLE[], I_ee DOUBLE[], I_load DOUBLE[], I_total DOUBLE[], K_F_ext_hat_K DOUBLE[], NE_T_EE DOUBLE[], O_F_ext_hat_K DOUBLE[], O_T_EE DOUBLE[], O_T_EE_c DOUBLE[], O_T_EE_d DOUBLE[], O_dP_EE_c DOUBLE[], O_dP_EE_d DOUBLE[], O_ddP_EE_c DOUBLE[], O_ddP_O DOUBLE[], cartesian_collision DOUBLE[], cartesian_contact DOUBLE[], control_command_success_rate DOUBLE, ddelbow_c DOUBLE[], ddq_d DOUBLE[], delbow_c DOUBLE[], dq DOUBLE[], dq_d DOUBLE[], dtau_J DOUBLE[], dtheta DOUBLE[], elbow DOUBLE[], elbow_c DOUBLE[], elbow_d DOUBLE[], joint_collision DOUBLE[], joint_contact DOUBLE[], m_ee DOUBLE, m_load DOUBLE, m_total DOUBLE, q DOUBLE[], q_d DOUBLE[], tau_J DOUBLE[], tau_J_d DOUBLE[], tau_ext_hat_filtered DOUBLE[], theta DOUBLE[]), gripper DOUBLE[]), frames STRUCT(right_wrist STRUCT(rgb STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[])), left_wrist STRUCT(rgb STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[])), head STRUCT(rgb STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[])), head_right STRUCT(rgb STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[])))) │ YES │ NULL │ NULL │ NULL │\n", + " │ info │ STRUCT(\"left\" STRUCT(platform VARCHAR, robot_type VARCHAR, gripper_type VARCHAR, absolute_action DOUBLE[], terminated BOOLEAN, truncated BOOLEAN), \"right\" STRUCT(platform VARCHAR, robot_type VARCHAR, gripper_type VARCHAR, absolute_action DOUBLE[], terminated BOOLEAN, truncated BOOLEAN), camera_available BOOLEAN, frame_timestamp DOUBLE) │ YES │ NULL │ NULL │ NULL │\n", + " │ reward │ DOUBLE │ YES │ NULL │ NULL │ NULL │\n", + " │ step │ BIGINT │ YES │ NULL │ NULL │ NULL │\n", + " │ uuid │ VARCHAR │ YES │ NULL │ NULL │ NULL │\n", + " │ success │ BOOLEAN │ YES │ NULL │ NULL │ NULL │\n", + " │ action │ STRUCT(\"left\" STRUCT(tquat DOUBLE[], gripper DOUBLE[]), \"right\" STRUCT(tquat DOUBLE[], gripper DOUBLE[])) │ YES │ NULL │ NULL │ NULL │\n", + " │ env_action │ STRUCT(\"left\" STRUCT(tquat DOUBLE[], gripper DOUBLE[]), \"right\" STRUCT(tquat DOUBLE[], gripper DOUBLE[])) │ YES │ NULL │ NULL │ NULL │\n", + " │ instruction │ VARCHAR │ YES │ NULL │ NULL │ NULL │\n", + " │ timestamp │ DOUBLE │ YES │ NULL │ NULL │ NULL │\n", + " │ left │ STRUCT(tquat DOUBLE[], joints DOUBLE[], xyzrpy DOUBLE[], robot_state STRUCT(EE_T_K DOUBLE[], F_T_EE DOUBLE[], F_T_NE DOUBLE[], F_x_Cee DOUBLE[], F_x_Cload DOUBLE[], F_x_Ctotal DOUBLE[], I_ee DOUBLE[], I_load DOUBLE[], I_total DOUBLE[], K_F_ext_hat_K DOUBLE[], NE_T_EE DOUBLE[], O_F_ext_hat_K DOUBLE[], O_T_EE DOUBLE[], O_T_EE_c DOUBLE[], O_T_EE_d DOUBLE[], O_dP_EE_c DOUBLE[], O_dP_EE_d DOUBLE[], O_ddP_EE_c DOUBLE[], O_ddP_O DOUBLE[], cartesian_collision DOUBLE[], cartesian_contact DOUBLE[], control_command_success_rate DOUBLE, ddelbow_c DOUBLE[], ddq_d DOUBLE[], delbow_c DOUBLE[], dq DOUBLE[], dq_d DOUBLE[], dtau_J DOUBLE[], dtheta DOUBLE[], elbow DOUBLE[], elbow_c DOUBLE[], elbow_d DOUBLE[], joint_collision DOUBLE[], joint_contact DOUBLE[], m_ee DOUBLE, m_load DOUBLE, m_total DOUBLE, q DOUBLE[], q_d DOUBLE[], tau_J DOUBLE[], tau_J_d DOUBLE[], tau_ext_hat_filtered DOUBLE[], theta DOUBLE[]), gripper DOUBLE[]) │ YES │ NULL │ NULL │ NULL │\n", + " │ right │ STRUCT(tquat DOUBLE[], joints DOUBLE[], xyzrpy DOUBLE[], robot_state STRUCT(EE_T_K DOUBLE[], F_T_EE DOUBLE[], F_T_NE DOUBLE[], F_x_Cee DOUBLE[], F_x_Cload DOUBLE[], F_x_Ctotal DOUBLE[], I_ee DOUBLE[], I_load DOUBLE[], I_total DOUBLE[], K_F_ext_hat_K DOUBLE[], NE_T_EE DOUBLE[], O_F_ext_hat_K DOUBLE[], O_T_EE DOUBLE[], O_T_EE_c DOUBLE[], O_T_EE_d DOUBLE[], O_dP_EE_c DOUBLE[], O_dP_EE_d DOUBLE[], O_ddP_EE_c DOUBLE[], O_ddP_O DOUBLE[], cartesian_collision DOUBLE[], cartesian_contact DOUBLE[], control_command_success_rate DOUBLE, ddelbow_c DOUBLE[], ddq_d DOUBLE[], delbow_c DOUBLE[], dq DOUBLE[], dq_d DOUBLE[], dtau_J DOUBLE[], dtheta DOUBLE[], elbow DOUBLE[], elbow_c DOUBLE[], elbow_d DOUBLE[], joint_collision DOUBLE[], joint_contact DOUBLE[], m_ee DOUBLE, m_load DOUBLE, m_total DOUBLE, q DOUBLE[], q_d DOUBLE[], tau_J DOUBLE[], tau_J_d DOUBLE[], tau_ext_hat_filtered DOUBLE[], theta DOUBLE[]), gripper DOUBLE[]) │ YES │ NULL │ NULL │ NULL │\n", + " │ frames │ STRUCT(right_wrist STRUCT(rgb STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[])), left_wrist STRUCT(rgb STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[])), head STRUCT(rgb STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[])), head_right STRUCT(rgb STRUCT(\"data\" BLOB, intrinsics DOUBLE[], extrinsics DOUBLE[], intrinsics_shape BIGINT[], extrinsics_shape BIGINT[]))) │ YES │ NULL │ NULL │ NULL │\n", + " └─────────────┴───────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┴─────────┴─────────┴─────────┴─────────┘\n", + " 13 rows 6 columns,\n", " ┌──────────┐\n", " │ n_frames │\n", " │ int64 │\n", " ├──────────┤\n", - " │ 5321 │\n", + " │ 67528 │\n", " └──────────┘)" ] }, - "execution_count": 1, + "execution_count": 2, "metadata": {}, "output_type": "execute_result" } ], "source": [ "import duckdb\n", - "path = \"/home/tobi/coding/rcs_clones/robot-control-stack/data_grasp\"\n", - "duckdb.sql(f\"describe select *, unnest(obs.frames) from read_parquet('{path}')\"), duckdb.sql(f\"select count(*) as n_frames from read_parquet('{path}')\")" + "path = \"/home/juelg/code/duobench/robot-control-stack/bin_sortv2\"\n", + "duckdb.sql(f\"describe select *, unnest(obs) from read_parquet('{path}')\"), duckdb.sql(f\"select count(*) as n_frames from read_parquet('{path}')\")" + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "id": "6c50d53e", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Latest Episode UUID and Timestamp: ('5f3c0399f9544621ba6caca3363635e8', 1779292467.945553)\n" + ] + } + ], + "source": [ + "import duckdb\n", + "\n", + "path = \"/home/juelg/code/duobench/robot-control-stack/bin_sortv2\"\n", + "\n", + "# Pull only the single latest record\n", + "query = f\"\"\"\n", + " SELECT uuid, timestamp \n", + " FROM read_parquet('{path}') \n", + " ORDER BY timestamp DESC \n", + " LIMIT 1\n", + "\"\"\"\n", + "\n", + "# Fetch as a standard Python tuple: (uuid, timestamp)\n", + "latest_record = duckdb.sql(query).fetchone()\n", + "\n", + "print(\"Latest Episode UUID and Timestamp:\", latest_record)" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "id": "4c70a2ea", + "metadata": {}, + "outputs": [ + { + "data": { + "application/vnd.jupyter.widget-view+json": { + "model_id": "7ce86cc47a58401f86e5c2825e37bf77", + "version_major": 2, + "version_minor": 0 + }, + "text/plain": [ + "FloatProgress(value=0.0, layout=Layout(width='auto'), style=ProgressStyle(bar_color='black'))" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Successfully set 'success' to False for UUID: 5f3c0399f9544621ba6caca3363635e8\n" + ] + } + ], + "source": [ + "import duckdb\n", + "\n", + "path = \"/home/juelg/code/duobench/robot-control-stack/bin_sortv2\"\n", + "path2 = \"/home/juelg/code/duobench/robot-control-stack/bin_sortv3\"\n", + "target_uuid = \"5f3c0399f9544621ba6caca3363635e8\"\n", + "\n", + "# SQL to select all data, but override 'success' for the specific UUID\n", + "query = f\"\"\"\n", + " SELECT \n", + " * EXCLUDE (success), \n", + " CASE \n", + " WHEN uuid = '{target_uuid}' THEN false \n", + " ELSE success \n", + " END AS success\n", + " FROM read_parquet('{path}')\n", + "\"\"\"\n", + "\n", + "# Execute and load into a Pandas DataFrame\n", + "df = duckdb.sql(query).df()\n", + "\n", + "# Overwrite the original Parquet file with the updated data\n", + "df.to_parquet(path2)\n", + "\n", + "print(f\"Successfully set 'success' to False for UUID: {target_uuid}\")" ] }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 4, "id": "8085186f", "metadata": {}, "outputs": [ { "data": { "text/plain": [ - "┌────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐\n", - "│ info │\n", - "│ struct(\"left\" struct(collision boolean, ik_success boolean, is_sim_converged boolean, gripper_width double, is_grasped boolean, terminated boolean, truncated boolean), \"right\" struct(collision boolean, ik_success boolean, is_sim_converged boolean, gripper_width double, is_grasped boolean, terminated boolean, truncated boolean), camera_available boolean, frame_timestamp double, is_grasped boolean, success boolean) │\n", - "├────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┤\n", - "│ {'left': {'collision': false, 'ik_success': true, 'is_sim_converged': true, 'gripper_width': 1.0, 'is_grasped': false, 'terminated': false, 'truncated': false}, 'right': {'collision': false, 'ik_success': true, 'is_sim_converged': true, 'gripper_width': 0.4277359972585904, 'is_grasped': true, 'terminated': false, 'truncated': false}, 'camera_available': true, 'frame_timestamp': 5.5799999999996075, 'is_grasped': false, 'success': true} │\n", - "└────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘" + "┌──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐\n", + "│ info │\n", + "│ struct(\"left\" struct(platform varchar, robot_type varchar, gripper_type varchar, absolute_action double[], terminated boolean, truncated boolean), \"right\" struct(platform varchar, robot_type varchar, gripper_type varchar, absolute_action double[], terminated boolean, truncated boolean), camera_available boolean, frame_timestamp double) │\n", + "├──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┤\n", + "│ {'left': {'platform': hardware, 'robot_type': FR3, 'gripper_type': Robotiq2F85, 'absolute_action': [0.43102648854255676, 0.15267090499401093, 0.4907831847667694, -0.8132432068150006, -0.25469918399466873, -0.08214187685901374, 0.5167364166649981], 'terminated': false, 'truncated': false}, 'right': {'platform': hardware, 'robot_type': FR3, 'gripper_type': Robotiq2F85, 'absolute_action': [0.4207998514175415, -0.10432350635528564, 0.4641386866569519, 0.8890941201964603, -0.14876354495806932, -0.04081969258450916, 0.43094640713306454], 'terminated': false, 'truncated': false}, 'camera_available': true, 'frame_timestamp': 1779290162.1749835} │\n", + "└──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘" ] }, - "execution_count": 2, + "execution_count": 4, "metadata": {}, "output_type": "execute_result" } @@ -79,6 +180,95 @@ ")" ] }, + { + "cell_type": "code", + "execution_count": 19, + "id": "69753776", + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "┌──────────────────────────────────┐\n", + "│ successful │\n", + "│ varchar │\n", + "├──────────────────────────────────┤\n", + "│ 0e61faf0c4d147938802da6f285cc053 │\n", + "│ 56626f8b6c5d4e73bd6efd911aea68c0 │\n", + "│ 7c5e7de2d7aa4db8b361ec5b22499c6b │\n", + "│ 87901475844a441395b3c7d51d82c1de │\n", + "└──────────────────────────────────┘" + ] + }, + "execution_count": 19, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "duckdb.sql(\n", + " \"SELECT DISTINCT uuid as successful \"\n", + " f\"FROM read_parquet('{path}') \"\n", + " \"WHERE success ORDER BY uuid\"\n", + ")" + ] + }, + { + "cell_type": "code", + "execution_count": 25, + "id": "3856373f", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Reading data from /home/juelg/code/duobench/robot-control-stack/ball_maze/2026-05-12_part-0.parquet...\n", + "Updating 'success' to false for UUID: 7c5e7de2d7aa4db8b361ec5b22499c6b...\n", + "Writing to temporary file...\n", + "Overwriting the original file...\n", + "Done! Directory structure is preserved.\n" + ] + } + ], + "source": [ + "import duckdb\n", + "import os\n", + "\n", + "# --- Configuration Variables ---\n", + "directory_path = \"/home/juelg/code/duobench/robot-control-stack/ball_maze\"\n", + "file_name = \"2026-05-12_part-0.parquet\"\n", + "target_uuid = \"7c5e7de2d7aa4db8b361ec5b22499c6b\"\n", + "\n", + "# Construct the full paths\n", + "file_path = os.path.join(directory_path, file_name)\n", + "temp_path = file_path + \".tmp\"\n", + "\n", + "# --- Database Operations ---\n", + "con = duckdb.connect()\n", + "\n", + "print(f\"Reading data from {file_path}...\")\n", + "# 1. Load the Parquet data from the specific file\n", + "con.execute(f\"CREATE TABLE dataset AS SELECT * FROM read_parquet('{file_path}')\")\n", + "\n", + "print(f\"Updating 'success' to false for UUID: {target_uuid}...\")\n", + "# 2. Execute the update\n", + "con.execute(\"UPDATE dataset SET success = false WHERE uuid = ?\", (target_uuid,))\n", + "\n", + "print(\"Writing to temporary file...\")\n", + "# 3. Write the modified table back to a temporary file inside the directory\n", + "con.execute(f\"COPY dataset TO '{temp_path}' (FORMAT PARQUET)\")\n", + "\n", + "# Close the database connection before manipulating files\n", + "con.close()\n", + "\n", + "print(\"Overwriting the original file...\")\n", + "# 4. Safely replace the exact file, leaving the directory intact\n", + "os.replace(temp_path, file_path)\n", + "\n", + "print(\"Done! Directory structure is preserved.\")" + ] + }, { "cell_type": "code", "execution_count": 3, @@ -92,13 +282,13 @@ " │ successful │\n", " │ int64 │\n", " ├────────────┤\n", - " │ 27 │\n", + " │ 113 │\n", " └────────────┘,\n", " ┌────────────┐\n", " │ n_episodes │\n", " │ int64 │\n", " ├────────────┤\n", - " │ 30 │\n", + " │ 115 │\n", " └────────────┘)" ] }, @@ -120,22 +310,22 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 84, "id": "f1ee638e", "metadata": {}, "outputs": [ { "data": { "text/plain": [ - "┌────────────────────┬────────────────────┬───────────────────┐\n", - "│ (max(step) / 30) │ (min(step) / 30) │ (avg(step) / 30) │\n", - "│ double │ double │ double │\n", - "├────────────────────┼────────────────────┼───────────────────┤\n", - "│ 17.533333333333335 │ 1.0666666666666667 │ 5.346779661016949 │\n", - "└────────────────────┴────────────────────┴───────────────────┘" + "┌────────────────────┬───────────────────┬───────────────────┐\n", + "│ (max(step) / 30) │ (min(step) / 30) │ (avg(step) / 30) │\n", + "│ double │ double │ double │\n", + "├────────────────────┼───────────────────┼───────────────────┤\n", + "│ 19.533333333333335 │ 8.533333333333333 │ 11.66923076923077 │\n", + "└────────────────────┴───────────────────┴───────────────────┘" ] }, - "execution_count": 4, + "execution_count": 84, "metadata": {}, "output_type": "execute_result" } @@ -152,7 +342,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 20, "id": "97808e66", "metadata": {}, "outputs": [ @@ -160,14 +350,14 @@ "name": "stdout", "output_type": "stream", "text": [ - "episode uuid: bda71d1e8bf44a6e9a0467ca9e1e7bfd, success: False, n_steps: 150, info: {'left': {'collision': False, 'ik_success': True, 'is_sim_converged': True, 'gripper_width': 1.0, 'is_grasped': False, 'terminated': False, 'truncated': False}, 'right': {'collision': False, 'ik_success': True, 'is_sim_converged': True, 'gripper_width': 1.0, 'is_grasped': False, 'terminated': False, 'truncated': False}, 'camera_available': True, 'frame_timestamp': 4.899999999999682, 'is_grasped': False, 'success': False}\n" + "episode uuid: 7c5e7de2d7aa4db8b361ec5b22499c6b, success: False, n_steps: 844, info: {'left': {'platform': 'hardware', 'absolute_action': [0.5092409253120422, 0.2895634174346924, 0.16640011966228485, 0.8264918230390301, 0.3795456871273817, 0.1573973020068592, -0.3848147959130286], 'terminated': False, 'truncated': False}, 'right': {'platform': 'hardware', 'absolute_action': [0.46342507004737854, -0.32870620489120483, 0.1969984769821167, 0.8623926086992065, -0.3068727980040084, 0.05247313104626525, 0.3991924909418636], 'terminated': False, 'truncated': False}, 'camera_available': True, 'frame_timestamp': 1778597070.9116964}\n" ] }, { "data": { - "image/png": "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", + "image/png": "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", "text/plain": [ - "
" + "
" ] }, "metadata": {}, @@ -179,11 +369,11 @@ "from matplotlib import pyplot as plt\n", "from PIL import Image\n", "import duckdb\n", - "episode = 0\n", - "step = 100\n", + "episode = 2\n", + "step = 800\n", "\n", "\n", - "uuids = duckdb.sql(f\"SELECT DISTINCT uuid FROM read_parquet('{path}') WHERE success\").fetchnumpy()\n", + "uuids = duckdb.sql(f\"SELECT DISTINCT uuid FROM read_parquet('{path}') WHERE success ORDER BY uuid\").fetchnumpy()\n", "# uuids\n", "uuid1 = uuids[\"uuid\"][episode]\n", "rel = duckdb.read_parquet(path)\n", @@ -195,7 +385,7 @@ "\n", "\n", "# Create a figure with 1 row and 2 columns\n", - "fig, ax = plt.subplots(1, 3, figsize=(20, 5))\n", + "fig, ax = plt.subplots(1, 4, figsize=(20, 5))\n", "\n", "\n", "img1_data = rel.filter(f\"uuid='{uuid1}' and step={step}\").select(\"obs.frames.head.rgb.data\").fetchone()[0]\n", @@ -203,6 +393,7 @@ "ax[0].imshow(image1)\n", "ax[0].set_title(\"Head Camera\")\n", "\n", + "\n", "img2_data = rel.filter(f\"uuid='{uuid1}' and step={step}\").select(\"obs.frames.left_wrist.rgb.data\").fetchone()[0]\n", "image2 = Image.open(io.BytesIO(img2_data))\n", "ax[1].imshow(image2)\n", @@ -213,6 +404,11 @@ "ax[2].imshow(image3)\n", "ax[2].set_title(\"Right Wrist Camera\") # Optional title\n", "\n", + "img1_data = rel.filter(f\"uuid='{uuid1}' and step={step}\").select(\"obs.frames.head_right.rgb.data\").fetchone()[0]\n", + "image1 = Image.open(io.BytesIO(img1_data))\n", + "ax[3].imshow(image1)\n", + "ax[3].set_title(\"Head right Camera\")\n", + "\n", "\n", "\n", "plt.show()" @@ -220,7 +416,82 @@ }, { "cell_type": "code", - "execution_count": 7, + "execution_count": 96, + "id": "9a4574f4", + "metadata": {}, + "outputs": [ + { + "ename": "BinderException", + "evalue": "Binder Error: Could not find key \"depth\" in struct\n\nCandidate Entries: \"rgb\"", + "output_type": "error", + "traceback": [ + "\u001b[31m---------------------------------------------------------------------------\u001b[39m", + "\u001b[31mBinderException\u001b[39m Traceback (most recent call last)", + "\u001b[36mCell\u001b[39m\u001b[36m \u001b[39m\u001b[32mIn[96]\u001b[39m\u001b[32m, line 28\u001b[39m\n\u001b[32m 24\u001b[39m LIMIT \u001b[32m1\u001b[39m;\n\u001b[32m 25\u001b[39m \"\"\"\n\u001b[32m 26\u001b[39m \n\u001b[32m 27\u001b[39m \u001b[38;5;66;03m# Execute the query and fetch the single row\u001b[39;00m\n\u001b[32m---> \u001b[39m\u001b[32m28\u001b[39m row = duckdb.sql(query).fetchone()\n\u001b[32m 29\u001b[39m \n\u001b[32m 30\u001b[39m \u001b[38;5;66;03m# Extract the BLOBs (returned as Python bytes)\u001b[39;00m\n\u001b[32m 31\u001b[39m left_wrist_blob, right_wrist_blob, head_blob = row\n", + "\u001b[31mBinderException\u001b[39m: Binder Error: Could not find key \"depth\" in struct\n\nCandidate Entries: \"rgb\"" + ] + } + ], + "source": [ + "import duckdb\n", + "import io\n", + "import matplotlib.pyplot as plt\n", + "from PIL import Image\n", + "\n", + "# Define the path to your parquet file(s)\n", + "\n", + "# SQL query to get the first step of the first episode\n", + "query = f\"\"\"\n", + "WITH first_episode AS (\n", + " -- Identify the first episode (uuid) by taking the earliest timestamp\n", + " SELECT uuid\n", + " FROM read_parquet('{path}')\n", + " ORDER BY \"timestamp\" ASC\n", + " LIMIT 1\n", + ")\n", + "SELECT \n", + " obs.frames.left_wrist.depth.data AS left_wrist_blob,\n", + " obs.frames.right_wrist.depth.data AS right_wrist_blob,\n", + " obs.frames.head.depth.data AS head_blob\n", + "FROM read_parquet('{path}')\n", + "WHERE uuid = (SELECT uuid FROM first_episode)\n", + "ORDER BY step ASC\n", + "LIMIT 1;\n", + "\"\"\"\n", + "\n", + "# Execute the query and fetch the single row\n", + "row = duckdb.sql(query).fetchone()\n", + "\n", + "# Extract the BLOBs (returned as Python bytes)\n", + "left_wrist_blob, right_wrist_blob, head_blob = row\n", + "\n", + "# Convert bytes to PIL Images\n", + "img_left = Image.open(io.BytesIO(left_wrist_blob))\n", + "img_right = Image.open(io.BytesIO(right_wrist_blob))\n", + "img_head = Image.open(io.BytesIO(head_blob))\n", + "\n", + "# Plot the frames side-by-side\n", + "fig, axes = plt.subplots(1, 3, figsize=(18, 5))\n", + "\n", + "axes[0].imshow(img_left)\n", + "axes[0].set_title(\"Left Wrist Frame\")\n", + "axes[0].axis(\"off\")\n", + "\n", + "axes[1].imshow(img_right)\n", + "axes[1].set_title(\"Right Wrist Frame\")\n", + "axes[1].axis(\"off\")\n", + "\n", + "axes[2].imshow(img_head)\n", + "axes[2].set_title(\"Head Frame\")\n", + "axes[2].axis(\"off\")\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": 38, "id": "758f3147", "metadata": {}, "outputs": [ @@ -231,35 +502,35 @@ "│ timestamp │\n", "│ double │\n", "├───────────────────┤\n", - "│ 1777204228.532817 │\n", - "│ 1777204228.583433 │\n", - "│ 1777204228.635595 │\n", - "│ 1777204228.686985 │\n", - "│ 1777204228.735731 │\n", - "│ 1777204228.7872 │\n", - "│ 1777204228.83733 │\n", - "│ 1777204228.884319 │\n", - "│ 1777204228.934861 │\n", - "│ 1777204076.763415 │\n", + "│ 1777976566.764664 │\n", + "│ 1777976566.796761 │\n", + "│ 1777976566.828648 │\n", + "│ 1777976566.861564 │\n", + "│ 1777976566.892437 │\n", + "│ 1777976566.925095 │\n", + "│ 1777976566.973188 │\n", + "│ 1777976567.004589 │\n", + "│ 1777976567.037067 │\n", + "│ 1777976567.070343 │\n", "│ · │\n", "│ · │\n", "│ · │\n", - "│ 1777204207.432611 │\n", - "│ 1777204207.474623 │\n", - "│ 1777204207.51622 │\n", - "│ 1777204207.553477 │\n", - "│ 1777204207.595021 │\n", - "│ 1777204207.629543 │\n", - "│ 1777204207.667513 │\n", - "│ 1777204207.704982 │\n", - "│ 1777204207.745933 │\n", - "│ 1777204207.783519 │\n", + "│ 1777976516.320072 │\n", + "│ 1777976516.370078 │\n", + "│ 1777976516.400288 │\n", + "│ 1777976516.433601 │\n", + "│ 1777976516.464637 │\n", + "│ 1777976516.496684 │\n", + "│ 1777976516.530015 │\n", + "│ 1777976516.560782 │\n", + "│ 1777976516.593983 │\n", + "│ 1777976516.624152 │\n", "└───────────────────┘\n", - " 5321 rows \n", + " 1108 rows \n", " (20 shown) " ] }, - "execution_count": 7, + "execution_count": 38, "metadata": {}, "output_type": "execute_result" } @@ -273,6 +544,18 @@ ")" ] }, + { + "cell_type": "code", + "execution_count": 199, + "id": "e6cd3e1d", + "metadata": {}, + "outputs": [], + "source": [ + "path = \"/home/juelg/code/duobench/robot-control-stack/real_bin_sort_test2_new2_without_nogrp\"\n", + "# path = \"/home/juelg/code/duobench/robot-control-stack/real_bin_sort_test2_new_without_nogrp\"\n", + "# path = \"/home/juelg/code/duobench/robot-control-stack/real_bin_sort_test2_old_without_nogrp\"" + ] + }, { "cell_type": "code", "execution_count": 8, @@ -286,7 +569,7 @@ "│ average_frequency_hz │\n", "│ double │\n", "├──────────────────────┤\n", - "│ 20.90057259306587 │\n", + "│ 22.238600508286407 │\n", "└──────────────────────┘" ] }, @@ -315,22 +598,22 @@ }, { "cell_type": "code", - "execution_count": 9, + "execution_count": 6, "id": "b67b4bf2", "metadata": {}, "outputs": [ { "data": { "text/plain": [ - "┌────────────────────┐\n", - "│ std_frequency_hz │\n", - "│ double │\n", - "├────────────────────┤\n", - "│ 1.9147779001859897 │\n", - "└────────────────────┘" + "┌──────────────────┐\n", + "│ std_frequency_hz │\n", + "│ double │\n", + "├──────────────────┤\n", + "│ NULL │\n", + "└──────────────────┘" ] }, - "execution_count": 9, + "execution_count": 6, "metadata": {}, "output_type": "execute_result" } @@ -355,22 +638,22 @@ }, { "cell_type": "code", - "execution_count": 10, + "execution_count": 7, "id": "0eac2e74", "metadata": {}, "outputs": [ { "data": { "text/plain": [ - "┌───────────────────┬───────────────────┐\n", - "│ mean_frequency_hz │ std_frequency_hz │\n", - "│ double │ double │\n", - "├───────────────────┼───────────────────┤\n", - "│ 21.94798549029336 │ 4.965794976134775 │\n", - "└───────────────────┴───────────────────┘" + "┌────────────────────┬───────────────────┐\n", + "│ mean_frequency_hz │ std_frequency_hz │\n", + "│ double │ double │\n", + "├────────────────────┼───────────────────┤\n", + "│ 28.036486568649778 │ 17.32944834547649 │\n", + "└────────────────────┴───────────────────┘" ] }, - "execution_count": 10, + "execution_count": 7, "metadata": {}, "output_type": "execute_result" } @@ -403,45 +686,24 @@ }, { "cell_type": "code", - "execution_count": 11, + "execution_count": 65, "id": "a7b09572", "metadata": {}, "outputs": [ { "data": { "text/plain": [ - "┌──────────────────────────────────┬────────────────────┬─────────────┬────────────────────┬─────────────┐\n", - "│ uuid │ min_freq_hz │ step_at_min │ max_freq_hz │ step_at_max │\n", - "│ varchar │ double │ int64 │ double │ int64 │\n", - "├──────────────────────────────────┼────────────────────┼─────────────┼────────────────────┼─────────────┤\n", - "│ bda71d1e8bf44a6e9a0467ca9e1e7bfd │ 5.9396196596507576 │ 31 │ 28.946996466431095 │ 77 │\n", - "│ 66cbb1ca310f435e99f780de83895bd9 │ 5.826619916316131 │ 63 │ 28.967788275595336 │ 89 │\n", - "│ 1c6853006d9e4b02b2a31dac40fcd2bd │ 6.0373760477197385 │ 95 │ 30.792018441569883 │ 2 │\n", - "│ 3aa324d79982427182cc5df4f465d1bb │ 4.8488334857395206 │ 31 │ 29.719435981010417 │ 108 │\n", - "│ 4497782de6c34767b0aaa425b2e26eb3 │ 6.3683313114258775 │ 95 │ 33.85697795500593 │ 21 │\n", - "│ a7757dcc23904a8b82c1274c42d9715c │ 5.752982583195486 │ 31 │ 29.731865514528145 │ 6 │\n", - "│ 14da252f8ffe4293bcd2ade05d7f0519 │ 4.957952658175478 │ 447 │ 24.100486111909166 │ 241 │\n", - "│ 27c6b0e231094c76bbe8e3e93460cd2f │ 6.442051846004037 │ 31 │ 21.560997676474823 │ 17 │\n", - "│ 6d3bac5e8e7641419677573d1c09d817 │ 6.4079591044785245 │ 159 │ 30.754087782845243 │ 48 │\n", - "│ c8a8d90fb7484ebf8852760ce2046007 │ 6.316199712373222 │ 127 │ 30.063462710102858 │ 91 │\n", - "│ · │ · │ · │ · │ · │\n", - "│ · │ · │ · │ · │ · │\n", - "│ · │ · │ · │ · │ · │\n", - "│ 73ce9d02be9c4d9fb8a3ab1356062aca │ 6.078736688328628 │ 31 │ 28.515221972941735 │ 119 │\n", - "│ a70da27eb26046d58cb03b18e82947db │ 5.946263510678114 │ 31 │ 30.023650680028634 │ 88 │\n", - "│ 08e6a2023e794cdb93e27709cd73bcee │ 6.197898718839124 │ 31 │ 31.30965497678446 │ 5 │\n", - "│ 36cfab4f02cf48b88dfd58b5c0c71596 │ 6.028672207162015 │ 31 │ 29.214144917845527 │ 74 │\n", - "│ 0686f634cc844c09be7dce44e519346c │ 6.107388472520928 │ 159 │ 29.564001353332582 │ 148 │\n", - "│ 11b8aef48c4641fe8b2fa12f6aa269e8 │ 6.009797810895659 │ 31 │ 29.010866182034487 │ 139 │\n", - "│ 730e310a0095461794f2eedb0faf15a0 │ 6.5395399890235995 │ 31 │ 30.061523465496975 │ 15 │\n", - "│ 8174017865424b349f766454a8e63a6d │ 6.308438315946528 │ 31 │ 30.07337831346034 │ 52 │\n", - "│ 84399ec490944ff4ac15b13ff9c1c3e8 │ 6.1951340557019465 │ 31 │ 30.397912740976953 │ 14 │\n", - "│ af89603bb83742828785b22507b4406d │ 3.75373892373768 │ 31 │ 28.77699105329601 │ 94 │\n", - "└──────────────────────────────────┴────────────────────┴─────────────┴────────────────────┴─────────────┘\n", - " 30 rows (20 shown) 5 columns" + "┌──────────────────────────────────┬────────────────────┬─────────────┬───────────────────┬─────────────┐\n", + "│ uuid │ min_freq_hz │ step_at_min │ max_freq_hz │ step_at_max │\n", + "│ varchar │ double │ int64 │ double │ int64 │\n", + "├──────────────────────────────────┼────────────────────┼─────────────┼───────────────────┼─────────────┤\n", + "│ db2c428740ef4693aecaa6ed4db5f761 │ 15.220687602969887 │ 364 │ 76.42960749298445 │ 365 │\n", + "│ c9fd93d28de541059df9b87b575ae526 │ 13.4226318484383 │ 600 │ 79.47219432707429 │ 1 │\n", + "│ 21198747942f4118b7f969a4a250fea4 │ 14.582137654580663 │ 936 │ 80.05160797786048 │ 937 │\n", + "└──────────────────────────────────┴────────────────────┴─────────────┴───────────────────┴─────────────┘" ] }, - "execution_count": 11, + "execution_count": 65, "metadata": {}, "output_type": "execute_result" } @@ -483,7 +745,7 @@ ], "metadata": { "kernelspec": { - "display_name": "rcs", + "display_name": "base", "language": "python", "name": "python3" }, @@ -497,7 +759,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.11.14" + "version": "3.12.2" } }, "nbformat": 4, diff --git a/extensions/rcs_fr3/src/hw/Franka.cpp b/extensions/rcs_fr3/src/hw/Franka.cpp index 4d0eb285..f5ad2b9d 100644 --- a/extensions/rcs_fr3/src/hw/Franka.cpp +++ b/extensions/rcs_fr3/src/hw/Franka.cpp @@ -518,11 +518,11 @@ void Franka::joint_controller() { this->set_default_robot_behavior(); // high collision threshold values for high impedance - // this->robot.setCollisionBehavior( - // {{100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0}}, - // {{100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0}}, - // {{100.0, 100.0, 100.0, 100.0, 100.0, 100.0}}, - // {{100.0, 100.0, 100.0, 100.0, 100.0, 100.0}}); + this->robot.setCollisionBehavior( + {{100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0}}, + {{100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0}}, + {{100.0, 100.0, 100.0, 100.0, 100.0, 100.0}}, + {{100.0, 100.0, 100.0, 100.0, 100.0, 100.0}}); // deoxys/config/joint-impedance-controller.yml common::Vector7d Kp; diff --git a/python/rcs/envs/base.py b/python/rcs/envs/base.py index 40d1dbeb..84791d62 100644 --- a/python/rcs/envs/base.py +++ b/python/rcs/envs/base.py @@ -3,6 +3,7 @@ import copy import logging from enum import Enum, auto +from time import sleep from typing import Annotated, Any, ClassVar, Literal, TypeAlias, cast import gymnasium as gym @@ -394,7 +395,17 @@ def reset( self.prev_action = None self.robot.reset() if self.home_on_reset: - self.robot.move_home() + exception = True + # sleep(1) + while exception: + try: + self.robot.move_home() + exception = False + except Exception: + # sleep(0.1) + self.robot.automatic_error_recovery() + sleep(0.1) + # sleep(4) return super().reset(seed=seed, options=options) def close(self): @@ -606,6 +617,7 @@ def __init__( self.trpy_key = get_space_keys(LimitedTRPYRelDictType)[0] self.tquat_key = get_space_keys(LimitedTQuatRelDictType)[0] self._absolute_action: common.Pose | VecType | None = None + self._robot = cast(common.Robot, self.get_wrapper_attr("robot")) self.max_mov = max_mov def _get_current(self) -> np.ndarray: diff --git a/python/rcs/envs/storage_wrapper.py b/python/rcs/envs/storage_wrapper.py index 58929bf3..23b33252 100644 --- a/python/rcs/envs/storage_wrapper.py +++ b/python/rcs/envs/storage_wrapper.py @@ -326,4 +326,4 @@ def close(self): self.queue.put(self.QueueSentinel) wait([self._writer_future]) - StorageWrapper.consolidate(self.base_dir, self.schema) + # StorageWrapper.consolidate(self.base_dir, self.schema) diff --git a/python/rcs/lerobot_joint_converter.py b/python/rcs/lerobot_joint_converter.py index 6092c2ba..047b0f97 100644 --- a/python/rcs/lerobot_joint_converter.py +++ b/python/rcs/lerobot_joint_converter.py @@ -9,11 +9,7 @@ import numpy as np import pandas as pd import pyarrow as pa -import torch -from lerobot.datasets.lerobot_dataset import LeRobotDataset from rcs._core.common import GripperType, RobotType -from torchvision.io import decode_jpeg -from torchvision.transforms import v2 import rcs @@ -435,6 +431,10 @@ def run_conversion( video_encoding: bool = False, video_backend: str | None = None, ) -> None: + import torch + from lerobot.datasets.lerobot_dataset import LeRobotDataset + from torchvision.io import decode_jpeg + from torchvision.transforms import v2 robot_type_converted = RobotType(robot_type) gripper_type_converted = GripperType(gripper_type) converter = JointDatasetConverter( diff --git a/python/rcs/utils.py b/python/rcs/utils.py index 1571233c..a9cc71f6 100644 --- a/python/rcs/utils.py +++ b/python/rcs/utils.py @@ -8,12 +8,7 @@ import duckdb os.environ.setdefault("MPLCONFIGDIR", "/tmp/matplotlib") -import matplotlib -matplotlib.use("Agg") import numpy as np -import torch -from matplotlib import pyplot as plt -from torchvision.io import decode_jpeg logger = logging.getLogger(__name__) logger.setLevel(logging.INFO) @@ -52,6 +47,138 @@ def __call__(self): self.t = perf_counter() +class SimpleFrameRateN: + def __init__(self, frame_rate: float | None, loop_name: str = "HybridFrameRate", spin_buffer: float = 0.002): + """ + Utility class to manage frame rates with high precision using a hybrid sleep/spin technique. + + Args: + frame_rate (float | None): The desired frame rate in frames per second. + loop_name (str): Identifier for logging. + spin_buffer (float): Seconds to wake up early for the precision spin-wait (default 2ms). + """ + self.frame_rate = frame_rate + self.loop_name = loop_name + self.frame_interval = 1.0 / frame_rate if frame_rate else 0.0 + self.spin_buffer = spin_buffer + + # Timing state + self.next_target_time: float | None = None + + # Logging state + self.frames_since_print = 0 + self.last_print_time: float | None = None + + def reset(self): + """Resets the internal timers.""" + self.next_target_time = None + self.frames_since_print = 0 + self.last_print_time = None + + def __call__(self): + """Limits the loop to the target frame rate.""" + if self.frame_rate is None: + return + + now = perf_counter() + + # 1. Initialize on the very first frame + if self.next_target_time is None: + self.next_target_time = now + self.frame_interval + self.last_print_time = now + self.frames_since_print = 0 + return + + # 2. Hybrid Wait Strategy + wait_time = self.next_target_time - now + + if wait_time > 0: + # Step A: Sleep and yield CPU for the bulk of the waiting time + sleep_time = wait_time - self.spin_buffer + if sleep_time > 0: + sleep(sleep_time) + + # Step B: "Spin" for the remaining sub-millisecond precision + # This loops infinitely and hogs the CPU until the exact microsecond is reached + while perf_counter() < self.next_target_time: + pass + + # 3. Advance target time strictly by interval to prevent long-term drift + self.next_target_time += self.frame_interval + + # Anti-Spam: If the system lagged massively (e.g., loading a large file), + # fast-forward the target time so we don't try to rapidly catch up without sleeping. + now_after_wait = perf_counter() + if now_after_wait > self.next_target_time + self.frame_interval * 2: + self.next_target_time = now_after_wait + + # 4. Accurate FPS Logging + self.frames_since_print += 1 + elapsed_since_print = now_after_wait - self.last_print_time + + if elapsed_since_print > 10.0: + actual_fps = self.frames_since_print / elapsed_since_print + logger.debug(f"FPS {self.loop_name}: {actual_fps:.2f}") + self.last_print_time = now_after_wait + self.frames_since_print = 0 + + + +class SimpleFrameRateNN: + def __init__(self, frame_rate: float | None, loop_name: str = "PrecisionInterval", spin_buffer: float = 0.0015): + self.frame_rate = frame_rate + self.loop_name = loop_name + self.frame_interval = 1.0 / frame_rate if frame_rate else 0.0 + self.spin_buffer = spin_buffer + + self.t = None + self._last_print = None + self._frame_count = 0 + + def reset(self): + self.t = None + self._frame_count = 0 + + def __call__(self): + if self.frame_rate is None: + return + + now = perf_counter() + + # Initial call setup + if self.t is None: + self.t = now + self._last_print = now + return + + # 1. Calculate how much time is left for THIS frame + elapsed = now - self.t + remaining = self.frame_interval - elapsed + + if remaining > 0: + # 2. Hybrid Sleep: yield the majority of the time to the OS + if remaining > self.spin_buffer: + sleep(remaining - self.spin_buffer) + + # 3. Precision Spin: busy-wait for the last tiny fraction + target = self.t + self.frame_interval + while perf_counter() < target: + pass + + # 4. Logging logic (Average over time) + self._frame_count += 1 + curr_time = perf_counter() + if curr_time - self._last_print > 10: + fps = self._frame_count / (curr_time - self._last_print) + logger.debug(f"FPS {self.loop_name}: {fps:.2f}") + self._last_print = curr_time + self._frame_count = 0 + + # 5. Reset the stopwatch AFTER the wait + # This prevents the 'oscillating jitter' by not forcing a catch-up + self.t = perf_counter() + + class ContextManager: def __enter__(self): pass @@ -144,6 +271,11 @@ def export_episode_videos( fps: int = 30, n: int = -1, ) -> None: + import matplotlib + matplotlib.use("Agg") + import torch + from matplotlib import pyplot as plt + from torchvision.io import decode_jpeg dataset = Path(dataset) output = Path(output) output.mkdir(parents=True, exist_ok=True) From 71e0a722aacddc9bdac4487ee5bf73c9b538dea0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Thu, 21 May 2026 13:41:21 +0200 Subject: [PATCH 30/33] stash: add notes --- notes.md | 45 +++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 45 insertions(+) create mode 100644 notes.md diff --git a/notes.md b/notes.md new file mode 100644 index 00000000..79fa4b87 --- /dev/null +++ b/notes.md @@ -0,0 +1,45 @@ +```shell +# build, only if changes in cpp +docker build -f docker/Dockerfile -t rcs-dev . + + +# run docker + +docker compose -f docker/compose/dev.yml run --rm rcs +bash +export PYTHONPATH="/workspace/robot-control-stack/vlagents/src" +python examples/inference/franka.py + +``` + + +# act +```shell +python -m vlagents start-server lerobot --port 20000 --host 0.0.0.0 --kwargs '{"policy_name": "act", "checkpoint_path": "/hdd_data/juelg/duobench/weights/act/bin_sort/real/duobench_act_bin_sort_real_2026-05-18_21-54-59/150000/pretrained_model", "n_action_steps": 1}' + +python -m vlagents start-server lerobot --port 20000 --host 0.0.0.0 --kwargs '{"policy_name": "act", "checkpoint_path": "/hdd_data/juelg/duobench/weights/act/transfer_cube/duobench_act_transfer_cube_real_2026-05-18_21-55-01/150000/pretrained_model/", "n_action_steps": 1}' +``` + +# pi0 +```shell +python -m vlagents start-server lerobot --port 20000 --host 0.0.0.0 --kwargs '{"policy_name": "pi05", "checkpoint_path": "/hdd_data/juelg/duobench/weights/pi05/duobench_pi05_merged_real_v1_2026-05-19_07-14-26/040000/pretrained_model", "n_action_steps": 1}' + +python -m vlagents start-server lerobot --port 20000 --host 0.0.0.0 --kwargs '{"policy_name": "pi05", "checkpoint_path": "/hdd_data/juelg/duobench/weights/pi05/duobench_pi05_bin_sort_real_2026-05-19_22-52-01/030000/pretrained_model", "n_action_steps": 1}' +``` + + + +# xvla +```shell +python -m vlagents start-server lerobot --port 20000 --host 0.0.0.0 --kwargs '{"policy_name": "xvla", "checkpoint_path": "/hdd_data/juelg/duobench/weights/xvla/duobench_xvla_merged_real_v1_2026-05-19_17-00-27/040000/pretrained_model", "n_action_steps": 1, "rename_map": {"head": "image", "left_wrist": "image2", "right_wrist": "image3"}}' +``` + + +# tasks +## bin sort +``` +0: "pick up a box", +1: "pick up the other box with the other arm", +2: "place the box in the correct bin", +3: "task completed; both boxes are in the correct bins", +``` \ No newline at end of file From aeb75695ae47f22f91111771fd9592d56c7ee6d4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Thu, 21 May 2026 22:56:16 +0200 Subject: [PATCH 31/33] fix: left/right wrist camera bug --- examples/inference/franka.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/inference/franka.py b/examples/inference/franka.py index 20c04173..8171fe61 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -44,8 +44,8 @@ # set camera dict to none disable cameras CAMERA_DICT = { - "left_wrist": "230422272017", - "right_wrist": "230422271040", + "right_wrist": "230422272017", + "left_wrist": "230422271040", # "side": "243522070385", # "bird_eye": "243522070364", } From 2cb216984016fbdf002f6f1ac71d75a72f508951 Mon Sep 17 00:00:00 2001 From: Tobias Juelg Date: Fri, 22 May 2026 10:01:25 +0200 Subject: [PATCH 32/33] fix: docker dependency --- docker/Dockerfile | 1 + examples/inference/franka.json | 6 +-- notes.md | 71 ++++++++++++++++++++++------------ 3 files changed, 50 insertions(+), 28 deletions(-) diff --git a/docker/Dockerfile b/docker/Dockerfile index 7770f522..d40dace2 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -20,6 +20,7 @@ RUN apt-get update && apt-get install -y --no-install-recommends \ libglfw3-dev \ libpoco-dev \ ninja-build \ + liburdfdom-dev \ && rm -rf /var/lib/apt/lists/* RUN curl -LsSf https://astral.sh/uv/install.sh | sh diff --git a/examples/inference/franka.json b/examples/inference/franka.json index 7dac17c1..f14d956b 100644 --- a/examples/inference/franka.json +++ b/examples/inference/franka.json @@ -2,7 +2,7 @@ "vlagents_host": "localhost", "vlagents_port": 20000, "vlagents_model": "lerobot", - "instruction": "open the box with the right arm and place the cube inside the box with the left arm", + "instruction": "use the left arm to place the white cube in the white bowl; use the right arm to place the black cube in the black bowl", "robot_keys": [ "left", "right" @@ -10,8 +10,8 @@ "jpeg_encoding": true, "on_same_machine": false, "fps": 30, - "record_path": "inference_recordings_hinge_chest_duobench_act_hinge_chest_real_2026-05-18_21-55-00", - "n_action_steps": 100, + "record_path": "inference_recordings_bin_sort_duobench_xvla_bin_sort_real_2026-05-20_23-25-47_040000", + "n_action_steps": 30, "max_rel_mov_joints": 0.08726646259971647, "max_rel_mov_cart": [ 0.5, diff --git a/notes.md b/notes.md index 79fa4b87..33a306de 100644 --- a/notes.md +++ b/notes.md @@ -1,45 +1,66 @@ + +## robot setup +- switich on the power (socket button and foot button) +- create an ssh connection to transformer from multihead (the machine with the screen) ```shell -# build, only if changes in cpp -docker build -f docker/Dockerfile -t rcs-dev . +ssh -D 10000 transformer +``` +- go to setttings in your browser and type proxy, set manual proxy configuration and fill socks host "localhost" and port 10000 +- then open "https://192.168.101.1/" for the left, and "https://192.168.102.1/desk/" for right (our left) +- wait for the robot s to stop blinking and unlock the joints in desk +## shutdown +- press shutdown in both franka desk interfaces +- wait 2 minutes +- switch of socket and foot button +- lock the pc, dont shut it down -# run docker -docker compose -f docker/compose/dev.yml run --rm rcs -bash -export PYTHONPATH="/workspace/robot-control-stack/vlagents/src" -python examples/inference/franka.py -``` -# act +## policy server setup +- run the models outside the docker with the following commands; replace the path to match the checkpoint (make sure you run it in the following path: /code/duobench/robot-control-stack) +### act ```shell -python -m vlagents start-server lerobot --port 20000 --host 0.0.0.0 --kwargs '{"policy_name": "act", "checkpoint_path": "/hdd_data/juelg/duobench/weights/act/bin_sort/real/duobench_act_bin_sort_real_2026-05-18_21-54-59/150000/pretrained_model", "n_action_steps": 1}' - -python -m vlagents start-server lerobot --port 20000 --host 0.0.0.0 --kwargs '{"policy_name": "act", "checkpoint_path": "/hdd_data/juelg/duobench/weights/act/transfer_cube/duobench_act_transfer_cube_real_2026-05-18_21-55-01/150000/pretrained_model/", "n_action_steps": 1}' +uv run python -m vlagents start-server lerobot --port 20000 --host 0.0.0.0 --kwargs '{"policy_name": "act", "checkpoint_path": "/hdd_data/juelg/duobench/weights/act/transfer_cube/duobench_act_transfer_cube_real_2026-05-18_21-55-01/150000/pretrained_model/", "n_action_steps": 1}' ``` -# pi0 +### pi05 ```shell -python -m vlagents start-server lerobot --port 20000 --host 0.0.0.0 --kwargs '{"policy_name": "pi05", "checkpoint_path": "/hdd_data/juelg/duobench/weights/pi05/duobench_pi05_merged_real_v1_2026-05-19_07-14-26/040000/pretrained_model", "n_action_steps": 1}' - -python -m vlagents start-server lerobot --port 20000 --host 0.0.0.0 --kwargs '{"policy_name": "pi05", "checkpoint_path": "/hdd_data/juelg/duobench/weights/pi05/duobench_pi05_bin_sort_real_2026-05-19_22-52-01/030000/pretrained_model", "n_action_steps": 1}' +uv run python -m vlagents start-server lerobot --port 20000 --host 0.0.0.0 --kwargs '{"policy_name": "pi05", "checkpoint_path": "/hdd_data/juelg/duobench/weights/pi05/duobench_pi05_merged_real_v1_2026-05-19_07-14-26/040000/pretrained_model", "n_action_steps": 1}' ``` +### xvla +```shell +uv run python -m vlagents start-server lerobot --port 20000 --host 0.0.0.0 --kwargs '{"policy_name": "xvla", "checkpoint_path": "/hdd_data/juelg/duobench/weights/xvla/duobench_xvla_merged_real_v1_2026-05-20_23-32-13/040000/pretrained_model", "n_action_steps": 1, "rename_map": {"head": "image", "left_wrist": "image2", "right_wrist": "image3"}}' +``` +## docker setup -# xvla ```shell -python -m vlagents start-server lerobot --port 20000 --host 0.0.0.0 --kwargs '{"policy_name": "xvla", "checkpoint_path": "/hdd_data/juelg/duobench/weights/xvla/duobench_xvla_merged_real_v1_2026-05-19_17-00-27/040000/pretrained_model", "n_action_steps": 1, "rename_map": {"head": "image", "left_wrist": "image2", "right_wrist": "image3"}}' +exec su -l $USER +cd /code/duobench/robot-control-stack + + +# build, only once or if changes in c++ +# docker build -f docker/Dockerfile -t rcs-dev . + + +# run docker +docker compose -f docker/compose/dev.yml run --rm rcs +bash +export PYTHONPATH="/workspace/robot-control-stack/vlagents/src" + +# run the following command in the docker to start eval +python examples/inference/franka.py ``` # tasks -## bin sort -``` -0: "pick up a box", -1: "pick up the other box with the other arm", -2: "place the box in the correct bin", -3: "task completed; both boxes are in the correct bins", -``` \ No newline at end of file +- for each new model and task you need to go to the [franka.json](examples/inference/franka.json) file and adapt + - instruction: can be found in the task in [rcs_duobench/src/rcs_duobench/tasks](rcs_duobench/src/rcs_duobench/tasks) + - record_path: "inference_recordings___" + - for example: task=transfer_cube, modelpoath=duobench_xvla_merged_real_v1_2026-05-19_17-00-27, checkpoint=150000 +- run the new policy server +- start examples/inference/franka.py or press "o" if its already running \ No newline at end of file From 76a4dc0155b8d037d5377ea5599ca1e4e847f009 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Tobias=20J=C3=BClg?= Date: Fri, 22 May 2026 22:07:32 +0200 Subject: [PATCH 33/33] fix(inference): image resize method to match conversion --- examples/inference/franka.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/inference/franka.py b/examples/inference/franka.py index 8171fe61..7ba61123 100644 --- a/examples/inference/franka.py +++ b/examples/inference/franka.py @@ -170,7 +170,7 @@ def obs_rcs2agents(self, obs: dict, info: dict | None = None) -> Obs: cameras = {} for frame in obs["frames"]: cameras[frame] = obs["frames"][frame]["rgb"]["data"] - cameras[frame] = np.array(Image.fromarray(cameras[frame]).resize((224, 224), Image.Resampling.LANCZOS)) + cameras[frame] = np.array(Image.fromarray(cameras[frame]).resize((224, 224), Image.Resampling.BILINEAR)) state = [] for robot in self._cfg.robot_keys: