OpenArm开源项目总结(移植lerobot框架)
📋 项目概述
OpenArm 是一款开源的人形机械臂,专为以人为中心的 AI 和机器人研究设计。其模块化的硬件和易用的软件使其成为一个灵活的平台,适用于远程操作、模仿学习和现实世界数据收集。OpenArm 的目标是推动物理智能的发展,实现机器人能够安全、有效地与人类共同工作------在家居、服务和护理环境中。
由于其并没有高层python接口所以一直起来比较麻烦,下文仅供参考。
本项目将 OpenArm 双臂机械臂适配到 LeRobot 框架,实现了通过 LeRobot 进行遥操作和 VLA 数据采集的功能。
注 :下方代码只适用我们自己的设备,改了电机与硬件结构。

项目目标
- 让 OpenArm 双臂机械臂能够使用 LeRobot 框架进行遥操作
- 支持 VLA(Vision-Language-Action)算法的数据采集
- 保持与现有 ROS2 控制系统的兼容性
最终成果
- ✅ 成功实现
bi_openarm_leader遥操作器(Leader 端) - ✅ 成功实现
bi_openarm_follower机器人(Follower 端) - ✅ 完成遥操作测试验证
🏗️ 系统架构
整体架构图
┌─────────────────────────────────────────────────────────────────────────┐
│ LeRobot 框架 │
│ ┌─────────────────────┐ ┌─────────────────────────────┐ │
│ │ BiOpenArmLeader │ │ BiOpenArmFollower │ │
│ │ (遥操作器) │ 动作数据 │ (机器人) │ │
│ │ │ ──────────→ │ │ │
│ │ - 读取 Leader 位置 │ │ - 发送位置命令到 Follower │ │
│ │ - 方向反转处理 │ │ - 读取 Follower 状态 │ │
│ │ - 夹爪坐标转换 │ │ - 相机图像采集 │ │
│ └─────────────────────┘ └─────────────────────────────┘ │
└─────────────────────────────────────────────────────────────────────────┘
│ │
│ CAN 总线 │ ROS2 话题
▼ ▼
┌─────────────────────┐ ┌─────────────────────────────────┐
│ 主动端 (Leader) │ │ 从动端 (Follower) │
│ ┌───────┐ ┌───────┐│ │ ┌───────────────────────────┐ │
│ │右臂 │ │左臂 ││ │ │ ROS2 Controller │ │
│ │can0 │ │can1 ││ │ │ forward_position_ctrl │ │
│ │8 DOF │ │8 DOF ││ │ └───────────────────────────┘ │
│ └───────┘ └───────┘│ │ │ │ │
└─────────────────────┘ │ ┌────┴────┐ ┌────┴────┐ │
│ │右臂 │ │左臂 │ │
│ │can2 │ │can3 │ │
│ │8 DOF │ │8 DOF │ │
│ └─────────┘ └─────────┘ │
└─────────────────────────────────┘
数据流
1. Leader 端读取:
CAN 总线 → motor_control.py → 电机角度(rad) → 方向反转 → 夹爪坐标转换 → LeRobot 动作
2. Follower 端控制:
LeRobot 动作 → ROS2 Float64MultiArray → forward_position_controller → 电机
🔧 核心实现细节
1. BiOpenArmLeader(主动端)
文件位置 : lerobot/src/lerobot/teleoperators/bi_openarm_leader/
关键技术点
a) CAN 总线直接读取
python
# 使用 python-can 库直接读取电机状态
self._right_bus = can.interface.Bus(
bustype="socketcan",
channel="can0",
bitrate=1000000
)
# 调用 motor_control.py 中的函数读取电机状态
state, rx_data, rx_id = get_motor_status(bus, motor_id)
fb = parse_motor_feedback(rx_data, motor_id)
position = fb["angle"] # 弧度
b) 方向反转处理
python
# 关键发现:主动端和从动端电机安装方向相反(镜像安装)
# 需要将 Leader 读取的角度取反才能正确控制 Follower
INVERT_JOINTS = True # 反转7个关节方向
def _apply_inversion(self, positions):
if self.config.invert_joints:
for i in range(7):
positions[i] = -positions[i]
return positions
c) 夹爪坐标转换
python
# 电机角度(弧度) → 关节距离(米)
# 与 ROS2 hardware 包保持一致
GRIPPER_JOINT_0_POSITION = 0.044 # 夹爪完全打开距离(m)
GRIPPER_MOTOR_1_RADIANS = 1.0472 # 对应电机角度(rad, 60度)
def _motor_radians_to_joint(self, motor_radians):
return GRIPPER_JOINT_0_POSITION * (motor_radians / GRIPPER_MOTOR_1_RADIANS)
2. BiOpenArmFollower(从动端)
文件位置 : lerobot/src/lerobot/robots/bi_openarm_follower/
关键技术点
a) ROS2 话题通信
python
# 订阅关节状态
self._joint_state_sub = self._ros_node.create_subscription(
JointState,
'/joint_states',
self._joint_state_callback,
10
)
# 发布位置命令
self._left_cmd_pub = self._ros_node.create_publisher(
Float64MultiArray,
'/left_forward_position_controller/commands',
10
)
b) 关节名称映射
python
# LeRobot 名称 → ROS2 关节名称
LEFT_JOINT_NAMES = [f"openarm_left_joint{i}" for i in range(1, 8)]
LEFT_GRIPPER_NAME = "openarm_left_finger_joint1"
c) 安全限制
python
# 相对位置限制,防止突然大幅度运动
def _apply_relative_limit(self, target_positions, arm, max_delta):
for i, (target, joint_name) in enumerate(zip(target_positions, joint_names)):
current = self._get_joint_position(joint_name)
delta = target - current
if abs(delta) > max_delta:
limited = current + sign(delta) * max_delta
🐛 开发过程中遇到的问题
问题 1: motor_control 库导入失败
现象 : ImportError: No module named 'lib.motor_control'
原因 : Python 路径计算错误,无法找到 motor_tests_openarm_com 目录
解决方案:
python
# 正确的路径计算
LEROBOT_SRC = os.path.dirname(os.path.dirname(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))))
WORKSPACE_SRC = os.path.dirname(os.path.dirname(LEROBOT_SRC))
MOTOR_TESTS_PATH = os.path.join(WORKSPACE_SRC, 'motor_tests_openarm_com')
sys.path.insert(0, MOTOR_TESTS_PATH)
问题 2: 所有关节运动方向相反
现象: 移动 Leader 时,Follower 向相反方向运动
原因: 主动端和从动端机械臂安装方向不同(镜像安装)通过改参数我们可以实现镜像遥操作
发现过程:
- 查看 ROS2 遥操作代码
teleop_leader_node.cpp - 发现关键配置:
static constexpr bool INVERT_JOINTS = true;
解决方案:
python
# 在 get_action() 中添加方向反转
def _apply_inversion(self, positions):
if self.config.invert_joints:
for i in range(7):
positions[i] = -positions[i]
return positions
问题 3: 夹爪控制不正确
现象: 夹爪开合程度与预期不符
原因: Leader 返回的是电机角度(弧度),Follower 期望的是关节距离(米)
解决方案: 添加坐标转换函数,与 ROS2 hardware 包保持一致
📊 与其他机械臂的对比
OpenArm vs SO100 vs Piper
| 特性 | SO100 | Piper | OpenArm |
|---|---|---|---|
| 硬件接口 | USB 串口 | USB 串口 | CAN 总线 |
| 通信协议 | Dynamixel | Piper SDK | CAN + ROS2 |
| Leader 读取 | Dynamixel 总线 | SDK API | 直接 CAN 读取 |
| Follower 控制 | Dynamixel 总线 | SDK API | ROS2 话题 |
| 启动方式 | 直接连接 | SDK 初始化 | 需要先启动 ROS2 |
| 自由度 | 6 DOF | 7 DOF | 7 DOF + 夹爪 |
| 双臂支持 | 是 | 否 | 是 |
| 方向反转 | 不需要 | 不需要 | 需要 |
| 坐标转换 | 不需要 | 不需要 | 夹爪需要 |
为什么 OpenArm 更复杂?
-
混合通信架构
- Leader: 直接 CAN 总线(底层)
- Follower: ROS2 话题(高层)
- 需要理解两种不同的通信机制
-
需要方向反转
- 主从端机械臂镜像安装
- 必须分析现有 ROS2 代码才能发现
-
坐标系统不一致
- 电机返回弧度
- ROS2 控制器期望米(夹爪)
- 需要坐标转换
-
依赖外部系统
- 必须先启动 ROS2 launch
- 需要正确配置 CAN 接口
- 多个系统协同工作
-
双臂协调
- 4 个 CAN 接口
- 16 个电机
- 复杂的关节映射
📁 项目文件结构
lerobot/src/lerobot/
├── teleoperators/
│ └── bi_openarm_leader/
│ ├── __init__.py
│ ├── bi_openarm_leader.py # Leader 主类
│ └── config_bi_openarm_leader.py # Leader 配置
│
└── robots/
└── bi_openarm_follower/
├── __init__.py
├── bi_openarm_follower.py # Follower 主类
├── config_bi_openarm_follower.py # Follower 配置
├── README.md # 使用说明
├── openarm_for_lerobot.md # 适配指南
└── test_openarm.py # 测试脚本
🔬 底层知识涉及
1. CAN 总线通信
python
# CAN 扩展帧格式
# 仲裁ID: 29位
# 数据: 0-8 字节
# 电机状态查询
arbitration_id = 0x01000000 | (torque_uint16 << 8) | motor_id
data = [pos_high, pos_low, vel_high, vel_low, kp_high, kp_low, kd_high, kd_low]
# 反馈解析
angle_raw = (rx_data[0] << 8) | rx_data[1]
current_angle = uint16_to_float(angle_raw, P_MIN, P_MAX)
2. ROS2 控制架构
ros2_control 架构:
┌─────────────────┐
│ Controller │ ← forward_position_controller
│ Manager │
└────────┬────────┘
│
┌────────▼────────┐
│ Hardware │ ← openarm_hardware
│ Interface │
└────────┬────────┘
│
┌────────▼────────┐
│ CAN 总线 │
└─────────────────┘
3. 坐标转换
python
# 电机角度 → 关节距离(夹爪)
# 线性映射关系
joint_distance = GRIPPER_JOINT_0_POSITION * (motor_radians / GRIPPER_MOTOR_1_RADIANS)
# 数值范围
# 电机: 0 rad (关闭) → 1.0472 rad (打开)
# 关节: 0 m (关闭) → 0.044 m (打开)
4. LeRobot 框架结构
python
# Teleoperator 基类
class Teleoperator:
def connect(self): ...
def get_action(self) -> dict[str, float]: ...
def disconnect(self): ...
# Robot 基类
class Robot:
def connect(self): ...
def get_observation(self) -> dict[str, Any]: ...
def send_action(self, action: dict) -> dict: ...
def disconnect(self): ...
📝 使用指南
快速开始
1. 配置 CAN 接口
bash
# Leader 端
sudo ip link set can0 up type can bitrate 1000000
sudo ip link set can1 up type can bitrate 1000000
# Follower 端
sudo ip link set can2 up type can bitrate 1000000
sudo ip link set can3 up type can bitrate 1000000
2. 启动 ROS2 (Follower)
bash
cd ~/openarm_ws
source install/setup.bash
ros2 launch openarm_bringup openarm.bimanual.launch.py \
right_can_interface:=can2 \
left_can_interface:=can3 \
robot_controller:=forward_position_controller \
control_mode:=mit
3. 运行遥操作
bash
lerobot-teleoperate \
--robot.type=bi_openarm_follower \
--robot.id=openarm_follower \
--robot.cameras="{ top: {type: opencv, index_or_path: 0, width: 640, height: 480, fps: 30}}" \
--teleop.type=bi_openarm_leader \
--teleop.id=openarm_leader \
--teleop.right_can_interface=can0 \
--teleop.left_can_interface=can1 \
--display_data=true
4. 数据采集
bash
lerobot-record \
--robot.type=bi_openarm_follower \
--robot.id=openarm_follower \
--robot.cameras="{ top: {type: opencv, index_or_path: 0, width: 640, height: 480, fps: 30}}" \
--teleop.type=bi_openarm_leader \
--teleop.id=openarm_leader \
--dataset.repo_id=your_username/openarm_dataset \
--dataset.num_episodes=10 \
--display_data=true
配置参数
Leader 配置
| 参数 | 默认值 | 说明 |
|---|---|---|
right_can_interface |
can0 |
右臂 CAN 接口 |
left_can_interface |
can1 |
左臂 CAN 接口 |
invert_joints |
True |
是否反转关节方向 |
invert_gripper |
False |
是否反转夹爪方向 |
Follower 配置
| 参数 | 默认值 | 说明 |
|---|---|---|
right_can_interface |
can2 |
右臂 CAN 接口 |
left_can_interface |
can3 |
左臂 CAN 接口 |
control_mode |
mit |
控制模式 |
left_arm_max_relative_target |
0.5 |
左臂最大相对位置变化 (rad) |
right_arm_max_relative_target |
0.5 |
右臂最大相对位置变化 (rad) |
🔍 故障排查
CAN 通信问题
bash
# 检查 CAN 接口状态
ip link show can0
# 监控 CAN 消息
candump can0
# 重新配置 CAN
sudo ip link set can0 down
sudo ip link set can0 up type can bitrate 1000000
ROS2 问题
bash
# 检查话题
ros2 topic list
# 查看关节状态
ros2 topic echo /joint_states
# 检查控制器
ros2 control list_controllers
常见错误
| 错误 | 原因 | 解决方案 |
|---|---|---|
ImportError: motor_control |
路径配置错误 | 检查 MOTOR_TESTS_PATH |
TimeoutError: joint states |
ROS2 未启动 | 先启动 ROS2 launch |
CAN bus error |
CAN 接口未配置 | 运行 ip link set 命令 |
| 运动方向相反 | 未启用方向反转 | 设置 invert_joints=True |
📚 参考资料
文档更新时间: 2025年12月10日