Aloha真机训练与部署#

本章节将以松灵 Cobot Magic 机器人为例,讲解如何使用真机数据训练和部署。

数据格式转换#

松灵 Cobot Magic 机器人提供的采集脚本会将数据以 HDF5 格式保存。我们首先需要将这些数据转换为 LeRobot 数据集 v2.1 格式用于 FluxVLA 训练。

我们提供了转换脚本,可以一键将数据从HDF5转换为LeRobotv2.1格式 数据转换脚本请从项目仓库获取,详见项目 README 中的说明。


HDF5 文件应命名为 episode_*.hdf5 格式,脚本会递归搜索指定目录下的所有匹配文件。

运行前请检查HDF5文件中是否包含下列必须字段

/observations/qpos - 机器人关节位置#

  • 数据类型float32float64

  • 形状[num_frames, 14][num_frames, 16](16 维会自动转换为 14 维)

  • 关节顺序:左臂(7 个关节)+ 右臂(7 个关节)

  • 格式说明

    • 16 维格式:夹爪开合由两个夹爪的绝对位置(共 8 维)表示

    • 14 维格式:夹爪开合由归一化到 [0, 0.1] 相对位置表示

    • 转换公式gripper_value = (left_finger - right_finger) * (0.1 / 0.07)

/observations/images/<camera_name> - 相机图像#

  • 支持的相机head_cam, left_cam, right_cam

  • 格式

    • 未压缩的 4 维 numpy 数组 [num_frames, height, width, channels]uint8

    • 或 JPEG 压缩字节流 [num_frames](会自动解码为 RGB)

转换后的数据集采用 LeRobot v2.1 格式,存储在 HuggingFace Datasets 兼容的目录结构中:

<output_dir>/<repo_id>/
├── data/
│   ├── train/
│   │   ├── episode_0.parquet
│   │   └── ...
│   └── video/
│       ├── episode_0/
│       │   ├── observation.images.head_cam.mp4
│       │   └── ...
│       └── ...
├── info.json
└── meta.json

模型训练#

我们以微调Pi0.5模型为例。 首先,准备好Pi0.5预训练模型权重,或下载我们提供的pi0.5预训练权重: 请从 HuggingFace 或项目提供的下载链接获取 Pi0.5 预训练权重。

然后修改configs/pi05/pi05_paligemma_aloha_full_finetune.py中的数据集路径

    ...
    freeze_vision_backbone=False,
    pretrained_name_or_path=  # noqa: E251
    './checkpoints/pi05_base/model.safetensors' ,  # 修改预训练权重路径为实际路径
    name_mapping={
            ...

    ...
    datasets=dict(
            type='ParquetDataset',
            data_root_path=  # noqa: E251
                [
                    './datasets/RealRobot_AgileX_aloha_lerobot_v2/20250601_20250615_02_4090', 
                ],  # 修改数据集路径为实际路径
            transforms=[
                ...

最后根据机器数量设置环境变量:

单机多卡 需要根据实际GPU数量修改MLP_WORKER_GPU,然后使用 scripts/train.sh 启动训练:

export MLP_WORKER_GPU=8  #根据实际GPU数量修改
export MLP_WORKER_NUM=1
export MLP_ROLE_INDEX=0
export MLP_WORKER_0_HOST=localhost
export MLP_WORKER_0_PORT=29500
bash scripts/train.sh \
    configs/pi05/pi05_paligemma_libero10_full_finetune.py \
    work_dirs/pi05_paligemma_libero10_full_finetune # 修改为希望的训练产物保存路径

多机多卡 需要为每台机器设置环境变量:

节点 0(主节点):

export MLP_WORKER_GPU=8
export MLP_WORKER_NUM=2
export MLP_ROLE_INDEX=0
export MLP_WORKER_0_HOST={MASTER_NODE_IP}
export MLP_WORKER_0_PORT=29500

bash scripts/train.sh \
    configs/pi05/pi05_paligemma_libero10_full_finetune.py \
    work_dirs/pi05_paligemma_libero10_full_finetune

节点 1:

export MLP_WORKER_GPU=8
export MLP_WORKER_NUM=2
export MLP_ROLE_INDEX=1
export MLP_WORKER_0_HOST={MASTER_NODE_IP}
export MLP_WORKER_0_PORT=29500

bash scripts/train.sh \
    configs/pi05/pi05_paligemma_libero10_full_finetune.py \
    work_dirs/pi05_paligemma_libero10_full_finetune

真机部署#

1. 机器人上电#

  • 打开机器电源,对四个机械臂进行上电

  • 检查四个机械臂是否都亮绿灯,正常上电

2. 软件环境准备#

2.1 创建 Conda 环境#

conda create -n aloha_sdk3.0 python=3.8.19
conda activate aloha_sdk3.0

2.2 安装 Piper SDK#

git clone https://github.com/agilexrobotics/piper_sdk.git
cd piper_sdk
pip3 install .

3. 启动机械臂#

启动机械臂使能与控制节点(mode:=1 为从动模式,auto_enable:=true 自动上使能):

conda activate aloha_sdk3.0
roslaunch piper start_ms_piper.launch mode:=1 auto_enable:=true

4. 启动相机#

启动三路深度相机:

roslaunch astra_camera nmulti_camera.launch

启动完成后,通过 rostopic list 确认以下 Topic 正常发布:

相机

Color Topic

Depth Topic

点云 Topic

前方 (f)

/camera_f/color/image_raw

/camera_f/depth/image_raw

/camera_f/depth/points

手部 (h)

/camera_h/color/image_raw

/camera_h/depth/image_raw

/camera_h/depth/points

左侧 (l)

/camera_l/color/image_raw

/camera_l/depth/image_raw

/camera_l/depth/points

右侧 (r)

/camera_r/color/image_raw

/camera_r/depth/image_raw

/camera_r/depth/points

机械臂关节状态 Topic:

Topic

说明

/master/joint_left

左主臂关节状态

/master/joint_right

右主臂关节状态

/puppet/joint_left

左从臂关节状态

/puppet/joint_right

右从臂关节状态

/puppet/end_pose_left

左从臂末端位姿

/puppet/end_pose_right

右从臂末端位姿

/left_arm/trajectory

左臂轨迹指令

/right_arm/trajectory

右臂轨迹指令

/left_arm/model_trajectory

左臂模型输出轨迹

/right_arm/model_trajectory

右臂模型输出轨迹


5. 运行 FluxVLA 模型推理#

在 IDE 中通过”运行与调试”启动,或直接命令行运行:

WANDB_MODE=disabled HF_ENDPOINT=https://hf-mirror.com \
python scripts/inference_real_robot.py \
    --config configs/gr00t/gr00t_eagle_3b_aloha_fold_towel_3cam_4090_full_train.py \
    --ckpt-path ./work_dirs/work_dirs/419acaf40_gr00t_eagle_3b_aloha_fold_towel_3cam_4090_full_train_bs256/checkpoints/step-037356-epoch-06-loss=0.0617.pt

对应的 VSCode launch.json 配置:

{
    "name": "Inference gr00t eagle",
    "type": "debugpy",
    "request": "launch",
    "program": "scripts/inference_real_robot.py",
    "console": "integratedTerminal",
    "args": [
        "--config", "configs/gr00t/gr00t_eagle_3b_aloha_fold_towel_3cam_4090_full_train.py",
        "--ckpt-path", "./work_dirs/work_dirs/419acaf40_gr00t_eagle_3b_aloha_fold_towel_3cam_4090_full_train_bs256/checkpoints/step-037356-epoch-06-loss=0.0617.pt"
    ],
    "env": {
        "WANDB_MODE": "disabled",
        "HF_ENDPOINT": "https://hf-mirror.com"
    }
}

6. 机械臂复位#

任务结束或需要归零时,发送复位指令将双臂回到零位(末端夹爪保持微张 0.1):

左臂复位:

rostopic pub /master/joint_left sensor_msgs/JointState "header:
  seq: 0
  stamp: {secs: 0, nsecs: 0}
  frame_id: ''
name: ['']
position: [0,0,0,0,0,0,0.1]
velocity: [0]
effort: [0]"

右臂复位:

rostopic pub /master/joint_right sensor_msgs/JointState "header:
  seq: 0
  stamp: {secs: 0, nsecs: 0}
  frame_id: ''
name: ['']
position: [0,0,0,0,0,0,0.1]
velocity: [0]
effort: [0]"

position 中的 7 个值对应 6 个关节角度 + 1 个夹爪开合量,全部置零表示回到初始位姿,0.1 使夹爪保持微张状态。