【睿尔曼-RealMan】睿尔曼超轻量仿人机械臂--二次开发之Python 调用API接口
Forrest 2023-11-23
一、API文件简介
睿尔曼系列机械臂提供多种高级语言可用的API,可以根据所需进行选择。在这里,我将列举Python语言的项目创建及接口使用。
本文章涉及的示例项目网盘链接如下:
链接:https://pan.baidu.com/s/1B_NBbbry_N-xUK83_ij5OA?pwd=exbr
提取码:exbr
二、Python语言开发环境说明及接口使用
Win10系统下使用
1.开发环境
系统:win10
IDE:PyCharm
Python版本:python 3.11.2
SDK版本号:4.1.3
由于机械臂相关软件版本不定期更新,如果你使用的软件接口或协议与本文有出入,请联系官方技术人员及时更新。
2.项目创建&加载SDK
创建python文件,可以通过多种方式,本文中以Pycharm为示例。详述从项目创建到添加SDK、实际运行控制机械臂。
创建Python项目。打开Pycharm软件,在右上角’File-->New Project’。打开新建项目界面,在界面中可选择项目路径及项目名称、Python版本等信息。最后点击界面右下角‘Create’按钮。
加载SDK文件
第一步,添加dll文件。找到项目创建的目录,在设备资料中‘RM-65\(2)API\C\windows’中选择对应本地电脑的SDK版本(此处可选32位/64位),将dll文件复制并粘贴至上一步骤中创建项目的文件夹中。SDK中的接口可以通过SDK接口函数示例文档查看。
第二步,程序中添加库文件。可在程序界面右击选择‘Run main’选项进行运行程序测试。
第三步,测试项目运行。在程序界面右击选择“Run main”,查看是否会报错。成功界面如下所示:
第四步,写入机械臂通信、读取及控制程序。将以下程序写入Python程序中。
from robotic_arm_package.robotic_arm import *
import sys
# 画八字
def demo1(robot):
ret = robot.Movej_Cmd([18.44, -10.677, -124.158, -15, -71.455], 30)
if ret != 0:
print("设置初始位置失败:" + str(ret))
sys.exit()
for num in range(0, 3):
po1 = [0.186350, 0.062099, 0.2, 3.141, 0, 1.569]
ret = robot.Movel_Cmd(po1, 30)
if ret != 0:
print("Movel_Cmd 1 失败:" + str(ret))
sys.exit()
po2 = [0.21674, 0.0925, 0.2, 3.141, 0, 1.569]
po3 = [0.20785, 0.114, 0.2, 3.141, 0, 1.569]
ret = robot.Movec_Cmd(po2, po3, 30)
if ret != 0:
print("Movec_Cmd 1 失败:" + str(ret))
sys.exit()
po4 = [0.164850, 0.157, 0.2, 3.141, 0, 1.569]
ret = robot.Movel_Cmd(po4, 30)
if ret != 0:
print("Movel_Cmd 2 失败:" + str(ret))
sys.exit()
po5 = [0.186350, 0.208889, 0.2, 3.141, 0, 1.569]
po6 = [0.20785, 0.157, 0.2, 3.141, 0, 1.569]
ret = robot.Movec_Cmd(po5, po6, 30)
if ret != 0:
print("Movel_Cmd 2 失败:" + str(ret))
sys.exit()
print("cycle draw 8 demo success")
# 获取机械臂状态、坐标系
def demo2(robot):
# 获取机械臂当前状态
ret, joint, pose, arm_err, sys_err = robot.Get_Current_Arm_State(retry=1)
if ret != 0:
print("获取机械臂当前状态失败:" + str(ret))
sys.exit()
print("当前关节角度:" + str(joint))
print("错误码: " + str(arm_err) + str(sys_err))
# 获取当前坐标系
retval, frame = robot.Get_Current_Work_Frame(retry=1)
if retval == 0:
print('当前工作坐标系:', frame.frame_name.name)
print('当前工作坐标系位置:', frame.pose.position.x, frame.pose.position.y, frame.pose.position.z)
else:
print(f'获取当前坐标系失败:{retval}')
sys.exit()
# 设置工作坐标系
retval = robot.Manual_Set_Work_Frame('new', [0.1, 0.2, 0.3, 3.0, 0.2, 0.1])
if retval != 0:
print(f'设置坐标系失败:{retval}')
# sys.exit()
# 切换当前工作坐标系
robot.Change_Work_Frame('new')
# 获取当前工作坐标系
retval, frame = robot.Get_Current_Work_Frame(retry=1)
if retval == 0:
print('当前工作坐标系:', frame.frame_name.name)
print('当前工作坐标系位置:', frame.pose.position.x, frame.pose.position.y, frame.pose.position.z)
else:
print(f'获取当前坐标系失败:{retval}')
sys.exit()
# 获取指定坐标系
retval, frame = robot.Get_Given_Work_Frame('new', retry=1)
if retval == 0:
print('指定工作坐标系位置:', frame)
else:
print(f'获取指定坐标系失败:{retval}')
sys.exit()
# 夹爪使用例程(需机械臂末端安装夹爪)
def demo3(robot):
# 回零位
zero = [0, 0, 0, 0, 0, 0]
ret = robot.Movej_Cmd(zero, 20)
if ret != 0:
print("回零位失败:" + str(ret))
sys.exit()
# 张开夹爪,抓取位置
robot.Set_Gripper_Release(500)
if ret != 0:
print("张开夹爪失败:" + str(ret))
sys.exit()
joint1 = [4.61, 93.549, 75.276, -10.098, -76.508, 57.224]
ret = robot.Movej_Cmd(joint1, 20)
if ret != 0:
print("到达抓取位置失败:" + str(ret))
sys.exit()
# 抓取
ret = robot.Set_Gripper_Pick_On(500, 500)
if ret != 0:
print("抓取失败:" + str(ret))
sys.exit()
# 放置
joint2 = [-106.244, 67.172, 96.15, -10.385, -71.097, 58.243]
ret = robot.Movej_Cmd(joint2, 20)
if ret != 0:
print("到达放置位置失败:" + str(ret))
sys.exit()
robot.Set_Gripper_Release(200)
if ret != 0:
print("放置失败:" + str(ret))
sys.exit()
# 回零位
ret = robot.Movej_Cmd(zero, 20, 0, 1)
if ret != 0:
print("回零位失败:" + str(ret))
sys.exit()
print("夹爪抓取成功")
# 位置示教例程
def demo4(robot):
# 初始位置
joint = [0, -20, -70, 0, -90, 0]
zero = [0, 0, 0, 0, 0, 0]
robot.Movej_Cmd(joint, 20)
# 切换示教坐标系为基坐标系
robot.Set_Teach_Frame(0)
# 位置示教
ret = robot.Pos_Teach_Cmd(2, 1, 10)
time.sleep(2)
if ret != 0:
print("Z轴正方向示教失败:" + str(ret))
sys.exit()
ret = robot.Teach_Stop_Cmd()
if ret != 0:
print("停止示教失败:" + str(ret))
sys.exit()
# 切换示教坐标系为工具坐标系
robot.Set_Teach_Frame(1)
# 位置示教
ret = robot.Pos_Teach_Cmd(2, 1, 20)
time.sleep(2)
if ret != 0:
print("Z轴正方向示教失败:" + str(ret))
sys.exit()
ret = robot.Teach_Stop_Cmd()
if ret != 0:
print("停止示教失败:" + str(ret))
sys.exit()
print("Z轴位置示教成功")
# 透传
def demo5(robot):
# 读取文件内容,文件中的点位为拖动示教所得
with open('75.txt', 'r') as f:
lines = f.readlines()
# 转换为浮点数列表
point = []
for line in lines:
nums = line.strip().split(',')
point.append([float(num) for num in nums])
# 运动到透传的第一个点位
num_lines = len(point)
robot.Movej_Cmd(point[0], 5, 0, True)
# 低跟随透传
for i in range(num_lines):
robot.Movej_CANFD(point[i], False)
time.sleep(0.005)
print("透传结束")
# 力位混合控制透传(需为六维力版本机械臂)
def demo6(robot):
# 读取文件内容
with open('75.txt', 'r') as f:
lines = f.readlines()
# 转换为浮点数列表
zero = []
for line in lines:
nums = line.strip().split(',')
zero.append([float(num) for num in nums])
# 使用文件行数
num_lines = len(zero)
robot.Movej_Cmd(zero[0], 20, 0, True)
# 开启透传力位混合控制补偿模式
robot.Start_Force_Position_Move()
time.sleep(1)
for i in range(num_lines):
robot.Force_Position_Move_Joint(zero[i], 1, 0, 2, 2, False)
print(zero[i])
time.sleep(0.001)
robot.Stop_Force_Position_Move()
# 正逆解示例
def demo7(robot):
# 初始位置
joint = [0, 0, -90, 0, -90, 0]
ret = robot.Movej_Cmd(joint, 20)
print("Movej_Cmd ret:" + str(ret))
time.sleep(1)
# 正解
compute_pose = Arm.Algo_Forward_Kinematics(joint)
print(f'正解结果:{compute_pose}')
# 逆解
compute_pose[0] += 0.
res = Arm.Algo_Inverse_Kinematics(joint, compute_pose, 1)
print(f'逆解:{res}')
if __name__ == "__main__":
def mcallback(data):
print("MCallback MCallback MCallback")
# 判断接口类型
if data.codeKey == MOVEJ_CANFD_CB: # 角度透传
print("透传结果:", data.errCode)
print("当前角度:", data.joint[0], data.joint[1], data.joint[2], data.joint[3], data.joint[4], data.joint[5])
elif data.codeKey == MOVEP_CANFD_CB: # 位姿透传
print("透传结果:", data.errCode)
print("当前角度:", data.joint[0], data.joint[1], data.joint[2], data.joint[3], data.joint[4], data.joint[5])
print("当前位姿:", data.pose.position.x, data.pose.position.y, data.pose.position.z, data.pose.euler.rx,
data.pose.euler.ry, data.pose.euler.rz)
elif data.codeKey == FORCE_POSITION_MOVE_CB: # 力位混合透传
print("透传结果:", data.errCode)
print("当前力度:", data.nforce)
# 连接机械臂,注册回调函数
callback = CANFD_Callback(mcallback)
robot = Arm(65, "192.168.1.18", callback)
# API版本信息
print(robot.API_Version())
# 运行示例
demo1(robot)
# 断开连接
robot.RM_API_UnInit()
robot.Arm_Socket_Close()
Linux系统下使用
1.开发环境说明
系统:Ubuntu 18.04
编译器:默认
SDK版本号:4.1.3
Python版本:python3
2.项目创建&加载PythonSDK
Ubuntu下Python项目创建可参考win10下项目的创建,在本文中Ubuntu下创建项目未使用IDE,采用创建文本的方式实现。在同文件夹添加库文件。下面是具体的操作过程。
第一步,创建python文本。在主目录下新建文件夹,名称可根据个人习惯来,在创建完成的文件夹下使用以下命令新建’.py’文件:touch 文件名.py;
第二步,添加机械臂SDK文件。将资料目录“RM-65\(2)API\C\linux”下linux_arm_base_release_v4.0.6.tar.bz2压缩包(此压缩包根据各自系统选择合适的文件),复制到Ubuntu系统下对应的文件夹中。并进行解压操作。
第三步,剪切.SO文件至python文件同级目录下。
第四步,python程序在此处我直接复制win10下的程序,修改文件中配置的文件名称即可运行程序。
第五步,运行程序。在python文件目录下打开终端,编译并运行上一步骤中的文件。
撰写评论