2D/6D视觉抓取
1. 介绍
灵动操作臂控制系统是一套基于ROS的完整解决方案,专为本公司自主研发的灵动系列六自由度操作臂及夹爪量身打造(参考:https://github.com/Synria-Robotics/Alicia-D-ROS1) 该系统提供标准化的 ROS 接口,以弧度为统一角度单位,简化机械臂控制流程,屏蔽底层通信细节,使用户能够专注于上层应用的开发。系统的核心功能包括:
-
实时控制六自由度机械臂;
-
精准控制夹爪开合;
-
提供夹爪独立控制接口(新增功能);
-
实时反馈所有关节状态;
-
提供标准化 ROS 接口;
-
支持串口自动检测与断线重连;
-
具备良好的跨平台兼容性。
2. 单操作臂的数据读取和控制
注意:
安全第一:始终确保机械臂工作区域内没有障碍物或其他人员;
角度限制:所有命令应在有效范围内,特别注意夹爪限制在0-100°(机械结构限制);
数据单位:所有API使用弧度为单位,不是角度,需要使用
math.radians()和math.degrees()进行转换;启动顺序:始终先启动控制系统,然后再启动应用程序;
串口权限:首次使用可能需要配置串口访问权限;
系统资源:保持ROS核心系统正常运行;
使用Ctrl+C安全地停止正在运行的节点。
2.1 系统节点
2.1 接口规范
系统由alicia_d_driver_node进行硬件通信,完成硬件数据帧和标准关节状态之间的数据转换。
2.1.1 主要接口
用户仅需关注以下主要接口:
| 话题名称 | 消息类型 | 方向 | 描述 |
|---|---|---|---|
| /joint_states | sensor_msgs/JointState | 输入(订阅) | 接收机械臂及夹爪当前状态 |
| /joint_commands | sensor_msgs/JointState | 输出(发布) | 控制机械臂及夹爪 |
| /zero_calibrate | std_msgs/Bool | 发布/订阅 | 机械臂零点标定 |
| /demonstration | std_msgs/Bool | 发布/订阅 | 机械臂力矩开闭 |
2.1.2 数据单位与限制
所有角度值使用弧度作为标准单位:
| 参数名称 | 角度范围(弧度) | 角度范围(度°) | 备注 |
|---|---|---|---|
| Joint1 | -2.16 到 +2.16 | -123.7 到 +123.7 | 基座关节,超出范围会被自动截断 |
| Joint2 | -1.57 到 +1.57 | -90 到 +90 | 肩部关节,超出范围会被自动截断 |
| Joint3 | -0.5 到 +2.356 | -28.6 到 +135 | 肘部关节,超出范围会被自动截断 |
| Joint4 | -3.14 到 +3.14 | -180 到 +180 | 腕部旋转关节,超出范围会被自动截断 |
| Joint5 | -1.57 到 +1.5 | -90 到 +85.9 | 腕部俯仰关节,超出范围会被自动截断 |
| Joint6 | -3.14 到 +3.14 | -180 到 +180 | 腕部滚转关节,超出范围会被自动截断 |
| right_finger | 0 到 1.745 | 0 到 100° (内部映射) | 夹爪开合,使用米作为单位的棱镜关节 |
注意:由于机械结构的限制,夹爪的角度范围为0到1.745弧度(即0到100°)。
right_finger即为夹爪控制的关节名。
2.3 系统部署及启动
2.3.1 系统依赖安装
系统依赖:
-
Ubuntu 20.04
-
ROS(Noetic或其他ROS 1版本) ROS 安装:
wget http://fishros.com/install -O fishros && . fishros -
Python 3.8
-
rosdepc或rosdep
工作空间创建及依赖安装:
# 创建工作空间
mkdir -p ~/alicia_ws/src
cd ~/alicia_ws
git clone https://github.com/Synria-Robotics/Alicia-D-ROS1.git -b v5.5.0 ./src/
# 安装库所需的依赖包
./src/install/alicia_amd64_install.sh
设置串口权限
# 方法1:添加用户到dialout组(推荐,永久有效)
sudo usermod -a -G dialout $USER
# 注意:需要注销并重新登录使组权限生效
# 方法2:临时设置串口权限
sudo chmod 666 /dev/ttyUSB*
# 方法3:创建udev规则(永久有效)
echo 'KERNEL=="ttyUSB*", MODE="0666"' | sudo tee /etc/udev/rules.d/99-serial.rules
sudo udevadm control --reload-rules
sudo udevadm trigger
硬件连接验证
-
将机械臂通过USB连接至计算机;
-
检查串口是否被系统识别;
ls -l /dev/ttyUSB*
- 确认串口设备名称(如ttyUSB0、ttyUSB1等)。
2.3.2 启动命令
使用以下命令启动完整控制系统:
roslaunch alicia_d_driver alicia_d_driver.launch
2.3.3 配置参数
启动时可以配置以下参数:
# 指定串口设备
roslaunch alicia_d_driver alicia_d_driver.launch port:=/dev/ttyUSB1
# 设置波特率
roslaunch alicia_d_driver alicia_d_driver.launch baudrate:=1000000
# 组合参数
roslaunch alicia_d_driver alicia_d_driver.launch port:=ttyUSB0 baudrate:=921600
2.3.4 启动文件参数说明
| 参数名称 | 默认值 | 说明 |
|---|---|---|
| port | ttyUSB0 | 串口设备名称,位于/dev/下 |
| baudrate | 1000000 | 串口波特率, v5.4.0默认值为921600 |
2.4 使用方法
发送所有关节归零命令:
# 使用标准 sensor_msgs/JointState 消息格式
rostopic pub -1 /joint_commands sensor_msgs/JointState "header:
stamp: now
frame_id: ''
name: ['Joint1', 'Joint2', 'Joint3', 'Joint4', 'Joint5', 'Joint6', 'right_finger']
position: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
velocity: []
effort: []"
单独控制夹爪:
# 发送夹爪控制命令(张开到50%位置,约0.025米)
rostopic pub -1 /joint_commands sensor_msgs/JointState "header:
stamp: now
frame_id: ''
name: ['right_finger']
position: [0.025]
velocity: []
effort: []"
监听关节状态:
# 监听所有关节状态反馈
rostopic echo /joint_states
2.4.2 常用话题操作
零点标定:
# 启动零点标定模式
rostopic pub -1 /zero_calibrate std_msgs/Bool "data: true"
力矩开关控制:
# 开启示教模式(0力矩状态)
rostopic pub -1 /demonstration std_msgs/Bool "data: true"
# 关闭示教模式(恢复力矩控制)
rostopic pub -1 /demonstration std_msgs/Bool "data: false"
查看可用话题:
# 列出所有相关话题
rostopic list | grep -E "(joint|calibrate|demonstration)"
2.5 详细示例
系统提供了一个完整的演示示例,可用于测试和学习:
# 确保系统已启动
roslaunch alicia_d_driver alicia_d_driver.launch
# 运行演示程序
rosrun alicia_d_driver arm_control_test.py
演示程序将执行以下测试序列:
-
所有关节归零;
-
测试关节1的正反向运动;
-
测试关节2的正反向运动;
-
测试夹爪开合;
-
测试复合动作。
2.6 故障排除
2.6.1 常见问题
| 问题描述 | 可能原因 | 解决方法 |
|---|---|---|
| 无法连接到串口 | 权限不足 | 使用sudo chmod 666 /dev/ttyUSB*或添加用户到dialout组 |
| 串口连接失败 | 端口名称错误 | 检查dev下的可用设备并指定正确的port参数 |
| 通信中断 | USB连接不稳定 | 使用高质量USB线缆,检查USB接口是否松动 |
| 机械臂不响应 | 波特率错误 | 确认波特率设置与硬件一致(默认921600) |
| 运动范围受限 | 软件限制 | 检查代码中的角度限制是否与实际机械匹配 |
| 夹爪行为异常 | 超出范围 | 确保夹爪角度在0-100度范围内 |
2.6.2 诊断方法
启用调试模式可以获取更多信息:
roslaunch alicia_d_driver alicia_d_driver.launch debug_mode:=true
检查服务节点状态:
rosnode list
rosnode info /alicia_d_driver_node
监控原始数据:
rostopic echo /joint_states
3. 单操作臂的Moveit!与ROS Control控制
3.1 启动命令
MoveIt 仿真控制,不涉及连接真实机械臂:
roslaunch alicia_d_moveit demo.launch
连接真实机械臂的MoveIt 和ROS Control 控制:
roslaunch alicia_d_driver alicia_d_bringup.launch
3.2 MoveIt配置修改
alicia_d_moveit ROS 包配置了alicia运动控制规划组和manipulator运动控制规划组。
alicia规划组
包含了base_link 到tool0的正逆运动学规划,即包含机械臂基座到夹爪尖端中点的一系列坐标转换关系。
hand规划组
夹爪控制, Link8对应的right_finger带动left_finger平移。
增减规划控制组和其他参数主要是通过MoveIt Assistant配置,运行以下指令启动:
roslaunch moveit_setup_assistant setup_assistant.launch
4. 单操作臂的调零
若观察到启动alicia_d_bringup.launch后rviz中机械臂的运动状态和机械臂的不一致,这主要是机械臂设置的零点位置和Moveit不匹配导致,需要重新调节机械臂的零点。
主要分为两个步骤:
-
机械臂进入0力矩状态;
-
设置目标姿态;
-
运行调零代码。
4.1 步骤1
运行机械臂的ROS硬件通讯代码:
roslaunch alicia_d_driver alicia_d_driver.launch
在终端中运行指令以0力矩控制(无力矩状态时机械臂无法维持当前姿态,请注意安全):
rostopic pub /demonstration std_msgs/Bool "data: true"
成功后按ctrl-C 结束发布指令。
4.2 步骤2
将机械臂摆放到目标零点位置:

1处保持垂直,2处保持45度角,3处保持平行。
4.3 步骤3
运行调零代码:
cd ~/alicia_ws/src/examples/
python3 alicia_d_zero_calibration.py
机械臂重新回到满力矩状态后表示完成调零工作。
5. 单操作臂的拖动示教
5.1 启动命令
roslaunch alicia_d_driver alicia_d_driver.launch
在另一个终端
roscd alicia_d_drag_teaching/scripts
python3 pose_record.py
运行
pose_record.py前建议捏住机械臂的上端合适位置以防止机械臂0力矩后碰撞桌面。
5.2 停止拖动示教
停止拖动示教的方式:
-
达到设定最长时间后自动停止录制;
-
按键
s中断;
其中,设定时长在pose_record.py的PoseRecorder类初始化中修改。
class PoseRecorder:
"""用于记录机器人关节姿态的ROS节点类"""
def __init__(self):
"""初始化姿态记录器节点"""
rospy.init_node('pose_recorder', anonymous=True)
# 获取记录时长参数
self.record_duration = 10 # 默认记录10秒
...
在完成记录后可键入Enter选择实时姿态还原。
或者键入其他任意键退出,运行:
python3 pose_replicator.py
也可还原姿态,还原的数据是同目录下的pose_data.bag存储的上一个示教记录。
5.3 效果展示
终端的运行结果如下:
[INFO] [1746864088.321231]: 姿态记录器已初始化,正在监听 /arm_joint_state 主题
[INFO] [1746864088.323308]: 按 's' 键停止记录并保存数据
[INFO] [1746864089.830843]: 已开始记录关节状态,数据将保存到: ....../alicia_d_drag_teaching/script/pose_data.bag
s
[INFO] [1746864096.982006]: 已停止记录
[INFO] [1746864096.986897]: --------------------------------------------------------------------------------
[INFO] [1746864096.996564]: 主题: /recorded_arm_joint_state
[INFO] [1746864096.998525]: 消息类型: alicia_d_driver/ArmJointState
[INFO] [1746864097.000337]: 消息数量: 598
[INFO] [1746864097.002062]: 开始时间: 1746864089.8384588
[INFO] [1746864097.003416]: 结束时间: 1746864096.975816
[INFO] [1746864097.004634]: 持续时间: 7.14 秒
[INFO] [1746864097.005741]: --------------------------------------------------------------------------------
[INFO] [1746864097.006784]: 前5条消息预览:
[INFO] [1746864097.014022]: [1746864089.8384588] J1=-0.0966, J2=-0.4019, J3=0.5323, J4=0.0138, J5=0.4878, J6=0.0077, Gripper=0.0102
[INFO] [1746864097.014769]: [1746864089.8501806] J1=-0.0966, J2=-0.4111, J3=0.5369, J4=0.0138, J5=0.4863, J6=0.0077, Gripper=0.0102
[INFO] [1746864097.015336]: [1746864089.8617556] J1=-0.0966, J2=-0.4203, J3=0.5430, J4=0.0138, J5=0.4863, J6=0.0077, Gripper=0.0102
[INFO] [1746864097.015824]: [1746864089.873515] J1=-0.0966, J2=-0.4326, J3=0.5492, J4=0.0138, J5=0.4863, J6=0.0077, Gripper=0.0102
[INFO] [1746864097.016265]: [1746864089.8853006] J1=-0.0966, J2=-0.4433, J3=0.5553, J4=0.0138, J5=0.4863, J6=0.0077, Gripper=0.0102
[INFO] [1746864097.016673]: ... (总共 598 条消息)
[INFO] [1746864097.017077]: --------------------------------------------------------------------------------
[INFO] [1746864097.018954]: 正在关闭拖动示教模式...
[INFO] [1746864098.521311]: --------------------------------------------------------------------------------
[INFO] [1746864098.524080]: 记录已完成,是否要执行姿态还原?
[INFO] [1746864098.526465]: 按 Enter 键启动姿态还原,按其他键退出...
[INFO] [1746864103.597721]: 启动姿态还原...
[INFO] [1746864103.606679]: 姿态还原节点启动命令已发送
[INFO] [1746864103.609799]: 姿态记录器退出...
[INFO] [1746864104.046068]: 姿态复制器初始化完成
[INFO] [1746864104.050654]: 执行速度因子: 1.00
[INFO] [1746864104.086647]: 成功读取 598 个轨迹点
[INFO] [1746864104.087331]: 按 Enter 键开始执行轨迹...
[INFO] [1746864107.390125]: 开始执行轨迹,总时长:7.14秒
[INFO] [1746864115.534549]: 轨迹执行完成
[INFO] [1746864115.537771]: 轨迹执行完成
6. 单操作臂的2D抓取
6.1 环境搭建
采用的设备:
-
Alicia D单操作臂;
-
玄雅相机;
-
A4纸
-
绿色/蓝色正方体(2 cm X 2 cm )
注: 仅需图中机械臂上的玄雅相机。
6.1.1 抓取区域搭建
准备一张A4纸,放置在与白色对比度相对较高的平面垫/桌面上。
6.1.2 相机准备
将相机固定在机械臂相机夹上,确保不会晃动。 相机需要包含RGB镜头,能够读取出RGB图像。
6.2 相机参数标定
详情可见于玄雅科技 - 动手学AI + 机器人系列课程
6.2 配置修改
预定义放置位置
您可能需要修改 cube_sorting.py 中的以下预定义位置以匹配您的设置:
# 预定义位置
self.HOME_POSITION = [0.5101731659675737, -0.1741493363528409, 1.1561367836287713, 0.03145428542055679, -1.5228477209708768, -0.5163105875130477]
self.DROP_ZONE_POSITION = [1.4139084885387032, 0.08822543471619682, 0.33985971808065407, 0.046797839284243144, -1.2804195699246312, -1.3249158761293214]
self.DROP_ZONE_POSITION_2 = [1.3218471653565846, -0.24012661796669224, 0.8032350447639837, -0.026851219261451377, -1.4292520424023896, -1.1837551805834068]
程序启动
- 启动机器人控制
在终端 1 中:
roslaunch alicia_d_driver alicia_d_bringup.launch
- 启动物体检测
在终端 2 中:
roscd alicia_d_object_sort/scripts
python3 camera_obj_detection.py
- 启动立方体分拣
在终端 3 中:
roscd alicia_d_object_sort/scripts
python3 cube_sorting.py
配置
预定义位置
您可能需要修改 cube_sorting.py 中的以下预定义位置以匹配您的设置:
# 预定义位置
self.HOME_POSITION = [0.5101731659675737, -0.1741493363528409, 1.1561367836287713, 0.03145428542055679, -1.5228477209708768, -0.5163105875130477]
self.DROP_ZONE_POSITION = [1.4139084885387032, 0.08822543471619682, 0.33985971808065407, 0.046797839284243144, -1.2804195699246312, -1.3249158761293214]
self.DROP_ZONE_POSITION_2 = [1.3218471653565846, -0.24012661796669224, 0.8032350447639837, -0.026851219261451377, -1.4292520424023896, -1.1837551805834068]
查找您所需的位姿:
- 使用 MoveIt 的交互式标记拖拽机器人末端执行器
- 记录相应的机器人关节状态
- 在代码中更新位置值
7. 单操作臂的6D抓取
7.1 环境搭建
采用的设备:
-
Alicia d单操作臂;
-
ORBBEC(奥比中光)相机;
-
正方体

7.1.1 抓取物体准备
准备大小合适的物体用于抓取。

7.1.2 相机准备
通过相机支架或其他工具将固定相机位置,确保相机的视野包含待识别的抓取区域。
相机需要包含RGB镜头,能够读取出RGB和depth深度图像。
7.2 相机外参标定
详情可见于玄雅科技 - 动手学AI + 机器人系列课程
7.3 前置要求
-
GPU (nvidia-smi查看)
-
Anaconda3 或 Miniconda3
-
CUDA Toolkit (nvcc --verison查看)
7.4 Conda环境配置
- Conda环境创建及基本库安装
conda create -n grasp python=3.8
conda activate grasp
conda install pytorch torchvision torchaudio pytorch-cuda=11.8 -c pytorch -c nvidia
MinkowskiEngine安装
cd ~/alicia_ws/src/alicia_d_grasp_6d
git clone https://github.com/NVIDIA/MinkowskiEngine.git
cd MinkowskiEngine
export CXX=g++-7
python setup.py install --blas_include_dirs=${CONDA_PREFIX}/include --blas=openblas
graspnetAPI安装
pip install graspnetAPI
graspness_implementation安装
cd cd ~/alicia_ws/src
git clone https://github.com/rhett-chen/graspness_implementation ./alicia_d_grasp_6d/
cd alicia_d_grasp_6d/pointnet2
python setup.py install # install pointnet2 packg
cd ../knn
python setup.py install # install knn package
具体可参考https://github.com/rhett-chen/graspness\_implementation
7.5 启动命令
启动机械臂控制及相机:
roslaunch alicia_d_driver serial_server.launch
roslaunch alicia_d_moveit real_robot_control.launch camera_load:=true2
因graspness模型的物体识别和抓取预测已训练完成,可直接调用训练好的checkpoint文件直接预测目标物体位姿及最优抓取位姿。
cd ~/alicia_ws/src/alicia_d_grasp_6d/
conda activate grasp
python alicia_grasp.py