4/5-Axis Single or Dual Yaw (PRsRR) Coupled Axis Module

This module controls a 4 or 5-Axis Single or Dual Yaw (PRsRR) mechanism that is similar to a PRRR device except that it has an extra axis and link that are electronically coupled to the first rotary axis. The coupled axis converts the motion of the shoulder rotation to a linear translation. This module consists of a vertical linear axis that moves the robot's carriage up and down in the World Z direction. This is followed by a shoulder axis (q2) that rotates the inner most link about the World Z-axis. This rotary axis is electronically coupled (by the controller) to a second rotary Z-axis (q2') that drives a link that is the same dimensions as the inner link. A third rotary Z-axis (q3, the elbow) is connected to the output of the coupled link and drives the outer link, which in turn is connected to one or two wrist joints (q4,q5) that also rotate about Z.  The rotary axes position and orient the robot's end-effector(s) in the X-Y plane and produce a Yaw motion. 

When properly configured, the electronically coupled rotary axis (q2') is automatically driven by the controller such that its joint angle will be equal to -2 times the joint angle of the shoulder axis (q2). This results in the semi-circular output motion of the shoulder axis being converted into a linear motion. In the drawing below, the center of rotation of the elbow axis (q3) can be seen to linearly move along the World Y-axis for different positions of the shoulder axis (q2).

If we look at the working space of this robot in a XY plane, this electronic coupling changes the extreme reach of this robot from a circle or semi-circle to a more narrow but longer rectangular range of travel with semi-circular ends. This is advantageous in some applications, such as Semi-conductor front-end handlers, where robots need to service several devices that are aligned in a long row.

From an application programming point of view, the coupled axis (q2') is invisible and only the shoulder axis (q2) is controlled. From a configuration point of view, the coupled axis must be tuned and setup using the system's "Split-Axis Control" capability. The split-axis control permits the system to keep the coupled axis in alignment with the shoulder joint.

In GPL 4.3 and later, the vertical axis can be optionally driven by a two-stage telescoping pair of actuators, S1 and S1', that are electronically coupled to automatically and synchronously move together. From an application programming point of view, these telescoping stages operate as a single logical Z-axis. From a configuration point of view, these coupled actuators must be tuned and setup using the system's "Split-Axis Control" capability. The split-axis control permits the system to keep these coupled axis in alignment.

Several characteristics of the Split-Axis control, which is employed for both the telescoping Z-axis and the coupled q2, must be kept in mind:

- By convention, the coupled motor for the first Split-axis pair will be the 5th motor for a single Yaw system and the 6th motor for a dual Yaw system. If two Split-axis pairs exist, the coupled motor for the second Split-axis pair will be the 6th motor for a single Yaw system and the 7th motor for a dual Yaw system. So, if the telescoping Z-axis option is enabled for a dual Yaw robot, the coupled motor for the Z-axis will be the 6th motor and the coupled motor for q2' will be the 7th motor.
- It is highly recommended that absolute encoders be used for all coupled motors since this greatly simplifies homing and commutation reference finding.
- When the robot is homed and during each subsequent time that motor power is enabled, the system will automatically move coupled axes slowly into alignment. The motor speed during the alignment process is controlled by the "Homing speed 1" (DataID 2804).
- For this kinematic module, the "Joint to motor scale factors" (DataID 2300) for the coupled q2' motor must be set to -2.
- If the optional telescoping Z-axis is configured, the "Joint to motor scale factors" (DataID 2300) for the coupled S1' motor is typically set to 1 to indicate that the travel and scale factor for both stages are identical. If the travel and scale factors for the two stages are different, the "Joint to motor scale factor" for S1' should be adjusted appropriately. The "Joint to motor scale factor" for the S1 motor should be set to represent the full motion generated by the combination of the two coupled axes. That is, if each of the two motors moves the axis 1 mm for every 1000 encoder counts, the scale factor for S1 should be set to 2000.
- Manual control "Free" mode is not permitted for any split axes since Split-axis control does not operate in Free mode and split axes re-alignment is not performed when Free mode is terminated.

Kinematics Module Number and Required Software License

Module number to be entered into the "Robot type" (DataID 116):  21

Required software kinematic license (entered using the web interface panel Utilities > Controller Options if not already installed):   Advanced Kinematics.

Kinematic Model

Axis Optional Max Range Description

1: S1

No

Unlimited

Linear axis that moves the robot in the direction of the World Z-axis. A positive change in the axis position results in a movement in the direction of the positive World Z-axis (up).

2: q2

No

Limited to +/- 90 °

Rotary axis that rotates the inner link of the robot about the World Z-axis.  A positive change in the axis angle results in a positive rotation about the World Z-axis.

3: q3

No

Several rotations but typically set to +/- 179.9°

Rotary axis that rotates the outer link about the World Z-axis.  A positive change in the axis angle results in a positive rotation about the World Z-axis.  The center of this axis' travel can be arbitrarily set, although it is typically centered about 0, 180 or -180 degrees.

4: q4

No

Several rotations but typically set to +/- 359.9°

Rotary axis that rotates the end-effector about World Z-axis. A positive change in the axis angle results in a positive rotation about the World Z-axis. The center of this axis' travel can be arbitrarily set, although it is typically centered about 0, 180 or -180 degrees.

5: q5

Yes

Several rotations but typically set to +/- 359.9°

(Upper Yaw) Rotary axis that rotates the optional second end-effector about World Z-axis. A positive change in the axis angle results in a positive rotation about the World Z-axis. The center of this axis' travel can be arbitrarily set, although it is typically centered about 0, 180 or -180 degrees.

Parameter Database Values

The following table describes the Parameter Database values that are utilized to configure the kinematic module. Standard motion control parameters such as servo tuning values, limit stops, the homing specification, etc are not included in the table.

Parameter Database ID Parameter Name Description

2000

Number of axes

Must be set to one of the following values:

4: Single Yaw robot.
5: Dual Yaw robot.

2001

Split-axis mask

Must be set to 2 to enable split axis control for the shoulder joint. If the optional telescoping Z-axis is configured, this value must be set to 3.

2003

Axis mask

Defines the axes that are configured.  Must be set to one of the following values:

15 (&H0f):  Single Yaw robot.
31 (&H1f):  Dual Yaw robot.

2005

Motor linearity compensation

Not supported.

2006

Robot type special option flags

Bit mask that enables special features of the kinematic module.   These bits are interpreted as follows:

&H02: If set, 2x2 coupling matrix between joints 4 and 5.  If not set, none of the axes are coupled by a coupling matrix.

NOTE: The 2x2 coupling matrix should not be enabled for single yaw systems since this will cause an error with the Split-axis control.

2300

Joint to motor scale factors

The scale factor for the coupled q2' split-axis must be set to -2. For example, for a dual yaw robot with no telescoping Z and no coupling matrix, the 6th scale factor should be -2. For the coupled axis of the telescoping Z, the scale factor is typically set to 1 to indicate that the range of travel and scale factor for both coupled Z-axes are identical. For a dual yaw robot with a telescoping Z-axis and no coupling matrix, the 6th scale factor is for S1' and the 7th scale factor is for q2'. For a telescoping Z, the scale factor for the uncoupled axis should represent the combined mm/encoder scale factor for both telescoping stages.

2701 / 2703

100% Cartesian speeds and accels

Value 1:  Cartesian 100% linear speed and acceleration of the robot's end-effector measured along any vector in X, Y and Z.

Value 2:  Cartesian 100% rotation speed and acceleration of the end-effector about the world Z-axis.

Value 3:  100% rotation speed and acceleration of the 5th logical axis when the primary yaw is being moved along a Cartesian straight-line path.  This is normally set equal to the joint speed and acceleration of the fifth axis.

Values 4-n:  Not used.

2823

Free mode inhibited axes mask

Specifies axes that cannot be enabled in manual control "Free" mode. For this module, the split axes cannot be set into Free mode. Therefore, at least the second bit of this parameter must be set, e.g. a value of 2 must be set, along with whatever other axes are to be inhibited from entering free mode. If the telescoping Z-axis option is enabled, at a minimum, a value of 3 must be set to inhibit the first two axes.

16050

Kinematic dimensional constants

Value 1 (S0):  Vertical (Z) offset of the lower Yaw axis relative to the origin of the World coordinate system when joint 1 (S1) is at its zero position.  Can be arbitrary set by the robot designer to establish the height of the World coordinate system.

Value 2 (a2): Length of the inner link measured from the axis of q2 to that of q2'. The length of the coupled link (axis of q2' to axis q3) must be the same.

Value 3 (a3): Length of the outer link measured from the axis of q3 to that of q4.

Value 4 (S5):  Vertical (Z) offset of the upper Yaw axis relative to the Z height of the lower Yaw axis.  This height is automatically considered in the kinematic solution when the upper Yaw axis is selected as part of the Cartesian solution for the robot.

Values 5-n: Not used.

16051

Tool set at restart

When the controller is restarted, this specifies the initial value for the position and orientation of the robot's tool center point relative to the wrist joint, q4 or q5. For most simple tools, only the length of the tool needs to be defined by setting this parameter to:  (0, 0, tool_length, 0, 0, 0) or (tool_length, 0, 0, 0, 0, 0) for "World Relative" configurations.

16052

Base set at restart

When the controller is restarted, this defines how the base of the robot is positioned and oriented relative to the World coordinate system.  Normally, this parameter is set to 0, 0, 0, 0, 0, 0.

Robot Configuration ("Config") Parameters

This kinematic module makes use of the following Location Config property flags to control how Cartesian positions and orientations are converted to joint angles since multiple sets of joint angles are possible: 

GPL_Righty, GPL_Lefty, GPL_Single.

Special Compensation

This kinematic module does not support "Continuous Turn Axes" capability for any axes.

This kinematic module does support "Motor Coupling", please see above.

This kinematic module does not support "Linearity Compensation".

This kinematic module does support "Split-Axis Control", please see above.

This kinematic module does not support "Dynamic Feedforward" compensation (DFF).

Additional Considerations

The first element of the Robot.Custom property defines which of the two yaw axes is factored into the Cartesian control of the robot (i.e. is the primary yaw axis).  Specifically,

Robot.Custom(1) = 0     ' Selects the lower yaw (q4) as primary
Robot.Custom(1) = 1 ' Selects the upper yaw (q5) as primary

Whenever you modify the Robot.Custom property, execution of the thread will automatically pause until the robot has come to a stop and the change can be put into effect.

To move the secondary yaw during the next motion of the primary axes to a Cartesian Location, execute the Move.Extra method.  If this method is not invoked and the next motion is to a Cartesian Location, the position of the secondary yaw will not be altered.  The following illustrates the use of Move.Extra.

Move.Extra(30)   ' Move secondary axis to 30 deg during next motion
Move.Loc(Location.XYZValue(300,0,100),pf1) ' Move primary arms tool

The yaw axes can also be simultaneously moved by performing a motion to an Angles Location.  The value of the location will explicitly define the final position for all axes.

In GPL 4.3 and later, as another means of controlling the secondary yaw axis, the position of this axis can automatically be set to the same position as the primary axis (plus a fixed angular offset) when the destination of a joint interpolated motion or each setpoint of a Cartesian motion is computed. This mode is very useful for moving both grippers along a straight line path to simultaneously pick or place two parts.

The following illustrates how to enable and disable this mode:

Robot.Custom(2) = 1        ' Enable synchronization of yaw axes
Robot.Custom(3) = offset ' Specifies offset angle added to primary yaw
:
Robot.Custom(2) = 0 ' Disable synchronization of yaw axes

This mode requires that the two yaw axes be in alignment at the start of any Cartesian motion.  After this mode has been enabled, it is the responsibility of the application program to execute a joint interpolated motion to a Cartesian Location to force the two yaw axes into alignment before a Cartesian motion is executed.  If the yaw axes are not in alignment at the start of a Cartesian motion or during World or Tool manual control, the following error will be generated:

-1056  Incompatible robot position

Whenever you modify the Robot.Custom property to set the parameters for this mode, execution of the thread will automatically pause until the robot has come to a stop and the change can be put into effect.