MC_MoveLinearAbsolute
FUNCTION_BLOCK MC_MoveLinearAbsolute
This function block commands a linear interpolated movement from the current robot position to the specified absolute position in the specified coordinate system.
The speed of the robot is calculated with both
- Parameters related to axes of the robot (Velocity / Acceleration / Deceleration)
- Parameter related to the Tool Center Point (CartesianVel / RotationalVel)
The final robot speed is set by the most limiting of these parameters.When the speed of the object, carried by the robot, does not need to be handled with special care, parameters related to Tool Center Point can be ignored (kept to default values). The speed along the trajectory may changed depending on the robot position in the space.
On the contrary, if a constant speed is required for the Tool Center Point, it shall be set with CartesianVel parameter.
Example: The speed of the object carried by the robot shall be 100mm/s.
Set the CartesianVel parameter to 100.However, axes related speed/acceleration parameters are still active.If you set the Velocity parameter too low (e.g 10%), the objet may not reach 100mm/s.
Syntax
Definition:
FUNCTION_BLOCK MC_MoveLinearAbsolute
VAR_INPUT
Execute : BOOL := FALSE;
Position : T_CartesianPos;
Velocity : REAL := REAL#100;
Acceleration : REAL := REAL#100;
Deceleration : REAL := REAL#100;
CartesianVel : REAL := REAL#99999;
RotationalVel : REAL := REAL#99999;
CoordSystem : UINT := 0;
ToolNumber : UINT := 0;
BufferMode : eMC_BUFFER_MODE := Buffered;
TransitionMode : UINT := 0;
TransitionParam : MC_TransitionParameter;
END_VAR
VAR_OUTPUT
Busy : BOOL := FALSE;
Done : BOOL := FALSE;
Active : BOOL := FALSE;
CommandTransferred : BOOL := FALSE;
CommandAborted : BOOL := FALSE;
Error : BOOL := FALSE;
ErrorID : UDINT := 0;
MovementID : INT := -1;
END_VAR
VAR_IN_OUT
AxesGroup : T_StaeubliRobot;
END_VAR
Inputs
Name |
Type |
Description |
---|---|---|
Execute |
BOOL |
Rising edge triggers function execution |
Position |
Absolute end positions for each dimension in the specified coordinate system. | |
Velocity |
REAL |
Joint velocity. Percentage of the nominal speed of the robot. Range [0.01 .. 500] |
Acceleration |
REAL |
Joint acceleration. Percentage of the nominal acceleration of the robot. Range [0.01 .. 500] |
Deceleration |
REAL |
Joint deceleration. Percentage of the nominal deceleration of the robot. Range [0.01 .. 500] |
CartesianVel |
REAL |
Optional: Maximum cartesian velocity at Tool Center Point in mm/s |
RotationalVel |
REAL |
Optional: Maximum rotational velocity at Tool Center Point in degree/s |
CoordSystem |
UINT |
Number of the coordinate system (located in a database on robot side) in which the Position input parameter is applicated |
ToolNumber |
UINT |
Index of the Tool in the bank that shall be used for the movement. |
BufferMode |
0 = aborting / 1= buffered / 6-7 = blending | |
TransitionMode |
UINT |
Defines the profile of the robot trajectory nearby the set points. 0 = None / 3 = Corner distance / 10 = blending distances |
TransitionParam |
Outputs
Name |
Type |
Description |
---|---|---|
Busy |
BOOL |
Set when function block is executing. Reset when Done or Error is set |
Done |
BOOL |
This output is set when function block has terminated with success |
Active |
BOOL |
Set when commanded movement is currently executed by the robot |
CommandTransferred |
BOOL |
Commanded motion is successfully buffered inside robot controler |
CommandAborted |
BOOL |
Command is aborted by another command |
Error |
BOOL |
This output is set when function block has terminated with error |
ErrorID |
UDINT |
Error code |
MovementID |
INT |
Identifier for this commanded movement |