Movements - Joint/Linear/Complex Paths

Joint movement

Define waypoint cartesian

If the waypoint is to be specified cartesian, the moveJoint() function is used.

Use

moveJoint(x, y, z, q0, q1, q2, q3, speed);

Parameters

8 parameters: x, y and z value (in metres) of the target point, the four quaternions q0, q1, q2 and q3 and the speed velocity between 0 and 1.

Optional 9th parameter for naming the movement.

Example

moveJoint(0.62100, 0.00000, 0.69726, 0.70711, 0.00000, 0.70711, 0.00000, 0.50000, "Cartesian waypoint");

Define waypoint via axis angle

If the waypoint is to be specified via the axis angles, the joints() function is used.

Use

joints(joint1, joint2, joint3, joint4, joint5, joint6, velocity);

Parameters

7 parameters: 6 joint values (in degrees) and the speed velocity between 0 and 1.

Optional 8th parameter for naming the movement.

Example

joints(-20.00, 0.00, 45.00, 78.25, 90.00, -130.5, 0.5, "Waypoint with axis angles");

2 Linear movement

Depending on the position of the robot, a linear path cannot be executed. This happens, for example, if the robot would collide with itself or the movement cannot be executed linearly due to the kinematics.

2.1 Defining a Cartesian waypoint

If the waypoint is to be specified Cartesian, the moveLinear() function is used.

Use

moveLinear(x, y, z, q0, q1, q2, q3, speed);

Parameters

8 parameters: x, y and z value (in metres) of the target point, the four quaternions q0, q1, q2 and q3 and the speed between 0 and 1.

Optional ninth parameter for naming the movement.

Example

moveLinear(0.62100, 0.00000, 0.69726, 0.70711, 0.00000, 0.70711, 0.00000, 0.50000, "Cartesian waypoint");

2.2 Defining a waypoint via axis angle

If the waypoint is to be specified via the axis angles, the jointsLinear() function is used.

Use

jointsLinear(joint1, joint2, joint3, joint4, joint5, joint6, speed);

Parameters

7 parameters: 6 joint values (in degrees) and the speed velocity between 0 and 1.

Optional 8th parameter for naming the movement.

Example

jointsLinear(-20.00, 0.00, 45.00, 78.25, 90.00, -130.5, 0.5, "Waypoint with axis angles");

3 Complex paths

horstFX version: from 2021.04 (only in textual programming)

Complex paths are paths that are neither a joint movement nor a linear movement. Three different types of complex paths can be used in horstFX. These are circle (circle), spline curve (spline) and polygon chain (polygonChain).

General

If the current robot position deviates from the start position of the path, a joint movement is automatically made to the start of the path. This can be prevented by:

"moveToStart" : false // optional, true by default

The speed of this joint movement can be specified as a relative speed in relation to the maximum speed:

"moveToStart.speed.ratio" : 0.5 // optional, default1.0

Delayed outputs and stop conditions can be specified as with the extended move command.

Specifying the speed

The control of the speed of the actual complex path is described below. The speed must be specified.

It can be specified as a relative speed:

"speed.ratio" : 0.35

Or as Cartesian speed/acceleration (at least one of the following specifications required):

"speed.vmax.xyz" : 0.02 (m/s)

"speed.accl.xyz" : 0.1 (m/s�)

"speed.vmax.orient" : 10 (�/s)

"speed.accl.orient" : 5 (�/s�)

Values not specified are automatically set to the maximum permitted in each case. If speed.vmax.xyz has been specified, the following can also be set using

"speed.vmax.xyz.ensure" : true // optional, default false

to ensure that the Cartesian speed is maintained during the entire movement. 

The speed controller is deactivated for such paths. The distance required for the acceleration and deceleration phase is displayed during execution. If the specified speed cannot be maintained, the programme is aborted.

CAUTION:

The movement is executed at the specified speed even if the speed controller was not at 100% beforehand. The speed controller is deactivated for such paths. At 10%, the robot moves just as fast as at 100%!

3.1 Circle

A circular movement can be defined in two ways.

3.1.1 Definition by centre point, start of path and vector in circular plane

  • Specified by the centre of the circle (centre), start of the path (p1) and vector in the plane of the circle (p2):
    circle({

        "speed.ratio" : 0.5,

        "center" : {"xyz" : [ 0.4049, -0.0096, 0.3413]},

        "p1" : {"xyz+quat" : [ 0.4049, 0.0395, 0.3413, -0.00008, 0.00000, 0.98613, -0.16600]},

        "p2" : {"xyz" : [ 0.4360, 0.0395, 0.3413]},

       "angle" : 120, // in degrees, mandatory

       "fixedOrientation" : true // optional, default true

    })
  • The circular movement always starts at the position and with the orientation specified by p1.
  • The circular plane is defined by the two vectors p1-centre and p2-centre. This means that p2 lies in the circular plane, but not necessarily on the circular path.
  • Any existing orientation in the definitions of centre and p2 is ignored. This means that the following specifications are equivalent:
  • "center" : {"xyz" : [ 0.4049, -0.0096, 0.3413]}

    "center" : {"xyz+euler" : [ 0.4049, -0.0096, 0.3413, 180, 0, 180]}

    "center" : {"xyz+quat" : [ 0.4049, -0.0096, 0.3413, 0, 1, 0, 1]}
  • The angle must be specified. If the angle is negative, the movement is in the opposite direction.
  • With
    "fixedOrientation" : false

    the initial orientation is rotated.

3.1.2 Definition by three points on an arc

Specification by three points p1, p2, and p3 on the circular arc:

circle({

    "speed.ratio" : 0.5,

    "p1" : {"xyz+quat" : [ 0.3471, 0.0000, 0.6932, 0.70711, 0.00000, 0.70711, 0.00000]},

    "p2" : {"xyz" : [ 0.3471, 0.0668, 0.6515]},

    "p3" : {"xyz" : [ 0.3471, 0.0225, 0.5967]},

   "angle" : 120, // in degrees, optional

   "fixedOrientation" : true // optional, true by default

})
  • The circular movement always starts at the position and with the orientation specified by p1.
  • Any existing orientation in the definitions of p2 and p3 is ignored.
  • If no angle angle is specified, the circular movement passes through p2 and ends at p3. If a negative angle is specified, the movement starts at p1 in the direction of p3 (opposite direction).
  • With
    "fixedOrientation" : false

    the initial orientation is rotated.

3.2 Polygon chain

A polygon chain is a sequence of lines through specified corner points. 

polygonChain({

    "speed.ratio" : 0.5,

   "blendradius.xyz" : 0.01, // in meters, optional

    "vertices" : [

        {"xyz+quat": [ 0.350, -0.080,  0.380,  0.70711,  0.00000,  0.70711,  0.00000]},

        {"xyz+quat": [ 0.350, -0.080,  0.390,  0.70711,  0.00000,  0.70711,  0.00000]},

        {"xyz+quat": [ 0.350, -0.090,  0.390,  0.70711,  0.00000,  0.70711,  0.00000]},

        {"xyz+quat": [ 0.350, -0.085,  0.395,  0.70711,  0.00000,  0.70711,  0.00000], "blendradius.xyz" : 0.05},

        {"xyz+quat": [ 0.350, -0.080,  0.390,  0.70711,  0.00000,  0.70711,  0.00000]},

        {"xyz+quat": [ 0.350, -0.090,  0.380,  0.70711,  0.00000,  0.70711,  0.00000]},

        {"xyz+quat": [ 0.350, -0.080,  0.380,  0.70711,  0.00000,  0.70711,  0.00000]},

        {"xyz+quat": [ 0.350, -0.090,  0.390,  0.70711,  0.00000,  0.70711,  0.00000]},

        {"xyz+quat": [ 0.350, -0.090,  0.380,  0.70711,  0.00000,  0.70711,  0.00000]},

    ]

})
  • An overshoot radius valid for all corner points can be specified with blendradius.xyz in the main block.

  • The corner points can be specified as xyz+euler, xyz+quat, joints or any mixture of these (see also spline curve).

  • Each corner point (except for the first and last) can be given a separate overshoot radius.
    4 Extended move command


4 Extended move command

The extended move command offers a wide range of settings and can be parameterised to a large extent.

The target position can be transferred in axis angles or as TCP coordinates with an absolute or relative target orientation. The following list is sorted according to the priority of the parameters. For example, when transferring a Cartesian and an axis angle target position, the axis angles are ignored.

The individual parameters of the function are described below.

4.1. Function

The function requires an arbitrary list of parameters and values.

move( {parameter : value, ...}, waypoint name);

4.2. Mandatory parameters

The parameters described here are mandatory parameters. Without these parameters, the move call is invalid and the robot reports an error.

4.2.1 Movement type

'movetype': VALUE,

Depending on whether the robot is to move to the waypoint in a joint or linear motion, either 'JOINT' or 'LINEAR' must be entered as the value.

4.2.2 Target specification

'poserelation': VALUE,

This defines whether the target position is absolute or relative.

If the target position is absolute, the robot moves to the specified values. For this, 'ABSOLUTE' must be entered as the value.

If the target position is to be relative, i.e. relative to the current position of the robot at that time, the value 'RELATIVE' must be entered.

4.2.3 Coordinate system

'coord': VALUE,

The coordinate system in which the target point is specified is defined here.

For positions in Cartesian coordinates, either 'cartesian_base' or 'cartesian_tcp' is entered for the value, depending on whether the base or TCP coordinate system is to be used.

If the position is defined in axis angles, the value must be set to 'joint'.

4.2.4 Target position

The target position can generally be specified in two variants. Either Cartesian or in axis angles.

If the target position is specified in Cartesian, the position must be specified as in target position (Cartesian). The target orientation must also be specified. Only one of the three target orientation types may be specified here (Euler angle, rotation axis, quaternions).

If the target position is specified in axis angles, none of the target positions described above may be specified.

4.2.4.1. Target position (kartesisch)

'targetpose.x': X-VALUE,

'targetpose.y': Y-VALUE,

'targetpose.z': Z-VALUE,

For the target position, the corresponding values must be specified in metres.

4.2.4.2. Target position (Euler-Winkel)

'targetpose.rx': X-WERT,

'targetpose.ry': Y-WERT,

'targetpose.rz': Z-WERT,
For the target orientation in Euler angles, the corresponding orientation must be specified in degrees.

4.2.4.3. Target orientation (around rotation axes)

'targetpose.rotationaxis.rx': X-VALUE,

'targetpose.rotationaxis.ry': Y-VALUE,

'targetpose.rotationaxis.rz': Z-VALUE,

'targetpose.rotationaxis.angle': ANGLE,

For the target pose around a rotation axis, the corresponding rotation axis must be specified in the respective part and the rotation angle in degrees.

4.2.4.4. Target orientation (quaternions)

'targetpose.q0': Q0-VALUE,

'targetpose.q1': Q1-VALUE,

'targetpose.q2': Q2-VALUE,

'targetpose.q2': Q3-VALUE,

The corresponding orientation must be specified for the target orientation in quaternions.

4.2.4.5. Target position (axis angle)

'targetjoints.j1': J1-VALUE,

'targetjoints.j2': J2-VALUE,

'targetjoints.j3': J3-VALUE,

'targetjoints.j4': J4-VALUE,

'targetjoints.j5': J5-VALUE,

'targetjoints.j6': J6-VALUE,

For target alignment with axis angles, the corresponding axis values must be specified in degrees.

4.2.5. Speed

F�r einen move-Befehl muss und darf nur eine der folgenden Arten f�r die Geschwindigkeitsangabe genutzt werden.

4.2.5.1 Speed (Factor)

'speep.ratio': VALUE,

The speed of the path is specified here as a percentage (from 0 to 1, corresponds to 0-100%)

4.2.5.2. Acceleration / Speed (TCP)

Attention!
If the speed is defined in this way, the slider has no effect on the speed. The robot moves just as fast at 10% as it does at 100%.

These parameters can only be used for linear movements.

'speed.accl.xyz': VALUE,

'speed.vmax.xyz': VALUE,

'speed.accl.orient': VALUE,

'speed.vmax.orient': VALUE,
The values transferred must each be double values.
  • speed.accl.xyz : Acceleration in XYZ direction
  • speed.vmax.xyz : Maximum speed in XYZ direction
  • speed.accl.orient : Rotational acceleration
  • speed.vmax.orient : Maximum rotation speed

4.2.5.3 Acceleration / speed (axes)

Attention!
If the speed is defined in this way, the slider has no effect on the speed. With 10% the robot moves just as fast as with 100%.

'speed.accl.j1': VALUE,

'speed.accl.j2': VALUE,

'speed.accl.j3': VALUE,

'speed.accl.j4': VALUE,

'speed.accl.j5': VALUE,

'speed.accl.j6': VALUE,

'speed.vmax.j1': VALUE,

'speed.vmax.j2': VALUE,

'speed.vmax.j3': VALUE,

'speed.vmax.j4': VALUE,

'speed.vmax.j5': VALUE,

'speed.vmax.j6': VALUE,

The transferred values must each be double values.

  • speed.accl.j1: Acceleration joint 1 in degrees/s�
  • speed.accl.j2: Acceleration of joint 2 in degrees/s�
  • speed.accl.j3: Acceleration of joint 3 in degrees/s�
  • speed.accl.j4: Acceleration of joint 4 in degrees/s�
  • speed.accl.j5: Acceleration of joint 5 in degrees/s�
  • speed.accl.j6: Acceleration of joint 6 in degrees/s�
  • speed.vmax.j1: Speed of joint 1 in degrees/s
  • speed.vmax.j2: Speed of joint 2 in degrees/s
  • speed.vmax.j3: Speed of joint 3 in degrees/s
  • speed.vmax.j4: Speed of joint 4 in degrees/s
  • speed.vmax.j5: Speed of joint 5 in degrees/s
  • speed.vmax.j6: Speed of joint 6 in degrees/s

4.3 Optional, additional parameters

The following parameters are all optional and are only required for additional functionalities during a path.

4.3.1. Loop over

When looping over, a waypoint is not approached directly. Instead, an arc is travelled past the waypoint.

4.3.1.1.  Traversing (axis angle)

'blendradius.j1': VALUE,

'blendradius.j2': VALUE,

'blendradius.j3': VALUE,

'blendradius.j4': VALUE,

'blendradius.j5': VALUE,

'blendradius.j6': VALUE,

The maximum axis angle tolerance in degrees must be defined for each axis.

4.3.1.2 Overshoot (TCP)

'blendradius.xyz': VALUE,

'blendradius.orient': VALUE,

The first argument specifies the blending radius in metres.

The second argument specifies the permissible orientation radius in degrees.

4.3.2 Delayed outputs

Delayed outputs are switched while the robot is moving. Any number of parameters can be passed here.

The argument of the delayedOutput parameter contains several parameters, all of which must be specified.

'delayedOutput':[

        {

         'on': VALUE,

         'output': VALUE,

         'time': VALUE,

         'type': VALUE,

        },

]

on : The output is switched to this value (True or False, for On or Off)

output : Name of the output as a string

type : "PATH" or "TIME"

time :

if type "PATH": decimal number from 0 to 1 (1 = 100%)

if type "TIME": Value in milliseconds

4.3.2.1 Example

"delayedOutput":[

        {

          "on": True,

          "output": "OUTPUT_1",

          "time": 0.5,

          "type": "PATH",

        },

]

4.3.3 Stop condition

Stop conditions are added to the move command if the corresponding path is to be paused or cancelled. If the path is paused, the robot brakes and remains stationary for as long as the condition is valid. If the path is interrupted, the robot moves directly to the next waypoint in the programme sequence.

The argument of the interrupt parameter contains several parameters, all of which must be specified.

'interrupt':[

        {

           'name': VALUE,

           'operator': VALUE,

           'type': VALUE,

           'value': VALUE

        },

]

name : This specifies the value to be checked to determine whether the programme should be aborted. Either INPUT_x, TOOL_INPUT_x, BOOL_REGISTER_x, INT_REGISTER_x, FLOAT_REGISTER_x, InOutBits_x, InBits_x, InOutRegister_x, InRegister_x.

operator : Gibt an, mit welchem Operator verglichen wird (>, <, >=, <=, ==, !=).

type : "PAUSE" or "CANCEL" to pause the programme or cancel the waypoint.

value : The value that must be reached for the stop condition to take effect.

4.3.3.1 Example

'interrupt':[

        {

            'name': 'INPUT_1',

            'operator': '==',

            'type': 'PAUSE',

            'value': 1.0

        },

        {

            'name': 'FLOAT_REGISTER_3',

            'operator': '>',

            'type': 'CANCEL',

            'value': 5.0

        }

]

4.4 Examples

Various examples are shown below.

4.4.1. Example 1 Linear path with delayed outputs and cancellation conditions

move({

        'movetype': 'LINEAR',

        'poserelation': 'ABSOLUTE',

        'coord' : 'cartesian_basis',

        'speed.ratio': 0.75,

        'targetpose.x': -0.255,

        'targetpose.y': 0.60422 ,

        'targetpose.z': 0.27460,

        'targetpose.rx': -180,

        'targetpose.ry': 0,

        'targetpose.rz': 180,

        'delayedOutput':[

        {

          'on': True,

          'output': 'OUTPUT_1',

          'time': 0.5,

          'type': 'PATH',

        },

        {

          'on': True,

          'output': 'OUTPUT_2',

          'time': 500,

          'type': 'TIME',

        },

        ],

        'interrupt':[

        {

            'name': 'INPUT_1',

            'operator': '==',

            'type': 'PAUSE',

            'value': 1.0

        },

        {

            'name': 'FLOAT_REGISTER_3',

            'operator': '>',

            'type': 'CANCEL',

            'value': 5.0

        },

        ],

    }, "Wegpunkt 1");

The command moves the robot linearly to the coordinates X: -0.255, Y: 0.60422, Z: 0.27460, with the orientation RX: -180, RY: 0, RZ: 180.

After 50% of the path time, the OUTPUT_1 output is switched. In addition, the OUTPUT_2 output is switched after 500ms.

If INPUT_1 reaches the value 1 while the robot is travelling to this waypoint, the robot pauses as long as the value remains at 1. If a value greater than 5.0 is entered in FLOAT_REGISTER_3, the robot cancels this path and moves to the next waypoint.