机器人夹爪的选型与ROS通讯——机器人抓取系统基础系列(六)

发布于:2025-06-03 ⋅ 阅读:(22) ⋅ 点赞:(0)


前言

本文将介绍夹爪的选型方法和通讯方式。以鞋子这类操作对象为例,将详细阐述了对应的夹爪选型过程及其ROS通讯控制方法。


一、夹爪的选型

1.1 任务需求分析

夹爪选型的第一步是确定任务需求,然后根据任务需求逐步确定夹爪的要素。
任务需求能够用两类宏观的参数进行概括 [1]:

第一类是描述物体的属性,包括物理属性和几何属性。
1)物理属性包括诸如尺寸、重量、刚度等,对于一些特殊行业可能还要考虑电导率(3C行业)和卫生性(食品行业);
2)几何属性包括形状、粗糙度、结构等。

第二类是描述物体的操作需求,比如
1)放置(例如高精度对准);
2)上料(例如上料物体的定向/非定向状态);
3)搬运(例如提升、移动、重定向)。

以鞋子打包任务为例,被操作对象为鞋子(图1),分析如下:
物体属性:鞋子可变形而且形状不规则,鞋子的重量虽轻,但是其尺寸各异。
操作需求:鞋子的放置虽然不需要高精度,但是从任意初态到打包状态,需要对物体进行重定向。
鞋子的属性

图1:某品牌单只运动鞋的属性。

综合上述两类宏观参数,软体夹爪为优先选择。首先,软体夹爪对于鞋子的形状、刚度、尺寸都具有较好的适应性;其次,在重定向过程中,软体夹爪的柔顺性也能够保护鞋面不被划伤。尽管软体夹爪的夹持力较小并且精度有限,但能够满足该任务的需求。

1.2 软体夹爪的选型

对于软体夹爪,国内的厂家主要有Rochu [2] 和SRT [5] 两家。对于该任务,两家的产品均能满足需求,本文以Rochu夹爪为例,简单展示其选型过程。

根据上述分析,鞋子的长度较长,为了稳定地抓取,最好选择两指并拢的四指布局。同时,Rochu的末端执行器是模块化的,所以要按照模块逐步选择(图2)。

柔触抓取系统

图2:柔触抓取系统 [3]。左:完整的机器人抓取系统。右:机器人末端执行器模块。

针对鞋子打包任务,各模块选择的主要依据如下:
1)手指模块选型的主要依据是鞋子的高度,确保能够有效包络鞋子;
2)滑移安装板选型的主要依据是鞋子的宽度,确保其指间距足够大;
3)法兰连接模块需要考虑其长度对安装的便携性;
4)快换模块对于此任务暂不需要;

综合上述因素,最终确定的柔触夹爪的型号为GC-4FMA6V5/LS1-SMP2L-FCMR03。

温馨提示:
1)柔触夹爪的选型手册下载地址:https://www.rochu.com/fileDownload。
2)对于各模块的选型,相关销售也会辅助决策。

二、夹爪的ROS通讯

2.1 夹爪的通信方式介绍

当机器人的末端执行器确定之后,需要确定其对应的驱动器。本案例选择无源驱动器PCU(图3),其输入包括来自气泵的气体和电脑的控制信号,其输出气体直接控制着夹爪的状态 [4]。
柔触夹爪驱动器

图3:柔触驱动器(PCU)的功能示意图 [4]。

根据驱动器手册 [4],驱动器的控制方式有以下两种:
1)I/O控制方式:通过24VDC电平信号和DB25端口进行控制。
2)Modbus通信方式:通过TCP/RTU-485协议进行通信。

如果要集成到ROS系统,推荐使用Modbus通信方式,因为它提供了更灵活的控制方式,并且可以通过网络进行通信,适合ROS环境中的分布式控制。

在进行通讯测试之前请确保所有的气路连接和通讯连接都已完成。如图3所示,包括进气口和出气口,还有Modbus通信连接线。如果使用Modbus TCP,就准备网线,如果使用Modbus RTU-485,就准备好USB转485的通讯数据线。

本文以Modbus RTU-485通讯方式为例,需要额外准备一根USB转485的通讯数据线,其端口TR+/TR-和DB25的17/18端子线(对应485通讯)连接,以保证信号的转换和传输。

2.2 串口助手测试

在进行ROS通讯之前,最好先进行串口通讯测试,一方面可以测试系统的联通性,另一方面可以熟悉系统的工作特性。其中,夹爪的状态包括open, close, nature三个状态,而夹爪的控制信号是四个,分别是open, relax_open, close, relax_close (如图5(a)所示)。

在Windows上进行串口测试时,首先确保系统的串口驱动已安装,然后再安装串口助手软件(如SSCOM,ECOM等)。串口助手的通讯参数设置如图4(左)所示,发送的十六进制指令的对应功能参考PCU驱动器手册 [4]。

串口助手

图4:串口助手界面。左:Windows中的ECOM串口助手。右:Ubuntu中的CuteCom串口助手。

对于Ubuntu系统,可安装其串口助手如cutecom(图4(右)),进行通讯测试,通讯参数设置和Windows类似。以cutecom串口助手为例,其安装和串口设置如下所示 [6]:

# 安装cutecom
sudo apt-get install cutecom

# 编辑串口权限
ls -l /dev/ttyUSB* # 串口查询并设置权限
sudo chmod 777 /dev/ttyUSB0  #根据自己的设备名自行改变

# 打开串口
cutecom

注意在cutecom串口中输入的16进制控制指令,要加上末尾的CRC校验码,在图4(左)的Windows串口助手中的历史数据就是包含CRC校验码的数据。这些带CRC校验码的16进制控制指令也将会用到接下来的ROS通讯中。

2.3 ROS通讯节点实现

ROS的serial功能包是一个用于ROS与串行设备进行通信的库。这个库是跨平台的,简单易用,它提供了一个C++的面向对象接口。通过安装serial功能包,可以创建一个串口对象,并通过该对象的成员函数read读取数据。serial功能包的安装指令如下:

sudo apt update
sudo apt install ros-noetic-serial # 注意替换为你的系统名称

这里创建一个专门用于ROS和串行设备通信的功能包,该功能包的消息传输路线如下图5(b)所示,该功能包包括两个节点 [7]。
夹爪不同状态切换和ROS通讯控制

图5:夹爪的不同状态切换和ROS通讯控制功能包。(a)夹爪的三个状态和控制它们之间切换的四个控制指令(通过/gripper_control话题传输给ROS通讯功能包)。(b)控制串口设备(如本文柔触驱动器)的ROS通讯功能包的话题消息传递。

第一个节点负责接受Gripper的指令,Rochu Gripper的四个指令包括open, relax_open, close, relax_close(图5(a)),然后将这些指令转换为对应的Modbus RTU协议格式16进制控制指令发布出去。具体实施代码和详细注释如下所示:

#include <ros/ros.h>
#include <serial/serial.h>
#include <std_msgs/String.h>
#include <std_msgs/Bool.h>
#include <std_msgs/Empty.h>
#include "serial_msgs/serial.h"

#define rBUFFERSIZE 8  // 定义接收缓冲区大小
unsigned char r_buffer[rBUFFERSIZE];  // 接收缓冲区
serial::Serial ser;  // 串口对象
std_msgs::String gripper;  // 夹爪控制消息

// 订阅者回调函数,接收夹爪控制指令
void write_callback(const std_msgs::String::ConstPtr& msg)
{
    ROS_INFO_STREAM("写入串口数据: " << msg->data);
    gripper.data = msg->data;  // 更新夹爪状态
}

int main(int argc, char** argv)
{
    // ROS节点初始化
    ros::init(argc, argv, "serial_example_node1");
    ros::NodeHandle nh;

    // 创建订阅者订阅夹爪控制指令
    ros::Subscriber write_sub = nh.subscribe("/gripper_control", 10, write_callback);
    // 创建发布者发布串口消息
    ros::Publisher msg_pub = nh.advertise<serial_msgs::serial>("read1", 10);

    // 设置循环频率50Hz
    ros::Rate loop_rate(50);

    while(ros::ok()){
        serial_msgs::serial msg;  // 创建串口消息对象
        msg.serial.clear();      // 清空消息内容

        ros::spinOnce();  // 处理回调函数

        // 根据接收到的指令生成对应的串口控制指令
        if(gripper.data == "close") {          // 闭合夹爪指令
            r_buffer[0] = 0x01;
            r_buffer[1] = 0x05;
            r_buffer[2] = 0x01;
            r_buffer[3] = 0x00;
            r_buffer[4] = 0xFF;
            r_buffer[5] = 0x00;
            r_buffer[6] = 0x8D;
            r_buffer[7] = 0xC6;
        }
        else if(gripper.data  == "relax_close") { // 松开闭合指令
            r_buffer[0] = 0x01;
            r_buffer[1] = 0x05;
            r_buffer[2] = 0x01;
            r_buffer[3] = 0x00;
            r_buffer[4] = 0x00;
            r_buffer[5] = 0x00;
            r_buffer[6] = 0xCC;
            r_buffer[7] = 0x36;
        }
        else if(gripper.data  == "open") {      // 打开夹爪指令
            r_buffer[0] = 0x01;
            r_buffer[1] = 0x05;
            r_buffer[2] = 0x01;
            r_buffer[3] = 0x01;
            r_buffer[4] = 0xFF;
            r_buffer[5] = 0x00;
            r_buffer[6] = 0xDC;
            r_buffer[7] = 0x06;
        }
        else if(gripper.data == "relax_open") { // 松开打开指令
            r_buffer[0] = 0x01;
            r_buffer[1] = 0x05;
            r_buffer[2] = 0x01;
            r_buffer[3] = 0x01;
            r_buffer[4] = 0x00;
            r_buffer[5] = 0x00;
            r_buffer[6] = 0x9D;
            r_buffer[7] = 0xF6;
        }

        // 将缓冲区数据填充到消息中
        for(int l=0; l<rBUFFERSIZE; l++) {
            msg.serial.push_back(r_buffer[l]);
        }

        msg_pub.publish(msg);  // 发布串口消息
        loop_rate.sleep();     // 维持循环频率
    }
}

第二个节点负责接受第一个节点传过来的控制指令,然后将其通过成员函数read写到串口设备。具体实施代码和详细注释如下所示:

#include "ros/ros.h"
#include "std_msgs/String.h"
#include "serial_msgs/serial.h"
#include <serial/serial.h>
#include <std_msgs/Empty.h>

#define sBUFFERSIZE 8       // 定义发送缓冲区大小
unsigned char s_buffer[sBUFFERSIZE]; // 发送缓冲区
serial::Serial ser;         // 串口通信对象

// 串口数据回调函数
void chatterCallback(const serial_msgs::serial::ConstPtr& msg)
{
    ROS_INFO_STREAM("正在写入串口数据");
    
    // 将接收到的消息数据复制到发送缓冲区
    for(int i=0; i<msg->serial.size(); ++i)
    {
        s_buffer[i] = msg->serial[i];
    }
    
    // 通过串口发送二进制数据
    ser.write(s_buffer, sBUFFERSIZE);
}

int main(int argc, char **argv)
{
    // ROS节点初始化
    ros::init(argc, argv, "listen1");
    ros::NodeHandle n;

    // 串口配置和初始化
    try {
        ser.setPort("/dev/ttyUSB0");    // 设置串口设备
        ser.setBaudrate(9600);          // 设置波特率
        serial::Timeout to = serial::Timeout::simpleTimeout(1000);
        ser.setTimeout(to);             // 设置超时时间
        ser.open();                    // 打开串口
    } catch (serial::IOException& e) {
        ROS_ERROR_STREAM("无法打开串口端口"); // 异常处理
        return -1;
    }

    // 检查串口是否成功打开
    if(ser.isOpen()) {
        ROS_INFO_STREAM("串口初始化成功");
    } else {
        return -1;
    }
    
    // 创建订阅者,监听read1主题
    ros::Subscriber sub = n.subscribe("read1", 10, chatterCallback);
    
    // 进入ROS事件循环
    ros::spin();
    
    return 0;
}

在调试节点时,可以使用以下常用的关于ros topic的指令来调试:

rostopic list # 列出当前所有活跃的话题。
rostopic info /topic_name # 显示指定话题的详细信息,包括发布者和订阅者。
rostopic echo /topic_name # 打印指定话题上的消息内容。
rostopic pub /topic_name message_type "message_content" # 向指定话题发布消息。message_type 是消息的类型,message_content 是消息内容。

本文中ROS和串口设备(如本文柔触驱动器)通讯的完整功能包下载地址参考博主的博客资源。
本文是以柔触的旧版驱动器(PCU-v1.2.6)开展的实验,注意和新版驱动器的区别。


总结

本文主要讲解了夹爪的选型和通讯控制。首先介绍了如何根据任务需求对夹进行选型,其次以柔触夹爪为例,讲解了其控制方式和ROS通讯控制方法,为类似的夹爪选型和通讯任务提供参考。

Reference:

[1] Fantoni G, Capiferri S, Tilli J. Method for supporting the selection of robot grippers[J]. Procedia CIRP, 2014, 21: 330-335.
[2] 柔触官网:https://www.rochu.com/.
[3] 柔触机器人选型手册V2.6版: https://www.rochu.com/fileDownload.
[4] Rochu用户手册PCU-V1.2.6版: https://www.rochu.com/fileDownload.
[5] SRT官网:https://softrobottech.com/.
[6] Linux下使用可视化的串口调试工具cutecom: https://www.cnblogs.com/Netsharp/p/16010814.html.
[7] 在ROS中与其他器件使用十六进制串口通信 - 代码下载: https://download.csdn.net/download/chduan_10/9920218.


网站公告

今日签到

点亮在社区的每一天
去签到