agilexrobotics / piper_sdk

MIT License
9 stars 1 forks source link

Piper 机械臂 SDK使用说明

EN

ubuntu

Test:

PYTHON STATE
python3.8 Pass

本SDK用于接收can数据帧,然后处理为自定义数据类型,没有包括数据偏移帧

具体的接口函数的详细说明请看Interface README

协议解析部分说明Protocol README

消息部分说明Msgs README

有关机械臂全部的DMEO

安装方法

安装依赖

pip3 install python-can
pip3 install piper_sdk

安装can工具

sudo apt update && sudo apt install can-utils ethtool

这两个工具用来配置can模块

如果执行bash脚本出现ip: command not found

请安装ip指令,一般是sudo apt-get install iproute2

快速使用

使能can模块

首先需要设置好shell脚本参数

单条机械臂

pc只插入一个usb转can模块

直接执行

bash can_activate.sh can0 1000000
pc插入多个usb转can模块

拔掉所有can模块

只将连接到机械臂的can模块插入PC,执行

sudo ethtool -i can0 | grep bus

并记录下bus-info的数值例如1-2:1.0

ps:一般第一个插入的can模块会默认是can0,如果没有查询到can可以使用bash find_all_can_port.sh来查看刚才usb地址对应的can名称

假设上面的操作记录的bus-info数值为1-2:1.0

然后执行,查看can设备是否激活成功

bash can_activate.sh can_piper 1000000 "1-2:1.0"

ps:此处的意思是,1-2:1.0硬件编码的usb端口插入的can设备,名字被重命名为can_piper,波特率为1000000,并激活

然后执行ifconfig查看是否有can_piper,如果有则can模块设置成功

想要同时激活多个can模块

can_config.sh中,EXPECTED_CAN_COUNT参数为想要激活的can模块数量,现在假设为2

然后can模块中的其中一个单独插入PC,执行

sudo ethtool -i can0 | grep bus

并记录下bus-info的数值例如1-2:1.0

接着插入下一个can模块,注意不可以与上次can模块插入的usb口相同,然后执行

sudo ethtool -i can1 | grep bus

ps:一般第一个插入的can模块会默认是can0,第二个为can1,如果没有查询到can可以使用bash find_all_can_port.sh来查看刚才usb地址对应的can名称

假设上面的操作记录的bus-info数值分别为1-2:1.01-4:1.0

则将下面的USB_PORTS["1-9:1.0"]="can_left:1000000"的中括号内部的双引号内部的参数换为1-2:1.0

另一个同理

USB_PORTS["1-5:1.0"]="can_right:1000000" -> USB_PORTS["1-4:1.0"]="can_right:1000000"

ps:此处的意思是,1-2:1.0硬件编码的usb端口插入的can设备,名字被重命名为can_left,波特率为1000000,并激活

然后执行bash can_config.sh,查看终端输出是否激活成功

然后执行ifconfig查看是不是有can_leftcan_right,如果有则can模块设置成功

读取机械臂消息

#!/usr/bin/env python3
# -*-coding:utf8-*-
# 注意demo无法直接运行,需要pip安装sdk后才能运行
# 读取机械臂消息并打印,需要先安装piper_sdk
from typing import (
    Optional,
)
from piper_sdk import *

# 测试代码
if __name__ == "__main__":
    piper = C_PiperInterface()
    piper.ConnectPort()
    while True:
        import time
        # a.SearchMotorMaxAngleSpdAccLimit(1, 1)
        # a.ArmParamEnquiryAndConfig(1,0,2,0,3)
        # a.GripperCtrl(50000,1500,0x01)
        print(piper.GetArmJointMsgs())
        print(piper.GetArmGripperMsgs())
        time.sleep(0.005)
        pass

机械臂reset

#!/usr/bin/env python3
# -*-coding:utf8-*-
# 注意demo无法直接运行,需要pip安装sdk后才能运行
# 设置机械臂重置,需要在mit或者示教模式切换为位置速度控制模式时执行

from typing import (
    Optional,
)
import time
from piper_sdk import *

# 测试代码
if __name__ == "__main__":
    piper = C_PiperInterface()
    piper.ConnectPort()
    piper.MotionCtrl_1(0x02,0,0)#恢复
    piper.MotionCtrl_2(0, 0, 0, 0x00)#位置速度模式

控制机械臂运动

注意若机械臂进入过示教模式或者mit模式,需要执行一次reset,令机械臂切换为位置速度模式

#!/usr/bin/env python3
# -*-coding:utf8-*-
# 注意demo无法直接运行,需要pip安装sdk后才能运行
from typing import (
    Optional,
)
import time
from piper_sdk import *

def enable_fun(piper:C_PiperInterface):
    '''
    使能机械臂并检测使能状态,尝试5s,如果使能超时则退出程序
    '''
    enable_flag = False
    # 设置超时时间(秒)
    timeout = 5
    # 记录进入循环前的时间
    start_time = time.time()
    elapsed_time_flag = False
    while not (enable_flag):
        elapsed_time = time.time() - start_time
        print("--------------------")
        enable_flag = piper.GetArmLowSpdInfoMsgs().motor_1.foc_status.driver_enable_status and \
            piper.GetArmLowSpdInfoMsgs().motor_2.foc_status.driver_enable_status and \
            piper.GetArmLowSpdInfoMsgs().motor_3.foc_status.driver_enable_status and \
            piper.GetArmLowSpdInfoMsgs().motor_4.foc_status.driver_enable_status and \
            piper.GetArmLowSpdInfoMsgs().motor_5.foc_status.driver_enable_status and \
            piper.GetArmLowSpdInfoMsgs().motor_6.foc_status.driver_enable_status
        print("使能状态:",enable_flag)
        piper.EnableArm(7)
        piper.GripperCtrl(0,1000,0x01, 0)
        print("--------------------")
        # 检查是否超过超时时间
        if elapsed_time > timeout:
            print("超时....")
            elapsed_time_flag = True
            enable_flag = True
            break
        time.sleep(1)
        pass
    if(elapsed_time_flag):
        print("程序自动使能超时,退出程序")
        exit(0)

if __name__ == "__main__":
    piper = C_PiperInterface("can0")
    piper.ConnectPort()
    piper.EnableArm(7)
    enable_fun(piper=piper)
    # piper.DisableArm(7)
    piper.GripperCtrl(0,1000,0x01, 0)
    factor = 57324.840764 #1000*180/3.14
    position = [0,0,0,0,0,0,0]
    count = 0
    while True:
        print(piper.GetArmStatus())
        import time
        count  = count + 1
        # print(count)
        if(count == 0):
            print("1-----------")
            position = [0,0,0,0,0,0,0]
        elif(count == 500):
            print("2-----------")
            position = [0.2,0.2,-0.2,0.3,-0.2,0.5,0.08]
        elif(count == 1000):
            print("1-----------")
            position = [0,0,0,0,0,0,0]
            count = 0

        joint_0 = round(position[0]*factor)
        joint_1 = round(position[1]*factor)
        joint_2 = round(position[2]*factor)
        joint_3 = round(position[3]*factor)
        joint_4 = round(position[4]*factor)
        joint_5 = round(position[5]*factor)
        joint_6 = round(position[6]*1000*1000)
        # piper.MotionCtrl_1()
        piper.MotionCtrl_2(0x01, 0x01, 50, 0x00)
        piper.JointCtrl(joint_0, joint_1, joint_2, joint_3, joint_4, joint_5)
        piper.GripperCtrl(abs(joint_6), 1000, 0x01, 0)
        piper.MotionCtrl_2(0x01, 0x01, 50, 0x00)
        time.sleep(0.005)
        pass

注意事项