跳到主要内容

灵动示教臂ROS API

1. 概述

本 ROS API(alicia_duo_driver)旨在实现与机械臂底层硬件之间的串口通信。它负责解析接收到的原始数据,并将机械臂的运行状态(如关节角度、夹爪状态、按钮信息)以标准 ROS 消息格式发布,供上层系统使用。

该驱动由多个协同工作的节点组成,分别承担不同的功能模块:

  • 串口服务节点(serial_server_node):使用 C++ 实现,负责与底层硬件进行串口数据的读写操作,包括原始数据帧的接收、校验、解析与转发,同时接收来自 ROS 的串口写入请求;

  • 数据类型分发节点(serial_data_type_node.py):使用 Python 实现,订阅 serial_server_node 发布的原始数据,根据数据帧中的指令 ID(Command ID)进行分类解析,并将不同类型的数据分别发布到对应的 ROS 话题中;

  • 舵机状态处理节点(servo_states_node.py):同样由 Python 实现,订阅 serial_data_type_node.py 发布的舵机和夹爪状态数据,并将其转换为标准的 ArmJointState ROS 消息(以弧度为单位),以供控制器或可视化工具使用。

2. 系统依赖

在开始部署之前,请确保您的系统满足以下要求:

  • 操作系统: Ubuntu 18.04 (Melodic) 或 Ubuntu 20.04 (Noetic),推荐使用 Ubuntu 20.04 / ROS Noetic;

  • ROS: ROS Melodic 或 ROS Noetic (推荐 Desktop-Full 安装);

  • ROS serial 库: 用于串口通信 (sudo apt-get install ros-$ROS_DISTRO-serial)。

3. 安装与部署

以下步骤将引导您完成 alicia_duo_driver 的安装与部署。 本指南假设您已正确安装 ROS,并具备基本的 Linux 命令行操作经验。

3.1 环境准备

请确保您的 ROS 环境已正确安装并完成初始化配置。 如尚未安装 ROS,建议参考官方安装指南或使用更为简便的鱼香 ROS 安装教程进行快速部署。

3.2 创建并进入 Catkin 工作空间

# 创建工作空间目录
mkdir -p ~/alicia_ws/src
cd ~/alicia_ws
# 下载相关ROS库
git clone https://github.com/Xianova-Robotics/Alicia_duo_leader_ros.git ./src/
# 安装和编译库
rosdep install --from-paths src --ignore-src -r -y
catkin_make
注意:编译过程可能需要一些时间,如果遇到错误,请检查依赖项是否已正确安装以及代码是否完整。

3.3 配置环境

运行以下命令添加工作空间环境到终端环境中:

echo "source ~/alicia_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc
注意:

如果您使用的是 'zsh',请将'.bashrc'替换为'.zshrc'。

3.4 串口权限

设置串口权限:

# 方法1:添加用户到dialout组(推荐,永久有效)
sudo usermod -a -G dialout $USER
# 注意:需要注销并重新登录使组权限生效

# 方法2:临时设置串口权限,每次启动终端均需运行
sudo chmod 666 /dev/ttyUSB*

硬件连接验证

  1. 将机械臂通过USB连接至计算机;

  2. 检查串口是否被系统识别;

ls -l /dev/ttyUSB*
  • 确认串口设备名称(如ttyUSB0、ttyUSB1等)。

3.5 使用说明

3.5.1 启动 ROS 驱动

要启动机械臂的驱动程序和所有相关节点,请运行 serial_server.launch 文件。确保机械臂已通过 USB 连接到计算机。

roslaunch alicia_duo_leader_driver serial_server.launch 

该命令将启动以下节点:

  1. serial_server_node:处理底层串口通信;

  2. serial_data_type_node.py:分类转发串口数据;

  3. servo_states_node.py:处理状态数据并发布 /arm_joint_state;

  4. servo_control_node.py:示教臂调零;

您可以通过添加参数来修改启动行为,例如启用调试模式或指定串口:

# 启用调试模式
roslaunch alicia_duo_leader_driver serial_server.launch debug_mode:=true

# 指定串口为 ttyUSB0
roslaunch alicia_duo_leader_driver serial_server.launch port:=ttyUSB0

# 同时指定端口和启用调试
roslaunch alicia_duo_leader_driver serial_server.launch port:=ttyUSB0 debug_mode:=true

3.5.2 运行状态读取示例

本项目提供了一个简单的 Python 示例脚本(arm_read_demo.py),用于演示如何订阅并打印机械臂的状态信息。在运行示例脚本前,请确保完成以下准备工作:

  1. 已按下示教臂握把左侧的同步按钮:以便启动状态同步;

  2. 核心服务已启动:请确认 serial_server.launch 已在运行中;

  3. 打开一个新的终端窗口: (确保已执行source setup.bash);

随后,请运行示例脚本:

rosrun alicia_duo_leader_driver arm_read_demo.py

运行后终端持续打印的机械臂关节角度(度和弧度)、夹爪角度和按钮状态:

[INFO] [1747805831.447121]: --- Received Arm Joint State ---
[INFO] [1747805831.448002]: Timestamp: 1747805831446895837
[INFO] [1747805831.448727]: Joint 1: 0.70 deg (0.0123 rad)
[INFO] [1747805831.449427]: Joint 2: -9.84 deg (-0.1718 rad)
[INFO] [1747805831.450081]: Joint 3: 8.53 deg (0.1488 rad)
[INFO] [1747805831.450709]: Joint 4: 0.44 deg (0.0077 rad)
[INFO] [1747805831.451373]: Joint 5: -38.58 deg (-0.6734 rad)
[INFO] [1747805831.452103]: Joint 6: -6.24 deg (-0.1089 rad)
[INFO] [1747805831.452744]: Gripper: 0.00 deg (0.0000 rad)
[INFO] [1747805831.453342]: Button 1: 1
[INFO] [1747805831.453917]: Button 2: 0

4. 示教臂调零方法

注意:
  1. 本方法展示的是基于玄雅出厂默认零位姿态对示教臂进行重新调零的标准操作方法。如需调零至其他姿态,请结合第五章相关说明

  2. 非必要情况下请勿擅自执行调零操作,以免影响系统的精度与运行稳定性。

在重新设置机械臂的初始位置前,请先将示教臂摆放至下图所示的指定初始姿态(玄雅出厂默认零位姿态),确认姿态正确后,按以下顺序操作:

  1. 连接电源和 Type-C 数据线;

  2. 按下示教臂的电源按钮,启动设备。

正确姿态参考:1处关节保持垂直,2处关节保持45度角,3处刻度线对准,4处保持按钮朝上。

在两个按键没有按下的情况下(无蓝灯亮起),运行以下代码:

# 在终端1
roslaunch alicia_duo_leader_driver serial_server.launch
# 在终端2
cd ~/alicia_ws/src/examples/
python3 alicia_duo_zero_calibration.py

成功调零后示教臂姿态会固定(电机满力矩状态),按下右侧按钮两次可恢复无力矩状态。

5. ROS API 说明

5.1 主要节点

节点名称类型描述
serial_server_nodeC++alicia_duo_leader_driver负责底层串口通信、数据帧校验和原始数据收发。
serial_data_type_nodePythonalicia_duo_leader_driver订阅原始串口数据,根据指令 ID 分类转发到不同话题。
servo_states_nodePythonalicia_duo_leader_driver处理舵机/夹爪状态,发布标准 ArmJointState 消息 (弧度)。

5.2 重要话题 (Topics)

话题名称消息类型发布者订阅者描述
/read_serial_datastd_msgs/UInt8MultiArrayserial_server_nodeserial_data_type_node从串口接收到的原始字节数据帧。
/send_serial_datastd_msgs/UInt8MultiArrayservo_control_nodeserial_server_node要发送到串口的原始字节数据帧。
/gripper_anglestd_msgs/UInt32MultiArrayserial_data_type_nodeservo_states_node处理后的夹爪原始值和按钮状态 [gripper_raw, but1, but2]
/servo_statesstd_msgs/UInt8MultiArrayserial_data_type_nodeservo_states_node处理后的舵机状态原始数据帧 (指令 ID 0x04)。
/servo_states_6std_msgs/UInt8MultiArrayserial_data_type_node(无标准订阅者)处理后的扩展舵机状态原始数据帧 (指令 ID 0x06),用途待定。
/error_frame_dealstd_msgs/UInt8MultiArrayserial_data_type_node(无标准订阅者)从串口接收到的错误帧 (指令 ID 0xEE)。
/arm_joint_statealicia_duo_leader_driver/ArmJointStateservo_states_nodearm_read_demo.py, 其他用户节点主要的机械臂状态话题,包含所有关节和夹爪的角度 (弧度) 及按钮状态。
/servo_states_mainstd_msgs/Float32MultiArrayservo_states_node(用于向后兼容)包含 6 个关节角度和夹爪角度 (弧度) 的数组。
/startup_completestd_msgs/Stringserial_server.launch(无标准订阅者) 在所有核心节点启动后发布一次,表示系统准备就绪。

5.3 消息类型 (Messages)

alicia_duo_leader_driver/ArmJointState消息定义说明:

std_msgs/Header header:标准消息头,包含时间戳 (stamp) 与参考坐标系 (frame_id);

float32 joint1float32 joint6:六个主要关节的角度,单位为弧度;

float32 gripper:夹爪的开合角度,单位为弧度;

int32 but1, int32 but2:按钮状态,通常为0或1;

float32 time:期望的运动时间,单位为秒,若=0表示立即执行。

5.4 故障排查

  1. 无法连接串口 / Permission denied

    • 首先,请确认当前用户是否具备串口访问权限。您需要将当前用户添加到 dialout 用户组,并在添加后注销重新登录或重启系统以使权限生效。可通过运行 groups $USER 命令查看当前用户所属的用户组,结果中应包含 dialout

    • 接下来,检查设备连接情况。确保机械臂已通过 USB 正确连接到计算机,并使用 ls /dev/ttyUSB*ls /dev/ttyACM* 命令确认串口设备是否已经被系统识别;

    • 如果您在启动节点时指定了 port 参数,请确保端口号填写正确且对应的设备确实存在。建议在初次调试时不指定该参数,允许节点自动识别可用的串口设备;

    • 最后,请确保串口未被其他程序占用,例如 Arduino IDE 的串口监视器、串口调试助手等软件。如有此类程序正在运行,建议关闭后再次尝试启动节点,以避免设备冲突导致无法连接串口。

  2. 节点崩溃或无响应

    • 若节点出现崩溃或无响应的情况,建议首先检查系统日志。您可以查看 roslaunch 命令行输出,或进入 ~/.ros/log 目录查阅对应时间戳的 ROS 日志文件,以获取更详细的错误信息;

    • 同时,请确认项目的所有依赖项已正确安装,包括 ROS 库及相关第三方依赖。若存在缺失,建议根据安装指南补齐依赖后重新编译;

    • 此外,还需检查代码是否完整克隆或下载,确保未出现文件缺失或路径错误。编译过程中应使用 catkin_makecatkin build 等工具,并确保编译过程无报错,所有节点均已成功生成。

  3. 数据接收不正确或不稳定

    • 检查波特率:确认 launch 文件中的 baudrate 与机械臂硬件设置完全一致;

    • 检查连接:检查 USB 线缆是否连接牢固,尝试更换 USB 端口或线缆;

    • 启用调试模式:运行 roslaunch alicia_duo_leader_driver serial_server.launch debug_mode:=true 查看原始串口数据,判断问题出在底层通信还是上层解析。