机器人抓取系统基础系列文章目录
1. UR机械臂的ROS驱动安装官方教程详解——机器人抓取系统基础系列(一)
2. MoveIt控制机械臂的运动实现——机器人抓取系统基础系列(二)
3. 机器人(机械臂)的相机选型与安装——机器人抓取系统基础系列(三)
4. Realsense相机驱动安装及其ROS通讯配置——机器人抓取系统基础系列(四)
5. 机器人的手眼标定——机器人抓取系统基础系列(五)
6. 机器人夹爪的选型与ROS通讯——机器人抓取系统基础系列(六)
7. 机器人抓取流程介绍与实现——机器人抓取系统基础系列(七)


机器人抓取流程介绍与实现——机器人抓取系统基础系列(七)

  • 前言
  • 一、抓取路线介绍
  • 二、物体的定位
  • 三、物体位姿和抓取位姿估计
  • 四、坐标系转换与运动规划
  • 五、抓取实施
  • 总结
  • Reference


前言

本文介绍了机器人抓取的流程和具体实施过程,主要包括物体的定位、位姿估计、坐标系转换、抓取系统硬件与抓取实施。不仅提供了关键步骤的示例函数和代码,也提供了整个基于ROS的抓取系统运行步骤。为机器人相关工作人员提供参考。


一、抓取路线介绍

机器人的抓取实施的主要流程包括 [1]:

1)相机发布视觉相关信息;
2)订阅视觉信息并计算物体在像素坐标系下的信息(如位置,关键点,角度等);
3)根据物体的初步信息计算物体在相机坐标系下的物体位姿和抓取位姿;
4)将相机坐标系下的抓取位姿转换为机器人坐标系下的抓取位姿,进一步转换为机器人末端执行位姿,然后规划路径;
5)机器人通过运动规划算法控制末端执行器的抓取。

本文假设读者已经根据前述系列教程完成了基础配置工作,包括机械臂的ROS驱动配置、相机的驱动与通讯配置、夹爪的通讯配置和手眼标定相关工作。接下来,就是具体物体的识别和抓取规划实现了。

基于视觉的抓取估计分为2D抓取和6D抓取,2D抓取适用于垂直水平面的特定角度抓取(需要确定2D位置和1个抓取角),6D抓取则实现任意角度抓取(需要确定3D位置和3D姿态)。本文为便于说明抓取的实施流程,以简单的2D抓取为例。

二、物体的定位

根据相关资料 [2, 3],基于视觉的抓取检测包含三个子任务:物体定位,物体位姿估计,抓取位姿估计。对于具体的抓取任务,这三个子任务可以通过不同的组合方式来实现抓取。

第一步的物体定位又分为三种方法:
只定位不识别:获取目标物体的区域,但不知道目标物体的类别;
目标检测:获取目标物体的区域,同时识别出物体的类别;
目标实例分割:识别物体的同时,获得像素级/点云级物体区域。

以下表格为DeepSeek总结的三种物体定位方法的具体区别,根据表格内容,以下为简单选择建议:
• 追求极致速度和简单场景(单一物体):只定位不识别
• 需要区分抓取多种物体且定位要求不极致:目标检测 (性价比之选)。
• 需要极高抓取精度、处理复杂堆叠/遮挡、抓取特定部位:目标实例分割 (性能最优,但成本/计算量最高)。

用于机器人抓取的物体定位方法对比

给定机器人抓取场景,目前总能找到合适的技术方案来定位目标物体的位置,进而执行后续的物体位姿估计以及机器人抓取位姿估计等任务。

以目标检测为例,流行的算法如YOLO [4] 就可以获得物体的类别和位置信息(可以是四个识别框的角点,也可以是识别框的中心点、长、宽和角度)。

三、物体位姿和抓取位姿估计

对于桌面上的物体位姿估计,如中心对称物体(如圆形橡皮)为例,YOLO本身的输出信息就足够确定其物体位姿。比如其物体位置由YOLO识别的中心点确定,物体角度可以假设。

对于非中心对称物体(如长方形橡皮),除了YOLO确定的抓取中心点位置之外,还需要确定其抓取角度。比如可以再通过该物体分割区域最小外接矩形的角度来指定其抓取角度。

需要指出的是,YOLO的位置信息只有2D位置,而且是像素坐标系下的位置信息(单位为像素)。在实际的抓取任务中,我们需要先将其位置信息转换为相机坐标系下的位置信息(单位为米)。其中Z坐标上的值可以根据深度计算,也可以设定特定的数值(如果抓取高度已知)。

然后物体位姿就是在相机坐标系下的位姿信息和物体的角度定义的,其定义可以通过以下函数实现。

def pose3d(center3d, object_angle):"""根据物体的位置和角度定义物体的位姿参数:如下center3d: 相机坐标系下的物体3D位置object_angle: 物体的角度返回: 相机坐标系下的物体位姿"""center_pose = PoseStamped()center_pose.header.frame_id = "camera_color_frame"center_pose.header.stamp = rospy.Time.now()center_pose.pose.position = center3droll = 0pitch = 0yaw = math.radians(object_angle) q = quaternion_from_euler(roll, pitch, yaw)center_pose.pose.orientation = Quaternion(*q)return center_pose

对于形状规则的物体,其抓取位姿可以根据其物体位姿直接定义,只需要设置特定的对应关系即可。而对于一些不规则物体或者工具类物体,其抓取位姿还需要考虑其具体形状和任务需求。

本文的重点在于说明整个抓取Pipeline的工作流程,选择了形状规则的物体如长方形橡皮为抓取对象。对于长方形的橡皮,只需要保证执行器的末端位姿(即抓取位姿)和橡皮的位姿重合即可。

四、坐标系转换与运动规划

1 相机坐标系下的物体位姿TObjectCamera\mathbf{T}_{\text{Object}}^{\text{Camera}}TObjectCamera到机器人坐标系的物体位姿TObjectRobotBase\mathbf{T}_{\text{Object}}^{\text{RobotBase}}TObjectRobotBase转换原理如以下公式所示。
TObjectRobotBase=TObjectCamera⋅TCameraRobotBase\mathbf{T}_{\text{Object}}^{\text{RobotBase}}=\mathbf{T}_{\text{Object}}^{\text{Camera}} \cdot \mathbf{T}_{\text{Camera}}^{\text{RobotBase}} TObjectRobotBase=TObjectCameraTCameraRobotBase
其中,TCameraRobotBase\mathbf{T}_{\text{Camera}}^{\text{RobotBase}}TCameraRobotBase为提前手眼标定好的结果,存储在特定文件中,使用时将其标定结果发布出去即可,发布指令如下,参考基础系列博客(五)。

roslaunch easy_handeye publish.launch

在位姿转换时,可以直接使用TF坐标转换函数:

def transformCoor(msg, max_retries=3):tfBuffer = get_tf_buffer()  # Initializing TF system...for attempt in range(max_retries):try:# 使用最新可用变换(不指定特定时间)transform = tfBuffer.lookup_transform("base_link", "camera_color_frame",rospy.Time(0),  # 最新可用时间rospy.Duration(1.0))# 应用变换到目标坐标系pose_in_camera = PoseStamped()pose_in_camera.pose = msg.posepose_in_camera.header.frame_id = "camera_color_frame"pose_in_camera.header.stamp = rospy.Time.now()# 使用transform进行坐标变换pose_in_base = tf2_geometry_msgs.do_transform_pose(pose_in_camera, transform)return pose_in_base.poseexcept (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException) as e:rospy.logwarn(f"TF转换尝试 {attempt+1}/{max_retries} 失败: {str(e)}")rospy.sleep(0.1)  # 短暂等待后重试rospy.logerr("坐标变换失败,达到最大重试次数")return None

2 机器人坐标系下的物体位姿TObjectRobotBase\mathbf{T}_{\text{Object}}^{\text{RobotBase}}TObjectRobotBase到机器人末端的可执行位姿TTool0RobotBase\mathbf{T}_{\text{Tool0}}^{\text{RobotBase}}TTool0RobotBase的转换过程如下所示。
物体位姿到机器人末端位姿(可执行位姿)的坐标系转换
根据上图中机器人抓取系统的坐标关系,可得坐标系之间的关系如下:
TTool0RobotBase⋅TToolEndTool0=TObjectRobotBase⋅TToolEndObject\mathbf{T}_{\text{Tool0}}^{\text{RobotBase}} \cdot \mathbf{T}_{\text{ToolEnd}}^{\text{Tool0}} = \mathbf{T}_{\text{Object}}^{\text{RobotBase}} \cdot \mathbf{T}_{\text{ToolEnd}}^{\text{Object}} TTool0RobotBaseTToolEndTool0=TObjectRobotBaseTToolEndObject
移项可得如下公式:
TTool0RobotBase=TObjectRobotBase⋅TToolEndObject⋅(TToolEndTool0)−1\mathbf{T}_{\text{Tool0}}^{\text{RobotBase}} = \mathbf{T}_{\text{Object}}^{\text{RobotBase}} \cdot \mathbf{T}_{\text{ToolEnd}}^{\text{Object}} \cdot (\mathbf{T}_{\text{ToolEnd}}^{\text{Tool0}})^{-1} TTool0RobotBase=TObjectRobotBaseTToolEndObject(TToolEndTool0)1
其中:
TObjectRobotBase\mathbf{T}_{\text{Object}}^{\text{RobotBase}}TObjectRobotBase为上一步求出的物体在机器人坐标系下的表示;
TToolEndObject\mathbf{T}_{\text{ToolEnd}}^{\text{Object}}TToolEndObject为抓取位姿到物体位姿的关系,为提前设定的;
TToolEndTool0\mathbf{T}_{\text{ToolEnd}}^{\text{Tool0}}TToolEndTool0为夹爪末端坐标系和机械臂末端的关系,由夹爪的长度和安装方式决定;

实际执行时,我们可以专门定义一个坐标转换函数,如下所示,其中eelink表示tool0:

def transform_end(pos):# eelink_to_robot, object_to_robot, toolend_to_object, toolend_to_eelinkrealEnd = Pose()object_to_robot = tf.transformations.quaternion_matrix([pos.orientation.x, pos.orientation.y, pos.orientation.z, pos.orientation.w]) # the order of xyzwobject_to_robot[:, 3] = [pos.position.x, pos.position.y, pos.position.z, 1]toolend_to_object = tf.transformations.quaternion_matrix([0, 0, 0, 1]) # the order of xyzwtoolend_to_object[:, 3] = [0, 0, 0, 1]toolend_to_eelink = tf.transformations.quaternion_matrix([0, 0, 0, 1]) # the order of xyzwtoolend_to_eelink[:, 3] = [0.0, 0.0, 0.22, 1]eelink_to_robot = numpy.dot( numpy.dot(object_to_robot, toolend_to_object), numpy.linalg.inv(toolend_to_eelink))realEnd.position.x = eelink_to_robot[0, 3]realEnd.position.y = eelink_to_robot[1, 3]realEnd.position.z = eelink_to_robot[2, 3]q = tf.transformations.quaternion_from_matrix(eelink_to_robot)realEnd.orientation.x = q[0]realEnd.orientation.y = q[1]realEnd.orientation.z = q[2]realEnd.orientation.w = q[3]return realEnd

3 运动规划
在实际抓取过程中,我们可能还会设置接近位姿、抓取位姿、拾起位姿、home位姿等,只需要让机器人在这些位姿之间移动并配合夹爪的开合即可完成抓取任务。

运动规划使用MoveIt实现,在默认配置下,使用OMPL提供的RRTConnect算法来完成机械臂的运动规划任务。当然可以选择其他算法,也可以用自定义规划算法。

五、抓取实施

本文是在前述系列教程的基础上撰写的,在前述系列教程中,我们使用的机械臂为UR5e,相机为Realsense相机,夹爪为Rochu夹爪,控制系统使用的是ROS。整个硬件系统的如下图所示,其中,黄色线路表示气体驱动线路,紫色线路表示信号传输线路。

机器人抓取硬件系统

根据前述系列博客和本文的内容,在抓取和操作实施时,需要启动的节点依次如下所示:

1 Realsense相机相关节点启动:
发布包括/camera/color/image_raw话题在内的所有图像相关话题 [5],关于Realsense相机的ROS通讯配置参考基础系列博客(四)。

# 启动相机节点并发布相关图像话题
roslaunch realsense2_camera rs_camera.launch
# 如果需要深度图与彩色图像素精确匹配时(如RGB-D融合、点云生成、SLAM),对齐深度
roslaunch realsense2_camera rs_camera.launch align_depth:=true

2 视觉计算节点启动:
接收从相机传过来的RGB图像并做初步处理,获取像素坐标系中的物体位置,角度等信息。

# 根据任务需求自定义视觉处理算法,本案例中使用基于YOLO的视觉处理算法
rosrun ultralytics_ros yolo_ros_node.py

3 夹爪通讯相关节点启动:
基础系列博客(六)详细说明了夹爪的ROS通讯控制。

# 启动夹爪的通讯节点,等待接收夹爪控制指令
roslaunch serial_msgs gripper_control.launch 

4 机械臂相关节点启动:
启动UR5e工作所需要的所有相关节点,其配置过程参考基础系列博客(一)。

# 本文使用的是ur5e机械臂
roslaunch ur_robot_driver ur5e_work_all.launch

5 手眼标定结果发布节点启动:
发布手眼标定计算出的标定结果,基础系列博客(五)详细说明了手眼标定的原理和实操步骤。

# 本文使用easy_handeye标定功能包
roslaunch easy_handeye publish.launch

6 抓取或操作规划器节点启动:
启动抓取或者操作规划器,执行物体位姿计算与坐标系转换,发布路径点和夹爪控制指令。

# 根据任务需要自定义抓取或者操作规划器
rosrun ur_work TaskPlanner.py

上述节点中,需要自定义完成的是视觉计算节点和抓取规划器节点,在完成这些节点的定义后按照上述顺序依次启动节点,即可完成机械臂的抓取或操作任务。

当然,以上所有节点可以写在launch文件中,以减少启动窗口,在测试初期可以分别启动以测试不同节点的运行情况。


总结

以上就是今天要讲的内容,本文主要讲了机器人抓取流程和抓取实现,首先简单介绍了抓取的路线,然后重点讲解物体的识别和定位、物体的位姿和抓取位姿估计、抓取实施时的坐标系转换,最后介绍了抓取系统和抓取实施需要启动的节点。为机器人相关工作人员提供参考。

Reference

[1] 视觉机械臂自主抓取全流程:https://blog.csdn.net/knightsinghua/article/details/125328920?spm=1001.2014.3001.5501
[2] Du G, Wang K, Lian S, et al. Vision-based robotic grasping from object localization, object pose estimation to grasp estimation for parallel grippers: a review[J]. Artificial Intelligence Review, 2021, 54(3): 1677-1734
[3] 机器人抓取中物体定位算法概述:https://blog.csdn.net/dsoftware/article/details/105936927?spm=1001.2014.3001.5502
[4] Ultralytics YOLO 文件:https://docs.ultralytics.com/zh/
[5] Realsense-ROS1通讯配置:https://github.com/IntelRealSense/realsense-ros/tree/ros1-legacy

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。
如若转载,请注明出处:http://www.pswp.cn/pingmian/91740.shtml
繁体地址,请注明出处:http://hk.pswp.cn/pingmian/91740.shtml
英文地址,请注明出处:http://en.pswp.cn/pingmian/91740.shtml

如若内容造成侵权/违法违规/事实不符,请联系英文站点网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

【Qt】QObject::startTimer: Timers cannot be started from another thread

QTimer对象的 start 函数调用必须和创建QTimer对象是同一个线程。 #include "QtTimerTest.h" #include <QDebug>QtTimerTest::QtTimerTest(QWidget *parent): QMainWindow(parent),m_timer(nullptr),m_timerThread(nullptr), m_workingThread(nullptr) {ui.set…

社会治安满意度调查:为城市安全治理提供精准参考(满意度调查公司)

在社会治理不断深化的背景下&#xff0c;公众对社会治安的感知与评价已成为衡量城市治理水平的重要维度&#xff08;社会治安满意度调查&#xff09;&#xff08;公众满意度调查&#xff09;&#xff08;满意度调查&#xff09;。为全面掌握市民对治安状况的真实反馈&#xff0…

Python篇--- Python 的加载、缓存、覆盖机制

要理解 import 与 if __name__ "__main__": 的关系&#xff0c;以及 Python 的加载、缓存、覆盖机制&#xff0c;我们可以从 “模块的两种身份” 和 “导入的全过程” 入手&#xff0c;用通俗的例子一步步拆解。一、核心&#xff1a;模块的 “双重身份” 与 __name_…

Java设计模式之行为型模式(访问者模式)应用场景分析

访问者模式&#xff08;Visitor Pattern&#xff09;作为Java设计模式中的“隐形冠军”&#xff0c;常被开发者低估其价值。这一模式通过“双分派”机制巧妙解耦数据结构与操作&#xff0c;为复杂系统的扩展提供了强大武器。在大厂项目中&#xff0c;访问者模式往往出现在业务逻…

【IDEA】JavaWeb自定义servlet模板

方法一&#xff1a;&#xff08;推荐去使用方法二&#xff0c;还能创建其它代码模板&#xff09;使用servlet模板创建Servlet类如果创建时找不到servlet模板&#xff1a;File -> Project Structure然后应用 -> OK&#xff0c;如果还是找不到Servlet模板&#xff0c;看看项…

Linux选择

在内存中运行着的进程称为&#xff08; 服务 &#xff09;。负责控制systemd系统和服务管理器的工具为&#xff08; systemctl &#xff09;命令。systemd管理系统服务的基本单位是&#xff08; unit &#xff09;。分配和管理资源的基本单位是&#xff08; 进程 &#xf…

【Redis学习路|第一篇】初步认识Redis

概要: 深入探讨NoSQL数据库的核心特性&#xff0c;对比传统关系型数据库的差异&#xff0c;重点介绍Redis作为内存数据库的优势与应用场景。 文章目录认识 NoSQLNoSQL vs SQL 对比1️⃣ 结构化 vs 非结构化2️⃣ 关联 vs 非关联3️⃣ 查询方式对比4️⃣ 事务特性5️⃣ 存储方式…

java局域网聊天室小项目架构思路

java局域网聊天室小项目架构思路 项目需求 创建一个局域网聊天系统&#xff0c;要求&#xff1a;用户在登录界面登录后进入聊天窗口界面&#xff0c;能实现多用户同时在线聊天&#xff0c;并且用户之间可以进行私聊 项目用到的技术栈 java网络编程java多线程java面向对象编…

vulhub-corrosion2靶机

1.安装靶机 https://download.vulnhub.com/corrosion/Corrosion2.ovahttps://download.vulnhub.com/corrosion/Corrosion2.ova 2.扫描IP 3.扫描端口 4.访问端口 首先访问一下80端口 访问一个8080端口发现是一个apache的页面 5.扫描目录与漏洞探测 那么我们扫描一下目录 80…

Mysql深入学习:慢sql执行

目录 慢查询日志 慢查询主要步骤 11种慢查询的场景分析 场景一&#xff1a;SQL 没有建立索引 场景二&#xff1a;索引未生效的典型原因 场景三&#xff1a;LIMIT 深分页导致性能下降 场景四&#xff1a;单表数据量过大导致 SQL 性能下降 场景五&#xff1a;ORDER BY 出现…

李宏毅深度学习教程 第8-9章 生成模型+扩散模型

【2025版】12 生成式对抗网络GAN 一 – 基本概念介紹_哔哩哔哩_bilibili 目录 1. GAN生成式对抗网络 2. GAN的训练 散度差异 3.WGAN 4.训练GAN 5. 如何客观评估GAN 6. 条件型生成&#xff08;按照要求&#xff09; 7. Cycle GAN&#xff08;互转配对&#xff09; 8. d…

1.8 axios详解

Axios的定义与核心特性Axios是一个基于Promise的现代化HTTP客户端库&#xff0c;主要用于在浏览器和Node.js 环境中发送HTTP请求&#xff0c;旨在简化异步数据交互流程。其核心特性如下&#xff1a;跨平台支持&#xff1a;在浏览器中通过XMLHttpRequest对象发送请求&#xff0c…

41.安卓逆向2-frida hook技术-过firda检测(五)-利用ida分析app的so文件中frida检测函数过检测

免责声明&#xff1a;内容仅供学习参考&#xff0c;请合法利用知识&#xff0c;禁止进行违法犯罪活动&#xff01; 内容参考于&#xff1a;图灵Python学院 工具下载&#xff1a; 链接&#xff1a;https://pan.baidu.com/s/1bb8NhJc9eTuLzQr39lF55Q?pwdzy89 提取码&#xff1…

安卓调javaScript Not find method “forceLogout“ implementatidsignature or namesp

核对一下是否实现对应的javaScript或者javaScript的方法参数对不对&#xff0c; 在这里插入图片描述我这里一开始实现了这个方法但是没有给参数&#xff0c;一直报异常&#xff0c;后台说token没给就查token的问题&#xff0c;最后发现是搞偏了&#xff0c;两个原因&#xff0c…

【Linux网络】:UDP(传输层协议)

目录 一、铺垫知识 1、传输层 2、端口号 2.1、五元组表示 一个进程通信 2.2、端口号范围划分 2.3、知名端口 2.4、查看端口号 2.5、问题 3、pidof & netstat 命令 ①netsate 命令 ②pidof命令 二、UDP协议 1、UDP协议格式 2、UDP报文 1.1、UDP数据封装的过…

Effective C++ 条款19: 设计class犹如设计type

Effective C 条款19&#xff1a;设计class犹如设计type核心思想&#xff1a;设计新的class时&#xff0c;应当像语言设计者设计内置类型一样慎重&#xff0c;考虑对象的创建、销毁、初始化、拷贝、类型转换等所有方面。 ⚠️ 1. 类设计的关键问题域 对象生命周期管理&#xff1…

《汇编语言:基于X86处理器》第11章 MS-Windows编程(3)

本章展示的是如何用32 位Microsoft Windows API进行控制台窗口编程。应用编程接口(API:ApplicationProgramming Interface)是类型、常数和函数的集合体&#xff0c;它提供了一种用计算机代码操作对象的方式。本章将讨论文本I/O、颜色选择、时间与日期、数据文件I/O&#xff0c;…

在 macOS 上通过 Docker 部署DM8 (ARM 架构)

概述 达梦数据库 (DM8) 无法直接在 Apple macOS 操作系统上原生安装&#xff0c;通常需要通过虚拟机&#xff08;如 Parallels Desktop、VMware Fusion&#xff09;进行部署。另一种更轻量级且受 macOS 支持的方案是利用 Docker 容器技术来构建开发与测试环境。本文档将详细介…

网络协议之路由是怎么回事?

写在前面 要想去外面的世界看看, 就离不了路由器&#xff0c;而路由器工作的原理就是路由&#xff0c;那么具体是怎么路由的呢&#xff1f;本文就一起来看下这部分内容。 1&#xff1a;路由的配置 配置一条路由无非就是在配置以下三个信息&#xff1a; 1:包要去哪里&#x…

2106. 摘水果,梳理思路

文章目录题目概要java 解法详解题目概要 在一个无限的 x 坐标轴上&#xff0c;有许多水果分布在其中某些位置。给你一个二维整数数组 fruits &#xff0c;其中 fruits[i] [positioni, amounti] 表示共有 amounti 个水果放置在 positioni 上。fruits 已经按 positioni 升序排列…