Python 例程

Lua API

通过向 TCP 的 5180 端口发送 Lua API 来控制任务运行

import socket

client = socket.socket()
client.connect(('127.0.0.1', 5180))
client.send("scene(10087)".encode())

client.close()

SDK

通过下载安装 SDK 来控制任务运行

lebai_sdk

import lebai_sdk

# # 如果出现event loop相关的RuntimeError,尝试添加以下2行
# import nest_asyncio
# nest_asyncio.apply()

lebai_sdk.init()

def main():
    # print(lebai_sdk.discover_devices(2)) #发现同一局域网内的机器人

    robot_ip = "192.168.x.x" #设定机器人ip地址,需要根据机器人实际ip地址修改
    lebai = lebai_sdk.connect(robot_ip, False) #创建实例
    lebai.stop_sys() #停止手臂
    print(lebai.get_robot_state())  #获取手臂状态,IDLE 空闲 MOVING 运行中  ESTOP 紧急停止 具体官网有详细说明
    lebai.start_sys() #启动手臂
    print(lebai.get_robot_state()) 

    status_dic = lebai.get_kin_data()  #获取手臂当前运动数据,返回一个字典,具体官网有详细说明。 其中 actual_joint_pose 和 actual_tcp_pose 分别是关节角坐标表达的位置和笛卡尔坐标表达的位置
    print('反馈关节位置',status_dic['actual_joint_pose'])   # 形式如下 [-6.282171983178839, -1.4205823273455875, 1.553330269510449, -0.1335442689785058, -4.712171983247641, 0.0]
    print('反馈笛卡尔位置',status_dic['actual_tcp_pose'])   # 形式如下 {'x' : -0.383, 'y' : -0.121, 'z' : 0.36, 'rz' : -1.57, 'ry' : 0, 'rx' : 1.57}
  
    joint_pose = [0,-1.05,1.05,0,1.57,0] #目标位姿关节数据
    cartesian_pose = {'x' : -0.383, 'y' : -0.121, 'z' : 0.36, 'rz' : -1.57, 'ry' : 0, 'rx' : 1.57}#目标位姿笛卡尔数据
    a = 0.5 #关节加速度 (rad/s2)
    v = 0.2 #关节速度 (rad/s)
    t = 0   #运动时间 (s)。 当 t > 0 时,参数速度 v 和加速度 a 无效
    r = 0   #交融半径 (m)。用于指定路径的平滑效果
    lebai.movej(joint_pose,a,v,t,r) #关节运动 https://help.lebai.ltd/sdk/motion.html#%E5%85%B3%E8%8A%82%E8%BF%90%E5%8A%A8
    a = 0.3 #空间加速度 (m/s2)
    v = 0.1 #空间速度 (m/s)
    t = 0   #运动时间 (s)。 当 t > 0 时,参数速度 v 和加速度 a 无效
    r = 0   #交融半径 (m)。用于指定路径的平滑效果
    lebai.movel(cartesian_pose,a,v,t,r) #直线运动 https://help.lebai.ltd/sdk/motion.html#%E7%9B%B4%E7%BA%BF%E8%BF%90%E5%8A%A8
    lebai.wait_move() #等待运动完成
   
    cart = lebai.kinematics_forward(joint_pose) #反解 将关节位置 转成 笛卡尔位置 
    joints = lebai.kinematics_inverse(cartesian_pose, joint_pose) # 反解,将笛卡尔位置和姿态转换成关节位置。计算结果与当前 TCP 设置和当前关节位置有关。joints 关节空间参考位置,默认为当前反馈关节位置。

    #当想计算一个相对于法兰盘末端坐标系的新位置,在底座坐标系下的坐标时。例如相对与末端的法兰盘,沿着z轴向前0.1m的位置,在底座坐标系中的位置求解,可以用pose_trans
    current_tcp_pose = lebai.get_kin_data()['actual_tcp_pose'] #当前法兰盘末端坐标
    print('current_tcp_pose',current_tcp_pose)
    offset_position = {'x' : 0, 'y' :0, 'z' : 0.1, 'rz' :0, 'ry' : 0, 'rx' : 0}  #相对与法兰盘末端的位置偏移量
    calculate_location = lebai.pose_trans(current_tcp_pose, offset_position) #计算的新位置
    print('calculate_location',calculate_location)

    #如果想让当前位置姿态,以某个坐标系,进行姿态变换。例如相对于基座坐标系,沿着基座z轴增加0.1
    base = lebai.get_kin_data()['actual_tcp_pose'] #当前末端坐标
    delta = {'x' : 0, 'y' :0, 'z' : 0.1, 'rz' :0, 'ry' : 0, 'rx' : 0}  #沿着frame坐标系z轴方向移动0.1m
    frame  ={'x' : 0, 'y' :0, 'z' : 0, 'rz' :0, 'ry' : 0, 'rx' : 0}  #基座坐标系 位姿偏移量方向,仅姿态部分有效。
    pose = lebai.pose_add(base, delta, frame)
    print('pose',pose)
    # 相对于绕y轴旋转45°,使z轴斜向上 的新坐标系,沿着基座z轴增加0.1
    base = lebai.get_kin_data()['actual_tcp_pose'] #当前末端坐标
    delta = {'x' : 0, 'y' :0, 'z' : 0.1, 'rz' :0, 'ry' : 0, 'rx' : 0}  #沿着frame坐标系z轴方向移动0.1m
    frame  ={'x' : 0, 'y' :0, 'z' : 0, 'rz' :0, 'ry' :-0.78, 'rx' : 0}  #绕y轴旋转45°,使z轴斜向上 的新坐标系
    pose = lebai.pose_add(base, delta, frame)
    print('pose',pose)


    #机器人lua场景调用,lua场景的作用在于,可以在lua场景中编写一些连续的运动控制逻辑,然后通过sdk调用lua场景来执行这些运动控制逻辑;而且在前端界面中用lua编写运动逻辑更方便
    scene_number = "10000" #需要调用的场景编号
    task_id = lebai.start_task(scene_number, None, None, False, 1) #调用场景 启动任务
    state = lebai.get_task_state(task_id)  #获取任务状态
    print('state',state)
    lebai.cancel_task(task_id) #停止指定任务
    
    #工控机外部系统 和 机器人场景进程之间交互,可以用信号量交互,通过自定义,定义每个信号的含义
    value = lebai.get_signal(0) #获取信号量0 对应的值
    lebai.set_signal(0, 1)  #设置信号量0 对应的值为1
  
    #机器人夹爪的控制
    lebai.set_claw(100, 30) #设置夹爪的力度(0-100)和开合度(0-100),100代表力度最大,30代表最大开合度的30%
    claw_status = lebai.get_claw() #获取夹爪的状态返回字典,{'force': 100.0, 'amplitude': 31.0, 'weight': 0.0, 'hold_on': False}, weight参数没有任何作用  hold_on代表夹爪是否已经稳定
    print('claw_status',claw_status)

    #机器人设置和获取数字输入输出。这里主要是获取与机器连接的传感器的状态,以及设置do的输出。 其中机箱上4个di 4个do ,法兰处有2个di 2个do
    robot_di0 = lebai.get_di("ROBOT", 0)   # 0对应获取第一个di信号 
    print('robot_di0',robot_di0)
    flan_di0 = lebai.get_di("FLANGE", 0)   # 0对应获取第一个di信号 
    print('flan_di0',flan_di0)

    lebai.set_do("ROBOT", 0, 1)   #设置数字输出。将第一个do信号设置为1,对应do有24v电压输出
    lebai.set_do("FLANGE", 0, 1) 
    robot_do0 = lebai.get_do("ROBOT", 0)
    flan_do0 = lebai.get_do("FLANGE", 0)

    #如果机箱的485 232接口连接了其他设备,可以通过机箱串口进行控制
    device= "/dev/ttyS1" # 485串口地址    
    # device = "/dev/ttyS3" #232串口地址
    lebai.set_serial_baud_rate(device, 9600) #设置串口波特率
    lebai.set_serial_timeout(device, 1000) #设置超时时间 1000ms
    str_data = "123"
    str_byte = str_data.encode(encoding='utf-8')
    lebai.write_serial(device, str_byte) # 发送字符串数据
    # lebai.write_serial(device, [0x01, 0x02, 0x03])  #发送HEX数据
    try:
        data = lebai.read_serial(device,3)  #读取的数据长度达不到,会报超时,要注意读取数据时的处理 
        print(data)  #打印数据 以每个字节的整数类型展示出来  例如 收到 0xAA 0x56  打印显示[170,86]
        hex_data = []
        for byte in data:
            hex_data.append(hex(byte))
            print(hex(byte))
        print(hex_data)  #打印十六进制形式
    except Exception as e:
        print('read_serial error :%s'%e)

main()

lebai_sdk_asyncio

import asyncio
import lebai_sdk

lebai_sdk.init()

async def main():
    # print(await lebai_sdk.discover_devices(2)) #发现同一局域网内的机器人

    robot_ip = "192.168.x.x" #设定机器人ip地址,需要根据机器人实际ip地址修改
    lebai = await lebai_sdk.connect(robot_ip, False) #创建实例
    await lebai.start_sys() #启动手臂
    joint_pose = [0,-1.05,1.05,0,1.57,0] #目标位姿关节数据
    cartesian_pose = {'x' : -0.383, 'y' : -0.121, 'z' : 0.36, 'rz' : -1.57, 'ry' : 0, 'rx' : 1.57}#目标位姿笛卡尔数据
    a = 0.5 #关节加速度 (rad/s2)
    v = 0.2 #关节速度 (rad/s)
    t = 0   #运动时间 (s)。 当 t > 0 时,参数速度 v 和加速度 a 无效
    r = 0   #交融半径 (m)。用于指定路径的平滑效果
    await lebai.movej(joint_pose,a,v,t,r) #关节运动 https://help.lebai.ltd/sdk/motion.html#%E5%85%B3%E8%8A%82%E8%BF%90%E5%8A%A8
    a = 0.3 #空间加速度 (m/s2)
    v = 0.1 #空间速度 (m/s)
    t = 0   #运动时间 (s)。 当 t > 0 时,参数速度 v 和加速度 a 无效
    r = 0   #交融半径 (m)。用于指定路径的平滑效果
    await lebai.movel(cartesian_pose,a,v,t,r) #直线运动 https://help.lebai.ltd/sdk/motion.html#%E7%9B%B4%E7%BA%BF%E8%BF%90%E5%8A%A8
    await lebai.wait_move() #等待运动完成
    # scene_number = "10000" #需要调用的场景编号
    # await lebai.start_task(scene_number, None, None, False, 1) #调用场景
    await lebai.stop_sys() #停止手臂

asyncio.run(main())