LeRobot 文档

HIL-SERL 真实机器人训练工作流指南

Hugging Face's logo
加入 Hugging Face 社区

并获得增强的文档体验

开始使用

HIL-SERL 真实机器人训练工作流指南

在本教程中,您将使用 LeRobot 完整体验“人在环路中的样本高效强化学习”(Human-in-the-Loop Sample-Efficient Reinforcement Learning, HIL-SERL)工作流。您将掌握如何在短短几小时内在真实机器人上通过强化学习(RL)训练一个策略。

HIL-SERL 是一种样本高效的强化学习算法,它将人类演示、在线学习和人类干预相结合。该方法从少量人类演示开始,用它们训练一个奖励分类器,然后采用一个行动者-学习者(actor-learner)架构,在此架构中,人类可以在策略执行期间进行干预,以引导探索和纠正不安全的行为。在本教程中,您将使用游戏手柄进行干预并在学习过程中控制机器人。

它结合了三个关键要素:1. 离线演示与奖励分类器: 少量的人类遥操作片段加上一个基于视觉的成功检测器,为策略提供了一个有形的起点。2. 带有人类干预的机器人上行动者/学习者循环: 一个分布式的 Soft Actor Critic (SAC) 学习者更新策略,而一个行动者在实体机器人上进行探索;人类可以随时介入,以纠正危险或无效的行为。3. 安全与效率工具: 关节/末端执行器(EE)范围限制、感兴趣区域(ROI)裁剪预处理以及 WandB 监控,确保数据有效且硬件安全。

这些元素共同作用,使得 HIL-SERL 能够达到近乎完美的任务成功率,并且比纯模仿学习的基线方法有更快的周期时间。

HIL-SERL workflow

HIL-SERL 工作流,Luo 等人,2024

本指南提供了使用 LeRobot 的 HilSerl 实现来在真实机器人上训练一个机器人策略的分步说明。

我需要什么?

  • 一个游戏手柄(推荐)或键盘来控制机器人
  • 一块英伟达(Nvidia)GPU
  • 一个带有从动臂和主动臂的真实机器人(如果使用键盘或游戏手柄,则为可选)
  • 一个用于运动学包的机器人 URDF 文件(请检查 lerobot/model/kinematics.py

我可以训练什么样的任务?

您可以使用 HIL-SERL 来训练各种操作任务。一些建议:

  • 从一个简单的任务开始,以了解系统的工作原理。
    • 将方块推到目标区域
    • 用夹爪拾取并举起方块
  • 避免时间跨度极长的任务。专注于可以在 5-10 秒内完成的任务。
  • 一旦您对系统的工作方式有了很好的了解,就可以尝试更复杂的任务和更长的时间跨度。
    • 拾取并放置方块
    • 使用双臂拾取物体的双臂任务
    • 将物体从一只手臂传递到另一只手臂的交接任务
    • 尽情发挥你的想象力!

安装带 HIL-SERL 的 LeRobot

要安装带 HIL-SERL 的 LeRobot,您需要安装 hilserl 额外依赖项。

pip install -e ".[hilserl]"

真实机器人训练工作流

理解配置

训练过程始于为 HILSerl 环境进行适当的配置。需要关注的配置类是位于 lerobot/envs/configs.py 中的 HILSerlRobotEnvConfig。其定义如下

class HILSerlRobotEnvConfig(EnvConfig):
    robot: RobotConfig | None = None    # Main robot agent (defined in `lerobot/robots`)
    teleop: TeleoperatorConfig | None = None    # Teleoperator agent, e.g., gamepad or leader arm, (defined in `lerobot/teleoperators`)
    wrapper: EnvTransformConfig | None = None    # Environment wrapper settings; check `lerobot/scripts/server/gym_manipulator.py`
    fps: int = 10    # Control frequency
    name: str = "real_robot"    # Environment name
    mode: str = None    # "record", "replay", or None (for training)
    repo_id: str | None = None    # LeRobot dataset repository ID
    dataset_root: str | None = None    # Local dataset root (optional)
    task: str = ""    # Task identifier
    num_episodes: int = 10    # Number of episodes for recording
    episode: int = 0    # episode index for replay
    device: str = "cuda"    # Compute device
    push_to_hub: bool = True    # Whether to push the recorded datasets to Hub
    pretrained_policy_name_or_path: str | None = None    # For policy loading
    reward_classifier_pretrained_path: str | None = None    # For reward model
    number_of_steps_after_success: int = 0    # For reward classifier, collect more positive examples after a success to train a classifier

确定机器人工作空间边界

在收集演示数据之前,您需要确定机器人的适当操作边界。

这通过两种方式简化了在真实机器人上学习的问题:1)通过将机器人的操作空间限制在解决任务所需的特定区域,避免不必要或不安全的探索;2)通过允许在末端执行器空间而不是关节空间进行训练。经验表明,在操作任务的强化学习中,在关节空间学习通常是一个更难的问题——有些任务在关节空间几乎不可能学会,但当动作空间转换为末端执行器坐标系时则变得可学习。

使用 find_joint_limits.py

这个脚本帮助您找到机器人末端执行器的安全操作边界。如果您有一个从动臂和主动臂,您可以使用此脚本找到从动臂的边界,这些边界将在训练期间应用。限制动作空间将减少智能体的冗余探索并保证安全。

python -m lerobot.scripts.find_joint_limits \
    --robot.type=so100_follower \
    --robot.port=/dev/tty.usbmodem58760431541 \
    --robot.id=black \
    --teleop.type=so100_leader \
    --teleop.port=/dev/tty.usbmodem58760431551 \
    --teleop.id=blue

工作流程

  1. 运行脚本并在解决任务所需空间内移动机器人
  2. 该脚本将记录末端执行器的最小和最大位置以及关节角度,并将它们打印到控制台,例如
    Max ee position [0.2417 0.2012 0.1027]
    Min ee position [0.1663 -0.0823 0.0336]
    Max joint positions [-20.0, -20.0, -20.0, -20.0, -20.0, -20.0]
    Min joint positions [50.0, 50.0, 50.0, 50.0, 50.0, 50.0]
  3. 在您的遥操作设备配置(TeleoperatorConfig)的 end_effector_bounds 字段中使用这些值

配置示例

"end_effector_bounds": {
    "max": [0.24, 0.20, 0.10],
    "min": [0.16, -0.08, 0.03]
}

收集演示数据

在定义了边界后,您可以安全地收集用于训练的演示数据。使用离策略算法进行强化学习,允许我们使用收集到的离线数据集来提高学习过程的效率。

设置录制模式

创建一个用于录制演示的配置文件(或编辑一个现有的,如 env_config_so100.json

  1. mode 设置为 "record"
  2. 为您的数据集指定一个唯一的 repo_id(例如,“username/task_name”)
  3. num_episodes 设置为您想要收集的演示数量
  4. 初始时将 crop_params_dict 设置为 null(我们稍后会确定裁剪区域)
  5. 配置 robotcameras 和其他硬件设置

配置部分示例

"mode": "record",
"repo_id": "username/pick_lift_cube",
"dataset_root": null,
"task": "pick_and_lift",
"num_episodes": 15,
"episode": 0,
"push_to_hub": true

使用遥操作设备

除了您的机器人,您还需要一个遥操作设备来控制它,以便为您的任务收集数据集并在在线训练期间进行干预。我们支持使用游戏手柄、键盘或机器人的主动臂。

HIL-Serl 在机器人的末端执行器空间中学习动作。因此,遥操作将控制末端执行器的 x、y、z 位移。

为此,我们需要定义一个在末端执行器空间中执行动作的机器人版本。请查看机器人 SO100FollowerEndEffector 类及其配置 SO100FollowerEndEffectorConfig,了解与末端执行器空间相关的默认参数。

class SO100FollowerEndEffectorConfig(SO100FollowerConfig):
    """Configuration for the SO100FollowerEndEffector robot."""

    # Default bounds for the end-effector position (in meters)
    end_effector_bounds: dict[str, list[float]] = field( # bounds for the end-effector in x,y,z direction
        default_factory=lambda: {
            "min": [-1.0, -1.0, -1.0],  # min x, y, z
            "max": [1.0, 1.0, 1.0],  # max x, y, z
        }
    )

    max_gripper_pos: float = 50 # maximum gripper position that the gripper will be open at

    end_effector_step_sizes: dict[str, float] = field( # maximum step size for the end-effector in x,y,z direction
        default_factory=lambda: {
            "x": 0.02,
            "y": 0.02,
            "z": 0.02,
        }
    )

Teleoperator 定义了遥操作设备。您可以在 lerobot/teleoperators 中查看可用的遥操作设备列表。

设置游戏手柄

游戏手柄提供了一种非常方便的方式来控制机器人和回合状态。

要设置游戏手柄,您需要将 control_mode 设置为 "gamepad" 并在配置文件中定义 teleop 部分。

    "teleop": {
        "type": "gamepad",
        "use_gripper": true
    },

Figure shows the control mappings on a Logitech gamepad.

用于机器人控制和回合管理的游戏手柄按钮映射

设置 SO101 主动臂

SO101 主动臂具有减速齿轮,使其能够在探索过程中移动并跟踪从动臂。因此,接管比无齿轮的 SO100 更平滑。

要设置 SO101 主动臂,您需要将 control_mode 设置为 "leader" 并在配置文件中定义 teleop 部分。

    "teleop": {
        "type": "so101_leader",
        "port": "/dev/tty.usbmodem585A0077921", # check your port number
        "use_degrees": true
    },

为了标注回合的成功/失败,您将需要使用键盘按 s 表示成功,esc 表示失败。在在线训练期间,按 `空格键` 接管策略,再次按 `空格键` 将控制权交还给策略。

视频:SO101 主动臂遥操作

SO101 主动臂遥操作示例,主动臂跟踪从动臂,按 `空格键` 进行干预

录制演示数据

开始录制过程,配置文件示例可以在此处找到

python -m lerobot.scripts.rl.gym_manipulator --config_path src/lerobot/configs/env_config_so100.json

在录制期间

  1. 机器人将重置到配置文件 fixed_reset_joint_positions 中定义的初始位置
  2. 成功完成任务
  3. 当您按下“成功”按钮时,回合以奖励为 1 结束
  4. 如果达到时间限制,或按下失败按钮,回合以奖励为 0 结束
  5. 您可以通过按“重新录制”按钮重新录制一个回合
  6. 该过程自动继续到下一个回合
  7. 录制完所有回合后,数据集将被推送到 Hugging Face Hub(可选)并保存在本地

处理数据集

收集演示数据后,处理它们以确定最佳的摄像头裁剪区域。强化学习对背景干扰很敏感,因此将图像裁剪到相关工作空间区域非常重要。

视觉强化学习算法直接从像素输入中学习,这使得它们容易受到无关视觉信息的影响。背景元素,如变化的灯光、阴影、移动的人或工作空间外的物体,都可能干扰学习过程。好的感兴趣区域(ROI)选择应该:

  • 仅包括任务发生的基本工作空间
  • 捕捉机器人的末端执行器和任务中涉及的所有物体
  • 排除不必要的背景元素和干扰

注意:如果您已经知道裁剪参数,可以跳过此步骤,直接在录制期间的配置文件中设置 crop_params_dict

确定裁剪参数

使用 crop_dataset_roi.py 脚本以交互方式选择摄像头图像中的感兴趣区域

python -m lerobot.scripts.rl.crop_dataset_roi --repo-id username/pick_lift_cube
  1. 对于每个摄像头视图,脚本将显示第一帧
  2. 在相关工作空间区域周围画一个矩形
  3. 按“c”键确认选择
  4. 对所有摄像头视图重复此操作
  5. 该脚本会输出裁剪参数并创建一个新的裁剪过的数据集

示例输出

Selected Rectangular Regions of Interest (top, left, height, width):
observation.images.side: [180, 207, 180, 200]
observation.images.front: [180, 250, 120, 150]

用于选择感兴趣区域的交互式裁剪工具

更新配置

将这些裁剪参数添加到您的训练配置中

"crop_params_dict": {
    "observation.images.side": [180, 207, 180, 200],
    "observation.images.front": [180, 250, 120, 150]
},
"resize_size": [128, 128]

推荐的图像分辨率

大多数基于视觉的策略都在 128×128(默认)或 64×64 像素的方形输入上得到了验证。因此,我们建议将 resize_size 参数设置为 [128, 128]——或者如果您需要节省 GPU 内存和带宽,可以设置为 [64, 64]。其他分辨率也是可行的,但未经广泛测试。

训练奖励分类器

奖励分类器在 HIL-SERL 工作流程中扮演着重要角色,它通过自动化奖励分配和自动检测回合成功来发挥作用。奖励分类器学会从视觉观察中预测成功/失败,而不是手动定义奖励函数或依赖于每个时间步的人类反馈。这使得强化学习算法能够通过基于机器人摄像头输入的持续且自动化的奖励信号来高效学习。

本指南解释了如何为 LeRobot 的人在环路中的强化学习实现训练一个奖励分类器。奖励分类器学习在给定状态下预测奖励值,这可以在强化学习设置中用于训练策略。

注意:训练奖励分类器是可选的。您可以通过使用游戏手柄或键盘设备手动标注成功来开始第一轮强化学习实验。

modeling_classifier.py 中的奖励分类器实现使用预训练的视觉模型来处理图像。它可以输出用于预测成功/失败情况的二元奖励的单个值,或用于多类别设置的多个值。

为奖励分类器收集数据集

在训练之前,您需要收集一个带有标记示例的数据集。gym_manipulator.py 中的 record_dataset 函数能够收集观察、动作和奖励的数据集。

要收集数据集,您需要根据 HILSerlRobotEnvConfig 修改环境配置中的一些参数。

python -m lerobot.scripts.rl.gym_manipulator --config_path src/lerobot/configs/reward_classifier_train_config.json

数据收集的关键参数

  • mode: 设置为 "record" 以收集数据集
  • repo_id: "hf_username/dataset_name",数据集的名称和在 Hub 上的仓库
  • num_episodes: 要录制的回合数
  • number_of_steps_after_success: 检测到成功(reward=1)后要额外录制的帧数
  • fps: 每秒录制的帧数
  • push_to_hub: 是否将数据集推送到 Hub

number_of_steps_after_success 参数至关重要,因为它允许您收集更多的正例。当检测到成功时,系统将继续录制指定步数,同时保持 reward=1 的标签。否则,数据集中将没有足够标记为 1 的状态来训练一个好的分类器。

数据收集的配置部分示例

{
  "mode": "record",
  "repo_id": "hf_username/dataset_name",
  "dataset_root": "data/your_dataset",
  "num_episodes": 20,
  "push_to_hub": true,
  "fps": 10,
  "number_of_steps_after_success": 15
}

奖励分类器配置

奖励分类器使用 configuration_classifier.py 进行配置。以下是关键参数

  • model_name: 基础模型架构(例如,我们主要使用 "helper2424/resnet10"
  • model_type: "cnn""transformer"
  • num_cameras: 摄像头输入数量
  • num_classes: 输出类别数量(对于二元成功/失败通常为 2)
  • hidden_dim: 隐藏表示的大小
  • dropout_rate: 正则化参数
  • learning_rate: 优化器的学习率

训练奖励分类器的配置示例

{
  "policy": {
    "type": "reward_classifier",
    "model_name": "helper2424/resnet10",
    "model_type": "cnn",
    "num_cameras": 2,
    "num_classes": 2,
    "hidden_dim": 256,
    "dropout_rate": 0.1,
    "learning_rate": 1e-4,
    "device": "cuda",
    "use_amp": true,
    "input_features": {
      "observation.images.front": {
        "type": "VISUAL",
        "shape": [3, 128, 128]
      },
      "observation.images.side": {
        "type": "VISUAL",
        "shape": [3, 128, 128]
      }
    }
  }
}

训练分类器

要训练分类器,请使用带有您配置的 train.py 脚本

lerobot-train --config_path path/to/reward_classifier_train_config.json

部署和测试模型

要使用您训练好的奖励分类器,请配置 HILSerlRobotEnvConfig 以使用您的模型

env_config = HILSerlRobotEnvConfig(
    reward_classifier_pretrained_path="path_to_your_pretrained_trained_model",
    # Other environment parameters
)

或者在 json 配置文件中设置该参数。

{
  "reward_classifier_pretrained_path": "path_to_your_pretrained_model"
}

运行 gym_manipulator.py 来测试模型。

python -m lerobot.scripts.rl.gym_manipulator --config_path path/to/env_config.json

奖励分类器将根据机器人摄像头的视觉输入自动提供奖励。

训练奖励分类器的工作流示例

  1. 创建配置文件:为奖励分类器和环境创建必要的 json 配置文件。请查看此处的示例。

  2. 收集数据集:

    python -m lerobot.scripts.rl.gym_manipulator --config_path src/lerobot/configs/env_config.json
  3. 训练分类器:

    lerobot-train --config_path src/lerobot/configs/reward_classifier_train_config.json
  4. 测试分类器:

    python -m lerobot.scripts.rl.gym_manipulator --config_path src/lerobot/configs/env_config.json

使用行动者-学习者进行训练

LeRobot 系统使用分布式的行动者-学习者架构进行训练。该架构将机器人交互与学习过程解耦,使它们能够并发运行而互不阻塞。行动者服务器处理机器人观察和动作,将交互数据发送给学习者服务器。学习者服务器执行梯度下降并定期更新行动者的策略权重。您将需要启动两个进程:一个学习者和一个行动者。

配置设置

创建一个训练配置文件(示例可在此处获取)。训练配置基于 lerobot/configs/train.py 中的主 TrainRLServerPipelineConfig 类。

  1. 配置策略设置(type="sac", device, 等)
  2. dataset 设置为您裁剪过的数据集
  3. 使用裁剪参数配置环境设置
  4. configuration_sac.py中检查与 SAC 相关的其他参数。
  5. 验证 `policy` 配置是否正确,具有适合您任务的 `input_features` 和 `output_features`。

启动学习者

首先,启动学习者服务器进程

python -m lerobot.scripts.rl.learner --config_path src/lerobot/configs/train_config_hilserl_so100.json

学习者

  • 初始化策略网络
  • 准备回放缓冲区
  • 打开一个 gRPC 服务器与行动者通信
  • 处理转换并更新策略

启动行动者

在另一个终端中,使用相同的配置启动行动者进程

python -m lerobot.scripts.rl.actor --config_path src/lerobot/configs/train_config_hilserl_so100.json

行动者

  • 通过 gRPC 连接到学习者
  • 初始化环境
  • 执行策略的 rollout 以收集经验
  • 将转换发送给学习者
  • 接收更新后的策略参数

训练流程

训练自动进行

  1. 行动者在环境中执行策略
  2. 收集转换并发送给学习者
  3. 学习者根据这些转换更新策略
  4. 更新后的策略参数被发送回行动者
  5. 该过程持续进行,直到达到指定的步数限制

人在环路中

  • 高效学习的关键是有人类干预来提供纠正性反馈并完成任务,以辅助策略学习和探索。
  • 要进行人类干预,您可以按游戏手柄上的右上触发按钮(或键盘上的`空格键`)。这将暂停策略动作并允许您接管。
  • 一个成功的实验是,人类在开始时需要干预,但随着策略的改进,干预的次数减少。您可以在 `wandb` 仪表板中监控干预率。

Figure shows the control mappings on a Logitech gamepad.

示例展示了人类干预如何随着时间的推移帮助引导策略学习

  • 该图显示了回合奖励随交互步数变化的曲线。该图显示了人类干预对策略学习的影响。
  • 橙色曲线是没有人类干预的实验。而粉色和蓝色曲线是有人类干预的实验。
  • 我们可以观察到,当存在人类干预时,策略开始达到最大奖励的步数减少了四分之一。

监控与调试

如果您的配置中将 wandb.enable 设置为 true,您可以通过 Weights & Biases 仪表板实时监控训练进度。

人类干预指南

学习过程对干预策略非常敏感。需要几次运行才能理解如何有效干预。一些技巧和提示:

  • 在训练开始时,允许策略在几个回合内进行探索。
  • 避免长时间干预。尝试在机器人偏离轨道时介入,以纠正其行为。
  • 一旦策略开始完成任务,即使不完美,您也可以将干预限制在简单的快速动作上,如简单的抓取命令。

理想的行为是,您的干预率应在训练过程中逐渐下降,如下图所示。

Intervention rate

在拾取和举起方块任务的训练运行中,干预率的曲线图

需要调整的关键超参数

一些配置值对训练的稳定性和速度有不成比例的影响

  • temperature_init (policy.temperature_init) – SAC 中初始的熵温度。较高的值鼓励更多探索;较低的值使策略在早期更具确定性。一个好的起点是 1e-2。我们观察到,设置过高会使人类干预无效并减慢学习速度。
  • policy_parameters_push_frequency (policy.actor_learner_config.policy_parameters_push_frequency) – 从学习者到行动者两次权重推送之间的间隔,以秒为单位。默认为 4 秒。减少到 1-2 秒 可以提供更新鲜的权重(代价是更多的网络流量);仅当您的连接速度慢时才增加,因为这会降低样本效率。
  • storage_device (policy.storage_device) – 学习者保存策略参数的设备。如果您有空余的 GPU 内存,请将其设置为 "cuda"(而不是默认的 "cpu")。将权重保留在 GPU 上可以消除 CPU→GPU 的传输开销,并可以显著增加每秒的学习者更新次数。

恭喜 🎉,您已完成本教程!

如果你有任何问题或需要帮助,请在 Discord 上联系我们。

论文引用

@article{luo2024precise,
  title={Precise and Dexterous Robotic Manipulation via Human-in-the-Loop Reinforcement Learning},
  author={Luo, Jianlan and Xu, Charles and Wu, Jeffrey and Levine, Sergey},
  journal={arXiv preprint arXiv:2410.21845},
  year={2024}
}
< > 在 GitHub 上更新