跳转至

同构遥操数据采集

本页对应 OpenArmX 同构双臂遥操作的 LeRobot 数据采集流程,支持重力补偿非重力补偿两种遥操模式。


🧩 硬件清单

设备 数量 说明
OpenArmX 双臂机器人(从动端) 1 台 执行端,接收遥操指令
OpenArmX 双臂机器人(主动端) 1 台 操作端,操作者拖动
RealSense D405 2 个 左右手腕相机
RealSense D435 1 个 头部相机
USB 3.0 高速拓展坞(≥3 口) 1 个 保证相机带宽
采集主机(工控机) 1 台 机器人 + 相机端
千兆路由器 + 千兆网线 各 1 双机通信(单机方案可省略)

如果采用本地服务器进行训练的话,也可以在本地服务器直接接收数据,只需要两台主机在同一 wifi 下。


⚠️ 采集前安全检查

  • 启动双臂前,确认 CAN 板已启动(蓝灯常亮)
  • 轻晃机械臂,确认电机有阻力(使能成功)
  • 远离易燃、易爆、腐蚀性危险物品
  • 采集过程中与机器人保持安全距离

1. 启动同构遥操

1.1 启动 CAN

python3 /home/openarmx/openarmx_ws/src/openarmx_motor_manager/scripts/en_all_can.py
注意:有多种启动 can 的方式,也可以使用上位机或通过命令行手动启动也可以

终端 1:启动从动端机器人

cd ~/openarmx_ws
source install/setup.bash
ros2 launch openarmx_bringup openarmx.bimanual.launch.py \
    right_can_interface:=can2 \
    left_can_interface:=can3 \
    control_mode:=mit \
    robot_controller:=forward_position_controller

终端 2:启动遥操作节点

根据实际情况选择非重力补偿重力补偿其中一种:

非重力补偿模式

主动端机械臂自重较小、拖动顺畅时使用。

cd ~/openarmx_ws
source install/setup.bash
ros2 launch openarmx_teleop_bimanual teleop_bimanual.launch.py

可选参数:

参数 默认值 说明
leader_right_can can0 主动端右臂 CAN 接口
leader_left_can can1 主动端左臂 CAN 接口
follower_right_prefix right 从动端右臂前缀
follower_left_prefix left 从动端左臂前缀
control_rate_hz 200 控制循环频率(Hz)

重力补偿模式

主动端机械臂较重、操作者拖动费力时使用,可有效降低操作疲劳。先生成 URDF,再启动节点:

cd ~/openarmx_ws
source install/setup.bash

# 步骤一:生成 URDF
xacro ./src/openarmx_description/urdf/robot/v10.urdf.xacro \
    arm_type:=v10 bimanual:=true > /tmp/v10_bimanual.urdf

# 步骤二:启动带重力补偿的遥操节点
ros2 launch openarmx_teleop_bimanual teleop_bimanual_with_gravitycomp.launch.py

可选参数:

参数 默认值 说明
leader_urdf_path /tmp/v10_bimanual.urdf URDF 文件路径
control_rate_hz 300 控制频率(Hz)
g_scale 0.9 重力补偿缩放因子
kd_damp 0.0 阻尼系数
kp_hold 0.0 位置保持刚度
vel_hold_thresh 0.02 速度保持阈值(rad/s)

模式选择: 操作者感觉拖动费力 → 重力补偿模式;拖动顺畅 → 非重力补偿模式。


2. 数据采集

终端 3:启动三相机发布

cd ~/openarmx_ws
source install/setup.bash
W=424; H=240; FPS=30
ros2 launch openarmx_lerobot camera_publisher.launch.py \
  width:=$W height:=$H fps:=$FPS \
  cam_left_serial:=左手序列号 cam_left_type:=D405 \
  cam_right_serial:=右手序列号 cam_right_type:=D405 \
  cam_head_serial:=头部序列号 cam_head_type:=D435

查询相机序列号(输出按左、中、右顺序排列,使用 Serial Number 字段,不要用 Asic Serial Number):

D405 D435
D405 D435
rs-enumerate-devices | grep "Serial Number"

注意: width/height/fps 须与后续 LeRobot 采集命令完全一致。

检查相机画面(可选)

rqt
Plugins -> Visualization -> Image View -> 添加三路相机话题

三路相机话题:/cam_left/color/image/cam_right/color/image/cam_head/color/image

终端 4:启动 LeRobot 采集

先进入 LeRobot 环境,再执行录制命令:

  • W/H/FPS 用于配置采集时的相机分辨率与帧率(例如 W=640; H=480; FPS=30)。
  • 这里的 W/H/FPS 必须与相机发布节点 camera_publisher.launch.pywidth/height/fps 完全一致。
  • 修改相机发布节点的 W/H/FPS 后,请同步将数据采集命令中的 W/H/FPS 改为一致;否则相机格式不匹配会导致报错。

🚨 关键约束:采集 W/H/FPS = 相机发布 width/height/fps 默认保存路径:~/.cache/huggingface/lerobot/local

如整批采集出现问题,删除 local 目录下同名文件夹后重新运行采集。如不删除则会报错,采集失败!

通用模板:

lerobot-env  # 进入 lerobot 环境
W=424; H=240; FPS=15
HF_HUB_OFFLINE=1 lerobot-record \
  --robot.type=openarmx_follower_ros2 \
  --robot.cameras="{cam_left: {type: ros2, image_topic: /cam_left/color/image, depth_topic: /cam_left/depth/image, use_depth: true, width: $W, height: $H, fps: $FPS}, cam_right: {type: ros2, image_topic: /cam_right/color/image, depth_topic: /cam_right/depth/image, use_depth: true, width: $W, height: $H, fps: $FPS}, cam_head: {type: ros2, image_topic: /cam_head/color/image, depth_topic: /cam_head/depth/image, use_depth: true, width: $W, height: $H, fps: $FPS}}" \
  --teleop.type=openarmx_leader_ros2 \
  --dataset.repo_id=local/你的数据名称 \
  --dataset.single_task="你执行的任务描述" \
  --dataset.num_episodes=采集的总组数 \
  --dataset.episode_time_s=每组时长秒数 \
  --dataset.reset_time_s=组间重置时长秒数 \
  --dataset.push_to_hub=false \
  --display_data=true

示例:

lerobot-env  # 进入 lerobot 环境
W=424; H=240; FPS=15
HF_HUB_OFFLINE=1 lerobot-record \
  --robot.type=openarmx_follower_ros2 \
  --robot.cameras="{cam_left: {type: ros2, image_topic: /cam_left/color/image, depth_topic: /cam_left/depth/image, use_depth: true, width: $W, height: $H, fps: $FPS}, cam_right: {type: ros2, image_topic: /cam_right/color/image, depth_topic: /cam_right/depth/image, use_depth: true, width: $W, height: $H, fps: $FPS}, cam_head: {type: ros2, image_topic: /cam_head/color/image, depth_topic: /cam_head/depth/image, use_depth: true, width: $W, height: $H, fps: $FPS}}" \
  --teleop.type=openarmx_leader_ros2 \
  --dataset.repo_id=local/act_tg_100 \
  --dataset.single_task="tg_100" \
  --dataset.num_episodes=100 \
  --dataset.episode_time_s=60 \
  --dataset.reset_time_s=6 \
  --dataset.push_to_hub=false \
  --display_data=true

⌨️ 采集快捷键

按键 操作
右方向键 结束并保存当前 episode
左方向键 丢弃当前 episode,重新录制
Esc 停止录制并退出

注意:示例中展示的单个数据采集时长是60秒,在60内完成采集任务可按 右方向键保存数据,如没有按则等到60秒后自动保存。如数据采集错误可按 左方向键丢弃当前的错误数据,但一定要在 60 秒之前丢弃数据否则错误数据将会自动保存。而且数据采集阶段是不能停止的!如数据量比较大,建议多人交替采集!


🔍 常用参数说明

参数 说明
--dataset.repo_id 数据集名称,如 local/tg_100
--dataset.single_task 任务描述文字
--dataset.num_episodes 总回合数
--dataset.episode_time_s 每回合最大时长(秒)
--dataset.reset_time_s 每回合间重置场景时长(秒)
--display_data 是否开启可视化调试
--dataset.root 自定义数据保存目录
--dataset.vcodec 视频编码器,可选 h264hevclibsvtav1

📷 相机参数参考

可用分辨率 / 帧率组合

Intel RealSense D405

分辨率 支持帧率
1280 × 720 5, 15, 30
848 × 480 5, 15, 30, 60, 90
640 × 480 5, 15, 30, 60, 90
640 × 360 5, 15, 30, 60, 90
480 × 270 5, 15, 30, 60, 90
424 × 240 5, 15, 30, 60, 90

Intel RealSense D435 / D435i

分辨率 支持帧率
1920 × 1080 6, 15, 30
1280 × 720 6, 15, 30
848 × 480 6, 15, 30, 60, 90
640 × 480 6, 15, 30, 60, 90
640 × 360 6, 15, 30, 60, 90
480 × 270 6, 15, 30, 60, 90
424 × 240 6, 15, 30, 60, 90

标配工控机 + 标配拓展坞下,三相机稳定上限为 640×480 @ 30fps。默认推荐 424×240 @ 15fps,带宽占用更低更稳定。

颜色参数调节

camera_publisher.launch.py 启动时可附加以下参数(* 替换为 cam_left / cam_right / cam_head):

参数 说明 范围 / 取值
cam_*_color_auto_exposure 自动曝光 true / false / unset
cam_*_color_exposure 手动曝光 1..10000
cam_*_color_gain 手动增益 0..128
cam_*_color_auto_white_balance 自动白平衡 true / false / unset
cam_*_color_white_balance 手动白平衡 2800..6500
cam_*_color_brightness 亮度 -64..64
cam_*_color_contrast 对比度 0..100
cam_*_color_saturation 饱和度 0..100
cam_*_color_sharpness 锐度 0..100

只写 cam_*_color_exposurecam_*_color_gain 时,launch 会自动补 cam_*_color_auto_exposure:=false;只写 cam_*_color_white_balance 时自动补 cam_*_color_auto_white_balance:=false


🧠 经验建议

  • 先小批量(10~20 组)验证整体链路,再进行长时采集,建议不少于 50 组
  • 相机 width/height/fps 在采集、训练、推理三阶段必须完全一致
  • 保持相机曝光和机位一致,减少训练分布漂移
  • 每个任务单独建 repo_id,便于后续训练与复现