FANUC Example Programs

This topic introduces the example programs that perform an actual pick-and-place task.

Prerequisites

  1. You have set up the Standard Interface communication.

  2. You have completed the hand-eye calibration by referring to the section FANUC Automatic Calibration.

  3. Mech-Vision and Mech-Viz projects are created and set to autoload.

  4. You have defined a robot TCP.

  5. The robot velocity is set to a low value, so that the operator can notice any unexpected behavior before accidents occur.

Example Programs

The example programs are stored in Mech-Center/Robot_Interface/FANUC/sample in the installation directory of Mech-Vision & Mech-Viz.

Obtain Vision Result from Mech-Vision

 1:  !FUNCTION:Eye to Hand simple pick ;
 2:  !2022-05-30 ;
 3:   ;
 4:  !SET Tool ;
 5:  UTOOL_NUM=1 ;
 6:  !Move to HOME Position ;
 7:J P[1] 100% FINE    ;
 8:  !Move to Camera capture Position ;
 9:L P[2] 3000mm/sec FINE    ;
10:  !Set IP address and Port ;
11:  CALL MM_INIT_SKT('8','192.168.1.20',50000,1) ;
12:  WAIT    .10(sec) ;
13:  !Set Vision Recipe ;
14:  //CALL MM_SET_MOD(1,1) ;
15:  !Run Vision Project ;
16:  CALL MM_START_VIS(1,1,2,10) ;
17:  WAIT   1.00(sec) ;
18:  CALL MM_GET_VIS(1,51,53) ;
19:  IF R[53:status]<>1100,JMP LBL[99] ;
20:  CALL MM_GET_POS(1,60,70,80) ;
21:L PR[60] 800mm/sec CNT100 Offset,PR[1]    ;
22:L PR[60] 800mm/sec FINE    ;
23:  !Add object grasping logic here ;
24:   ;
25:L PR[60] 800mm/sec CNT100 Offset,PR[1]    ;
26:  !Add transition point ;
27:L P[3] 800mm/sec FINE    ;
28:  !Move to DROP Position ;
29:L P[4] 800mm/sec CNT100 Offset,PR[2]    ;
30:L P[4] 200mm/sec FINE    ;
31:  !Add object releasing logic here ;
32:   ;
33:L P[4] 800mm/sec CNT100 Offset,PR[2]    ;
34:  !Move to HOME Position ;
35:J P[1] 100% FINE    ;
36:  END ;
37:   ;
38:  LBL[99:vision error] ;
39:  PAUSE ;

Program Logic

  1. Move the robot to HOME position.

  2. Move the robot to the image-capturing pose.

  3. Initialize communication with MM_INIT_SKT.

  4. If parameter recipes are used in the Mech-Vision project, the recipe to be used is set with MM_SET_MOD.

  5. Run the Mech-Vision project with MM_START_VIS.

  6. Wait for one second. In the Eye To Hand setup, this WAIT instruction is not needed if there are motion steps between MM_START_VIS and MM_GET_VIS. In the Eye In Hand setup, this WAIT instruction is required to make sure the robot stays still until image acquisition is completed.

  7. Obtain the vision point from Mech-Vision.

  8. Check if the returned status code indicates any error. If an error code is returned, the program is paused.

  9. Move the robot to the picking waypoint and perform picking.

  10. Move the robot to an intermediate point between the picking waypoint and placing waypoint.

  11. Move the robot to the set placing waypoint and perform placing.

Customization Required

  • Define the HOME position

    J P[1] 100% FINE: Please set the HOME position in register P[1].

  • Define the TCP

    UTOOL_NUM=1: Please change the tool reference frame to the one in which the actual TCP value is stored. Please change the value 1 according to the actual TCP values.

  • Teach the image-capturing pose

    L P[2] 3000mm/sec FINE: Please record the image-capturing pose in register P[2].

  • Teach the intermediate point(s)

    L P[3] 800mm/sec FINE: Add one or more intermediate points between the picking waypoint and placing waypoint to ensure that the robot doesn’t collide with the surrounding when moving between the picking waypoint and placing waypoint.

  • Teach the placing waypoint

    L P[4] 200mm/sec FINE: Please record the placing waypoint in register P[4].

  • Define Z-offset from the picking/placing waypoint

    • Approach waypoint of picking

      L PR[60] 800mm/sec CNT100 Offset,PR[1]: the Z-offset when approaching the picking waypoint is saved in PR[1]. This setting moves the robot to a point 100 mm above the picking waypoint. Please modify the offset value to ensure that no collisions will occur in the approaching process.

    • Departure waypoint of picking

      L PR[60] 800mm/sec CNT100 Offset,PR[1]: the Z-offset when departing the picking waypoint is saved in register PR[1]. This setting moves the robot up 100 mm from the picking waypoint along the Z axis of the tool reference frame. Pease modify the offset value to ensure that no collisions will occur in the departing process.

    • Approach waypoint of placing

      L P[4] 800mm/sec CNT100 Offset,PR[2]: the Z-offset when approaching the placing waypoint is saved in register PR[2]. This setting moves the robot to a point 100 mm above the placing waypoint. Please modify the offset value to ensure that no collisions will occur in the approaching process.

    • Departure waypoint of placing

      L P[4] 800mm/sec CNT100 Offset,PR[2]: the Z-offset when departing the placing waypoint is saved in register PR[2]. This setting moves the robot up 100 mm from the placing waypoint along the Z axis of the tool reference frame. Please modify the offset value to ensure that no collisions will occur in the departing process.

  • Add the object picking and releasing logics for the tool

    When the robot moves to the picking waypoint and the placing waypoint, you need to add the tool control logics for picking and releasing the object respectively.

Obtain Planned Path from Mech-Viz

 1:  !FUNCTION:Eye to Hand simple pick ;
 2:  !and place with Mech-Viz ;
 3:  !2022-05-30 ;
 4:   ;
 5:  !SET Tool ;
 6:  UTOOL_NUM=1 ;
 7:  !Move to HOME Position ;
 8:J P[1] 100% FINE    ;
 9:  !Move to Camera capture Position ;
10:L P[2] 3000mm/sec FINE    ;
11:  !Set IP address and Port ;
12:  CALL MM_INIT_SKT('8','192.168.1.20',50000,1) ;
13:  WAIT    .10(sec) ;
14:  !Set Vision Recipe ;
15:  //CALL MM_SET_MOD(1,1) ;
16:  !Run Viz Project ;
17:  CALL MM_START_VIZ(0,10) ;
18:  WAIT    .10(sec) ;
19:  !set branch exitport ;
20:  //CALL MM_SET_BCH(1,1) ;
21:  !get planned path ;
22:  CALL MM_GET_VIZ(2,51,52,53) ;
23:  IF R[53:status]<>2100,JMP LBL[99] ;
24:  CALL MM_GET_POS(1,60,70,80) ;
25:  CALL MM_GET_POS(2,61,71,81) ;
26:  CALL MM_GET_POS(3,62,72,82) ;
27:  !follow the planned path to pick ;
28:L PR[60] R[80]mm/sec FINE    ;
29:L PR[61:Vpos] R[81]mm/sec FINE    ;
30:  !Add object grasping logic here ;
31:   ;
32:L PR[62] R[82]mm/sec FINE    ;
33:  !Add transition point ;
34:L P[3] 800mm/sec FINE    ;
35:  !Move to DROP Position ;
36:L P[4] 800mm/sec CNT100 Offset,PR[2]    ;
37:L P[4] 200mm/sec FINE    ;
38:  !Add object releasing logic here ;
39:   ;
40:L P[4] 800mm/sec CNT100 Offset,PR[2]    ;
41:  !Move to HOME Position ;
42:J P[1] 100% FINE    ;
43:  END ;
44:   ;
45:  LBL[99:vision error] ;
46:  PAUSE ;

Program Logic

In this example program, Mech-Viz leads the robot to pick and place objects under the guidance of vision result.

  1. Move the robot to HOME position.

  2. Move the robot to the image-capturing pose.

  3. Initialize communication with MM_INIT_SKT.

  4. If parameter recipes are used in the Mech-Vision project, the recipe to be used is set with MM_SET_MOD.

  5. Run the Mech-Viz project with MM_START_VIZ.

  6. Obtain the planned path from Mech-Viz.

  7. Check if the returned status code indicates any error. If an error code is returned, the program is paused.

  8. Store obtained waypoint poses in the planned path to PR[60], PR[61], and PR[62].

  9. Move the robot along the path planned by Mech-Viz and perform picking.

  10. Move the robot to an intermediate point between the picking waypoint and placing waypoint.

  11. Move the robot to the set placing waypoint and perform placing.

Customization Required

  • Define the HOME position

    J P[1] 100% FINE: Please set the HOME position in register P[1].

  • Define the TCP

    UTOOL_NUM=1: Please change the tool reference frame to the one in which the actual TCP value is stored. Please change the value 1 according to the actual TCP values.

  • Teach the image-capturing pose

    L P[2] 3000mm/sec FINE: Please record the image-capturing pose in register P[2].

  • Teach the intermediate point(s)

    L P[3] 800mm/sec FINE: Add one or more intermediate points between the picking waypoint and placing waypoint to ensure that the robot doesn’t collide with the surrounding when moving between the picking waypoint and placing waypoint.

  • Teach the placing waypoint

    L P[4] 200mm/sec FINE: Please record the placing waypoint in register P[4].

  • Add the object picking and releasing logics for the tool

    When the robot moves to the picking waypoint and the placing waypoint, you need to add the tool control logics for picking and releasing the object respectively.

Obtain Planned Path from Mech-Vision

 1:  !FUNCTION:Eye to Hand simple pick ;
 2:  !and place with Mech-Vision Path ;
 3:  !Planning Step ;
 4:  !2023-01-10 ;
 5:   ;
 6:  !SET Tool ;
 7:  UTOOL_NUM=1 ;
 8:  !Move to HOME Position ;
 9:J P[1] 100% FINE    ;
10:  !Move to Camera capture Position ;
11:L P[2] 3000mm/sec FINE    ;
12:  !Set IP address and Port ;
13:  CALL MM_INIT_SKT('8','192.168.1.20',50000,1) ;
14:  WAIT    .10(sec) ;
15:  !Set Vision Recipe ;
16:  //CALL MM_SET_MOD(1,1) ;
17:  !Run Vision Project ;
18:  CALL MM_START_VIS(1,0,2,10) ;
19:  WAIT   1.00(sec) ;
20:  CALL MM_GET_VISP(1,2,51,52,53) ;
21:  IF R[53:status]<>1103,JMP LBL[99] ;
22:  FOR R[100:i]=1 TO R[51:pos_num] ;
23:  R[101:preg no]=59+R[100:i]    ;
24:  R[102:lbl no]=69+R[100:i]    ;
25:  R[103:spd no]=79+R[100:i]    ;
26:  CALL MM_GET_POS(R[100:i],R[101:preg no],R[102:lbl no],R[103:spd no]) ;
27:  ENDFOR ;
28:  !follow the planned path to pick ;
29:  FOR R[110:j]=1 TO R[51:pos_num] ;
30:  R[111:preg]=59+R[110:j]    ;
31:  R[112:spd]=79+R[110:j]    ;
32:L PR[R[111]] R[R[112]]mm/sec FINE    ;
33:  IF (R[110:j]=R[52:vpos_num]) THEN ;
34:  PAUSE ;
35:  !Add object grasping logic here ;
36:  ENDIF ;
37:  ENDFOR ;
38:  !Add transition point ;
39:L P[3] 800mm/sec FINE    ;
40:  !Move to DROP Position ;
41:L P[4] 800mm/sec CNT100 Offset,PR[2]    ;
42:L P[5] 200mm/sec FINE    ;
43:  !Add object releasing logic here ;
44:   ;
45:L P[6] 800mm/sec CNT100 Offset,PR[2]    ;
46:  !Move to HOME Position ;
47:J P[7] 100% FINE    ;
48:  END ;
49:   ;
50:  LBL[99:vision error] ;
51:  PAUSE ;

Program Logic

In this example program, the path planned by Mech-Vision in the “Path Planning” Step will be used to pick and place objects.

  1. Move the robot to the HOME position.

  2. Move the robot to the image-capturing pose.

  3. Initialize communication with MM_INIT_SKT.

  4. If parameter recipes are used in the Mech-Vision project, the recipe to be used is set with MM_SET_MOD.

  5. Run the Mech-Vision project with MM_START_VIS.

  6. Obtain the planned path from the “Path Planning” Step of Mech-Vision with MM_GET_VISP.

  7. Check if the returned status code indicates any error. If an error code is returned, the program is paused.

  8. Store obtained waypoint poses in the planned path to PR[60] and consecutive position registers with a FOR loop.

  9. Move the robot along the planned path and perform picking.

  10. Move the robot to an intermediate point between the picking waypoint and placing waypoint.

  11. Move the robot to the set placing waypoint and perform placing.

Customization Required

  • Define the HOME position

    J P[1] 100% FINE: Please set the HOME position in register P[1].

  • Define the TCP

    UTOOL_NUM=1: Please change the tool reference frame to the one in which the actual TCP value is stored. Please change the value 1 according to the actual TCP values.

  • Teach the image-capturing pose

    L P[2] 3000mm/sec FINE: Please record the image-capturing pose in register P[2].

  • Teach the intermediate point(s)

    L P[3] 800mm/sec FINE: Add one or more intermediate points between the picking waypoint and placing waypoint to ensure that the robot doesn’t collide with the surrounding when moving between the picking waypoint and placing waypoint.

  • Teach the placing waypoint

    L P[4] 200mm/sec FINE: Please record the placing waypoint in register P[4].

  • Add the object picking and releasing logics for the tool

    When the robot moves to the picking waypoint and the placing waypoint, you need to add the tool control logics for picking and releasing the object respectively.

We Value Your Privacy

We use cookies to provide you with the best possible experience on our website. By continuing to use the site, you acknowledge that you agree to the use of cookies. If you decline, a single cookie will be used to ensure you're not tracked or remembered when you visit this website.