This commit is contained in:
Steven Palma 2025-04-04 12:33:26 +02:00 committed by GitHub
commit e0c381ad20
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
12 changed files with 133 additions and 33 deletions

View File

@ -17,12 +17,19 @@
import argparse import argparse
import datetime as dt import datetime as dt
import os
from pathlib import Path from pathlib import Path
import cv2 import cv2
import keyboard
import rerun as rr
def display_and_save_video_stream(output_dir: Path, fps: int, width: int, height: int): def display_and_save_video_stream(output_dir: Path, fps: int, width: int, height: int):
rr.init("lerobot_capture_camera_feed")
memory_limit = os.getenv("LEROBOT_RERUN_MEMORY_LIMIT", "5%")
rr.spawn(memory_limit=memory_limit)
now = dt.datetime.now() now = dt.datetime.now()
capture_dir = output_dir / f"{now:%Y-%m-%d}" / f"{now:%H-%M-%S}" capture_dir = output_dir / f"{now:%Y-%m-%d}" / f"{now:%H-%M-%S}"
if not capture_dir.exists(): if not capture_dir.exists():
@ -45,18 +52,18 @@ def display_and_save_video_stream(output_dir: Path, fps: int, width: int, height
if not ret: if not ret:
print("Error: Could not read frame.") print("Error: Could not read frame.")
break break
rr.log("video/stream", rr.Image(frame.numpy()), static=True)
cv2.imshow("Video Stream", frame)
cv2.imwrite(str(capture_dir / f"frame_{frame_index:06d}.png"), frame) cv2.imwrite(str(capture_dir / f"frame_{frame_index:06d}.png"), frame)
frame_index += 1 frame_index += 1
# Break the loop on 'q' key press # Break the loop on 'q' key press
if cv2.waitKey(1) & 0xFF == ord("q"): if keyboard.is_pressed("q"):
break break
# Release the capture and destroy all windows # Release the capture and destroy all windows
cap.release() cap.release()
cv2.destroyAllWindows() # TODO(Steven): Find a way to close visualizer: https://github.com/rerun-io/rerun/pull/9400
# cv2.destroyAllWindows()
if __name__ == "__main__": if __name__ == "__main__":

View File

@ -491,6 +491,13 @@ python lerobot/scripts/control_robot.py \
#### a. Teleop with displaying cameras #### a. Teleop with displaying cameras
Follow [this guide to setup your cameras](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#c-add-your-cameras-with-opencvcamera). Then you will be able to display the cameras on your computer while you are teleoperating by running the following code. This is useful to prepare your setup before recording your first dataset. Follow [this guide to setup your cameras](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#c-add-your-cameras-with-opencvcamera). Then you will be able to display the cameras on your computer while you are teleoperating by running the following code. This is useful to prepare your setup before recording your first dataset.
> **NOTE:** To visualize the data, enable `--control.display_data=true`. This streams the data using `rerun`. You can adjust the viewer's behavior with these environment variables:
> - `RERUN_FLUSH_NUM_BYTES`
> - `LEROBOT_RERUN_MEMORY_LIMIT`
> - `LEROBOT_VIEWER_IP` (only for remote robots)
> - `LEROBOT_VIEWER_PORT` (only for remote robots)
```bash ```bash
python lerobot/scripts/control_robot.py \ python lerobot/scripts/control_robot.py \
--robot.type=so100 \ --robot.type=so100 \

View File

@ -412,6 +412,12 @@ python lerobot/scripts/control_robot.py \
--control.fps=30 --control.fps=30
``` ```
> **NOTE:** To visualize the data, enable `--control.display_data=true`. This streams the data using `rerun`. You can adjust the viewer's behavior with these environment variables:
> - `RERUN_FLUSH_NUM_BYTES`
> - `LEROBOT_RERUN_MEMORY_LIMIT`
> - `LEROBOT_VIEWER_IP` (only for remote robots)
> - `LEROBOT_VIEWER_PORT` (only for remote robots)
You should see on your laptop something like this: ```[INFO] Connected to remote robot at tcp://172.17.133.91:5555 and video stream at tcp://172.17.133.91:5556.``` Now you can move the leader arm and use the keyboard (w,a,s,d) to drive forward, left, backwards, right. And use (z,x) to turn left or turn right. You can use (r,f) to increase and decrease the speed of the mobile robot. There are three speed modes, see the table below: You should see on your laptop something like this: ```[INFO] Connected to remote robot at tcp://172.17.133.91:5555 and video stream at tcp://172.17.133.91:5556.``` Now you can move the leader arm and use the keyboard (w,a,s,d) to drive forward, left, backwards, right. And use (z,x) to turn left or turn right. You can use (r,f) to increase and decrease the speed of the mobile robot. There are three speed modes, see the table below:
| Speed Mode | Linear Speed (m/s) | Rotation Speed (deg/s) | | Speed Mode | Linear Speed (m/s) | Rotation Speed (deg/s) |
| ---------- | ------------------ | ---------------------- | | ---------- | ------------------ | ---------------------- |

View File

@ -212,6 +212,13 @@ python lerobot/scripts/control_robot.py \
**Teleop with displaying cameras** **Teleop with displaying cameras**
Follow [this guide to setup your cameras](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#c-add-your-cameras-with-opencvcamera). Then you will be able to display the cameras on your computer while you are teleoperating by running the following code. This is useful to prepare your setup before recording your first dataset. Follow [this guide to setup your cameras](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#c-add-your-cameras-with-opencvcamera). Then you will be able to display the cameras on your computer while you are teleoperating by running the following code. This is useful to prepare your setup before recording your first dataset.
> **NOTE:** To visualize the data, enable `--control.display_data=true`. This streams the data using `rerun`. You can adjust the viewer's behavior with these environment variables:
> - `RERUN_FLUSH_NUM_BYTES`
> - `LEROBOT_RERUN_MEMORY_LIMIT`
> - `LEROBOT_VIEWER_IP` (only for remote robots)
> - `LEROBOT_VIEWER_PORT` (only for remote robots)
```bash ```bash
python lerobot/scripts/control_robot.py \ python lerobot/scripts/control_robot.py \
--robot.type=moss \ --robot.type=moss \

View File

@ -55,6 +55,13 @@ Finally, connect both arms to your computer via USB. Note that the USB doesn't p
Now you are ready to configure your motors for the first time, as detailed in the sections below. In the upcoming sections, you'll learn about our classes and functions by running some python code in an interactive session, or by copy-pasting it in a python file. Now you are ready to configure your motors for the first time, as detailed in the sections below. In the upcoming sections, you'll learn about our classes and functions by running some python code in an interactive session, or by copy-pasting it in a python file.
If you have already configured your motors the first time, you can streamline the process by directly running the teleoperate script (which is detailed further in the tutorial): If you have already configured your motors the first time, you can streamline the process by directly running the teleoperate script (which is detailed further in the tutorial):
> **NOTE:** To visualize the data, enable `--control.display_data=true`. This streams the data using `rerun`. You can adjust the viewer's behavior with these environment variables:
> - `RERUN_FLUSH_NUM_BYTES`
> - `LEROBOT_RERUN_MEMORY_LIMIT`
> - `LEROBOT_VIEWER_IP` (only for remote robots)
> - `LEROBOT_VIEWER_PORT` (only for remote robots)
```bash ```bash
python lerobot/scripts/control_robot.py \ python lerobot/scripts/control_robot.py \
--robot.type=koch \ --robot.type=koch \

View File

@ -97,6 +97,13 @@ This is equivalent to running `stretch_robot_home.py`
Before trying teleoperation, you need activate the gamepad controller by pressing the middle button. For more info, see Stretch's [doc](https://docs.hello-robot.com/0.3/getting_started/hello_robot/#gamepad-teleoperation). Before trying teleoperation, you need activate the gamepad controller by pressing the middle button. For more info, see Stretch's [doc](https://docs.hello-robot.com/0.3/getting_started/hello_robot/#gamepad-teleoperation).
Now try out teleoperation (see above documentation to learn about the gamepad controls): Now try out teleoperation (see above documentation to learn about the gamepad controls):
> **NOTE:** To visualize the data, enable `--control.display_data=true`. This streams the data using `rerun`. You can adjust the viewer's behavior with these environment variables:
> - `RERUN_FLUSH_NUM_BYTES`
> - `LEROBOT_RERUN_MEMORY_LIMIT`
> - `LEROBOT_VIEWER_IP` (only for remote robots)
> - `LEROBOT_VIEWER_PORT` (only for remote robots)
```bash ```bash
python lerobot/scripts/control_robot.py \ python lerobot/scripts/control_robot.py \
--robot.type=stretch \ --robot.type=stretch \

View File

@ -43,6 +43,13 @@ Teleoperation consists in manually operating the leader arms to move the followe
2. Our code assumes that your robot has been assembled following Trossen Robotics instructions. This allows us to skip calibration, as we use the pre-defined calibration files in `.cache/calibration/aloha_default`. If you replace a motor, make sure you follow the exact instructions from Trossen Robotics. 2. Our code assumes that your robot has been assembled following Trossen Robotics instructions. This allows us to skip calibration, as we use the pre-defined calibration files in `.cache/calibration/aloha_default`. If you replace a motor, make sure you follow the exact instructions from Trossen Robotics.
By running the following code, you can start your first **SAFE** teleoperation: By running the following code, you can start your first **SAFE** teleoperation:
> **NOTE:** To visualize the data, enable `--control.display_data=true`. This streams the data using `rerun`. You can adjust the viewer's behavior with these environment variables:
> - `RERUN_FLUSH_NUM_BYTES`
> - `LEROBOT_RERUN_MEMORY_LIMIT`
> - `LEROBOT_VIEWER_IP` (only for remote robots)
> - `LEROBOT_VIEWER_PORT` (only for remote robots)
```bash ```bash
python lerobot/scripts/control_robot.py \ python lerobot/scripts/control_robot.py \
--robot.type=aloha \ --robot.type=aloha \

View File

@ -41,7 +41,7 @@ class TeleoperateControlConfig(ControlConfig):
fps: int | None = None fps: int | None = None
teleop_time_s: float | None = None teleop_time_s: float | None = None
# Display all cameras on screen # Display all cameras on screen
display_cameras: bool = True display_data: bool = False
@ControlConfig.register_subclass("record") @ControlConfig.register_subclass("record")
@ -82,7 +82,7 @@ class RecordControlConfig(ControlConfig):
# Not enough threads might cause low camera fps. # Not enough threads might cause low camera fps.
num_image_writer_threads_per_camera: int = 4 num_image_writer_threads_per_camera: int = 4
# Display all cameras on screen # Display all cameras on screen
display_cameras: bool = True display_data: bool = False
# Use vocal synthesis to read events. # Use vocal synthesis to read events.
play_sounds: bool = True play_sounds: bool = True
# Resume recording on an existing dataset. # Resume recording on an existing dataset.
@ -116,6 +116,8 @@ class ReplayControlConfig(ControlConfig):
@dataclass @dataclass
class RemoteRobotConfig(ControlConfig): class RemoteRobotConfig(ControlConfig):
log_interval: int = 100 log_interval: int = 100
# Display all cameras on screen
display_data: bool = False
@dataclass @dataclass

View File

@ -24,7 +24,7 @@ from contextlib import nullcontext
from copy import copy from copy import copy
from functools import cache from functools import cache
import cv2 import rerun as rr
import torch import torch
from deepdiff import DeepDiff from deepdiff import DeepDiff
from termcolor import colored from termcolor import colored
@ -174,13 +174,13 @@ def warmup_record(
events, events,
enable_teleoperation, enable_teleoperation,
warmup_time_s, warmup_time_s,
display_cameras, display_data,
fps, fps,
): ):
control_loop( control_loop(
robot=robot, robot=robot,
control_time_s=warmup_time_s, control_time_s=warmup_time_s,
display_cameras=display_cameras, display_data=display_data,
events=events, events=events,
fps=fps, fps=fps,
teleoperate=enable_teleoperation, teleoperate=enable_teleoperation,
@ -192,7 +192,7 @@ def record_episode(
dataset, dataset,
events, events,
episode_time_s, episode_time_s,
display_cameras, display_data,
policy, policy,
fps, fps,
single_task, single_task,
@ -200,7 +200,7 @@ def record_episode(
control_loop( control_loop(
robot=robot, robot=robot,
control_time_s=episode_time_s, control_time_s=episode_time_s,
display_cameras=display_cameras, display_data=display_data,
dataset=dataset, dataset=dataset,
events=events, events=events,
policy=policy, policy=policy,
@ -215,7 +215,7 @@ def control_loop(
robot, robot,
control_time_s=None, control_time_s=None,
teleoperate=False, teleoperate=False,
display_cameras=False, display_data=False,
dataset: LeRobotDataset | None = None, dataset: LeRobotDataset | None = None,
events=None, events=None,
policy: PreTrainedPolicy = None, policy: PreTrainedPolicy = None,
@ -264,11 +264,15 @@ def control_loop(
frame = {**observation, **action, "task": single_task} frame = {**observation, **action, "task": single_task}
dataset.add_frame(frame) dataset.add_frame(frame)
if display_cameras and not is_headless(): # TODO(Steven): This should be more general (for RemoteRobot instead of checking the name, but anyways it will change soon)
if (display_data and not is_headless()) or (display_data and robot.robot_type.startswith("lekiwi")):
for k, v in action.items():
for i, vv in enumerate(v):
rr.log(f"sent_{k}_{i}", rr.Scalar(vv.numpy()))
image_keys = [key for key in observation if "image" in key] image_keys = [key for key in observation if "image" in key]
for key in image_keys: for key in image_keys:
cv2.imshow(key, cv2.cvtColor(observation[key].numpy(), cv2.COLOR_RGB2BGR)) rr.log(key, rr.Image(observation[key].numpy()), static=True)
cv2.waitKey(1)
if fps is not None: if fps is not None:
dt_s = time.perf_counter() - start_loop_t dt_s = time.perf_counter() - start_loop_t
@ -297,15 +301,15 @@ def reset_environment(robot, events, reset_time_s, fps):
) )
def stop_recording(robot, listener, display_cameras): def stop_recording(robot, listener, display_data):
robot.disconnect() robot.disconnect()
if not is_headless(): if not is_headless() and listener is not None:
if listener is not None:
listener.stop() listener.stop()
if display_cameras: # TODO(Steven): Find a way to close visualizer: https://github.com/rerun-io/rerun/pull/9400
cv2.destroyAllWindows() # if display_data:
# cv2.destroyAllWindows()
def sanity_check_dataset_name(repo_id, policy_cfg): def sanity_check_dataset_name(repo_id, policy_cfg):

View File

@ -135,15 +135,19 @@ python lerobot/scripts/control_robot.py \
""" """
import logging import logging
import os
import time import time
from dataclasses import asdict from dataclasses import asdict
from pprint import pformat from pprint import pformat
import rerun as rr
# from safetensors.torch import load_file, save_file # from safetensors.torch import load_file, save_file
from lerobot.common.datasets.lerobot_dataset import LeRobotDataset from lerobot.common.datasets.lerobot_dataset import LeRobotDataset
from lerobot.common.policies.factory import make_policy from lerobot.common.policies.factory import make_policy
from lerobot.common.robot_devices.control_configs import ( from lerobot.common.robot_devices.control_configs import (
CalibrateControlConfig, CalibrateControlConfig,
ControlConfig,
ControlPipelineConfig, ControlPipelineConfig,
RecordControlConfig, RecordControlConfig,
RemoteRobotConfig, RemoteRobotConfig,
@ -153,6 +157,7 @@ from lerobot.common.robot_devices.control_configs import (
from lerobot.common.robot_devices.control_utils import ( from lerobot.common.robot_devices.control_utils import (
control_loop, control_loop,
init_keyboard_listener, init_keyboard_listener,
is_headless,
log_control_info, log_control_info,
record_episode, record_episode,
reset_environment, reset_environment,
@ -232,7 +237,7 @@ def teleoperate(robot: Robot, cfg: TeleoperateControlConfig):
control_time_s=cfg.teleop_time_s, control_time_s=cfg.teleop_time_s,
fps=cfg.fps, fps=cfg.fps,
teleoperate=True, teleoperate=True,
display_cameras=cfg.display_cameras, display_data=cfg.display_data,
) )
@ -280,7 +285,7 @@ def record(
# 3. place the cameras windows on screen # 3. place the cameras windows on screen
enable_teleoperation = policy is None enable_teleoperation = policy is None
log_say("Warmup record", cfg.play_sounds) log_say("Warmup record", cfg.play_sounds)
warmup_record(robot, events, enable_teleoperation, cfg.warmup_time_s, cfg.display_cameras, cfg.fps) warmup_record(robot, events, enable_teleoperation, cfg.warmup_time_s, cfg.display_data, cfg.fps)
if has_method(robot, "teleop_safety_stop"): if has_method(robot, "teleop_safety_stop"):
robot.teleop_safety_stop() robot.teleop_safety_stop()
@ -296,7 +301,7 @@ def record(
dataset=dataset, dataset=dataset,
events=events, events=events,
episode_time_s=cfg.episode_time_s, episode_time_s=cfg.episode_time_s,
display_cameras=cfg.display_cameras, display_data=cfg.display_data,
policy=policy, policy=policy,
fps=cfg.fps, fps=cfg.fps,
single_task=cfg.single_task, single_task=cfg.single_task,
@ -326,7 +331,7 @@ def record(
break break
log_say("Stop recording", cfg.play_sounds, blocking=True) log_say("Stop recording", cfg.play_sounds, blocking=True)
stop_recording(robot, listener, cfg.display_cameras) stop_recording(robot, listener, cfg.display_data)
if cfg.push_to_hub: if cfg.push_to_hub:
dataset.push_to_hub(tags=cfg.tags, private=cfg.private) dataset.push_to_hub(tags=cfg.tags, private=cfg.private)
@ -363,6 +368,42 @@ def replay(
log_control_info(robot, dt_s, fps=cfg.fps) log_control_info(robot, dt_s, fps=cfg.fps)
def _init_rerun(control_config: ControlConfig, session_name: str = "lerobot_control_loop") -> None:
"""Initializes the Rerun SDK for visualizing the control loop.
Args:
control_config: Configuration determining data display and robot type.
session_name: Rerun session name. Defaults to "lerobot_control_loop".
Raises:
ValueError: If viewer IP is missing for non-remote configurations with display enabled.
"""
if (control_config.display_data and not is_headless()) or (
control_config.display_data and isinstance(control_config, RemoteRobotConfig)
):
# Configure Rerun flush batch size
batch_size = os.getenv("RERUN_FLUSH_NUM_BYTES", "8000")
os.environ["RERUN_FLUSH_NUM_BYTES"] = batch_size
# Get memory limit and viewer connection parameters
memory_limit = os.getenv("LEROBOT_RERUN_MEMORY_LIMIT", "5%")
viewer_ip = os.getenv("LEROBOT_VIEWER_IP")
viewer_port = os.getenv("LEROBOT_VIEWER_PORT", "9876")
# Initialize Rerun based on configuration
rr.init(session_name)
if isinstance(control_config, RemoteRobotConfig):
if not viewer_ip:
raise ValueError(
"Viewer IP required for remote config. Set LEROBOT_VIEWER_IP "
"or disable control_config.display_data."
)
logging.info(f"Connecting to viewer at {viewer_ip}:{viewer_port}")
rr.connect_tcp(f"{viewer_ip}:{viewer_port}")
else:
rr.spawn(memory_limit=memory_limit)
@parser.wrap() @parser.wrap()
def control_robot(cfg: ControlPipelineConfig): def control_robot(cfg: ControlPipelineConfig):
init_logging() init_logging()
@ -370,17 +411,22 @@ def control_robot(cfg: ControlPipelineConfig):
robot = make_robot_from_config(cfg.robot) robot = make_robot_from_config(cfg.robot)
# TODO(Steven): Blueprint for fixed window size
if isinstance(cfg.control, CalibrateControlConfig): if isinstance(cfg.control, CalibrateControlConfig):
calibrate(robot, cfg.control) calibrate(robot, cfg.control)
elif isinstance(cfg.control, TeleoperateControlConfig): elif isinstance(cfg.control, TeleoperateControlConfig):
_init_rerun(control_config=cfg.control, session_name="lerobot_control_loop_teleop")
teleoperate(robot, cfg.control) teleoperate(robot, cfg.control)
elif isinstance(cfg.control, RecordControlConfig): elif isinstance(cfg.control, RecordControlConfig):
_init_rerun(control_config=cfg.control, session_name="lerobot_control_loop_record")
record(robot, cfg.control) record(robot, cfg.control)
elif isinstance(cfg.control, ReplayControlConfig): elif isinstance(cfg.control, ReplayControlConfig):
replay(robot, cfg.control) replay(robot, cfg.control)
elif isinstance(cfg.control, RemoteRobotConfig): elif isinstance(cfg.control, RemoteRobotConfig):
from lerobot.common.robot_devices.robots.lekiwi_remote import run_lekiwi from lerobot.common.robot_devices.robots.lekiwi_remote import run_lekiwi
_init_rerun(control_config=cfg.control, session_name="lerobot_control_loop_remote")
run_lekiwi(cfg.robot) run_lekiwi(cfg.robot)
if robot.is_connected: if robot.is_connected:

View File

@ -60,7 +60,8 @@ dependencies = [
"jsonlines>=4.0.0", "jsonlines>=4.0.0",
"numba>=0.59.0", "numba>=0.59.0",
"omegaconf>=2.3.0", "omegaconf>=2.3.0",
"opencv-python>=4.9.0", "opencv-python-headless>=4.9.0",
"keyboard>=0.13.5",
"packaging>=24.2", "packaging>=24.2",
"av>=12.0.5,<13.0.0", "av>=12.0.5,<13.0.0",
"pymunk>=6.6.0", "pymunk>=6.6.0",

View File

@ -172,8 +172,7 @@ def test_record_and_replay_and_policy(tmp_path, request, robot_type, mock):
push_to_hub=False, push_to_hub=False,
# TODO(rcadene, aliberts): test video=True # TODO(rcadene, aliberts): test video=True
video=False, video=False,
# TODO(rcadene): display cameras through cv2 sometimes crashes on mac display_data=False,
display_cameras=False,
play_sounds=False, play_sounds=False,
) )
dataset = record(robot, rec_cfg) dataset = record(robot, rec_cfg)
@ -226,7 +225,7 @@ def test_record_and_replay_and_policy(tmp_path, request, robot_type, mock):
num_episodes=2, num_episodes=2,
push_to_hub=False, push_to_hub=False,
video=False, video=False,
display_cameras=False, display_data=False,
play_sounds=False, play_sounds=False,
num_image_writer_processes=num_image_writer_processes, num_image_writer_processes=num_image_writer_processes,
) )
@ -273,7 +272,7 @@ def test_resume_record(tmp_path, request, robot_type, mock):
episode_time_s=1, episode_time_s=1,
push_to_hub=False, push_to_hub=False,
video=False, video=False,
display_cameras=False, display_data=False,
play_sounds=False, play_sounds=False,
num_episodes=1, num_episodes=1,
) )
@ -330,7 +329,7 @@ def test_record_with_event_rerecord_episode(tmp_path, request, robot_type, mock)
num_episodes=1, num_episodes=1,
push_to_hub=False, push_to_hub=False,
video=False, video=False,
display_cameras=False, display_data=False,
play_sounds=False, play_sounds=False,
) )
dataset = record(robot, rec_cfg) dataset = record(robot, rec_cfg)
@ -380,7 +379,7 @@ def test_record_with_event_exit_early(tmp_path, request, robot_type, mock):
num_episodes=1, num_episodes=1,
push_to_hub=False, push_to_hub=False,
video=False, video=False,
display_cameras=False, display_data=False,
play_sounds=False, play_sounds=False,
) )
@ -433,7 +432,7 @@ def test_record_with_event_stop_recording(tmp_path, request, robot_type, mock, n
num_episodes=2, num_episodes=2,
push_to_hub=False, push_to_hub=False,
video=False, video=False,
display_cameras=False, display_data=False,
play_sounds=False, play_sounds=False,
num_image_writer_processes=num_image_writer_processes, num_image_writer_processes=num_image_writer_processes,
) )