Adaptive Assembly
Search
SlideSpiral
Primitive Description and Usage
Description: This primitive provides a force-search mechanism to find the hole in peg-in-hole assembly tasks. Specifically, it allows users to command the robot to search within a circular area along an increasingly dense spiral trajectory on a surface while maintaining a certain contact force.
Example Usage: Use this primitive prior to peg-in-hole assembly tasks.
Primitive Input Parameters
Input Parameter |
Description |
Type |
Unit |
Default Value & Range |
---|---|---|---|---|
contactAxis |
Contact (force control) direction in TCP coordinate system, which should be along one of TCP’s principal axes |
VEC_3d |
none |
0.0 0.0 1.0 |
searchAxis |
Search direction in TCP coordinate system, which should be perpendicular to the contact axis |
VEC_3d |
none |
1.0 0.0 0.0 |
contactForce |
Contact force when searching on the surface |
DOUBLE |
N |
5 ∈ [5 … 20] |
radius |
Searching area radius; when payload or contact surface friction/resistance is high, this value might be slightly smaller than its nominal value. |
DOUBLE |
m |
0.015 ∈ [0.001 … 0.015] |
startDensity |
Number of times the geometry pattern will be drawn in the start cycle |
INT |
none |
2 ∈ [1 … 5] |
timeFactor |
Time factor for how long it takes for TCP to form a pattern. Caution: 1. Small time factor for a large searching radius may cause the robot to exceed its capabilities and stop. 2. In Manual mode, this factor is approximately doubled regardless of the speed percentage. |
INT |
none |
2 ∈ [1 … 10] |
wiggleRange |
TCP wiggle range along the contact axis to find the right angle during searching. Caution: If this parameter is set to a large value, make sure to increase the wigglePeriod, otherwise, the robot may exceed its capabilities. |
DOUBLE |
deg |
0 ∈ [0 … 90] |
wigglePeriod |
Time period for TCP to wiggle along the contact axis back and forth once. Caution: 1. Setting this value too small will likely cause the robot exceeding its capabilities and stop, especially when the wiggle motion is not along the Z-axis of the robot flange. 2. In Manual mode, this factor is approximately doubled regardless of the speed percentage. |
DOUBLE |
s |
0.3 ∈ [0.2 … 30] |
randomFactor |
Factor of the randomness added to the slide searching trajectory |
DOUBLE |
none |
0 ∈ [0 … 1] |
searchImmed |
Start searching immediately without waiting for contact force to reach its set value |
BOOL |
none |
1 ∈ [0 / 1] |
searchStiffRatio |
Factor of the stiffness during searching motion. Caution: Setting this value too small, the robot may not follow the search trajectory very well, especially when the surface friction or contact force is very large. |
DOUBLE |
none |
1 ∈ [0.1 … 1] |
maxVelForceDir |
Maximum movement velocity along force control direction |
DOUBLE |
m/s |
0.1 ∈ [0.005 … 0.5] |
Primitive State Parameters
State Parameter |
Description |
Type |
Unit |
---|---|---|---|
terminated |
The termination flag of the primitive. It is set to true if the primitive is terminated. |
BOOL |
none |
timePeriod |
The time spent on running the current primitive. |
DOUBLE |
s |
searchResisForce |
Feedback force during searching motion, which could indicate the collision or resistance. |
DOUBLE |
N |
pushDis |
Pushed distance of TCP into the surface, which could signal a successful find. |
DOUBLE |
m |
forceDrop |
Dropped value from the set contact force. Caution: this state will not be reliable if input parameter searchImmed is set to TRUE. |
DOUBLE |
N |
lostContact |
Flag to indicate the loss of contact. This flag will only be switched on when the forces detected on all X, Y, Z, Rx, Ry, Rz axes are smaller than 1N or 1Nm for 1.5 consecutive seconds. |
BOOL |
none |
Primitive Output Parameters
Output Parameter |
Description |
Type |
Unit |
---|---|---|---|
tcpPoseOut |
The TCP pose when the primitive is terminated. It is represented in the world coordinate system. |
COORD |
m-deg |
Default Transition Condition
State Parameter |
Condition |
Value |
---|---|---|
pushDistance |
> |
0.005 |
SlideZigzag
Primitive Description and Usage
Description: This primitive provides a force-search mechanism to find the hole in peg-in-hole assembly tasks. Specifically, it allows users to command the robot to search within a rectangular area along an increasingly dense zigzag trajectory on a surface while maintaining a certain contact force.
Example Usage: Use this primitive prior to peg-in-hole assembly tasks.
Primitive Input Parameters
Input Parameter |
Description |
Type |
Unit |
Default Value & Range |
---|---|---|---|---|
contactAxis |
Contact (force control) direction in TCP coordinate system, which should be along one of TCP’s principal axes |
VEC_3d |
none |
0.0 0.0 1.0 |
searchAxis |
Search direction in TCP coordinate system, which should be perpendicular to the contact axis |
VEC_3d |
none |
1.0 0.0 0.0 |
contactForce |
Contact force when searching on the surface |
DOUBLE |
N |
5 ∈ [5 … 20] |
length |
Searching area length along the search axis; when payload or contact surface friction/resistance is high, this value might be slightly smaller than its nominal value. |
DOUBLE |
m |
0.03 ∈ [0.001 … 0.03] |
width |
Searching area width perpendicular to the search and contact axis; when payload or contact surface friction/resistance is high, this value might be slightly smaller than its nominal value. |
DOUBLE |
m |
0.03 ∈ [0.001 … 0.03] |
startDensity |
Number of times the geometry pattern will be drawn in the start cycle |
INT |
none |
2 ∈ [1 … 5] |
timeFactor |
Time factor for how long it takes for TCP to form a pattern. Caution: 1. Small time factor for a large searching radius may cause the robot to exceed its capabilities and stop. 2. In Manual mode, this factor is approximately doubled regardless of the speed percentage. |
INT |
none |
2 ∈ [1 … 10] |
wiggleRange |
TCP wiggle range along the contact axis to find the right angle during searching. Caution: If this parameter is set to a large value, make sure to increase the wigglePeriod, otherwise, the robot may exceed its capabilities |
DOUBLE |
deg |
0 ∈ [0 … 90] |
wigglePeriod |
Time period for TCP to wiggle along the contact axis back and forth once. Caution: 1. Setting this value too small will likely cause the robot exceeding its capabilities and stop, especially when the wiggle motion is not along the Z-axis of the robot flange. 2. In Manual mode, this factor is approximately doubled regardless of the speed percentage. |
DOUBLE |
s |
0.3 ∈ [0.2 … 30] |
randomFactor |
Factor of the randomness added to the slide searching trajectory |
DOUBLE |
none |
0 ∈ [0 … 1] |
searchImmed |
Start searching immediately without waiting for contact force to reach its set value |
BOOL |
none |
1 ∈ [0 / 1] |
searchStiffRatio |
Factor of the stiffness during searching motion. Caution: Setting this value too small, the robot may not follow the search trajectory very well, especially when the surface friction or contact force is very large. |
DOUBLE |
none |
1 ∈ [0.1 … 1] |
maxVelForceDir |
Maximum movement velocity along force control direction |
DOUBLE |
m/s |
0.1 ∈ [0.005 … 0.5] |
Primitive State Parameters
State Parameter |
Description |
Type |
Unit |
---|---|---|---|
terminated |
The termination flag of the primitive. It is set to true if the primitive is terminated. |
BOOL |
none |
timePeriod |
The time spent on running the current primitive. |
DOUBLE |
s |
searchResisForce |
Feedback force during searching motion, which could indicate the collision or resistance. |
DOUBLE |
N |
pushDis |
Pushed distance of TCP into the surface, which could signal a successful find. |
DOUBLE |
m |
forceDrop |
Dropped value from the set contact force. Caution: this state will not be reliable if input parameter searchImmed is set to TRUE. |
DOUBLE |
N |
lostContact |
Flag to indicate the loss of contact. This flag will only be switched on when the forces detected on all X, Y, Z, Rx, Ry, Rz axes are smaller than 1N or 1Nm for 1.5 consecutive seconds. |
BOOL |
none |
Primitive Output Parameters
Output Parameter |
Description |
Type |
Unit |
---|---|---|---|
tcpPoseOut |
The TCP pose when the primitive is terminated. It is represented in the world coordinate system. |
COORD |
m-deg |
Default Transition Condition
State Parameter |
Condition |
Value |
---|---|---|
pushDistance |
> |
0.005 |
CheckPih
Primitive Description and Usage
Description: This primitive helps check if a peg is already in a hole. Users can specify a contact axis and a search axis perpendicular to the contact axis, and a companion axis will be generated to form a frame. The robot will move toward the +searchAxis, -searchAxis, -companionAxis, +companionAxis. While moving along these axes, if the robot goes over the limit specified by searchRange, the primitive will terminate and the state parameter pegIsInHole will be set to false; if the robot encounters a force greater than searchForce along all these directions during the process, the primitive will terminate and pegIsInHole will be set to true.
Example Usage: Use this primitive to check if a peg-in-hole operation is completed.
Primitive Input Parameters
Input Parameter |
Description |
Type |
Unit |
Default Value & Range |
---|---|---|---|---|
contactAxis |
Force control direction in TCP coordinate system, which should be along one of TCP’s principal axes |
VEC_3d |
none |
0.0 0.0 1.0 |
searchAxis |
Search direction in TCP coordinate system, which should be perpendicular to the contact axis |
VEC_3d |
none |
1.0 0.0 0.0 |
searchRange |
Range within which the robot will make forward, backward, left, and right search motions |
DOUBLE |
m |
0.01 ∈ [0.001 … 0.1] |
searchForce |
Force threshold to detect if the robot can move along the searching direction. Robot will move along the next motion direction when detected force is greater than this value. |
DOUBLE |
N |
3 ∈ [2 … 20] |
searchVel |
TCP linear velocity for the searching motion |
DOUBLE |
m/s |
0.01 ∈ [0.001 … 0.1] |
linearSearchOnly |
Flag to indicate if the robot only searches linearly in the direction of +searchAxis and -searchAxis |
BOOL |
none |
0 ∈ [0 / 1] |
Primitive State Parameters
State Parameter |
Description |
Type |
Unit |
---|---|---|---|
terminated |
The termination flag of the primitive. It is set to true if the primitive is terminated. |
BOOL |
none |
timePeriod |
The time spent on running the current primitive. |
DOUBLE |
s |
pegIsInHole |
Flag to indicate if the peg is already in the hole |
BOOL |
none |
checkComplete |
Flag to indicate if the peg-in-hole check is complete |
BOOL |
none |
Primitive Output Parameters
Output Parameter |
Description |
Type |
Unit |
---|---|---|---|
tcpPoseOut |
The TCP pose when the primitive is terminated. It is represented in the world coordinate system. |
COORD |
m-deg |
initTcpPose |
Initial TCP pose when plan runs into this primitive |
COORD |
m-deg |
Default Transition Condition
State Parameter |
Condition |
Value |
---|---|---|
checkComplete |
= |
1 |
Peg-in-Hole
PihSpiral
Primitive Description and Usage
Description: This primitive provides a peg-in-hole strategy that uses repeated spiral trajectories and hybrid force/motion control to find and insert a peg in a hole within a circular area.
Example Usage: Use this primitive to handle environmental uncertainties in peg-in-hole assembly tasks where the peg position errors are too large for traditional position-based control methods to handle.
Primitive Input Parameters
Input Parameter |
Description |
Type |
Unit |
Default Value & Range |
---|---|---|---|---|
contactVel |
TCP linear velocity while moving to contact |
DOUBLE |
m/s |
0.01 ∈ [0.001 … 0.1] |
contactAxis |
Contact (force control) direction in TCP coordinate system, which should be along one of TCP’s principal axes |
VEC_3d |
none |
0.0 0.0 1.0 |
searchAxis |
Search direction in TCP coordinate system, which should be perpendicular to the contact axis |
VEC_3d |
none |
1.0 0.0 0.0 |
contactForce |
Contact force when searching on the surface |
DOUBLE |
N |
8 ∈ [5 … 20] |
pushDis |
Pushed distance of TCP into the surface, which could signal a successful find. |
DOUBLE |
m |
0.005 ∈ [0.002 … 0.02] |
radius |
Searching area radius; when payload or contact surface friction/resistance is high, this value might be slightly smaller than its nominal value. |
DOUBLE |
m |
0.015 ∈ [0.001 … 0.015] |
timeFactor |
Time factor for how long it takes for TCP to form a pattern. Caution: 1. Small time factor for a large searching radius may cause the robot to exceed its capabilities and stop. 2. In Manual mode, this factor is approximately doubled regardless of the speed percentage. |
INT |
none |
2 ∈ [1 … 10] |
wiggleRange |
TCP wiggle range along the contact axis to find the right angle during searching. Caution: If this parameter is set to a large value, make sure to increase the wigglePeriod, otherwise, the robot may exceed its capabilities. |
DOUBLE |
deg |
0 ∈ [0 … 10] |
wigglePeriod |
Time period for TCP to wiggle along the contact axis back and forth once. Caution: 1. Setting this value too small will likely cause the robot exceeding its capabilities and stop, especially when the wiggle motion is not along the Z-axis of the robot flange. 2. In Manual mode, this factor is approximately doubled regardless of the speed percentage. |
DOUBLE |
s |
0.3 ∈ [0.2 … 9] |
startDensity |
Number of times the geometry pattern will be drawn in the start cycle |
INT |
none |
2 ∈ [1 … 5] |
randomFactor |
Factor of the randomness added to the slide searching trajectory |
DOUBLE |
none |
0 ∈ [0 … 1] |
Primitive State Parameters
State Parameter |
Description |
Type |
Unit |
---|---|---|---|
terminated |
The termination flag of the primitive. It is set to true if the primitive is terminated. |
BOOL |
none |
timePeriod |
The time spent on running the current primitive. |
DOUBLE |
s |
Primitive Output Parameters
Output Parameter |
Description |
Type |
Unit |
---|---|---|---|
tcpPoseOut |
The TCP pose when the primitive is terminated. It is represented in the world coordinate system. |
COORD |
m-deg |
Default Transition Condition
State Parameter |
Condition |
Value |
---|---|---|
terminated |
= |
1 |
PihZigzag
Primitive Description and Usage
Description: This primitive provides a peg-in-hole strategy that uses repeated zigzag trajectories and hybrid force/motion control to find and insert a peg in a hole within a rectangular area.
Example Usage: Use this primitive to handle environmental uncertainties in peg-in-hole assembly tasks where the peg position errors are too large for traditional position-based control methods to handle.
Primitive Input Parameters
Input Parameter |
Description |
Type |
Unit |
Default Value & Range |
---|---|---|---|---|
contactVel |
TCP linear velocity while moving to contact |
DOUBLE |
m/s |
0.01 ∈ [0.001 … 0.1] |
contactAxis |
Contact (force control) direction in TCP coordinate system, which should be along one of TCP’s principal axes |
VEC_3d |
none |
0.0 0.0 1.0 |
searchAxis |
Search direction in TCP coordinate system, which should be perpendicular to the contact axis |
VEC_3d |
none |
1.0 0.0 0.0 |
contactForce |
Contact force when searching on the surface |
DOUBLE |
N |
8 ∈ [5 … 20] |
pushDis |
Pushed distance of TCP into the surface, which could signal a successful find. |
DOUBLE |
m |
0.005 ∈ [0.002 … 0.02] |
length |
Searching area length along the search axis; when payload or contact surface friction/resistance is high, this value might be slightly smaller than its nominal value. |
DOUBLE |
m |
0.03 ∈ [0.001 … 0.03] |
width |
Searching area width perpendicular to the search and contact axis; when payload or contact surface friction/resistance is high, this value might be slightly smaller than its nominal value. |
DOUBLE |
m |
0.03 ∈ [0.001 … 0.03] |
timeFactor |
Time factor for how long it takes for TCP to form a pattern. Caution: 1. Small time factor for a large searching radius may cause the robot to exceed its capabilities and stop. 2. In Manual mode, this factor is approximately doubled regardless of the speed percentage. |
INT |
none |
2 ∈ [1 … 10] |
wiggleRange |
TCP wiggle range along the contact axis to find the right angle during searching. Caution: If this parameter is set to a large value, make sure to increase the wigglePeriod, otherwise, the robot may exceed its capabilities |
DOUBLE |
deg |
0 ∈ [0 … 10] |
wigglePeriod |
Time period for TCP to wiggle along the contact axis back and forth once. Caution: 1. Setting this value too small will likely cause the robot exceeding its capabilities and stop, especially when the wiggle motion is not along the Z-axis of the robot flange. 2. In manual mode, this factor is approximately doubled regardless of the speed percentage. |
DOUBLE |
s |
0.3 ∈ [0.2 … 9] |
startDensity |
Number of times the geometry pattern will be drawn in the start cycle |
INT |
none |
2 ∈ [1 … 5] |
randomFactor |
Factor of the randomness added to the slide searching trajectory |
DOUBLE |
none |
0 ∈ [0 … 1] |
Primitive State Parameters
State Parameter |
Description |
Type |
Unit |
---|---|---|---|
terminated |
The termination flag of the primitive. It is set to true if the primitive is terminated. |
BOOL |
none |
timePeriod |
The time spent on running the current primitive. |
DOUBLE |
s |
Primitive Output Parameters
Output Parameter |
Description |
Type |
Unit |
---|---|---|---|
tcpPoseOut |
The TCP pose when the primitive is terminated. It is represented in the world coordinate system. |
COORD |
m-deg |
Default Transition Condition
State Parameter |
Condition |
Value |
---|---|---|
terminated |
= |
1 |
Sleeve
Primitive Description and Usage
Description: This primitive moves the robot in a predefined insertion direction until the total external force reaches a set value. The robot then adjusts its position and orientation in all directions except the insertion direction (as long as the external force in the corresponding direction exceeds the deadband). During the adjustment, the robot will stop the insertion motion.
Example Usage: Use this primitive in fine assembly tasks such as gearbox assembly, peg-in-hole assembly, or in machine tending applications like putting a sleeve (a hollow cylinder) on a shaft.
Primitive Input Parameters
Input Parameter |
Description |
Type |
Unit |
Default Value & Range |
---|---|---|---|---|
insertAxis* |
Insertion direction in TCP coordinate system |
TYPE |
none |
[X -X Y -Y Z -Z] |
compAxis |
Force compliance axes in TCP coordinate system. The robot performs compliant motion along the axis whose value is set to 1. For example, (0,1,0,1,0,0) means that the robot executes compliant motion at Y and Rx axis of TCP coordinate. |
VEC_6i |
none |
0 0 0 0 0 0 ∈ [0 0 0 0 0 0 … 1 1 1 1 1 1] |
compForceLimit |
Compliant force limit. Robot automatically adjusts TCP position and orientation to be compliant with this force. |
DOUBLE |
N |
5 ∈ [1 … 120] |
deadbandScale |
Deadband scale of applied alignment wrench. The robot only performs compliant motion when the external wrench is higher than this deadband. 0 means no deadband. |
DOUBLE |
none |
50 ∈ [10 … 100] |
insertVel |
TCP Linear velocity in insertion direction |
DOUBLE |
m/s |
0.01 ∈ [0.001 … 0.1] |
compVelScale |
Velocity scale of compliant motion. Higher velocity scale results in faster but less stable compliant motion. |
DOUBLE |
none |
20 ∈ [10 … 100] |
*Parameters marked with an asterisk must be assigned a value prior to executing the primitive.
Primitive State Parameters
State Parameter |
Description |
Type |
Unit |
---|---|---|---|
terminated |
The termination flag of the primitive. It is set to true if the primitive is terminated. |
BOOL |
none |
timePeriod |
The time spent on running the current primitive. |
DOUBLE |
s |
insertDis |
Robot moving distance in the insertion direction |
DOUBLE |
m |
isMoving |
Flag to indicate if robot is still moving |
BOOL |
none |
Primitive Output Parameters
Output Parameter |
Description |
Type |
Unit |
---|---|---|---|
tcpPoseOut |
The TCP pose when the primitive is terminated. It is represented in the world coordinate system. |
COORD |
m-deg |
Default Transition Condition
State Parameter |
Condition |
Value |
---|---|---|
isMoving |
= |
0 |
Mating
MatingSlide
Primitive Description and Usage
Description: This primitive uses hybrid motion/force control to repeatedly move the robot along a line trajectory while applying a certain force in a specific direction.
Example Usage: Use this primitive to assist parts mating operations in assembly applications.
Primitive Input Parameters
Input Parameter |
Description |
Type |
Unit |
Default Value & Range |
---|---|---|---|---|
matingAxis |
Sliding direction in TCP coordinate system, which should be perpendicular to the force control axis. |
VEC_3d |
none |
0 1 0 |
forceAxis |
Force control direction in TCP coordinate system, which should be perpendicular to the motion direction. |
VEC_3d |
none |
0 0 1 |
matingRange |
Sliding motion range |
DOUBLE |
m |
0.1 ∈ [0.001 … 0.35] |
matingVel |
TCP linear velocity during sliding motion |
DOUBLE |
m/s |
0.1 ∈ [0.001 … 0.5] |
matingTimes |
Total number of mating times. Caution: If set to 0, the robot performs ONLY forward motion once. |
INT |
none |
1 ∈ [0 … 1000] |
matingForce |
Target mating force |
DOUBLE |
N |
15 ∈ [5 … 50] |
matingAcc |
TCP linear acceleration during sliding motion |
DOUBLE |
m/s^2 |
1.0 ∈ [0.1 … 2.5] |
safetyForce |
Safety force limit during mating. The primitive will be terminated when the feedback force exceeds this value. |
DOUBLE |
N |
50.0 ∈ [20 … 80] |
safetyForceDis |
Maximum moving distance along force control axis. The primitive will be terminated when the moving distance exceeds this value. |
DOUBLE |
m |
0.05 ∈ [0.005 … 0.5] |
maxVelForceDir |
Maximum movement velocity along force control direction. It constrains the robot’s speed in cases where the robot suddenly loses contact with the environment. Note that if its value is set too small, the robot’s force control performance may degrade. |
DOUBLE |
m/s |
0.5 ∈ [0.002 … 0.5] |
Primitive State Parameters
State Parameter |
Description |
Type |
Unit |
---|---|---|---|
terminated |
The termination flag of the primitive. It is set to true if the primitive is terminated. |
BOOL |
none |
timePeriod |
The time spent on running the current primitive. |
DOUBLE |
s |
matingFinish |
Flag to indicate if the mating process is finished |
BOOL |
none |
Primitive Output Parameters
Output Parameter |
Description |
Type |
Unit |
---|---|---|---|
tcpPoseOut |
The TCP pose when the primitive is terminated. It is represented in the world coordinate system. |
COORD |
m-deg |
Default Transition Condition
State Parameter |
Condition |
Value |
---|---|---|
matingFinished |
= |
1 |
MatingRub
Primitive Description and Usage
Description: This primitive uses hybrid motion/force control to repeatedly rotate the robot TCP along a fixed axis while applying a certain force in a specific direction.
Example Usage: Use this primitive to assist parts mating operations in assembly applications.
Primitive Input Parameters
Input Parameter |
Description |
Type |
Unit |
Default Value & Range |
---|---|---|---|---|
matingAxis |
Rubbing motion direction in TCP coordinate system, which should be perpendicular to the force control axis. |
VEC_3d |
none |
1 0 0 |
forceAxis |
Force control direction in TCP coordinate system, which should be perpendicular to the motion direction. |
VEC_3d |
none |
0 0 1 |
matingRange |
Rubbing motion range |
DOUBLE |
deg |
10 ∈ [1 … 60] |
matingAngVel |
TCP angular velocity during mating motion |
DOUBLE |
deg/s |
10 ∈ [1.0 … 60.0] |
matingAngAcc |
TCP angular acceleration during mating motion |
DOUBLE |
deg/s^2 |
180 ∈ [5 … 500] |
matingTimes |
Total number of mating times. Caution: If set to 0, the robot performs ONLY forward motion once. |
INT |
none |
1 ∈ [0 … 1000] |
matingForce |
Target mating force |
DOUBLE |
N |
15 ∈ [1 … 50] |
safetyForce |
Safety force limit during mating. The primitive will be terminated when the feedback force exceeds this value. |
DOUBLE |
N |
50.0 ∈ [20 … 80] |
safetyForceDis |
Maximum moving distance along force control direction. The primitive will be terminated when the moving distance exceeds this value. |
DOUBLE |
m |
0.05 ∈ [0.001 … 0.5] |
maxVelForceDir |
Maximum movement velocity along force control direction. It constrains the robot’s speed in cases where the robot suddenly loses contact with the environment. Note that if its value is set too small, the robot’s force control performance may degrade. |
DOUBLE |
m/s |
0.5 ∈ [0.001 … 0.5] |
Primitive State Parameters
State Parameter |
Description |
Type |
Unit |
---|---|---|---|
terminated |
The termination flag of the primitive. It is set to true if the primitive is terminated. |
BOOL |
none |
timePeriod |
The time spent on running the current primitive. |
DOUBLE |
s |
matingFinish |
Flag to indicate if the mating process is finished |
BOOL |
none |
Primitive Output Parameters
Output Parameter |
Description |
Type |
Unit |
---|---|---|---|
tcpPoseOut |
The TCP pose when the primitive is terminated. It is represented in the world coordinate system. |
COORD |
m-deg |
Default Transition Condition
State Parameter |
Condition |
Value |
---|---|---|
matingFinished |
= |
1 |
MatingSlideZigzag
Primitive Description and Usage
Description: This primitive uses hybrid motion/force control to repeatedly move the robot along a zigzag trajectory (raster) while applying a certain force in a specific direction.
Example Usage: Use this primitive to assist parts mating operations in assembly applications.
Primitive Input Parameters
Input Parameter |
Description |
Type |
Unit |
Default Value & Range |
---|---|---|---|---|
matingAxis |
Sliding direction in TCP coordinate system, which should be perpendicular to the force control axis. |
VEC_3d |
none |
0 1 0 |
forceAxis |
Force control direction in TCP coordinate system, which should be perpendicular to the motion direction. |
VEC_3d |
none |
0 0 1 |
matingRange |
Sliding motion range |
DOUBLE |
m |
0.1 ∈ [0.001 … 0.35] |
matingVel |
TCP linear velocity during sliding motion |
DOUBLE |
m/s |
0.1 ∈ [0.001 … 0.5] |
matingTimes |
Total number of mating times. Caution: If set to 0, the robot performs ONLY forward motion once. |
INT |
none |
1 ∈ [0 … 1000] |
matingForce |
Target mating force |
DOUBLE |
N |
15 ∈ [5 … 50] |
matingAcc |
TCP linear acceleration during sliding motion |
DOUBLE |
m/s^2 |
1.0 ∈ [0.1 … 2.5] |
safetyForce |
Safety force limit during mating. The primitive will be terminated when the feedback force exceeds this value. |
DOUBLE |
N |
50.0 ∈ [20 … 80] |
safetyForceDis |
Maximum moving distance along force control direction. The primitive will be terminated when the moving distance exceeds this value. |
DOUBLE |
m |
0.05 ∈ [0.005 … 0.5] |
rasterRange |
Raster range along the raster slide direction |
DOUBLE |
m |
0.05 ∈ [0.001 … 0.1] |
rasterVel |
TCP Linear velocity along the raster trajectory |
DOUBLE |
m/s |
0.1 ∈ [0.001 … 0.5] |
rasterAcc |
TCP Linear acceleration along the raster trajectory |
DOUBLE |
m/s^2 |
1.0 ∈ [0.1 … 2.5] |
rasterDir |
Raster slide direction in TCP coordinate system |
VEC_3d |
none |
1 0 0 |
maxVelForceDir |
Maximum movement velocity along force control direction. It constrains the robot’s speed in cases where the robot suddenly loses contact with the environment. Note that if its value is set too small, the robot’s force control performance may degrade. |
DOUBLE |
m/s |
0.5 ∈ [0.001 … 0.5] |
Primitive State Parameters
State Parameter |
Description |
Type |
Unit |
---|---|---|---|
terminated |
The termination flag of the primitive. It is set to true if the primitive is terminated. |
BOOL |
none |
timePeriod |
The time spent on running the current primitive. |
DOUBLE |
s |
matingFinish |
Flag to indicate if the mating process is finished |
BOOL |
none |
Primitive Output Parameters
Output Parameter |
Description |
Type |
Unit |
---|---|---|---|
tcpPoseOut |
The TCP pose when the primitive is terminated. It is represented in the world coordinate system. |
COORD |
m-deg |
Default Transition Condition
State Parameter |
Condition |
Value |
---|---|---|
matingFinished |
= |
1 |
Fastening
FastenScrewExtFeed
Primitive Description and Usage
Description: This primitive helps the robot complete the whole screw fastening task through the following steps:1. Pick up the screw from the external feeder. 2. Move the screw gun to the top of the screw hole. 3. Fasten the screw into the screw hole.
Example Usage: Use this primitive to fasten the screws when screws are fed from the external feeder.
Primitive Input Parameters
Input Parameter |
Description |
Type |
Unit |
Default Value & Range |
---|---|---|---|---|
insertDir |
Screw insertion direction in TCP coordinate system |
TYPE |
none |
Z ∈ [X -X Y -Y Z -Z] |
maxInsertVel |
Maximum screw insertion velocity into the screw hole |
DOUBLE |
m/s |
0.01 ∈ [0.001 … 0.05] |
insertForce |
Screw insertion force during fastening process |
DOUBLE |
N |
20 ∈ [10 … 50] |
stiffScale |
Robot stiffness scale while fastening the screw. Lower scale applies higher motion compliance. |
DOUBLE |
none |
0.5 ∈ [0.1 … 1] |
screwPickPose* |
TCP pose at the screw picking position |
COORD |
m-deg |
[traj_start* world*] |
pickContactVel |
Linear velocity to move robot until the screw gun contacts the screw |
DOUBLE |
m/s |
0.02 ∈ [0.001 … 0.1] |
maxPickContactForce |
Maximum contact force to pick up screw. The primitive will be terminated when external force exceeds this limit. |
DOUBLE |
N |
5.0 ∈ [1.0 … 120] |
transPoints |
Waypoints from screw picking position to screw fastening position |
ARRAY_COORD |
m-deg |
[traj_start* traj_goal* traj_prev* world*] |
vel |
TCP linear velocity |
DOUBLE |
m/s |
0.02 ∈ [0.0005 … 2.2] |
acc |
TCP linear acceleration |
DOUBLE |
m/s^2 |
1.5 ∈ [0.1 … 3.0] |
jerk |
TCP linear jerk |
DOUBLE |
m/s^3 |
200.0 ∈ [50.0 … 1500.0] |
zoneRadius |
Blending zone radius while TCP approximating the waypoints |
TYPE |
mm |
Z50 ∈ [ZFine Z1 Z5 Z10 Z15 Z20 Z30 Z40 Z50 Z60 Z80 Z100 Z150 Z200] |
screwFastenPose* |
TCP pose at the screw fastening position |
COORD |
m-deg |
[traj_start* world*] |
fastenContactVel |
Linear velocity to move the robot until the screw contacts the screw hole |
DOUBLE |
m/s |
0.02 ∈ [0.001 … 0.1] |
maxFastenContactForce |
Maximum force when screw contacts the surface. The primitive will be terminated when external force exceeds this limit. |
DOUBLE |
N |
5.0 ∈ [1.0 … 120] |
diScrewInHole |
Digital input port receiving the signal which indicates the screw has been tightened a bit into the screw hole |
TYPE |
none |
NONE ∈ [NONE, gpioIn0 … gpioIn15, modbusIn0 … modbusIn15] |
diFastenFinish |
Digital input port receiving the signal which indicates the screw fastening process is finished |
TYPE |
none |
NONE ∈ [NONE, gpioIn0 … gpioIn15, modbusIn0 … modbusIn15] |
diFastenFailed |
Digital input port receiving the signal which indicates the screw fastening process is failed |
TYPE |
none |
NONE ∈ [NONE, gpioIn0 … gpioIn15, modbusIn0 … modbusIn15] |
*Parameters marked with an asterisk must be assigned a value prior to executing the primitive.
*Coordinate System Definition
Coordinate |
Definition |
Value Format |
---|---|---|
world |
WORLD coordinate system, which is a fixed Cartesian coordinate system located at the center of the robot base |
X Y Z Rx Ry Rz WORLD WORLD_ORIGIN |
work |
WORK coordinate system, which defines the position of the workpiece relative to the WORLD coordiante system |
X Y Z Rx Ry Rz WORK WorkCoordName |
tcp |
TCP coordinate system, which is located at the Tool Center Point relative to the center of robot flange |
X Y Z Rx Ry Rz TCP ONELINE |
tcp_start |
The fixed coordinate system which is located at the inital TCP pose of the primitive |
X Y Z Rx Ry Rz TCP START |
traj_start |
The offset of a waypoint relative to the initial TCP pose in the TCP coordinate system |
X Y Z Rx Ry Rz TRAJ START |
traj_goal |
The offset of a waypoint relative to the target TCP pose in the TCP coordinate system |
X Y Z Rx Ry Rz TRAJ GOAL |
traj_prev |
The offset of a waypoint relative to the previous waypoint in the TCP coordinate system |
X Y Z Rx Ry Rz TRAJ PREVIOUSWAYPOINT |
Primitive State Parameters
State Parameter |
Description |
Type |
Unit |
---|---|---|---|
terminated |
The termination flag of the primitive. It is set to true if the primitive is terminated. |
BOOL |
none |
timePeriod |
The time spent on running the current primitive. |
DOUBLE |
s |
Primitive Output Parameters
Output Parameter |
Description |
Type |
Unit |
---|---|---|---|
tcpPoseOut |
The TCP pose when the primitive is terminated. It is represented in the world coordinate system. |
COORD |
m-deg |
Default Transition Condition
State Parameter |
Condition |
Value |
---|---|---|
terminated |
= |
1 |
FastenScrewAutoFeed
Primitive Description and Usage
Description: This primitive helps the robot complete the whole screw fastening task through the following steps:1. Feed in the screw through an automatic feeding system. 2. Move the screw gun to the top of the screw hole. 3. Search the screw hole(Optional). 4. Fasten the screw into the screw hole.
Example Usage: Use this primitive to fasten the screws when screws are fed through an automatic feeding system.
Primitive Input Parameters
Input Parameter |
Description |
Type |
Unit |
Default Value & Range |
---|---|---|---|---|
insertDir |
Screw insertion direction in TCP coordinate system |
TYPE |
none |
Z ∈ [X -X Y -Y Z -Z] |
maxInsertVel |
Maximum screw insertion velocity into the screw hole |
DOUBLE |
m/s |
0.01 ∈ [0.001 … 0.05] |
insertForce |
Screw insertion force during fastening process |
DOUBLE |
N |
20 ∈ [10 … 50] |
stiffScale |
Robot stiffness scale while fastening the screw. Lower scale applies higher motion compliance. |
DOUBLE |
none |
0.5 ∈ [0.1 … 1] |
screwFastenPose* |
TCP pose at the screw fastening position |
COORD |
m-deg |
[traj_start* world*] |
screwApproachVel |
Linear velocity to approach the screw fastening position |
DOUBLE |
m/s |
0.2 ∈ [0.001 … 1.5] |
fastenContactVel |
Linear velocity to move the robot until the screw contacts the screw hole |
DOUBLE |
m/s |
0.02 ∈ [0.001 … 0.1] |
maxFastenContactForce |
Maximum force when screw contacts the surface. The primitive will be terminated when external force exceeds this limit. |
DOUBLE |
N |
5.0 ∈ [1.0 … 120] |
enableSearchHole |
Enable searching motion to search screw hole |
BOOL |
none |
0 ∈ [0 / 1] |
contactAxis |
Contact (force control) direction in TCP coordinate system, which should be along one of TCP’s principal axes. |
VEC_3d |
none |
0.0 0.0 1.0 |
searchAxis |
Search direction in TCP coordinate system, which should be perpendicular to the contact axis. |
VEC_3d |
none |
1.0 0.0 0.0 |
contactForce |
Contact force when searching on the surface |
DOUBLE |
N |
5 ∈ [5 … 20] |
searchRadius |
Searching area radius |
DOUBLE |
m |
0.015 ∈ [0.0002 … 0.015] |
pushDis |
Pushed distance of screw into the surface, which is used to judge whether the hole is successfully found |
DOUBLE |
m |
0.005 ∈ [0.002 … 0.02] |
timeFactor |
Time factor for how long it takes for TCP to form a pattern. Caution: 1. Small time factor for a large searching radius may cause the robot to exceed its capabilities and stop. 2. In manual mode, this factor is doubled regardless of the speed percentage. |
INT |
none |
2 ∈ [1 … 10] |
startDensity |
Number of times the geometry pattern will be drawn in the start cycle |
INT |
none |
2 ∈ [1 … 5] |
randomFactor |
Factor of the randomness added to the slide searching trajectory |
DOUBLE |
none |
0 ∈ [0 … 1] |
diScrewInHole |
Digital input port receiving the signal which indicates the screw has been tightened a bit into the screw hole |
TYPE |
none |
NONE ∈ [NONE, gpioIn0 … gpioIn15, modbusIn0 … modbusIn15] |
diFastenFinish |
Digital input port receiving the signal which indicates the screw fastening process is finished |
TYPE |
none |
NONE ∈ [NONE, gpioIn0 … gpioIn15, modbusIn0 … modbusIn15] |
diFastenFailed |
Digital input port receiving the signal which indicates the screw fastening process is failed |
TYPE |
none |
NONE ∈ [NONE, gpioIn0 … gpioIn15, modbusIn0 … modbusIn15] |
*Parameters marked with an asterisk must be assigned a value prior to executing the primitive.
*Coordinate System Definition
Coordinate |
Definition |
Value Format |
---|---|---|
world |
WORLD coordinate system, which is a fixed Cartesian coordinate system located at the center of the robot base |
X Y Z Rx Ry Rz WORLD WORLD_ORIGIN |
work |
WORK coordinate system, which defines the position of the workpiece relative to the WORLD coordiante system |
X Y Z Rx Ry Rz WORK WorkCoordName |
tcp |
TCP coordinate system, which is located at the Tool Center Point relative to the center of robot flange |
X Y Z Rx Ry Rz TCP ONELINE |
tcp_start |
The fixed coordinate system which is located at the inital TCP pose of the primitive |
X Y Z Rx Ry Rz TCP START |
traj_start |
The offset of a waypoint relative to the initial TCP pose in the TCP coordinate system |
X Y Z Rx Ry Rz TRAJ START |
traj_goal |
The offset of a waypoint relative to the target TCP pose in the TCP coordinate system |
X Y Z Rx Ry Rz TRAJ GOAL |
traj_prev |
The offset of a waypoint relative to the previous waypoint in the TCP coordinate system |
X Y Z Rx Ry Rz TRAJ PREVIOUSWAYPOINT |
Primitive State Parameters
State Parameter |
Description |
Type |
Unit |
---|---|---|---|
terminated |
The termination flag of the primitive. It is set to true if the primitive is terminated. |
BOOL |
none |
timePeriod |
The time spent on running the current primitive. |
DOUBLE |
s |
Primitive Output Parameters
Output Parameter |
Description |
Type |
Unit |
---|---|---|---|
tcpPoseOut |
The TCP pose when the primitive is terminated. It is represented in the world coordinate system. |
COORD |
m-deg |
Default Transition Condition
State Parameter |
Condition |
Value |
---|---|---|
terminated |
= |
1 |
FastenScrew
Primitive Description and Usage
Description: This primitive is applicable to screw fastening tasks. During the fastening process, the robot maintains contact with objects along the insertion direction while performing compliant motion in other directions.
Example Usage: Use this primitive to fasten the screws in assembly applications.
Primitive Input Parameters
Input Parameter |
Description |
Type |
Unit |
Default Value & Range |
---|---|---|---|---|
insertDir |
Screw insertion direction in TCP coordinate system |
TYPE |
none |
Z ∈ [X -X Y -Y Z -Z] |
maxInsertVel |
Maximum screw insertion velocity into the screw hole |
DOUBLE |
m/s |
0.01 ∈ [0.001 … 0.05] |
insertForce |
Screw insertion force during fastening process |
DOUBLE |
N |
20 ∈ [10 … 50] |
stiffScale |
Robot stiffness scale while fastening the screw. Lower scale applies higher motion compliance. |
DOUBLE |
none |
0.5 ∈ [0.1 … 1] |
diScrewInHole |
Digital input port which receives the signal from screw gun, indicating that screw has been tightened a bit into the screw hole. |
TYPE |
none |
NONE ∈ [NONE, gpioIn0 … gpioIn15, modbusIn0 … modbusIn15] |
diFastenFinish |
Digital input port which receives the signal from screw gun, indicating that screw has been totally tightened. |
TYPE |
none |
NONE ∈ [NONE, gpioIn0 … gpioIn15, modbusIn0 … modbusIn15] |
diScrewJam |
Digital input port which receives the signal from screw gun, indicating that screw has been jammed. |
TYPE |
none |
NONE ∈ [NONE, gpioIn0 … gpioIn15, modbusIn0 … modbusIn15] |
Primitive State Parameters
State Parameter |
Description |
Type |
Unit |
---|---|---|---|
terminated |
The termination flag of the primitive. It is set to true if the primitive is terminated. |
BOOL |
none |
timePeriod |
The time spent on running the current primitive. |
DOUBLE |
s |
insertDis |
Screw insertion distance into the screw hole |
DOUBLE |
m |
insertVel |
Screw insertion velocity into the screw hole |
DOUBLE |
m/s |
fastenState |
Screw fastening state: 0 means default state; 1 means screw has been tightened a bit into the screw hole; 2 means screw has been totally tightened; -1 means screw has been jammed. |
INT |
none |
reachedHole |
Flag to indicate screw has reached full contact with screw hole |
BOOL |
none |
Primitive Output Parameters
Output Parameter |
Description |
Type |
Unit |
---|---|---|---|
tcpPoseOut |
The TCP pose when the primitive is terminated. It is represented in the world coordinate system. |
COORD |
m-deg |
Default Transition Condition
State Parameter |
Condition |
Value |
---|---|---|
fastenState |
= |
2 |