YASKAWA Example Program

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

Prerequisites

  1. You have set up Standard Interface communication with the robot.

  2. You have completed the hand-eye calibration following the calibration program.

  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/YASKAWA/sample in the installation directory of Mech-Vision & Mech-Viz.

ARGF in the code of following example programs displays as parentheses in the teach pendant.

There are three example programs for different scenarios.

Obtain Vision Result from Mech-Vision

NOP
'*****************************
'FUNCTION:simple pick and place
'with Mech-Vision
'2022-5-27
'*****************************
'clear I50 to I69
CLEAR I050 20
'Initialize p variables
SUB P070 P070
SUB P071 P071
'set  200mm to Z
SETE P070 (3) 200000
'move to the home position
MOVJ C00000 VJ=80.00
'move to the camera position
MOVJ C00001 VJ=80.00 PL=0
'set ip address of IPC
CALL JOB:MM_INIT_SOCKET ARGF"192.168.170.22;50000;1"
TIMER T=0.20
CALL JOB:MM_OPEN_SOCKET
'set vision recipe
CALL JOB:MM_SET_MODEL ARGF"1;1"
'Run vision project
CALL JOB:MM_START_VIS ARGF"1;0;2"
'get result from Vis
CALL JOB:MM_GET_VISDATA ARGF"1;51;52"
PAUSE IF I052<>1100
'set the first pos to P071;
'set lables to I61;
'set speed to I62;
CALL JOB:MM_GET_POSE ARGF"1;71;61;62"
SFTON P070
MOVJ P071 VJ=50.00
SFTOF
MOVL P071 V=80.0 PL=0
'enable gripper
DOUT OT#(1) ON
SFTON P070
MOVJ P071 VJ=50.00
SFTOF
MOVJ C00002 VJ=80.00
'drop point
MOVJ C00003 VJ=80.00 PL=0
'release gripper
DOUT OT#(1) OFF
CALL JOB:MM_CLOSE_SOCKET
END

Program Logic

  1. Move the robot to the HOME position.

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

  3. Initialize communication with MM_INIT_SOCKET.

  4. Start TCP/IP connection with MM_OPEN_SOCKET.

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

  6. Run the Mech-Vision project with MM_START_VIS.

  7. Wait for one second. In the Eye To Hand setup, this TIMER instruction can be replaced with MOVJ or MOVL. In the Eye-In-Hand setup, this TIMER instruction is required to make sure that the robot stays still until image acquisition is completed.

  8. Obtain the vision point from Mech-Vision with MM_GET_VISDATA.

  9. Check if the returned status code indicates any error. If an error code is returned, the program should be halted.

  10. Store the obtained vision pose (picking waypoint) to P071 with MM_GET_POSE.

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

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

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

  14. End TCP/IP connection with MM_CLOSE_SOCKET.

Customization Required

  • Set Tool at the Vision Point

    Please see Setting Tool at the Vision Point for detailed information.

  • Teach the image-capturing Pose

    MOVJ C00000 VJ=80.00: Record the image-capturing pose in C00000.

  • Teach the intermediate point(s)

    MOVJ C00002 VJ=80.00: Intermediate points are between the picking waypoint and placing waypoint and are used to ensure that the robot doesn’t collide with the surrounding when moving between the picking and placing waypoints. Record the intermediate point to C00002. You can add more intermediate points if needed.

  • Define Z-Offset from the picking/placing waypoint: To ensure collision doesn’t occur when the robot is approaching or departing the picking/placing pose, you can define Z-offset distances relative to the tool frame from the picking/placing pose. With the Z-offset, the robot moves along the Z-direction of the tool frame.

    • Z-offset when approaching the picking waypoint

      SFTON P070

      MOVJ P071 VJ=50.00

      SFTOF

      In this example, the Z-offset when approaching the picking waypoint is 200 mm. The robot will move to 200 mm above the picking waypoint. Adjust the offset value 200000 in SETE P070 (3) 200000 according to your actual needs.

    • Z-offset when departing the picking waypoint

      SFTON P070

      MOVJ P071 VJ=50.00

      SFTOF

      In this example, the Z-offset when approaching the picking waypoint is 200 mm. The robot will move to 200 mm above the picking waypoint. Adjust the offset value 200000 in SETE P070 (3) 200000 according to your actual needs.

  • Teach the placing waypoint

    MOVJ C00003 VJ=80.00 PL=0: Record the placing waypoint in C00003.

  • Add object picking and releasing logics

    DOUT OT#(1) ON and DOUT OT#(1) OFF: Add logic for controlling the tool action when picking or releasing the object.

Obtain Planned Path from Mech-Viz

NOP
'*****************************
'FUNCTION:simple pick and place
'with Mech-Viz
'2022-5-27
'*****************************
'clear I50 to I69
CLEAR I050 20
'Initialize p variables
SUB P070 P070
SUB P071 P071
'set  200mm to Z
SETE P070 (3) 200000
'move to the home position
MOVJ C00000 VJ=80.00
'move to the camera position
MOVJ C00001 VJ=80.00 PL=0
'set ip address of IPC
CALL JOB:MM_INIT_SOCKET ARGF"192.168.170.22;50000;1"
TIMER T=0.20
CALL JOB:MM_OPEN_SOCKET
'set vision recipe
CALL JOB:MM_SET_MODEL ARGF"1;1"
TIMER T=0.20
'Run Viz project
CALL JOB:MM_START_VIZ ARGF"1"
TIMER T=0.20
CALL JOB:MM_SET_BRANCH ARGF"1;1"
'get result from Viz
TIMER T=1.00
CALL JOB:MM_GET_VIZDATA ARGF"2;51;52;53"
PAUSE IF I053<>2100
'set the first pos to P071;
'set lables to I61;
'set speed to I62;
CALL JOB:MM_GET_POSE ARGF"1;71;61;62"
SFTON P070
MOVJ P071 VJ=50.00
SFTOF
MOVL P071 V=80.0 PL=0
'enable gripper
DOUT OT#(1) ON
SFTON P070
MOVJ P071 VJ=50.00
SFTOF
MOVJ C00002 VJ=80.00
'drop point
MOVJ C00003 VJ=80.00 PL=0
'release gripper
DOUT OT#(1) OFF
CALL JOB:MM_CLOSE_SOCKET
END

Program Logic

This example program uses Mech-Viz for vision-guided picking and placing objects to the set placing waypoint.

  1. Move the robot to HOME position.

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

  3. Initialize communication with MM_INIT_SOCKET.

  4. Start TCP/IP connection with MM_OPEN_SOCKET.

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

  6. Run the Mech-Viz project with MM_START_VIZ.

  7. Select the branch along which the Mech-Viz project should proceed with MM_SET_BRANCH.

  8. Obtain the planned path from Mech-Viz with MM_GET_VIZDATA.

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

  10. Store the obtained vision pose (picking waypoint) to P071 with MM_GET_POSE.

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

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

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

  14. End TCP/IP connection with MM_CLOSE_SOCKET.

Customization Required

  • Set Tool at the Vision Point

    Please see Setting Tool at the Vision Point for detailed information.

  • Teach the image-capturing Pose

    MOVJ C00004 VJ=80.00: Record the image-capturing pose in C00004.

  • Teach the intermediate point(s)

    MOVJ C00006 VJ=80.00: Intermediate points are between the picking pose and placing waypoint and are used to ensure that the robot doesn’t collide with the surrounding when moving between the picking and placing waypoints. Record the intermediate point to C00006. You can add more intermediate points if needed.

  • Define Z-Offset from the picking/placing waypoint: To ensure collision doesn’t occur when the robot is approaching or departing the picking/placing pose, you can define Z-offset distances relative to the tool frame from the picking/placing pose. With the Z-offset, the robot moves along the Z-direction of the tool frame.

    • Z-offset when approaching the picking waypoint

      SFTON P070

      MOVJ P071 VJ=50.00

      SFTOF

      In this example, the Z-offset when approaching the picking waypoint is 200 mm. The robot will move to 200 mm above the picking waypoint. Adjust the offset value 200000 in SETE P070 (3) 200000 according to your actual needs.

    • Z-offset when departing the picking waypoint

      SFTON P070

      MOVJ P071 VJ=50.00

      SFTOF

      In this example, the Z-offset when approaching the picking waypoint is 200 mm. The robot will move to 200 mm above the picking waypoint. Adjust the offset value 200000 in SETE P070 (3) 200000 according to your actual needs.

  • Teach the placing waypoint

    MOVJ C00007 VJ=80.00 PL=0: Record the placing waypoint in C00007.

  • Add object picking and releasing logics

    DOUT OT#(1) ON and DOUT OT#(1) OFF: Add logic for controlling the tool action when picking or releasing the object.

Obtain Planned Path from Mech-Vision

NOP
'*****************************
'FUNCTION:105_GET_VISPATH
'with Mech-Vision
'2023-1-9
'*****************************
'clear I50 to I69
CLEAR I050 20
'Initialize p variables
SUB P070 P070
SUB P071 P071
SUB P072 P072
'move to the home position
MOVJ C00000 VJ=80.00
'move to the camera position
MOVJ C00001 VJ=80.00 PL=0
'set ip address of IPC
CALL JOB:MM_INIT_SOCKET ARGF"192.168.170.22;50000;1"
TIMER T=0.20
CALL JOB:MM_OPEN_SOCKET
'set vision recipe
CALL JOB:MM_SET_MODEL ARGF"1;1"
TIMER T=0.20
'Run vision project
CALL JOB:MM_START_VIS ARGF"1;0;3;90"
TIMER T=1.00
'get result from Vis
CALL JOB:MM_GET_VISPATH ARGF"1;2;51;52;53"
TIMER T=0.20
'Validation Status
PAUSE IF I053<>1103
'set the first pos to P070;
'set lables to I61;
'set speed to I62;
CALL JOB:MM_GET_POSE ARGF"1;70;61;62"
'set the second pos to P071;
'set lables to I63;
'set speed to I64;
CALL JOB:MM_GET_POSE ARGF"2;71;63;64"
'set the third pos to P072;
'set lables to I65;
'set speed to I66;
CALL JOB:MM_GET_POSE ARGF"3;72;65;66"
MOVJ P070 VJ=50.00
MOVL P071 V=80.0 PL=0
'enable gripper
DOUT OT#(1) ON
MOVJ P072 VJ=50.00
MOVJ C00002 VJ=80.00
'drop point
MOVL C00003 V=500.0 PL=0
'release gripper
DOUT OT#(1) OFF
CALL JOB:MM_CLOSE_SOCKET
END

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_SOCKET.

  4. Start TCP/IP connection with MM_OPEN_SOCKET.

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

  6. Run the Mech-Vision project with MM_START_VIS.

  7. Wait for one second. In the Eye To Hand setup, this TIMER instruction can be replaced with MOVJ or MOVL. In the Eye-In-Hand setup, this TIMER instruction is required to make sure that the robot stays still until image acquisition is completed.

  8. Get the planned path from the “Path Planning” Step of Mech-Vision with MM_GET_VISPATH. In the example, a total of 3 waypoints are obtained, out of which the second is the picking point.

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

  10. Store the obtained waypoints in the planned path to variables with MM_GET_POSE.

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

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

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

  14. End TCP/IP connection with MM_CLOSE_SOCKET.

Customization Required

  • Set Tool at the Vision Point

    Please see Setting Tool at the Vision Point for detailed information.

  • Teach the image-capturing Pose

    MOVJ C00009 VJ=80.00 PL=0: Record the image-capturing pose in C00009.

  • Teach the placing waypoint

    MOVL C00011 V=500.0 PL=0: Record the placing waypoint in C00011.

  • Add object picking and releasing logics

    DOUT OT#(1) ON and DOUT OT#(1) OFF: Add logic for controlling the tool action when picking or releasing the object.

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.