Tron2真机部署#
在Tron2真机上,通过FluxVLA进行模型推理部署。本文档说明如何在Tron2真实机器人上进行FluxVLA的部署与推理。
Tron2 Infra#
场景配置与建议#
场景参考:

头部相机角度#
将头部相机角度向下
mrostopic pub /move_cmd std_msgs/Float32MultiArray '{"layout":{"dim":[],"data_offset":0},"data":[2,3,1.0567,-0.0139998]}'
桌子高度与角度#
支架与桌子相隔距离一瓶半矿泉水,桌子边缘应与机器人支架形成垂线
桌子高度为75cm
硬件准备#
支架固定#
将四个旋钮拧紧,使其撑住地面

排线#
网线连接上网口,IP :
{TRON2_IP}三相机均通过10Gb/s拓展坞连接在本地主机
物理环境#
推理环境要求#
按照官方教程安装ROS1
前文配置的Conda环境
按照TRON2官方SDK开发教程TRON 2 SDK 开发指南安装运动控制开发库
git clone https://github.com/limxdynamics/limxsdk-lowlevel.git
pip install limxsdk-lowlevel/python3/amd64/limxsdk-*-py3-none-any.whl
安装realsense SDK和realsense-ros 包
https://github.com/IntelRealSense/librealsense/blob/master/doc/distribution_linux.md
https://github.com/rjwb1/realsense-ros
安装其他依赖
pip install websocket-client
sudo apt install net-tools
相机节点#
将三个相机连在本地主机上(非机器人板卡),直接运行. 会自动检查序列号.
Publishers:(主要用到)
camer0/color/image_raw
camer1/color/image_raw
camer2/color/image_raw
代码:
python tron2_infra/
#!/bin/bash
#source /opt/ros/noetic/setup.bash
# source {ROS_WORKSPACE}/devel/setup.bash
# export ROS_IP={TRON2_ROS_IP}
# Function to detect connected RealSense cameras
detect_cameras() {
# List all connected RealSense cameras, excluding Asic Serial Number
serial_numbers=($(rs-enumerate-devices | grep "Serial Number" | grep -v "Asic" | awk '{print $NF}'))
echo "${serial_numbers[@]}"
}
# Loop to check for the launch flag file and connected cameras
while true; do
serial_numbers=($(detect_cameras))
# Check if any cameras were found
if [ ${#serial_numbers[@]} -gt 0 ]; then
echo "Detected ${#serial_numbers[@]} cameras."
break # Exit the loop if cameras are detected
else
echo "No RealSense cameras detected. Retrying in 5 seconds..."
sleep 5 # Wait for a while before retrying
fi
done
# Automatically start a ROS node for each detected camera
if [ ${#serial_numbers[@]} -gt 0 ]; then
for i in "${!serial_numbers[@]}"; do
serial=${serial_numbers[$i]}
echo "Starting ROS node for camera $serial..."
# roslaunch realsense2_camera rs_camera.launch serial_no:=$serial camera:=camera$i enable_pointcloud:=True enable_accel:=True enable_gyro:=True enable_sync:=True unite_imu_method:=linear_interpolation &
roslaunch realsense2_camera rs_camera.launch serial_no:=$serial camera:=camera$i align_depth:=True color_width:=640 color_height:=480 color_fps:=30 &
sleep 10 # Optional: wait a bit before starting the next camera
done
# Wait for all background processes to finish
wait
else
echo "No cameras to start."
fi
Tips: 这里的相机序列号由你插入的相机usb顺序决定,因此相机话题的命名可能与相机流不是每次都对应.所以每次启动相机节点后要用rqt_image_view进行察看. 后续有问题请联系公司产品和软件组.
状态节点#
创建状态节点,实时订阅机器人状态.
Publishers:
/joint_states/left_arm
/joint_states/right_arm
/joint_states/head
python tron2_infra/tron2_state_rostopic.py
控制节点#
提供servoJ / moveJ接口,可以进行连续控制或单点位置控制
指定robot accid, 保证机器人型号与指定accid对应
python tron2_infra/tron2_control_rostopic.py
头部控制#
将Tron2的头部云台向下:
ssh {USER}@{TRON2_IP}
进入后输入:
mrostopic pub /move_cmd std_msgs/Float32MultiArray '{"layout":{"dim":[],"data_offset":0},"data":[2,3,1.0567,-0.0139998]}'
硬件环境异常处理#
当相机节点终端出现 “the frames didn’t arrive in 5 secondes”, 将三个相机的USB口进行重新插拔
每次相机节点重启时, 状态与控制节点也重启, 以防通讯失联
在一次相机节点正常启动后, 可进行持续推理. 不会断联.
FluxVLA 推理#
环境准备#
Cuda 12.4 :
出处: https://developer.nvidia.com/cuda-12-4-0-download-archive
选择 runfile 进行下载
[图片]
wget https://developer.download.nvidia.com/compute/cuda/12.4.0/local_installers/cuda_12.4.0_550.54.14_linux.run
sudo sh cuda_12.4.0_550.54.14_linux.run
LimVLA环境配置
Install pytorch:
pip install torch==2.6.0 torchvision==0.21.0 torchaudio==2.6.0 --index-url https://download.pytorch.org/whl/cu124
Install LIBERO:
git clone https://github.com/Lifelong-Robot-Learning/LIBERO
cd LIBERO
pip install -r requirements.txt
pip install -e .
Due to PyTorch version changes, LIBERO may require some accommodations; in particular, the way we use torch.load might need to be updated.
Install transformers:
pip install transformers==4.53.2
Install flash-attention
git clone https://github.com/Dao-AILab/flash-attention.git
cd flash-attention
git checkout v2.5.5
MAX_JOBS=4 python setup.py install
Install dlimp
git clone https://github.com/kvablack/dlimp
cd dlimp
pip install -e .
Install limvla
pip install -r requirements.txt
python -m pip install -e . --no-build-isolation
这样能保证limvla包相关修改能实时更新,不需要反复install
Tron2 启动#
先将机器人转为idle模式,再转为developer模式
打开相机节点、状态节点与控制节点
准备进行推理
launch.json#
将下述内容复制入 launch.json, 方便用python debugger进行调试
{
"name": "Inference Pi05",
"type": "debugpy",
"request": "launch",
"program": "{CONDA_ENV_PATH}/bin/torchrun",
"python": "{CONDA_ENV_PATH}/bin/python",
"args": [
"scripts/inference_real_robot.py",
"--config", "{PROJECT_PATH}/configs/pi05/pi05_paligemma_tron2_pick_bananas_full_finetune.py",
"--ckpt-path", "{CHECKPOINT_PATH}/checkpoints/step-001000-epoch-00-loss=0.0072.pt",
],
"console": "integratedTerminal",
"justMyCode": false,
"env": {
"CUDA_VISIBLE_DEVICES": "0",
"HF_ENDPOINT": "https://hf-mirror.com",
"WANDB_MODE": "disabled",
}
}
使用说明#
按 “0” 进行复位, 按 “1”进行对应 prompt 推理. 也支持多prompt输入.

在config中, inference/task_descriptions进行指定.
目前都是走moveJ控制, 运行时间 1~4秒.(可在状态节点中指定)
publish_rate在inference/publish_rate中指定, 刚开始可以调低点,方便看清楚轨迹.
流程:#
将桌子往前推,先进行手臂复位(到桌子水平面上)
再进行启动模型推理,在过程中可以去调整状态节点中的moveJ time,改变控制频率
推理结束后,撤出桌子,在用手柄进入idle模式