Human-Robot Collaboration
FloatingCartesian
Primitive Description and Usage
Description: This primitive enables users to drag the robot in the Cartesian coordinate system during project execution. Note: This primitive can only be used in human-robot collaboration scenarios. Using it directly in automation scenarios may result in unexpected robot motion or even injury.
Example Usage: Use this primitive in human-robot collaboration scenarios to manually move the robot to the desired position before having it perform subsequent actions.
Primitive Input Parameters
Input Parameter |
Description |
Type |
Unit |
Default Value & Range |
---|---|---|---|---|
floatingAxis |
Axes that allow floating in the floating coordinate system. 1 means floating is allowed; 0 means floating is not allowed. |
VEC_6i |
none |
1 1 1 1 1 1 ∈ [0 0 0 0 0 0 … 1 1 1 1 1 1] |
enableElbowMotion |
Flag to indicate if elbow motion is allowed during robot floating |
BOOL |
none |
0 ∈ [0 / 1] |
floatingCoord |
Reference floating coordinate system for dragging the robot |
COORD |
m-deg |
0 0 0 0 0 0 TCP START ∈ [world* tcp* tcp_start*] |
dampingLevel |
Damping level of the robot during floating. The lower the damping level, the easier it is for the robot to be dragged, but the less easy it is for the robot pose to be adjusted. |
VEC_6d |
none |
0 0 0 0 0 0 ∈ [0 0 0 0 0 0 … 100 100 100 100 100 100] |
diEnableFloating |
Digital input port that enables floating. The robot can only be dragged if this signal is ON. |
TYPE |
none |
NONE ∈ [NONE, gpioIn0 … gpioIn15, modbusIn0 … modbusIn15] |
responseTorque |
External floating joint torque that the robot will respond to. If the external joint torque is lower than this value, the robot will not be able to be dragged. |
VEC_7d |
Nm |
1.5 1.5 1.5 1.5 0.5 0.5 0.3 ∈ [0.0 0.0 0.0 0.0 0.0 0.0 0.0 … 3.0 3.0 3.0 3.0 3.0 3.0 3.0] |
*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 ONLINE |
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 |
You can use the simplified value format above to describ a waypoint, while the complete description of a Cartesian waypoint is: X Y Z Rx Ry Rz ReferenceCoordinate A1 A2 A3 A4 A5 A6 A7 E1 E2 E3 E4 E5 E6. A1 to A7 are the preferred joint positions of the robot; X1 to X6 are the target positions of external axes. The additional data can be added if necessary.
Add “:” to seperate the waypoints. For example: 0.2 0 0.3 0 180 0 WORLD WORLD_ORIGIN : 0.2 0.1 0.3 0 180 0 WORLD WORLD_ORIGIN.
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 |
idleTime |
The amount of time floating has not been performed on the robot. It can be used as a transition condition to terminate this 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 |
---|---|---|
idleTime |
> |
10.0 |
FloatingJoint
Primitive Description and Usage
Description: This primitive enables users to move the robot by dragging its joints during project execution. Note: This primitive can only be used in human-robot collaboration scenarios. Using it directly in automation scenarios may result in unexpected robot motion or even injury.
Example Usage: Use this primitive in human-robot collaboration scenarios to manually move the robot to the desired position when robot motion is limited.
Primitive Input Parameters
Input Parameter |
Description |
Type |
Unit |
Default Value & Range |
---|---|---|---|---|
floatingJoint |
Joints that allow floating. 1 means floating is allowed; 0 means floating is not allowed. |
VEC_7d |
none |
1.0 1.0 1.0 1.0 1.0 1.0 1.0 ∈ [0.0 0.0 0.0 0.0 0.0 0.0 0.0 … 1.0 1.0 1.0 1.0 1.0 1.0 1.0] |
dampingLevel |
Damping level of the robot during floating. The lower the damping level, the easier it is for the robot to be dragged, but the less easy it is for the robot pose to be adjusted. |
VEC_7d |
none |
0 0 0 0 0 0 0 ∈ [0 0 0 0 0 0 0 … 100 100 100 100 100 100 100] |
responseTorque |
External floating joint torque that the robot will respond to. If the external joint torque is lower than this value, the robot will not be able to be dragged. |
VEC_7d |
Nm |
1.5 1.5 1.5 1.5 0.5 0.5 0.3 ∈ [0.0 0.0 0.0 0.0 0.0 0.0 0.0 … 3.0 3.0 3.0 3.0 3.0 3.0 3.0] |
diEnableFloating |
Digital input port that enables floating. The robot can only be dragged if this signal is ON. |
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 |
idleTime |
The amount of time floating has not been performed on the robot. It can be used as a transition condition to terminate this 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 |
---|---|---|
idleTime |
> |
10.0 |