机器人TCP快速对准功能及实现

假设机器人当前TCP和base关系如下左图,希望能让当前tcp的Z方向快速垂直于base的xy平面,则可以运行如下align_tcp.jbi(将程序中的第一行设为SET B000 0)程序实现(无需加载对应lua程序)


NOP
SET B000 0
// B000为0, 当前TCP的Z就近垂直对准base坐标系的xy/yz/xz平面
// B000为1, 当前TCP的Z就近垂直对准当前user坐标系的xy/yz/xz平面
// 要使用对准user坐标系,需要先加载对应align_tcp.lua
GETPOS P000
JOINTTOPOSE P000 V000
IF B000 = 0 THEN
    CCOOD CART
    SET V000(4) 0
    IF V000(3) >-0.785398163 & V000(3) <0.785398163 THEN
    SET V000(3) 0
    ELSEIF V000(3) >0.785398163 & V000(3) <2.35619449 THEN
    SET V000(3) 1.570796327
    ELSEIF V000(3) >2.35619449 THEN
    SET V000(3) 3.141592654
    ELSEIF V000(3) <-0.785398163 & V000(3) >-2.35619449 THEN
    SET V000(3) -1.570796327
    ELSE
    SET V000(3) -3.141592654
    ENDIF
    POSETOJOINT V000 P000
    MOVL P000 V=10.0MM/S PL=0
    CCOOD JOINT
ELSE
    WAIT B000 = 0
    POSETOJOINT V000 P000
    MOVL P000 V=10.0MM/S PL=0
    CCOOD JOINT
ENDIF
END

若机器人当前tcp姿态如下左图,则使用以上对准程序后,tcp的z会和xy平面


机器人TCP对准User坐标系


若使用user坐标系,机器人当前姿态如上左图,则使用align.jbi(将第一行修改为SET B000 1并且需要将对应align.lua导入机器人并运行起来),机器人的TCP会就近垂直对准当前使用的user的平面(就近原则,也可能如对准Base中的第二种情况,TCP与user平行)

对应lua代码如下:

set_global_variable('B000',0)
sleep(0.1)
while true do
    B000 = get_global_variable("B0")
    if B000 == 1 then
        local V000 = get_tcp_pose_inuser()
        local userno = get_user_no()
        local user = get_user_frame(userno)
        V000[5] = 0
        if V000[4] > -0.785398163 and V000[4] < 0.785398163 then
            V000[4] = 0
        elseif V000[4] > 0.785398163 and V000[4] < 2.35619449 then
            V000[4] = 1.570796327
        elseif V000[4] > 2.35619449 then
            V000[4] = 3.141592654
        elseif V000[4] < -0.785398163 and V000[4] > -2.35619449 then
            V000[4] = -1.570796327
        else
            V000[4] = -3.141592654
        end
        local v_inBase = pose_mul(user, V000)
        set_global_variable("V000", v_inBase[1], v_inBase[2], v_inBase[3], v_inBase[4], v_inBase[5], v_inBase[6])
        set_global_variable('B000',0)
    end
    sleep(0.5)
end
点击显示全文
赞同0
发表评论
分享

手机扫码分享
0
556
收藏
举报
收起
登录
  • 密码登录
  • 验证码登录
还没有账号,立即注册
还没有账号,立即注册
注册
已有账号,立即登录
选择发帖板块
举报
请选择举报理由
举报
举报说明