7.1 myCobot 280-自适应夹爪

安装图示

对比 对比

产品安装教程

  • 第一步:

    使用乐高科技件将夹爪固定在机械臂顶部。

  • 第二步:

    连接到M5 Basic的末端执行器扩展接口(在安装图示中有标注)。

技巧 可以在夹爪指尖粘贴橡胶,以获得更好的摩擦力。

注意事项

  • 请确保产品已经按照说明连接成功
  • 请确保产品供电为附带适配器供电
  • 请确保电源适配器能正常工作

Arduino 环境下使用夹爪

  1. 电气连接

    • 夹爪引脚与 Basic的末端执行器扩展接口连接
  2. 新建一个Arduino程序,内容如下:

// 此文件用于mycobot设备控制末端夹爪运动,对应烧录设备为Basic
// 烧录前请将夹爪张开至最大角度
//导入相关库:
#include <MycobotBasic.h>
#include <ParameterList.h>
//实例化函数:
MycobotBasic myCobot;   
//初始化函数:
//编写setup函数,只在设备打开时执行一次setup函数:
void setup() {
  myCobot.setup();
  delay(10);
  myCobot.powerOn();
  delay(10);
  myCobot.setGripperIni();                          //设定夹爪当前位置电位值为2048
  delay(20);
  Serial.begin(9600);
}
//主体函数
//编写loop函数,程序循环执行loop函数:
void loop() {
    myCobot.setEncoder(7,2048);                     //设定末端夹爪打开至2048电位值
    delay(2000);
    Serial.println(myCobot.getGripperValue());      //读取末端夹爪电位值
    delay(50);
    myCobot.setEncoder(7,1700);                     //设定末端夹爪打开至1700电位值
    delay(2000);
    Serial.println(myCobot.getGripperValue());      //读取末端夹爪电位值
    delay(50);
}

Python 环境下使用夹爪

一、API 简介

1、 is_gripper_moving()

函数功能:判断夹爪是否正在运行。

返回参数:

1表示正在运行,0 表示没有运行,-1 表示出错

2、 set_encoder(joint_id, encoder)

函数功能:让指定关节点转动到指定位置

参数说明:

joint_id:取值范围 1~7,分别表示 1~6 个关节点以及夹爪。

encoder:取值范围 0~4096,2048 表示角度时的 0。

3、 set_encoders(encoders, sp)

函数功能:让机械臂移动到指定位置。

参数说明:

encoders:六个 int 元素的 list 集合,六个 encoder 数据的顺序分别代表 1~6 个关节点的位置。

sp:表示机械臂转动的速度。

4、 get_encoder(joint_id)

函数功能:获取指定关节点的 encoder 数据。

参数说明:

joint_id:取值范围 1~7,分别表示 1~6 个关节点以及夹爪。

返回值:

encoder:表示该关节的 encoder 数据信息。

5、 set_gripper_value(value, speed)

函数功能:让夹爪以指定的速度转动到指定的位置。

参数说明:

value:表示夹爪所要到达的位置,取值范围 0~4096。

speed:表示以多少的速度转动,取值范围 0~100。

6、 get_gripper_value()

函数功能:获取夹爪的encoder数据信息。

返回值:

encoder:夹爪的数据信息。

7、 set_gripper_state(flag, speed)

函数功能:让夹爪以指定的速度达到指定的状态。

参数说明:

flag:1 表示夹爪合拢,0 表示夹爪打开。

speed:表示以多快的速度达到指定的状态,取值范围 0~100。

二、代码内容

from pymycobot import PI_PORT, PI_BAUD  # 当使用树莓派版本的mycobot时,可以引用这两个变量进行MyCobot初始化
from pymycobot.mycobot import MyCobot
import time
def gripper_test(mc):
    print("Start check IO part of api\n")
    # 检测夹爪是否正在移动
    flag = mc.is_gripper_moving()
    print("Is gripper moving: {}".format(flag))
    time.sleep(1)

    # Set the current position to (2048).
    # Use it when you are sure you need it.
    # Gripper has been initialized for a long time. Generally, there
    # is no need to change the method.
    # mc.set_gripper_ini()
    # 设置关节点1,让其转动到2048这个位置
    mc.set_encoder(1, 2048)
    time.sleep(2)
    # 设置六个关节位,让机械臂以20的速度转动到该位置
    mc.set_encoders([1024, 1024, 1024, 1024, 1024, 1024], 20)
    time.sleep(3)
    # 获取关节点1的位置信息
    print(mc.get_encoder(1))
    # 设置夹爪转动到2048这个位置
    mc.set_encoder(7, 2048)
    time.sleep(3)
    # 设置夹爪让其转到1300这个位置
    mc.set_encoder(7, 1300)
    time.sleep(3)

    # 以70的速度让夹爪到达2048状态
    mc.set_gripper_value(2048, 70)
    time.sleep(3)
    # 以70的速度让夹爪到达1500状态
    mc.set_gripper_value(1500, 70)
    time.sleep(3)

    # 设置夹爪的状态,让其以70的速度快速打开爪子
    mc.set_gripper_state(0, 70)
    time.sleep(3)
    # 设置夹爪的状态,让其以70的速度快速收拢爪子
    mc.set_gripper_state(1, 70)
    time.sleep(3)

    # 获取夹爪的值
    print("")
    print(mc.get_gripper_value())

if __name__ == "__main__":
    # 初始化一个MyCobot对象
    mc = MyCobot(PI_PORT, PI_BAUD)
    # 让其移动到零位
    mc.set_encoders([2048, 2048, 2048, 2048, 2048, 2048], 20)
    time.sleep(3)
    gripper_test(mc)

Roboflow 环境下使用夹爪

1、登录RoboFlow

对比 2、点击创建空项目

对比 3、选择基础功能点击夹爪

对比

  • 用户通过一个简单的功能定义和控制夹爪。
    • 选择夹爪
    • 设置已存在夹爪
    • 选择夹爪,可以对已有夹爪进行编辑或者删除。
    • 定义新夹爪如下图所示,可以命名夹爪,同时控制多个输入信号:设置需要控制的输出信号的数量、在“设置”中选择设置第几个信号、设置状态(关系到具体执行时对应“打开”或“关闭”功能)、设置对应输出信号。在设置完成后,还可以选择等待条件。

对比

  • 设置已保存状态
    • 完全打开:执行夹爪定义中为“打开”状态的选项。
    • 完全关闭:执行夹爪定义中为“关闭”状态的选项。 调试控制
    • 打开夹爪:手动操作执行夹爪定义中为“打开”状态的选项。
    • 关闭夹爪:手动操作执行夹爪定义中为“关闭”状态的选项。

4、设置对应参数

对比

  • 1.设置程序数量
  • 2.设置程序ID
  • 3.设置夹爪打开或者关闭
  • 4.设置运行模式KEEP保持在设置状态
  • 5.执行后等待时间,建议设置在2s-5s

5、点击关闭切换到关闭的设置

对比 6、等待

  • 如下图所示,等待指令一共有四种模式。
    • 等待时间:可以设置延时时间,单位为秒。
    • 等待输入信号:对输入信号的状态进行判断,除非符合已设置的输入信号状态条件,否则一直等待。
    • 等待输出信号:对输出信号的状态进行判断,除非符合已设置的输出信号状态条件,否则一直等待。
    • 等待条件:可以自定义等待条件,除非符合等待条件,否则一直等待。

对比

7、设置

  • 如下图所示,设置指令有四种模式的选择。
    • 设置PIN:设置输出信号的状态,除了选择设置的输出信号,确定其是打开或关闭的状态,还可以设置该信号保持的时间。
    • 设置条件:自定义设置的内容。
    • 设置TCP(即工具中心点)。
    • 设置载荷。

对比

8、组合

  • 如下图所示,组合指令提供了常用组合模板,例如抓取和放置组合。

对比

  • 用户使用组合模板时,例如使用抓取和放置模板,可以直接在模板程序的基础上修改参数、示教路点等,也可以根据需求自由增删指令。 使用组合模板可以简化用户查找指令的过程,更方便快捷完成对应项目的编程。

Myblockly 环境下使用夹爪

  1. 案例介绍

    • 通过调用mycobot的Set_Gripper_State函数分别让夹爪进行10次张开收拢操作,并且在每组张开收拢后对其进行角度调位。
  2. demo内容

对比

Seria 环境下使用夹爪

1、通信协议与数据结构

  • 读取夹爪角度
数据域 说明 数据
Data[0] 识别帧 0XFE
Data[1] 识别帧 0XFE
Data[2] 数据长度帧 0X02
Data[3] 指令帧 0X65
Data[4] 结束帧 0XFA

串口发送实例:FE FE 02 65 FA

返回数据结构

数据域 说明 数据
Data[0] 返回识别帧 0XFE
Data[1] 返回识别帧 0XFE
Data[2] 返回数据长度帧 0X04
Data[3] 指令帧 0X65
Data[4] 角度值高位 Value_high
Data[5] 角度值低位 Value_low
Data[6] 结束帧 0XFA
  • 设置夹爪模式
数据域 说明 数据
Data[0] 识别帧 0XFE
Data[1] 识别帧 0XFE
Data[2] 数据长度帧 0X04
Data[3] 指令帧 0X66
Data[4] 夹爪开合 0X00/0X01
Data[5] 速度 Sp
Data[6] 结束帧 0XFA

设置夹爪以20的速度张开

串口发送示例:FE FE 04 66 00 20 FA

无返回值

  • 设置夹爪角度
数据域 说明 数据
Data[0] 识别帧 0XFE
Data[1] 识别帧 0XFE
Data[2] 数据长度帧 0X05
Data[3] 指令帧 0X67
Data[4] 角度值高位 Angle_high
Data[5] 角度值低位 Angle_low
Data[6] 速度 Sp
Data[7] 结束帧 0XFA

串口发送示例:FE FE 05 67 00 00 60 FA

Gripper_data:数据类型byte 取值范围0-1

无返回值

  • 夹爪设置零点
数据域 说明 数据
Data[0] 识别帧 0XFE
Data[1] 识别帧 0XFE
Data[2] 数据长度帧 0X02
Data[3] 指令帧 0X68
Data[4] 结束帧 0XFA

设置夹爪当前位置为零点

串口发送示例:FE FE 02 68 FA

  • 检测夹爪是否运动
数据域 说明 数据
Data[0] 识别帧 0XFE
Data[1] 识别帧 0XFE
Data[2] 数据长度帧 0X02
Data[3] 指令帧 0X69
Data[4] 结束帧 0XFA

串口发送示例:FE FE 02 69 FA

返回数据结构

数据域 说明 数据
Data[0] 返回识别帧 0XFE
Data[1] 返回识别帧 0XFE
Data[2] 返回数据长度帧 0X03
Data[3] 指令帧 0X69
Data[4] 静止/运动 0X00/0X01
Data[5] 结束帧 0XFA

2、具体使用

  • 设置夹爪零位

    • 串口发送:FE FE 02 68 FA
  • 设置夹爪模式

    • 设置夹爪处于张开状态

    • 串口发送:FE FE 04 66 00 70 FA

    • 设置夹爪处于收拢状态

    • 串口发送:FE FE 04 66 01 70 FA

  • 读取夹爪角度

    • 串口发送:FE FE 02 65 FA

results matching ""

    No results matching ""