diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000000..a7ed8b1183 --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "i2rt"] + path = i2rt + url = https://github.com/i2rt-robotics/i2rt.git diff --git a/i2rt b/i2rt new file mode 160000 index 0000000000..f3dbf01683 --- /dev/null +++ b/i2rt @@ -0,0 +1 @@ +Subproject commit f3dbf01683f624d1a3834be0c87361f4e90dc21a diff --git a/pyproject.toml b/pyproject.toml index e58f42a373..7095e44883 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -114,6 +114,7 @@ intelrealsense = [ "pyrealsense2-macosx>=2.54,<2.55.0 ; sys_platform == 'darwin'", ] phone = ["hebi-py>=2.8.0,<2.12.0", "teleop>=0.1.0,<0.2.0", "fastapi<1.0"] +yam = ["portal>=3.7.0,<4.0.0"] # Policies pi = ["transformers @ git+https://github.com/huggingface/transformers.git@fix/lerobot_openpi"] @@ -154,6 +155,7 @@ all = [ "lerobot[reachy2]", "lerobot[kinematics]", "lerobot[intelrealsense]", + "lerobot[yam]", "lerobot[pi]", "lerobot[smolvla]", # "lerobot[groot]", TODO(Steven): Gr00t requires specific installation instructions for flash-attn diff --git a/src/lerobot/robots/__init__.py b/src/lerobot/robots/__init__.py index 1dba0f1b08..69e5e94117 100644 --- a/src/lerobot/robots/__init__.py +++ b/src/lerobot/robots/__init__.py @@ -14,6 +14,7 @@ # See the License for the specific language governing permissions and # limitations under the License. +from . import bi_yam_follower from .config import RobotConfig from .robot import Robot from .utils import make_robot_from_config diff --git a/src/lerobot/robots/bi_yam_follower/README.md b/src/lerobot/robots/bi_yam_follower/README.md new file mode 100644 index 0000000000..572696d47f --- /dev/null +++ b/src/lerobot/robots/bi_yam_follower/README.md @@ -0,0 +1,266 @@ +# Bimanual Yam Arms with LeRobot + +This guide explains how to use bimanual Yam arms with LeRobot for data collection. + +## Overview + +The bimanual Yam setup consists of: +- **2 Follower Arms**: Controlled by LeRobot to execute actions +- **2 Leader Arms**: With teaching handles for teleoperation +- **4 CAN Interfaces**: For communication with the arms + +## Hardware Setup + +### Required CAN Interfaces + +You need to set up 4 CAN interfaces with the following names: +- `can_follower_r`: Right follower arm +- `can_follower_l`: Left follower arm +- `can_leader_r`: Right leader arm (with teaching handle) +- `can_leader_l`: Left leader arm (with teaching handle) + +### CAN Interface Configuration + +For details on setting up persistent CAN interface names, see: +- `i2rt/doc/set_persist_id_socket_can.md` + +Make sure all CAN interfaces are UP and accessible: +```bash +ip link show can_follower_r +ip link show can_follower_l +ip link show can_leader_r +ip link show can_leader_l +``` + +## Software Setup + +### Install Dependencies + +**Step 1: Clone with submodules** +```bash +# If you haven't cloned yet: +git clone --recursive https://github.com/huggingface/lerobot.git + +# If you already cloned without --recursive: +git submodule update --init --recursive +``` + +**Step 2: Install i2rt library** (required for the server processes) +```bash +cd i2rt +pip install -e . +cd .. +``` + +**Step 3: Install LeRobot with Yam support** +```bash +pip install -e ".[yam]" +``` + +This will install the `portal` library for client-server communication. + +## Running the System + +### Step 1: Start the Server Processes + +Before using LeRobot, you need to start the server processes that manage the Yam arms: + +```bash +python -m lerobot.scripts.setup_bi_yam_servers +``` + +This will start 4 server processes: +- Right follower arm server: `localhost:1234` +- Left follower arm server: `localhost:1235` +- Right leader arm server: `localhost:5001` +- Left leader arm server: `localhost:5002` + +Leave this running in a terminal window. + +### Step 2: Record Data with LeRobot + +In a new terminal, use `lerobot-record` to collect data: + +```bash +lerobot-record \ + --robot.type=bi_yam_follower \ + --robot.left_arm_port=1235 \ + --robot.right_arm_port=1234 \ + --robot.cameras='{ + left: {"type": "opencv", "index_or_path": 0, "width": 640, "height": 480, "fps": 30}, + top: {"type": "opencv", "index_or_path": 1, "width": 640, "height": 480, "fps": 30}, + right: {"type": "opencv", "index_or_path": 2, "width": 640, "height": 480, "fps": 30} + }' \ + --teleop.type=bi_yam_leader \ + --teleop.left_arm_port=5002 \ + --teleop.right_arm_port=5001 \ + --dataset.repo_id=${HF_USER}/bimanual-yam-demo \ + --dataset.num_episodes=10 \ + --dataset.single_task="Pick and place the object" \ + --display_data=true +``` + +### Configuration Parameters + +#### Robot Configuration (`bi_yam_follower`) + +- `robot.type`: Set to `bi_yam_follower` +- `robot.left_arm_port`: Server port for left follower arm (default: 1235) +- `robot.right_arm_port`: Server port for right follower arm (default: 1234) +- `robot.server_host`: Server hostname (default: "localhost") +- `robot.cameras`: Camera configurations (same as other robots) +- `robot.left_arm_max_relative_target`: Optional safety limit for left arm +- `robot.right_arm_max_relative_target`: Optional safety limit for right arm + +#### Teleoperator Configuration (`bi_yam_leader`) + +- `teleop.type`: Set to `bi_yam_leader` +- `teleop.left_arm_port`: Server port for left leader arm (default: 5002) +- `teleop.right_arm_port`: Server port for right leader arm (default: 5001) +- `teleop.server_host`: Server hostname (default: "localhost") + +## Gripper Control with Teaching Handles + +The teaching handles don't have physical grippers, but they have an **encoder knob** that controls the follower gripper: + +- **Turn the encoder knob**: Controls gripper position (0 = closed, 1 = open) +- The encoder position is automatically read by the enhanced leader server +- The follower grippers will mirror your encoder movements in real-time + +The `setup_bi_yam_servers.py` script automatically uses an enhanced server for leader arms that exposes encoder data through the RPC interface. + +## Architecture + +### Data Flow + +``` +┌─────────────────┐ ┌─────────────────┐ +│ Leader Arms │ │ Follower Arms │ +│ (Teaching │ │ (Execution) │ +│ Handles) │ │ │ +└────────┬────────┘ └────────▲────────┘ + │ │ + │ Read State │ Send Actions + │ │ + ┌────▼────┐ ┌───────┴─────┐ + │ Leader │ │ Follower │ + │ Servers │ │ Servers │ + │ (5001, │ │ (1234, │ + │ 5002) │ │ 1235) │ + └────┬────┘ └───────▲─────┘ + │ │ + │ │ + ┌────▼────────────────────────────┴─────┐ + │ LeRobot Recording │ + │ - bi_yam_leader (teleoperator) │ + │ - bi_yam_follower (robot) │ + │ - Cameras │ + │ - Dataset writer │ + └───────────────────────────────────────┘ +``` + +### Server Process Details + +Each server process (started by `setup_bi_yam_servers.py`) runs a separate instance of the i2rt `minimum_gello.py` script in "follower" mode. This mode: +1. Connects to the Yam arm via CAN +2. Provides gravity compensation +3. Exposes the robot state via a portal RPC server +4. Accepts position commands (for follower arms) or just reads state (for leader arms) + +## Troubleshooting + +### CAN Interface Issues + +If you get errors about missing CAN interfaces: +```bash +# Check if interfaces exist +ip link show | grep can + +# Bring up an interface if it's down +sudo ip link set can_follower_r up +``` + +### Port Already in Use + +If you get "address already in use" errors: +```bash +# Find and kill processes using the ports +lsof -ti:1234 | xargs kill -9 +lsof -ti:1235 | xargs kill -9 +lsof -ti:5001 | xargs kill -9 +lsof -ti:5002 | xargs kill -9 +``` + +### Connection Timeouts + +If LeRobot can't connect to the servers: +1. Make sure `setup_bi_yam_servers.py` is running +2. Check that all 4 servers started successfully +3. Verify the port numbers match in both scripts + +### Slow Control Loop + +If you see warnings about slow control frequency: +- This usually means the system is overloaded +- Try reducing camera resolution or FPS +- Check CPU usage and close unnecessary applications + +## Advanced Usage + +### Custom Server Ports + +You can run the servers on different ports by modifying the `setup_bi_yam_servers.py` script or running the i2rt `minimum_gello.py` script directly for each arm: + +```bash +# Find the i2rt script location +python -c "import i2rt, os; print(os.path.dirname(i2rt.__file__))" + +# Right follower +python -m i2rt.scripts.minimum_gello \ + --can_channel can_follower_r \ + --gripper linear_4310 \ + --mode follower \ + --server_port 1234 & + +# Left follower +python -m i2rt.scripts.minimum_gello \ + --can_channel can_follower_l \ + --gripper linear_4310 \ + --mode follower \ + --server_port 1235 & + +# Right leader +python -m i2rt.scripts.minimum_gello \ + --can_channel can_leader_r \ + --gripper yam_teaching_handle \ + --mode follower \ + --server_port 5001 & + +# Left leader +python -m i2rt.scripts.minimum_gello \ + --can_channel can_leader_l \ + --gripper yam_teaching_handle \ + --mode follower \ + --server_port 5002 & +``` + +### Without Teleoperation + +You can also use the bimanual Yam follower arms with a trained policy (without teleop): + +```bash +lerobot-record \ + --robot.type=bi_yam_follower \ + --robot.left_arm_port=1235 \ + --robot.right_arm_port=1234 \ + --robot.cameras='{...}' \ + --policy.path=path/to/trained/policy \ + --dataset.repo_id=${HF_USER}/bimanual-yam-eval \ + --dataset.num_episodes=5 +``` + +## References + +- i2rt library: Python library for controlling Yam arm hardware (install via `pip install -e '.[yam]'`) +- LeRobot documentation: See main docs for training and evaluation workflows + diff --git a/src/lerobot/robots/bi_yam_follower/__init__.py b/src/lerobot/robots/bi_yam_follower/__init__.py new file mode 100644 index 0000000000..b7feb3e6ed --- /dev/null +++ b/src/lerobot/robots/bi_yam_follower/__init__.py @@ -0,0 +1,19 @@ +#!/usr/bin/env python + +# Copyright 2025 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from .bi_yam_follower import BiYamFollower +from .config_bi_yam_follower import BiYamFollowerConfig + diff --git a/src/lerobot/robots/bi_yam_follower/bi_yam_follower.py b/src/lerobot/robots/bi_yam_follower/bi_yam_follower.py new file mode 100644 index 0000000000..05fc5c3217 --- /dev/null +++ b/src/lerobot/robots/bi_yam_follower/bi_yam_follower.py @@ -0,0 +1,334 @@ +#!/usr/bin/env python + +# Copyright 2025 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import logging +import time +from functools import cached_property +from typing import Any + +import numpy as np +import portal + +from lerobot.cameras.utils import make_cameras_from_configs + +from ..robot import Robot +from .config_bi_yam_follower import BiYamFollowerConfig + +logger = logging.getLogger(__name__) + + +class YamArmClient: + """Client interface for a single Yam arm using the portal RPC framework.""" + + def __init__(self, port: int, host: str = "localhost"): + """ + Initialize the Yam arm client. + + Args: + port: Server port for the arm + host: Server host address + """ + self.port = port + self.host = host + self._client = None + + def connect(self): + """Connect to the arm server.""" + logger.info(f"Connecting to Yam arm server at {self.host}:{self.port}") + self._client = portal.Client(f"{self.host}:{self.port}") + logger.info(f"Successfully connected to Yam arm server at {self.host}:{self.port}") + + def disconnect(self): + """Disconnect from the arm server.""" + if self._client is not None: + logger.info(f"Disconnecting from Yam arm server at {self.host}:{self.port}") + self._client = None + + @property + def is_connected(self) -> bool: + """Check if the client is connected.""" + return self._client is not None + + def num_dofs(self) -> int: + """Get the number of degrees of freedom.""" + if self._client is None: + raise RuntimeError("Client not connected") + return self._client.num_dofs().result() + + def get_joint_pos(self) -> np.ndarray: + """Get current joint positions.""" + if self._client is None: + raise RuntimeError("Client not connected") + return self._client.get_joint_pos().result() + + def command_joint_pos(self, joint_pos: np.ndarray) -> None: + """Command joint positions.""" + if self._client is None: + raise RuntimeError("Client not connected") + self._client.command_joint_pos(joint_pos) + + def get_observations(self) -> dict[str, np.ndarray]: + """Get current observations including joint positions, velocities, etc.""" + if self._client is None: + raise RuntimeError("Client not connected") + return self._client.get_observations().result() + + +class BiYamFollower(Robot): + """ + Bimanual Yam Arms follower robot using the i2rt library. + + This robot controls two Yam arms simultaneously. Each arm communicates via + the portal RPC framework with servers running on different ports. + + Expected setup: + - Two Yam follower arms connected via CAN interfaces + - Server processes running for each arm (see bimanual_lead_follower.py) + - Left arm server on port 1235 (default) + - Right arm server on port 1234 (default) + """ + + config_class = BiYamFollowerConfig + name = "bi_yam_follower" + + def __init__(self, config: BiYamFollowerConfig): + super().__init__(config) + self.config = config + + # Create clients for left and right arms + self.left_arm = YamArmClient(port=config.left_arm_port, host=config.server_host) + self.right_arm = YamArmClient(port=config.right_arm_port, host=config.server_host) + + # Initialize cameras + self.cameras = make_cameras_from_configs(config.cameras) + + # Store number of DOFs (will be set after connection) + self._left_dofs = None + self._right_dofs = None + + @property + def _motors_ft(self) -> dict[str, type]: + """Define motor feature types for both arms.""" + if self._left_dofs is None or self._right_dofs is None: + # Default to 7 DOFs (6 joints + 1 gripper) per arm if not yet connected + left_dofs = 7 + right_dofs = 7 + else: + left_dofs = self._left_dofs + right_dofs = self._right_dofs + + features = {} + # Left arm joints + for i in range(left_dofs): + features[f"left_joint_{i}.pos"] = float + + # Right arm joints + for i in range(right_dofs): + features[f"right_joint_{i}.pos"] = float + + return features + + @property + def _cameras_ft(self) -> dict[str, tuple]: + """Define camera feature types.""" + return { + cam: (self.config.cameras[cam].height, self.config.cameras[cam].width, 3) for cam in self.cameras + } + + @cached_property + def observation_features(self) -> dict[str, type | tuple]: + """Return observation features including motors and cameras.""" + return {**self._motors_ft, **self._cameras_ft} + + @cached_property + def action_features(self) -> dict[str, type]: + """Return action features (motor positions).""" + return self._motors_ft + + @property + def is_connected(self) -> bool: + """Check if both arms and all cameras are connected.""" + return ( + self.left_arm.is_connected + and self.right_arm.is_connected + and all(cam.is_connected for cam in self.cameras.values()) + ) + + def connect(self, calibrate: bool = True) -> None: + """ + Connect to both arm servers and cameras. + + Args: + calibrate: Not used for Yam arms (kept for API compatibility) + """ + logger.info("Connecting to bimanual Yam follower robot") + + # Connect to arm servers + self.left_arm.connect() + self.right_arm.connect() + + # Get number of DOFs from each arm + self._left_dofs = self.left_arm.num_dofs() + self._right_dofs = self.right_arm.num_dofs() + + logger.info(f"Left arm DOFs: {self._left_dofs}, Right arm DOFs: {self._right_dofs}") + + # Connect cameras + for cam in self.cameras.values(): + cam.connect() + + logger.info("Successfully connected to bimanual Yam follower robot") + + @property + def is_calibrated(self) -> bool: + """Yam arms don't require calibration in the lerobot sense.""" + return self.is_connected + + def calibrate(self) -> None: + """Yam arms don't require calibration in the lerobot sense.""" + pass + + def configure(self) -> None: + """Configure the robot (not needed for Yam arms).""" + pass + + def setup_motors(self) -> None: + """Setup motors (not needed for Yam arms).""" + pass + + def get_observation(self) -> dict[str, Any]: + """ + Get current observation from both arms and cameras. + + Returns: + Dictionary with joint positions for both arms and camera images + """ + obs_dict = {} + + # Get left arm observations + left_obs = self.left_arm.get_observations() + left_joint_pos = left_obs["joint_pos"] + if "gripper_pos" in left_obs: + left_joint_pos = np.concatenate([left_joint_pos, left_obs["gripper_pos"]]) + + # Add with "left_" prefix + for i, pos in enumerate(left_joint_pos): + obs_dict[f"left_joint_{i}.pos"] = pos + + # Get right arm observations + right_obs = self.right_arm.get_observations() + right_joint_pos = right_obs["joint_pos"] + if "gripper_pos" in right_obs: + right_joint_pos = np.concatenate([right_joint_pos, right_obs["gripper_pos"]]) + + # Add with "right_" prefix + for i, pos in enumerate(right_joint_pos): + obs_dict[f"right_joint_{i}.pos"] = pos + + # Get camera observations + for cam_key, cam in self.cameras.items(): + start = time.perf_counter() + obs_dict[cam_key] = cam.async_read() + dt_ms = (time.perf_counter() - start) * 1e3 + logger.debug(f"{self} read {cam_key}: {dt_ms:.1f}ms") + + return obs_dict + + def send_action(self, action: dict[str, Any]) -> dict[str, Any]: + """ + Send action commands to both arms. + + Args: + action: Dictionary with joint positions for both arms + + Returns: + The action that was sent + """ + # Extract left arm actions + left_action = [] + for i in range(self._left_dofs): + key = f"left_joint_{i}.pos" + if key in action: + left_action.append(action[key]) + + # Extract right arm actions + right_action = [] + for i in range(self._right_dofs): + key = f"right_joint_{i}.pos" + if key in action: + right_action.append(action[key]) + + # Apply max_relative_target if configured + if self.config.left_arm_max_relative_target is not None: + left_current = self.left_arm.get_joint_pos() + left_action = self._clip_relative_target( + np.array(left_action), left_current, self.config.left_arm_max_relative_target + ) + + if self.config.right_arm_max_relative_target is not None: + right_current = self.right_arm.get_joint_pos() + right_action = self._clip_relative_target( + np.array(right_action), right_current, self.config.right_arm_max_relative_target + ) + + # Send commands to arms + if len(left_action) > 0: + self.left_arm.command_joint_pos(np.array(left_action)) + + if len(right_action) > 0: + self.right_arm.command_joint_pos(np.array(right_action)) + + return action + + def _clip_relative_target( + self, target: np.ndarray, current: np.ndarray, max_relative: float | dict[str, float] + ) -> np.ndarray: + """ + Clip target positions to be within max_relative distance from current position. + + Args: + target: Target joint positions + current: Current joint positions + max_relative: Maximum relative change allowed (per joint or global) + + Returns: + Clipped target positions + """ + if isinstance(max_relative, dict): + # Per-joint limits + clipped = target.copy() + for i in range(len(target)): + key = f"joint_{i}.pos" + if key in max_relative: + max_delta = max_relative[key] + clipped[i] = np.clip(target[i], current[i] - max_delta, current[i] + max_delta) + return clipped + else: + # Global limit for all joints + return np.clip(target, current - max_relative, current + max_relative) + + def disconnect(self): + """Disconnect from both arms and cameras.""" + logger.info("Disconnecting from bimanual Yam follower robot") + + self.left_arm.disconnect() + self.right_arm.disconnect() + + for cam in self.cameras.values(): + cam.disconnect() + + logger.info("Disconnected from bimanual Yam follower robot") + diff --git a/src/lerobot/robots/bi_yam_follower/config_bi_yam_follower.py b/src/lerobot/robots/bi_yam_follower/config_bi_yam_follower.py new file mode 100644 index 0000000000..0353c49830 --- /dev/null +++ b/src/lerobot/robots/bi_yam_follower/config_bi_yam_follower.py @@ -0,0 +1,42 @@ +#!/usr/bin/env python + +# Copyright 2025 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from dataclasses import dataclass, field + +from lerobot.cameras import CameraConfig + +from ..config import RobotConfig + + +@RobotConfig.register_subclass("bi_yam_follower") +@dataclass +class BiYamFollowerConfig(RobotConfig): + # Server ports for left and right arm followers + # These should match the ports in the bimanual_lead_follower.py script + # Default: 1235 for left arm, 1234 for right arm + left_arm_port: int = 1235 + right_arm_port: int = 1234 + + # Server host (usually localhost for local setup) + server_host: str = "localhost" + + # Optional: Maximum relative target for safety + left_arm_max_relative_target: float | dict[str, float] | None = None + right_arm_max_relative_target: float | dict[str, float] | None = None + + # Cameras (shared between both arms) + cameras: dict[str, CameraConfig] = field(default_factory=dict) + diff --git a/src/lerobot/scripts/lerobot_record.py b/src/lerobot/scripts/lerobot_record.py index 6df92d893b..56621d83de 100644 --- a/src/lerobot/scripts/lerobot_record.py +++ b/src/lerobot/scripts/lerobot_record.py @@ -93,6 +93,7 @@ Robot, RobotConfig, bi_so100_follower, + bi_yam_follower, hope_jr, koch_follower, make_robot_from_config, @@ -103,6 +104,7 @@ Teleoperator, TeleoperatorConfig, bi_so100_leader, + bi_yam_leader, homunculus, koch_leader, make_teleoperator_from_config, diff --git a/src/lerobot/scripts/setup_bi_yam_servers.py b/src/lerobot/scripts/setup_bi_yam_servers.py new file mode 100755 index 0000000000..21a974d295 --- /dev/null +++ b/src/lerobot/scripts/setup_bi_yam_servers.py @@ -0,0 +1,248 @@ +#!/usr/bin/env python3 +""" +Helper script to launch the bimanual Yam arm servers for use with LeRobot. + +This script starts four server processes: +- Two follower arm servers (ports 1234 and 1235) +- Two leader arm servers (ports 5001 and 5002) + +The follower servers will be controlled by LeRobot's bi_yam_follower robot. +The leader servers expose the teaching handle positions to LeRobot's bi_yam_leader teleoperator. + +Expected CAN interfaces: +- can_follower_r: Right follower arm +- can_follower_l: Left follower arm +- can_leader_r: Right leader arm (with teaching handle) +- can_leader_l: Left leader arm (with teaching handle) + +Usage: + python -m lerobot.scripts.setup_bi_yam_servers + +Requirements: + - LeRobot installed with yam support: pip install -e ".[yam]" + - i2rt library (installed automatically with the above command) + - CAN interfaces configured and available + - Proper permissions to access CAN devices +""" + +import os +import signal +import subprocess +import sys +import time + + +def check_can_interface(interface): + """Check if a CAN interface exists and is available.""" + try: + result = subprocess.run( + ["ip", "link", "show", interface], capture_output=True, text=True, check=False + ) + if result.returncode != 0: + return False + + if "state UP" in result.stdout or "state UNKNOWN" in result.stdout: + return True + else: + print(f"Warning: CAN interface {interface} exists but is not UP") + return False + + except Exception as e: + print(f"Error checking CAN interface {interface}: {e}") + return False + + +def check_all_can_interfaces(): + """Check if all required CAN interfaces exist.""" + required_interfaces = ["can_follower_r", "can_leader_r", "can_follower_l", "can_leader_l"] + + missing_interfaces = [] + + for interface in required_interfaces: + if not check_can_interface(interface): + missing_interfaces.append(interface) + + if missing_interfaces: + raise RuntimeError(f"Missing or unavailable CAN interfaces: {', '.join(missing_interfaces)}") + + print("✓ All CAN interfaces are available") + return True + + +def find_i2rt_script(): + """Find the i2rt minimum_gello.py script from the installed package.""" + try: + import i2rt + + i2rt_path = os.path.dirname(i2rt.__file__) + script_path = os.path.join(os.path.dirname(i2rt_path), "scripts", "minimum_gello.py") + if os.path.exists(script_path): + return script_path + except ImportError: + raise RuntimeError( + "Could not import i2rt. Please install it separately:\n" + " cd i2rt && pip install -e . && cd ..\n" + "Then install LeRobot: pip install -e '.[yam]'" + ) + + raise RuntimeError( + "Could not find i2rt minimum_gello.py script. " + "The i2rt installation may be incomplete." + ) + + +def launch_server_process(can_channel, gripper, mode, server_port, use_encoder_server=False): + """Launch a single server process for a Yam arm.""" + if use_encoder_server: + # Use enhanced server with encoder support for teaching handles + script_path = os.path.join( + os.path.dirname(os.path.abspath(__file__)), "yam_server_with_encoder.py" + ) + if not os.path.exists(script_path): + print(f"Error: Enhanced server script not found at {script_path}") + sys.exit(1) + else: + # Use standard i2rt server for followers + try: + script_path = find_i2rt_script() + except RuntimeError as e: + print(f"Error: {e}") + sys.exit(1) + + cmd = [ + sys.executable, + script_path, + "--can_channel", + can_channel, + "--gripper", + gripper, + "--mode", + mode, + "--server_port", + str(server_port), + ] + + server_type = "Enhanced (Encoder)" if use_encoder_server else "Standard" + print(f"Starting [{server_type}]: {' '.join(cmd)}") + + try: + process = subprocess.Popen(cmd) + return process + except Exception as e: + print(f"Error starting process for {can_channel}: {e}") + return None + + +def main(): + """Main function to launch all server processes.""" + processes = [] + + try: + # Check CAN interfaces + print("Checking CAN interfaces...") + check_all_can_interfaces() + + # Define the server processes to launch + server_configs = [ + # Right follower arm (standard server) + { + "can_channel": "can_follower_r", + "gripper": "linear_4310", + "mode": "follower", + "server_port": 1234, + "use_encoder_server": False, + }, + # Left follower arm (standard server) + { + "can_channel": "can_follower_l", + "gripper": "linear_4310", + "mode": "follower", + "server_port": 1235, + "use_encoder_server": False, + }, + # Right leader arm (enhanced server with encoder support) + { + "can_channel": "can_leader_r", + "gripper": "yam_teaching_handle", + "mode": "follower", + "server_port": 5001, + "use_encoder_server": True, # Use enhanced server for encoder data + }, + # Left leader arm (enhanced server with encoder support) + { + "can_channel": "can_leader_l", + "gripper": "yam_teaching_handle", + "mode": "follower", + "server_port": 5002, + "use_encoder_server": True, # Use enhanced server for encoder data + }, + ] + + # Launch all processes + print("\nLaunching server processes...") + for config in server_configs: + process = launch_server_process(**config) + if process: + processes.append(process) + print(f"✓ Started process {process.pid} for {config['can_channel']} on port {config['server_port']}") + else: + raise RuntimeError(f"Failed to start process for {config['can_channel']}") + + print(f"\n✓ Successfully launched {len(processes)} server processes") + print("\nServer setup:") + print(" - Right follower arm: localhost:1234") + print(" - Left follower arm: localhost:1235") + print(" - Right leader arm: localhost:5001") + print(" - Left leader arm: localhost:5002") + print("\nYou can now use lerobot-record with:") + print(" --robot.type=bi_yam_follower") + print(" --teleop.type=bi_yam_leader") + print("\nPress Ctrl+C to stop all server processes") + + # Wait for processes and handle termination + try: + while True: + # Check if any process has died + for i, process in enumerate(processes): + if process.poll() is not None: + print(f"\nProcess {process.pid} has terminated") + processes.pop(i) + break + + if not processes: + print("All processes have terminated") + break + + time.sleep(1) + + except KeyboardInterrupt: + print("\n\nReceived Ctrl+C, terminating all server processes...") + + except Exception as e: + print(f"Error: {e}") + sys.exit(1) + + finally: + # Clean up: terminate all running processes + for process in processes: + try: + print(f"Terminating process {process.pid}...") + process.terminate() + + # Wait up to 5 seconds for graceful termination + try: + process.wait(timeout=5) + except subprocess.TimeoutExpired: + print(f"Force killing process {process.pid}...") + process.kill() + process.wait() + + except Exception as e: + print(f"Error terminating process {process.pid}: {e}") + + print("All server processes terminated") + + +if __name__ == "__main__": + main() + diff --git a/src/lerobot/scripts/yam_server_with_encoder.py b/src/lerobot/scripts/yam_server_with_encoder.py new file mode 100755 index 0000000000..728099980f --- /dev/null +++ b/src/lerobot/scripts/yam_server_with_encoder.py @@ -0,0 +1,166 @@ +#!/usr/bin/env python3 +""" +Enhanced Yam arm server that exposes encoder data for teaching handles. + +This script wraps the i2rt robot to expose encoder button states through +the portal RPC interface, allowing LeRobot to read gripper commands from +the teaching handle. + +Based on i2rt's minimum_gello.py but with encoder support. +""" + +import time +from dataclasses import dataclass +from typing import Dict, Literal + +import numpy as np +import portal +import tyro + +from i2rt.robots.get_robot import get_yam_robot +from i2rt.robots.motor_chain_robot import MotorChainRobot +from i2rt.robots.robot import Robot +from i2rt.robots.utils import GripperType + +DEFAULT_ROBOT_PORT = 11333 + + +class EnhancedYamRobot(Robot): + """ + Wrapper around MotorChainRobot that exposes encoder data. + + For teaching handles, reads encoder position and button states + to provide gripper control information. + """ + + def __init__(self, robot: MotorChainRobot, is_teaching_handle: bool = False): + self._robot = robot + self._motor_chain = robot.motor_chain + self._is_teaching_handle = is_teaching_handle + + def num_dofs(self) -> int: + """Get the number of joints in the robot.""" + return self._robot.num_dofs() + + def get_joint_pos(self) -> np.ndarray: + """Get the current joint positions.""" + joint_pos = self._robot.get_joint_pos() + + # For teaching handles, add gripper state from encoder + if self._is_teaching_handle: + try: + encoder_states = self._motor_chain.get_same_bus_device_states() + if encoder_states and len(encoder_states) > 0: + # Encoder position mapped to gripper (0=closed, 1=open) + gripper_pos = 1 - encoder_states[0].position + joint_pos = np.concatenate([joint_pos, [gripper_pos]]) + except Exception as e: + print(f"Warning: Could not read encoder state: {e}") + # Fallback to default open position + joint_pos = np.concatenate([joint_pos, [1.0]]) + + return joint_pos + + def command_joint_pos(self, joint_pos: np.ndarray) -> None: + """Command the robot to a given joint position.""" + # For teaching handles, ignore gripper command if included + if self._is_teaching_handle and len(joint_pos) > self._robot.num_dofs(): + joint_pos = joint_pos[: self._robot.num_dofs()] + + self._robot.command_joint_pos(joint_pos) + + def command_joint_state(self, joint_state: Dict[str, np.ndarray]) -> None: + """Command the robot to a given state.""" + self._robot.command_joint_state(joint_state) + + def get_observations(self) -> Dict[str, np.ndarray]: + """ + Get the current observations of the robot. + + For teaching handles, includes encoder data: + - joint_pos: 6 joint positions + - gripper_pos: Encoder position mapped to gripper (0=closed, 1=open) + - io_inputs: Button states from encoder + """ + obs = self._robot.get_observations() + + # For teaching handles, add encoder data + if self._is_teaching_handle: + try: + encoder_states = self._motor_chain.get_same_bus_device_states() + if encoder_states and len(encoder_states) > 0: + # Add gripper position from encoder + gripper_pos = 1 - encoder_states[0].position + obs["gripper_pos"] = np.array([gripper_pos]) + + # Add button states + obs["io_inputs"] = encoder_states[0].io_inputs + except Exception as e: + print(f"Warning: Could not read encoder state: {e}") + # Provide defaults + obs["gripper_pos"] = np.array([1.0]) + obs["io_inputs"] = np.array([0.0]) + + return obs + + +class ServerRobot: + """A simple server for a robot.""" + + def __init__(self, robot: Robot, port: int): + self._robot = robot + self._server = portal.Server(port) + print(f"Enhanced Robot Server Binding to {port}, Robot: {robot}") + + self._server.bind("num_dofs", self._robot.num_dofs) + self._server.bind("get_joint_pos", self._robot.get_joint_pos) + self._server.bind("command_joint_pos", self._robot.command_joint_pos) + self._server.bind("command_joint_state", self._robot.command_joint_state) + self._server.bind("get_observations", self._robot.get_observations) + + def serve(self) -> None: + """Serve the robot.""" + self._server.start() + + +@dataclass +class Args: + gripper: Literal["crank_4310", "linear_3507", "linear_4310", "yam_teaching_handle", "no_gripper"] = ( + "yam_teaching_handle" + ) + mode: Literal["follower", "leader"] = "follower" + server_host: str = "localhost" + server_port: int = DEFAULT_ROBOT_PORT + can_channel: str = "can0" + + +def main(args: Args) -> None: + """Main function to start the enhanced Yam server.""" + gripper_type = GripperType.from_string_name(args.gripper) + is_teaching_handle = gripper_type == GripperType.YAM_TEACHING_HANDLE + + # Get the base robot from i2rt + base_robot = get_yam_robot(channel=args.can_channel, gripper_type=gripper_type) + + # Wrap it with encoder support + robot = EnhancedYamRobot(base_robot, is_teaching_handle=is_teaching_handle) + + # Start the server + server_robot = ServerRobot(robot, args.server_port) + + print(f"\n{'='*60}") + print(f"Enhanced Yam Server Started") + print(f" CAN Channel: {args.can_channel}") + print(f" Gripper Type: {args.gripper}") + print(f" Teaching Handle: {is_teaching_handle}") + print(f" Port: {args.server_port}") + if is_teaching_handle: + print(f" Encoder Support: ENABLED ✓") + print(f"{'='*60}\n") + + server_robot.serve() + + +if __name__ == "__main__": + main(tyro.cli(Args)) + diff --git a/src/lerobot/teleoperators/__init__.py b/src/lerobot/teleoperators/__init__.py index ee508dddb3..95673c53b3 100644 --- a/src/lerobot/teleoperators/__init__.py +++ b/src/lerobot/teleoperators/__init__.py @@ -14,6 +14,7 @@ # See the License for the specific language governing permissions and # limitations under the License. +from . import bi_yam_leader from .config import TeleoperatorConfig from .teleoperator import Teleoperator from .utils import TeleopEvents, make_teleoperator_from_config diff --git a/src/lerobot/teleoperators/bi_yam_leader/__init__.py b/src/lerobot/teleoperators/bi_yam_leader/__init__.py new file mode 100644 index 0000000000..10d12454cf --- /dev/null +++ b/src/lerobot/teleoperators/bi_yam_leader/__init__.py @@ -0,0 +1,19 @@ +#!/usr/bin/env python + +# Copyright 2025 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from .bi_yam_leader import BiYamLeader +from .config_bi_yam_leader import BiYamLeaderConfig + diff --git a/src/lerobot/teleoperators/bi_yam_leader/bi_yam_leader.py b/src/lerobot/teleoperators/bi_yam_leader/bi_yam_leader.py new file mode 100644 index 0000000000..88b604c75a --- /dev/null +++ b/src/lerobot/teleoperators/bi_yam_leader/bi_yam_leader.py @@ -0,0 +1,268 @@ +#!/usr/bin/env python + +# Copyright 2025 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import logging +from functools import cached_property + +import numpy as np +import portal + +from ..teleoperator import Teleoperator +from .config_bi_yam_leader import BiYamLeaderConfig + +logger = logging.getLogger(__name__) + + +class YamLeaderClient: + """Client interface for a single Yam leader arm using the portal RPC framework.""" + + def __init__(self, port: int, host: str = "localhost"): + """ + Initialize the Yam leader arm client. + + Args: + port: Server port for the leader arm + host: Server host address + """ + self.port = port + self.host = host + self._client = None + + def connect(self): + """Connect to the leader arm server.""" + logger.info(f"Connecting to Yam leader arm server at {self.host}:{self.port}") + self._client = portal.Client(f"{self.host}:{self.port}") + logger.info(f"Successfully connected to Yam leader arm server at {self.host}:{self.port}") + + def disconnect(self): + """Disconnect from the leader arm server.""" + if self._client is not None: + logger.info(f"Disconnecting from Yam leader arm server at {self.host}:{self.port}") + self._client = None + + @property + def is_connected(self) -> bool: + """Check if the client is connected.""" + return self._client is not None + + def num_dofs(self) -> int: + """Get the number of degrees of freedom.""" + if self._client is None: + raise RuntimeError("Client not connected") + return self._client.num_dofs().result() + + def get_joint_pos(self) -> np.ndarray: + """Get current joint positions from the leader arm.""" + if self._client is None: + raise RuntimeError("Client not connected") + return self._client.get_joint_pos().result() + + def get_observations(self) -> dict[str, np.ndarray]: + """Get current observations including joint positions, velocities, etc.""" + if self._client is None: + raise RuntimeError("Client not connected") + return self._client.get_observations().result() + + def get_gripper_from_encoder(self) -> float: + """ + Try to get gripper state from teaching handle encoder button. + Returns a value between 0 (closed) and 1 (open). + Falls back to 1.0 (open) if not available. + """ + if self._client is None: + raise RuntimeError("Client not connected") + try: + # Try to get encoder state if the server exposes it + # This requires custom method in the i2rt server + obs = self._client.get_observations().result() + # Check if encoder button data is available in observations + # The encoder button state might be in io_inputs or similar field + if "io_inputs" in obs: + # Button pressed = closed gripper (0), not pressed = open (1) + return 0.0 if obs["io_inputs"][0] > 0.5 else 1.0 + return 1.0 # Default to open if no encoder data + except Exception: + return 1.0 # Default to open on any error + + +class BiYamLeader(Teleoperator): + """ + Bimanual Yam Arms leader (teleoperator) using the i2rt library. + + This teleoperator reads joint positions from two Yam leader arms (with teaching handles) + and provides them as actions for the follower robot. + + Expected setup: + - Two Yam leader arms connected via CAN interfaces with teaching handles + - Server processes running for each leader arm in read-only mode + - Left leader arm server on port 5002 (default) + - Right leader arm server on port 5001 (default) + + Note: You'll need to run separate server processes for the leader arms. + You can modify the i2rt minimum_gello.py script to create read-only + servers that just expose the leader arm state without trying to control + a follower. + """ + + config_class = BiYamLeaderConfig + name = "bi_yam_leader" + + def __init__(self, config: BiYamLeaderConfig): + super().__init__(config) + self.config = config + + # Create clients for left and right leader arms + self.left_arm = YamLeaderClient(port=config.left_arm_port, host=config.server_host) + self.right_arm = YamLeaderClient(port=config.right_arm_port, host=config.server_host) + + # Store number of DOFs (will be set after connection) + self._left_dofs = None + self._right_dofs = None + + @cached_property + def action_features(self) -> dict[str, type]: + """Define action features for both arms.""" + if self._left_dofs is None or self._right_dofs is None: + # Default to 7 DOFs (6 joints + 1 gripper) per arm if not yet connected + left_dofs = 7 + right_dofs = 7 + else: + left_dofs = self._left_dofs + right_dofs = self._right_dofs + + features = {} + # Left arm joints + for i in range(left_dofs): + features[f"left_joint_{i}.pos"] = float + + # Right arm joints + for i in range(right_dofs): + features[f"right_joint_{i}.pos"] = float + + return features + + @cached_property + def feedback_features(self) -> dict[str, type]: + """Yam leader arms don't support feedback.""" + return {} + + @property + def is_connected(self) -> bool: + """Check if both leader arms are connected.""" + return self.left_arm.is_connected and self.right_arm.is_connected + + def connect(self, calibrate: bool = True) -> None: + """ + Connect to both leader arm servers. + + Args: + calibrate: Not used for Yam arms (kept for API compatibility) + """ + logger.info("Connecting to bimanual Yam leader arms") + + # Connect to leader arm servers + self.left_arm.connect() + self.right_arm.connect() + + # Get number of DOFs from each arm + self._left_dofs = self.left_arm.num_dofs() + self._right_dofs = self.right_arm.num_dofs() + + logger.info(f"Left leader arm DOFs: {self._left_dofs}, Right leader arm DOFs: {self._right_dofs}") + logger.info("Successfully connected to bimanual Yam leader arms") + + @property + def is_calibrated(self) -> bool: + """Yam leader arms don't require calibration in the lerobot sense.""" + return self.is_connected + + def calibrate(self) -> None: + """Yam leader arms don't require calibration in the lerobot sense.""" + pass + + def configure(self) -> None: + """Configure the teleoperator (not needed for Yam leader arms).""" + pass + + def setup_motors(self) -> None: + """Setup motors (not needed for Yam leader arms).""" + pass + + def get_action(self) -> dict[str, float]: + """ + Get action from both leader arms by reading their current joint positions. + + For teaching handles (no physical gripper), we try to read encoder button state + to control the gripper, falling back to fully open if not available. + + Returns: + Dictionary with joint positions for both arms (including gripper) + """ + action_dict = {} + + # Get left arm observations + left_obs = self.left_arm.get_observations() + left_joint_pos = left_obs["joint_pos"] + + # Handle gripper: either from physical gripper or teaching handle encoder + if "gripper_pos" in left_obs: + left_joint_pos = np.concatenate([left_joint_pos, left_obs["gripper_pos"]]) + else: + # Teaching handle: try to get gripper from encoder button + left_gripper = self.left_arm.get_gripper_from_encoder() + left_joint_pos = np.concatenate([left_joint_pos, [left_gripper]]) + + # Add with "left_" prefix + for i, pos in enumerate(left_joint_pos): + action_dict[f"left_joint_{i}.pos"] = float(pos) + + # Get right arm observations + right_obs = self.right_arm.get_observations() + right_joint_pos = right_obs["joint_pos"] + + # Handle gripper: either from physical gripper or teaching handle encoder + if "gripper_pos" in right_obs: + right_joint_pos = np.concatenate([right_joint_pos, right_obs["gripper_pos"]]) + else: + # Teaching handle: try to get gripper from encoder button + right_gripper = self.right_arm.get_gripper_from_encoder() + right_joint_pos = np.concatenate([right_joint_pos, [right_gripper]]) + + # Add with "right_" prefix + for i, pos in enumerate(right_joint_pos): + action_dict[f"right_joint_{i}.pos"] = float(pos) + + return action_dict + + def send_feedback(self, feedback: dict[str, float]) -> None: + """ + Send feedback to leader arms (not supported for Yam teaching handles). + + Args: + feedback: Dictionary with feedback values (ignored) + """ + # Yam teaching handles are passive devices and don't support feedback + pass + + def disconnect(self) -> None: + """Disconnect from both leader arms.""" + logger.info("Disconnecting from bimanual Yam leader arms") + + self.left_arm.disconnect() + self.right_arm.disconnect() + + logger.info("Disconnected from bimanual Yam leader arms") + diff --git a/src/lerobot/teleoperators/bi_yam_leader/config_bi_yam_leader.py b/src/lerobot/teleoperators/bi_yam_leader/config_bi_yam_leader.py new file mode 100644 index 0000000000..68565313c2 --- /dev/null +++ b/src/lerobot/teleoperators/bi_yam_leader/config_bi_yam_leader.py @@ -0,0 +1,34 @@ +#!/usr/bin/env python + +# Copyright 2025 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from dataclasses import dataclass + +from ..config import TeleoperatorConfig + + +@TeleoperatorConfig.register_subclass("bi_yam_leader") +@dataclass +class BiYamLeaderConfig(TeleoperatorConfig): + # Server ports for left and right arm leaders + # These should be different from the follower ports + # Note: You'll need to run separate server processes for the leader arms + # that expose their state for reading (see i2rt minimum_gello.py) + left_arm_port: int = 5002 + right_arm_port: int = 5001 + + # Server host (usually localhost for local setup) + server_host: str = "localhost" + diff --git a/src/lerobot/utils/control_utils.py b/src/lerobot/utils/control_utils.py index 7cfe177ef8..aca4a13563 100644 --- a/src/lerobot/utils/control_utils.py +++ b/src/lerobot/utils/control_utils.py @@ -18,6 +18,7 @@ import logging +import threading import traceback from contextlib import nullcontext from copy import copy @@ -131,6 +132,8 @@ def init_keyboard_listener(): # Allow to exit early while recording an episode or resetting the environment, # by tapping the right arrow key '->'. This might require a sudo permission # to allow your terminal to monitor keyboard events. + # Initialize simple text-based keyboard listener to avoid sudo permission issues. + # Uses input() in a background thread - no special permissions required. events = {} events["exit_early"] = False events["rerecord_episode"] = False @@ -143,27 +146,42 @@ def init_keyboard_listener(): listener = None return listener, events - # Only import pynput if not in a headless environment - from pynput import keyboard + print("Text-based keyboard controls enabled:") + print(" 'n' + Enter: Next/forward command (simulate right arrow) - Exit current loop") + print(" 'b' + Enter: Back command (simulate left arrow) - Re-record episode") + print(" 's' + Enter: Stop recording completely") - def on_press(key): + def input_listener(): try: - if key == keyboard.Key.right: - print("Right arrow key pressed. Exiting loop...") - events["exit_early"] = True - elif key == keyboard.Key.left: - print("Left arrow key pressed. Exiting loop and rerecord the last episode...") - events["rerecord_episode"] = True - events["exit_early"] = True - elif key == keyboard.Key.esc: - print("Escape key pressed. Stopping data recording...") - events["stop_recording"] = True - events["exit_early"] = True + while not events["stop_recording"]: + try: + user_input = input().strip().lower() + if user_input == 'n': + print("Next/forward command received. Exiting loop...") + events["exit_early"] = True + elif user_input == 'b': + print("Back command received. Exiting loop and re-record episode...") + events["rerecord_episode"] = True + events["exit_early"] = True + elif user_input == 's': + print("Stop command received. Stopping data recording...") + events["stop_recording"] = True + events["exit_early"] = True + except EOFError: + # Handle case where input is not available (e.g., piped input) + break except Exception as e: - print(f"Error handling key press: {e}") + logging.debug(f"Input listener error: {e}") - listener = keyboard.Listener(on_press=on_press) - listener.start() + input_thread = threading.Thread(target=input_listener, daemon=True) + input_thread.start() + + # Return a simple object to maintain compatibility + class SimpleListener: + def stop(self): + events["stop_recording"] = True + + listener = SimpleListener() return listener, events