LeRobot 文件
HIL-SERL 真實機器人訓練工作流指南
並獲得增強的文件體驗
開始使用
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 工作流,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
工作流程
- 執行指令碼並在解決任務所需空間內移動機器人
- 該指令碼將記錄末端執行器的最小和最大位置以及關節角度,並將它們列印到控制檯,例如
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]
- 在您的遙操作裝置配置(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)
- 將
mode
設定為"record"
- 為您的資料集指定一個唯一的
repo_id
(例如,“username/task_name”) - 將
num_episodes
設定為您想要收集的演示數量 - 初始時將
crop_params_dict
設定為null
(我們稍後會確定裁剪區域) - 配置
robot
、cameras
和其他硬體設定
配置部分示例
"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
},
用於機器人控制和回合管理的遊戲手柄按鈕對映
設定 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
在錄製期間
- 機器人將重置到配置檔案
fixed_reset_joint_positions
中定義的初始位置 - 成功完成任務
- 當您按下“成功”按鈕時,回合以獎勵為 1 結束
- 如果達到時間限制,或按下失敗按鈕,回合以獎勵為 0 結束
- 您可以透過按“重新錄製”按鈕重新錄製一個回合
- 該過程自動繼續到下一個回合
- 錄製完所有回合後,資料集將被推送到 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
- 對於每個攝像頭檢視,指令碼將顯示第一幀
- 在相關工作空間區域周圍畫一個矩形
- 按“c”鍵確認選擇
- 對所有攝像頭檢視重複此操作
- 該指令碼會輸出裁剪引數並建立一個新的裁剪過的資料集
示例輸出
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
獎勵分類器將根據機器人攝像頭的視覺輸入自動提供獎勵。
訓練獎勵分類器的工作流示例
建立配置檔案:為獎勵分類器和環境建立必要的 json 配置檔案。請檢視此處的示例。
收集資料集:
python -m lerobot.scripts.rl.gym_manipulator --config_path src/lerobot/configs/env_config.json
訓練分類器:
lerobot-train --config_path src/lerobot/configs/reward_classifier_train_config.json
測試分類器:
python -m lerobot.scripts.rl.gym_manipulator --config_path src/lerobot/configs/env_config.json
使用行動者-學習者進行訓練
LeRobot 系統使用分散式的行動者-學習者架構進行訓練。該架構將機器人互動與學習過程解耦,使它們能夠併發執行而互不阻塞。行動者伺服器處理機器人觀察和動作,將互動資料傳送給學習者伺服器。學習者伺服器執行梯度下降並定期更新行動者的策略權重。您將需要啟動兩個程序:一個學習者和一個行動者。
配置設定
建立一個訓練配置檔案(示例可在此處獲取)。訓練配置基於 lerobot/configs/train.py
中的主 TrainRLServerPipelineConfig
類。
- 配置策略設定(
type="sac"
,device
, 等) - 將
dataset
設定為您裁剪過的資料集 - 使用裁剪引數配置環境設定
- 在configuration_sac.py中檢查與 SAC 相關的其他引數。
- 驗證 `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 以收集經驗
- 將轉換髮送給學習者
- 接收更新後的策略引數
訓練流程
訓練自動進行
- 行動者在環境中執行策略
- 收集轉換併發送給學習者
- 學習者根據這些轉換更新策略
- 更新後的策略引數被髮送回行動者
- 該過程持續進行,直到達到指定的步數限制
人在環路中
- 高效學習的關鍵是有人類干預來提供糾正性反饋並完成任務,以輔助策略學習和探索。
- 要進行人類干預,您可以按遊戲手柄上的右上觸發按鈕(或鍵盤上的`空格鍵`)。這將暫停策略動作並允許您接管。
- 一個成功的實驗是,人類在開始時需要干預,但隨著策略的改進,干預的次數減少。您可以在 `wandb` 儀表板中監控干預率。
示例展示了人類干預如何隨著時間的推移幫助引導策略學習
- 該圖顯示了回合獎勵隨互動步數變化的曲線。該圖顯示了人類干預對策略學習的影響。
- 橙色曲線是沒有人類干預的實驗。而粉色和藍色曲線是有人類干預的實驗。
- 我們可以觀察到,當存在人類干預時,策略開始達到最大獎勵的步數減少了四分之一。
監控與除錯
如果您的配置中將 wandb.enable
設定為 true
,您可以透過 Weights & Biases 儀表板即時監控訓練進度。
人類干預指南
學習過程對干預策略非常敏感。需要幾次執行才能理解如何有效干預。一些技巧和提示:
- 在訓練開始時,允許策略在幾個回合內進行探索。
- 避免長時間干預。嘗試在機器人偏離軌道時介入,以糾正其行為。
- 一旦策略開始完成任務,即使不完美,您也可以將干預限制在簡單的快速動作上,如簡單的抓取命令。
理想的行為是,您的干預率應在訓練過程中逐漸下降,如下圖所示。
在拾取和舉起方塊任務的訓練執行中,干預率的曲線圖
需要調整的關鍵超引數
一些配置值對訓練的穩定性和速度有不成比例的影響
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}
}