FANUC Robot自动回原点编程三

AUTO_HOME程序:

5: R[28:角度范围]=.5 ;后台逻辑记录机器人角度与启动自动回原点程序时机器人各轴角度之差。

6: ;

7: R[31:回原点J1最小角度]=R[21:自动停止J1角度]-R[28:角度范围] ;

8: R[32:回原点J2最小角度]=R[22:自动停止J2角度]-R[28:角度范围] ;

9: R[33:回原点J3最小角度]=R[23:自动停止J3角度]-R[28:角度范围] ;

10: R[34:回原点J4最小角度]=R[24:自动停止J4角度]-R[28:角度范围] ;

11: R[35:回原点J5最小角度]=R[25:自动停止J5角度]-R[28:角度范围] ;

12: R[36:回原点J6最小角度]=R[26:自动停止J6角度]-R[28:角度范围] ;

13: ;

14: R[41:回原点J1最大角度]=R[21:自动停止J1角度]+R[28:角度范围] ;

15: R[42:回原点J2最大角度]=R[22:自动停止J2角度]+R[28:角度范围] ;

16: R[43:回原点J3最大角度]=R[23:自动停止J3角度]+R[28:角度范围] ;

17: R[44:回原点J4最大角度]=R[24:自动停止J4角度]+R[28:角度范围] ;

18: R[45:回原点J5最大角度]=R[25:自动停止J5角度]+R[28:角度范围] ;

19: R[46:回原点J6最大角度]=R[26:自动停止J6角度]+R[28:角度范围] ;

20: ;

21: R[51:HOME_J1角度]= S C R G R P [ 1 ] . SCR_GRP[1]. SCRGRP[1].MCH_ANG[1]
;将机器人当前第一轴的角度赋值给数值寄存器R[51]。以下类似。

22: R[52:HOME_J2角度]= S C R G R P [ 1 ] . SCR_GRP[1]. SCRGRP[1].MCH_ANG[2]
;

23: R[53:HOME_J3角度]= S C R G R P [ 1 ] . SCR_GRP[1]. SCRGRP[1].MCH_ANG[3]
;

24: R[54:HOME_J4角度]= S C R G R P [ 1 ] . SCR_GRP[1]. SCRGRP[1].MCH_ANG[4]
;

25: R[55:HOME_J5角度]= S C R G R P [ 1 ] . SCR_GRP[1]. SCRGRP[1].MCH_ANG[5]
;

26: R[56:HOME_J6角度]= S C R G R P [ 1 ] . SCR_GRP[1]. SCRGRP[1].MCH_ANG[6]
;

27: ;

28: ;

29: IF R[51:HOME_J1角度]<R[31:回原点J1最小角度] OR R[51:HOME_J1角度]>R[41:回原点J1最大角度],JMP LBL[10000] ;若第一轴角度超标,则跳转到报警的标签。以下类似。

30: ;

31: IF R[52:HOME_J2角度]<R[32:回原点J2最小角度] OR R[52:HOME_J2角度]>R[42:回原点J2最大角度],JMP LBL[10000] ;

32: ;

33: IF R[53:HOME_J3角度]<R[33:回原点J3最小角度] OR R[53:HOME_J3角度]>R[43:回原点J3最大角度],JMP LBL[10000] ;

34: ;

35: IF R[54:HOME_J4角度]<R[34:回原点J4最小角度] OR R[54:HOME_J4角度]>R[44:回原点J4最大角度],JMP LBL[10000] ;

36: ;

37: IF R[55:HOME_J5角度]<R[35:回原点J5最小角度] OR R[55:HOME_J5角度]>R[45:回原点J5最大角度],JMP LBL[10000] ;

38: ;

39: IF R[56:HOME_J6角度]<R[36:回原点J6最小角度] OR R[56:HOME_J6角度]>R[46:回原点J6最大角度],JMP LBL[10000] ;

  • 6
    点赞
  • 19
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值