ABB Example Program

This topic introduces the example programs provided with Mech-Mind Software Suite and the operations required to perform an actual pick-and-place task.

Three example programs are provided:

The sample programs are stored in xxx\Mech-Mind Software Suite-x.x.x\Mech-Center\Robot_Interface\ABB\sample.

Before running the program, please make sure that:

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

  • You have completed the hand-eye calibration with the calibration program.

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

  • The TCP has been correctly specified.

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

Obtain Vision Result from Mech-Vision

PROC Vision_Sample_1()
    !**********************************************************
    ! FUNCTION:Eye to Hand simple pick and place with Mech-Vision
    ! mechmind, 2022-5-1
    !**********************************************************
    AccSet 100, 100;
    VelSet 100, 5000;
    MoveAbsJ Home\NoEOffs,v3000,fine,Gripp1TCP;!move robot home position
    MoveL camera_capture,v500,fine,Gripp1TCP;
    PoseNum:=0;
    !Set ip address of IPC
    MM_Init_Socket "127.0.0.1",50000,60;
    WaitTime 0.1;
    !Set vision recipe
    MM_Switch_Model 1,1;
    !Run vision project
    MM_Start_Vis 1,1,2,snap_jps;
    WaitTime 1;
    MM_Get_VisData 1,LastData,PoseNum,Status;
    IF Status<>1100 THEN
        Stop;
    ENDIF
    MM_Get_Pose 1,pickpoint,label,speed1;
    MoveL RelTool(pickpoint,0,0,-100),v1000,fine,Gripp1TCP;
    MoveL pickpoint,v300,fine,Gripp1TCP;
    Stop;
    !Add object grasping logic here.
    MoveL Offs(pickpoint,0,0,100), v1000, fine, Gripp1TCP;
    MoveL waypoint1,v1000,z50,Gripp1TCP;
    MoveL RelTool(drop,0,0,-100),v1000,fine,Gripp1TCP;
    MoveL drop,v300,fine,Gripp1TCP;
    Stop;
    !Add object releasing logic here.
    MoveL Offs(drop,0,0,100), v1000, fine, Gripp1TCP;
    MoveAbsJ Home\NoEOffs,v3000,fine,Gripp1TCP;
    RETURN ;
ENDPROC

Program Logic

  1. Move the robot to HOME position.

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

  3. Initialize communication with MM_Init_Socket.

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

  5. Run the Mech-Vision project with MM_Start_Vis.

  6. Wait for 1 second. Under Eye-In-Hand, this WaitTime instruction is required to make sure the robot stays still until image acquisition is completed. Under Eye-To-Hand, this WaitTime instruction can be replaced with MoveL or MoveJ.

  7. Obtain the vision result from Mech-Vision.

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

  9. Store the obtained vision pose (picking pose) to pickpoint with MM_Get_Pose.

  10. Move the robot to the picking pose and perform picking.

  11. Move the robot to an intermediate point between the picking pose and placing pose.

  12. Move the robot to the set placing pose and perform placing.

  13. Return the robot to HOME position.

The following parts should be modified according to your actual needs.

Define the TCP

The TOOL is defined as Gripp1TCP. Change the value of Gripp1TCP to the actual TCP values.

Define HOME Position

Set the Home position in Home.

Teach the Image-Capturing Pose

Record the image-capturing pose in camera_capture.

Teach the Intermediate Point(s)

Intermediate points are between the picking pose and placing pose and are used to ensure that the robot doesn’t collide with the surrounding when moving between the picking and placing poses.

You can add one or more intermediate points to waypoint.

Teach the Placing Pose

Record the placing pose in drop.

Define Z-Offset from Picking/Placing Pose

Z-offset distances relative to the tool frame from the picking/placing pose are used to ensure collision doesn’t occur when the robot is approaching or departing the picking/placing pose.

Adjust the following commands according to your actual needs.

  • MoveL RelTool(pickpoint,0,0,-100): the Z-offset when approaching the picking pose is set to 100 mm. The robot will move to 100 mm above the picking pose.

  • MoveL Offs(pickpoint,0,0,100): the Z-offset when departing the picking pose is set to 100 mm. The robot will move to 100 mm above the picking pose.

  • MoveL RelTool(drop,0,0,-100): the Z-offset when approaching the placing pose is set to 100 mm. The robot will move to 100 mm above the placing pose.

  • MoveL Offs(drop,0,0,100): the Z-offset when departing the placing pose is set to 100 mm. The robot will move to 100 mm above the placing pose.

Add Object Grasping and Releasing Logics

Add logic for controlling the tool action when picking or placing the object.

Obtain Planned Path from Mech-Viz

PROC vision_sample_2()
    !**********************************************************
    ! FUNCTION:Eye to Hand simple pick and place with Mech-Viz
    ! mechmind, 2022-5-1
    !**********************************************************
    AccSet 100, 100;
    VelSet 100, 5000;
    MoveAbsJ Home\NoEOffs,v3000,fine,Gripp1TCP;!move robot home position
    MoveL camera_capture,v500,fine,Gripp1TCP;
    PoseNum:=0;
    !Set ip address of IPC
    MM_Init_Socket "127.0.0.1",50000,60;
    WaitTime 0.1;
    !Set vision recipe
    MM_Switch_Model 1,1;
    !Run Viz project
    MM_Start_Viz 1,snap_jps;
    WaitTime 0.1;
    !set branch exitport
    MM_Set_Branch 1,1;
    !get planned path
    MM_Get_VizData 2, LastData, PoseNum, VisPosNum, MM_Status;
    IF MM_Status <> 2100 THEN
        Stop;
    ENDIF
    FOR i FROM 1 TO PoseNum DO
        count:=i;
        MM_Get_Pose count,P{count},label1{count},speed{count};
    ENDFOR
    !follow the planned path to pick
    FOR j FROM 1 TO PoseNum DO
        count:=j;
        MoveL p{count},v1000,fine,Gripp1TCP;
        IF count=VisPosNum THEN
            Stop;
            !add object grasping logic here
        ENDIF
    ENDFOR
    !go to drop location
    MoveL RelTool(drop,0,0,-100),v1000,z50,Gripp1TCP;
    MoveL drop,v500,fine,Gripp1TCP;!drop point
    stop;
    !add object releasing logic here
    MoveL Offs(drop,0,0,100), v1000, fine, Gripp1TCP;
    MoveAbsJ Home\NoEOffs,v3000,fine,Gripp1TCP;
    RETURN ;
ENDPROC

Program Logic

  1. Move the robot to HOME position.

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

  3. Initialize communication with MM_Init_Socket.

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

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

  8. Store obtained waypoint poses in the planned path to P{} with a FOR loop.

  9. Move the robot along the planned path with a FOR loop and perform picking.

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

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

  12. Return the robot to HOME position.

The following parts should be modified according to your actual needs.

Define the TCP

The TOOL is defined as Gripp1TCP. Change the value of Gripp1TCP to the actual TCP values.

Define HOME position

Set the Home position in Home.

Teach the image-capturing pose

Record the image-capturing pose in camera_capture.

Teach the Intermediate Point(s)

Intermediate points are between the picking pose and placing pose and are used to ensure that the robot doesn’t collide with the surrounding when moving between the picking and placing poses.

You can add one or more intermediate points to waypoint.

Teach the Placing Pose

Record the placing pose in drop.

Add Object Grasping and Releasing Logics

Add logic for controlling the tool action when picking or placing the object.

Define Z-Offset from Picking/Placing Pose

Z-offset distances relative to the tool frame from the picking/placing pose are used to ensure collision doesn’t occur when the robot is approaching or departing the picking/placing pose.

Adjust the following commands according to your actual needs.

  • MoveL RelTool(drop,0,0,-100): the Z-offset when approaching the placing pose is set to 100 mm. The robot will move to 100 mm above the placing pose.

  • MoveL Offs(drop,0,0,100): the Z-offset when departing the placing pose is set to 100 mm. The robot will move to 100 mm above the placing pose.

Obtain Planned Path from Mech-Vision

PROC Vision_Sample_3()
    !**********************************************************
    ! FUNCTION:Eye to Hand simple pick and place with Mech-Vision Path Planning Step
    ! mechmind, 2023-1-10
    !**********************************************************
    AccSet 100, 100;
    VelSet 100, 5000;
    MoveAbsJ Home\NoEOffs,v3000,fine,Gripp1TCP;!move robot home position
    MoveL camera_capture,v500,fine,Gripp1TCP;
    PoseNum:=0;
    !Set ip address of IPC
    MM_Init_Socket "127.0.0.1",50000,60;
    WaitTime 0.1;
    !Set vision recipe
    MM_Switch_Model 1,1;
    !Run vision project
    MM_Start_Vis 1,1,2,snap_jps;
    WaitTime 1;
    !get planned path from Mech-Vision Path Planning Step
    MM_Get_VisPath 1,2,LastData,PoseNum,VisPosNum,Status;
    IF Status<>1103 THEN
        Stop;
    ENDIF
    FOR i FROM 1 TO PoseNum DO
        count:=i;
        MM_Get_Pose count,P{count},label1{count},speed{count};
    ENDFOR
    !follow the planned path to pick
    FOR j FROM 1 TO PoseNum DO
        count:=j;
        MoveL p{count},v1000,fine,Gripp1TCP;
        IF count=VisPosNum THEN
            Stop;
            !add object grasping logic here
        ENDIF
    ENDFOR
    !go to drop location
    MoveL RelTool(drop,0,0,-100),v1000,z50,Gripp1TCP;
    MoveL drop,v500,fine,Gripp1TCP;!drop point
    stop;
    !add object releasing logic here
    MoveL Offs(drop,0,0,100), v1000, fine, Gripp1TCP;
    MoveAbsJ Home\NoEOffs,v3000,fine,Gripp1TCP;
    RETURN ;
ENDPROC

Program Logic

  1. Move the robot to HOME position.

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

  3. Initialize communication with MM_Init_Socket.

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

  5. Run the Mech-Vision project with MM_Start_Vis.

  6. Obtain the planned path from Mech-Vision with MM_Get_VisPath.

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

  8. Store obtained waypoint poses in the planned path to P{} with a FOR loop.

  9. Move the robot along the planned path with a FOR loop and perform picking.

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

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

  12. Return the robot to HOME position.

The following parts should be modified according to your actual needs.

Define the TCP

The TOOL is defined as Gripp1TCP. Change the value of Gripp1TCP to the actual TCP values.

Define HOME position

Set the Home position in Home.

Teach the image-capturing pose

Record the image-capturing pose in camera_capture.

Teach the Intermediate Point(s)

Intermediate points are between the picking pose and placing pose and are used to ensure that the robot doesn’t collide with the surrounding when moving between the picking and placing poses.

You can add one or more intermediate oints to waypoint.

Teach the Placing Pose

Record the placing pose in drop.

Add Object Grasping and Releasing Logics

Add logic for controlling the tool action when picking or placing the object.

Define Z-Offset from Picking/Placing Pose

Z-offset distances relative to the tool frame from the picking/placing pose are used to ensure collision doesn’t occur when the robot is approaching or departing the picking/placing pose.

Adjust the following commands according to your actual needs.

  • MoveL RelTool(drop,0,0,-100): the Z-offset when approaching the placing pose is set to 100 mm. The robot will move to 100 mm above the placing pose.

  • MoveL Offs(drop,0,0,100): the Z-offset when departing the placing pose is set to 100 mm. The robot will move to 100 mm above the placing pose.