Example program 2: Sample_2

You are viewing an old version of the documentation. You can switch to the documentation of the latest version by clicking the top-right corner of the page.

Program Introduction

Description

The robot triggers the Mech-Viz project to run, and then obtains the planned path for picking and placing.

File path

Mech-Vision and Mech-Viz are located in Communication Component/Robot_Interface/DENSO/sample.pcs.

This file contains three subprograms: Sample_1, Sample_2, and Sample_3. This section only introduces the Sample_2 subprogram.

Project

Mech-Vision and Mech-Viz projects

Prerequisites

  1. You have set up the standard interface communication.

  2. Automatic calibration is completed.

This example program is provided for reference only. Before using the program, please modify the program according to the actual scenario.

Program Description

This part provides and explains the code of the Sample_2 example program.

Sub Sample_2
'-------------------------------
'FUNCTION:simple pick and place
'with Mech-Viz
'Mech-Mind, 2022-8-4
'-------------------------------
'Getting control of the robot.
	TakeArm Keep = 0
'move to the home position
	Move P, P[1],speed=80
'move to the camera position
	Move P,@C P[2],speed=80
	Open_socket
'set vision recipe
	MM_Set_Model 1,1
	Delay 100
'Run Viz project
	MM_Start_Viz 2,0
	Delay 500
'set branch exitport
	MM_Set_Branch 1,1
'get result from Viz
	MM_Get_VizData 2,1,2,3
	IF I[3]<>2100 THEN
		stop
	END IF
'set the first pos to P20
'set lables to I11
'set speed to I12
	MM_Get_Pose 1,20,11,12
	Approach P, P[20], 100
	Move L,@C P[20],speed=80
'enable girpper
	Set IO[24]
	Approach L, P[20], 100
	Move P, P[3],speed=80
'drop point
	Move L,@C P[4],speed=80
'release gripper
	Reset IO[24]
'Giving up control of the robot
	GiveArm
	Close_socket
End Sub

The workflow corresponding to the above example program code is shown in the figure below.

sample2

The table below explains the above program. You can click the hyperlink to the command name to view its detailed description.

Feature Code and description

Obtain the control

TakeArm Keep = 0

Obtain the control of the robot arm group and perform the following initialization operations:

  • Set the internal velocity of the robot arm group to 100. Meanwhile, set the internal acceleration and internal deceleration to 100.

  • Initialize the current tool reference frame ID to Tool0.

  • Initialize the current workobject reference frame ID to Work0.

Move to the home position

Move P,P[1],speed=80

The robot moves from the current position to the home position (P[1]) at 80% of its velocity. The P parameter indicates the point-to point movement.

You should teach the home position in advance. For detailed instructions, see Teach Calibration Starting Point in the calibration document.

Move to the image-capturing position

Move P,@C P[2],speed=80

The robot moves from its current position to the image-capturing position (P[2]) at 80% of its velocity. @C indicates that the robot will execute the next command when it confirms that the transformed position and pose of the forearm have reached the desired objectives based on the encoded value.

You should teach the image-capturing position in advance. For detailed instructions, see Teach Calibration Starting Point in the calibration document.

Establish the communication

Open_socket

The TCP communication between the robot and the vision system is established by using the Open_socket command.

Switch the Mech-Vision parameter recipe

MM_Set_Model 1,1
  • MM_Set_Model: The command to switch the Mech-Vision parameter recipe.

  • 1: The Mech-Vision project ID.

  • 1: The ID of the parameter recipe in the Mech-Vision project.

In this entire statement, the parameter recipe of the Mech-Vision project whose ID is 1 is switched to recipe 1.

If no parameter recipe is used in the Mech-Vision project, delete or comment out this line.
Delay 100

Delay indicates that the task will be put on standby within the specified delay time. The delay time is measured in milliseconds (ms). The preceding statement indicates that the robot is on standby for 100 ms to ensure that the Mech-Vision has enough time to switch the parameter recipe.

Trigger the Mech-Vision project to run

MM_Start_Viz 2,0
  • MM_Start_Viz: The command to trigger the Mech-Viz project to run.

  • 2: A teaching point (not the current joint positions but the custom joint positions) of the robot is sent to the Mech-Viz project, which triggers the Mech-Vizproject to plan the next path in advance when the robot resides outside the image-capturing area. The camera mounting method is Eye To Hand.

  • 0: The ID of a variable J. J[0] stores custom joint position data.

The entire statement indicates that the robot triggers the vision system to run the Mech-Viz project and sends the joint position data represented by J[0] to the Mech-Viz project.

Delay 500

The above statement indicates that the robot is on standby for 500 ms to ensure that the camera has enough time to capture images.

Set the exit port for the Branch by Msg Step in Mech-Viz

MM_Set_Branch 1,1
  • MM_Set_Branch: The command to set the exit port for the Branch by Msg Step in Mech-Viz.

  • First 1: The Step ID of the Branch by Msg Step.

  • Second 1: The Mech-Viz project takes exit port 0 of the Branch by Msg Step. Note that if this parameter is set to N, the exit port is N-1.

In the entire statement, the Mech-Viz project with an ID of 1 takes the port 0 of the Branch by Msg Step, as shown in the following figure.

set branch

Get the planned path

MM_Get_VizData 2,1,2,3
  • MM_Get_VizData: The command to obtain the planned path.

  • 2: The pose type of the waypoint is set to TCP.

  • 1: The ID of a variable I. I[1] is used to store the number of obtained waypoints.

  • 2: The ID of a variable I. I[2] is used to store the position ID of the Vision Move waypoint (picking point) in the path.

  • 3: The ID of a variable I. I[3] is used to store the status code.

The entire statement indicates that the robot obtains the planned path from the Mech-Viz project.

The returned planned path is saved to the robot memory and cannot be directly obtained. To access the planned path, you must store the planned path in a subsequent step.
IF I[3]<>2100 THEN
	stop
END IF

When the status code is 2100 in I[3], the robot has successfully obtained all planned path. Otherwise, an error is returned in the vision system. You can perform the corresponding operation based on the specific error code.

Store the planned path

This example assumes that the first obtained waypoint is the picking point.
MM_Get_Pose 1,20,11,12
  • MM_Get_Pose: The command to store the planned path.

  • 1: The first waypoint is stored.

  • 20: The ID of a variable P. P[20] stores the TCP pose of the first waypoint, which is the TCP pose of the picking point.

  • 11: The ID of a variable I. I[11] stores the label corresponding to the first waypoint.

  • 12: The ID of a variable I. I[12] stores the velocity corresponding to the first waypoint.

The entire statement stores the TCP pose, label, and velocity of the first waypoint in the specified variables.

Move to the approach waypoint of picking

Approach P,P[20],100

The robot moves to the approach waypoint of picking in point-to-point mode. 100 represents 100 mm in the negative Z-direction relative to P[20] (i.e., the robot moves to 100 mm above the picking waypoint and reaches the approach waypoint of picking).

Adding approach waypoints of picking can prevent the robot from colliding with objects (such as bins) in the scene when moving. You can modify the Z-axis negative offset based on the actual scenario to ensure that no collision occurs during the approaching process.

Move to the picking waypoint

Move L,@C P[20],speed=80

The robot moves from the approach waypoint of picking to the picking waypoint (P[20]) in linear motion.

Set DO to perform picking

Set IO[24]

After the robot moves to the picking waypoint, you can set a DO (such as Set IO[24]) to control the robot to use the tool to perform picking. Please add the operation of setting DO according to the actual situation.

Move to the departure waypoint of picking

Approach L,P[20],100

The robot moves to 100 mm above the picking waypoint and reaches the departure waypoint of picking.

Adding departure waypoints of picking can prevent the robot from colliding with objects (such as bins) in the scene when moving. You can modify the Z-axis negative offset based on the actual scenario to ensure that no collision occurs during the departing process.

Move to the intermediate waypoint

Move P,P[3],speed=80

The robot moves to a intermediate waypoint (P[3]) between the departure waypoint of picking and the placing waypoint.

  • Adding intermediate waypoints can ensure smooth robot motion and avoid unnecessary collisions. You can add multiple intermediate waypoints according to the actual situation.

  • You need to teach the intermediate waypoint in advance. For information about how to teach the waypoint, see Teach Calibration Starting Point in the calibration document.

Move to the placing waypoint

Move L,@C P[4],speed=80

The robot moves from the intermediate waypoint to the placing waypoint (P[4]).

You need to teach the placing waypoint in advance. For information about how to teach the waypoint, see Teach Calibration Starting Point in the calibration document.

Set DO to perform placing

Reset IO[24]

After the robot moves to the placing waypoint, you can set a DO (such as Reset IO[24]) to control the robot to use the tool to perform placing. Please add the operation of setting DOs according to the actual situation.

Release the control

GiveArm

Release the control on the robot arm group.

Close the communication

Close_socket

The TCP communication between the robot and the vision system is closed by using the Close_socket command.

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.