Motion Plus - UR Script

Overview

This document collects all of the URScript functions that are provided by the MotionPlus project. The MotionPlus URScript functions rely on the World Model and are used to drive the external axis servos through MotionPlus EtherCAT URCap.

Please refer to these additional documents:

Note

In the function declarations below, you will find “xxx={}” in the parameter list which indicates this is a named parameter without a default value. Example:

    movep_with_axis_group(goal, a=1.2, v=0.25, r=0, name={}, axis_target={})

If it is an optional parameter, and if you don’t want to set a value, just omit it.

If it isn’t an optional parameter, or if you want to set a value, then you have to follow one of the following ways:

  • Set value by position, then all parameters before this one must also be set, even if they have default values. For instance, movep_with_axis_group(p[1,0,0,0,0,0], 1.2, 0.25, 0, "group1", [0.1]).

  • Set value by name, then name of the parameter must be typed. For instance, movep_with_axis_group(p[1,0,0,0,0,0], name="group1", axis_target=[0.1]).

  • EtherCAT drives are the only type of external axes supported.

  • If an external axis is referred to, usually by its name, in a function, and if the function would use the axis’s pose or would move the axis, an exception will be thrown, unless:

    • the axis’s EtherCAT drive has been configured with ethercat_config_axis();

    • and the EtherCAT Master has been started with ethercat_start().


Axis Group - URScript Functions

axis_group_add

axis_group_add(name, pose, ref_frame="base")

Adds a new axis group with the given name to the world model. It is placed at the given pose in the reference coordinate frame defined by ref_frame.

  • An axis group can only be attached to the world coordinate frame.

  • Each axis group has a coordinate frame attached to its base, which can be used as an argument to other world model functions by referring the name of the group.

  • At most 6 axis groups can be added to the world model.

Parameters

name: (string) Name of the axis group to add.
name cannot be an empty string.
Names used by world model objects (e.g., frame, axis group, axis, etc.) must be unique.

pose: (pose) Pose of the axis group’s base, in the reference coordinate frame.

ref_frame (optional): (string) Name of the reference coordinate frame that pose is defined in. This can be any world model entity with a coordinate system (e.g., frame, axis group, axis, etc.). The default value "base" refers to the robot’s base frame.

Return: n/a

Example

axis_group_add("AxisGroup1", p[0,0,1,0,0,0]) # adds an axis group named "AxisGroup1", placed at one meter in the z-positive direction of the robot's base frame

axis_group_delete

axis_group_delete(name)

Deletes the axis group with the given name from the world model.

  • All attached axes are also deleted.

  • This function will fail, if this axis group is under control by another URScript program.

  • This function will fail, if any attached axis is live and enabled.

Parameters

name: (string) Name of the axis group to delete.
Axis group with such name must exist.

Return: n/a

Example

axis_group_add("AxisGroup1", p[0,0,1,0,0,0]) # adds an axis group named "AxisGroup1"

axis_group_delete("AxisGroup1") # deletes the axis group named "AxisGroup1"

axis_group_add_axis

axis_group_add_axis(
    group_name, name, parent, pose, type, 
    v_limit, a_limit, q_limits=[-1e300, 1e300], 
    axis_index={}
    )

Adds an external axis with the given name to the axis group named group_name. The axis is attached at the given pose in the reference coordinate frame defined by parent. The type, max velocity, max acceleration, position limits, and index of this axis are defined by type, v_limit, a_limit, q_limits, and axis_index, respectively.

  • This function will fail, if this axis group is under control another URScript program.

  • This function will fail, if the kinematic chain created by the attachment forms a closed chain.

Note

As of Polyscope 5.16, only type 0 (revolute) is supported. As of Polyscope 5.16, only a single axis can be configured at a time.

Parameters

group_name: (string) Name of the axis group this new axis is added to. The axis group would have been created using axis_group_add().
Axis group with such name must exist.

name: (string) Name of the new axis.
name cannot be an empty string.
Names used by world model objects (e.g., frame, axis group, axis, etc.) must be unique.

parent: (string) Name of the parent axis. If it’s empty or the same as group_name, the new axis will be attached to the base of the axis group.
Axis with such name must exist in the axis group.

pose: (pose) Pose, in the parent coordinate frame, this axis will be placed and attached to. If type is 0 (revolute), then the z axis of the frame corresponds to the axis of rotation. If type is 1 (prismatic), then the z axis is the axis of translation.

type: (integer) Type of the axis: 0 (revolute) or 1 (prismatic).
type can only be 0 or 1.

v_limit: (float) Maximum axis velocity in rad/s (revolute) or m/s (prismatic).
v_limit must be positive.

a_limit: (float) Maximum axis acceleration in rad/s^2 (revolute) or m/s^2 (prismatic).
a_limit must be positive.

q_limits (optional): (float[]) Lower and upper limits of the axis position in rad (revolute) or m (prismatic). If left unassigned, then practically infinite limits are applied (e.g., a continuously rotating actuator).
The size of the q_limits must be 2.
The lower limit must be less than the upper limit.

axis_index (optional): (integer) Index of this axis in the RTDE target positions array and actual positions array, where this axis’ target and actual data will be stored. If left unassigned, the index will default to the lowest available index. For example, the first call to axis_group_add_axis() will assign index 0, the next call will assign index 1, and so on.
axis_index must be in range of [0, 5].
This function will fail, if axis_index is already occupied by an existing axis.

Return: n/a

Examples

axis_group_add("AxisGroup1", p[x,x,x,x,x,x]) # adds "AxisGroup1"

axis_group_add_axis("AxisGroup1", axis_name="Axis1", parent_name="", pose=p[x,x,x,x,x,x], type=0, v_limit=1, a_limit=1, q_limits=[-1,1], axis_index=3) # adds "Axis1" at index 3, attached to the base of "AxisGroup1"

axis_group_add_axis("AxisGroup1", axis_name="Axis2", parent_name="Axis1", pose=p[x,x,x,x,x,x], type=0, v_limit=1, a_limit=1, q_limits=[-1,1]) # adds "Axis2" at index 0, attached to "Axis1"

Here’s a diagram of what the configuration would look like:

img

axis_group_update_axis

axis_group_update_axis(
    name, pose={}, type={}, 
    v_limit={}, a_limit={}, 
    q_limits={}, axis_index={}
    )

Updates the corresponding properties of axis with name.

  • This function will fail, if the axis group the axis attached to is under control by another URScript program.

  • This function will fail, if any attached axis of the axis group is live and enabled.

Important

As of Polyscope 5.16, only type 0 (revolute) is supported.

Parameters

name: (string) Name of the axis to update.
Axis with such name must exist.

pose (optional): (pose) New pose, in the coordinate frame of the parent axis (or axis group), of the axis.

type (optional): (integer) New type of the axis.
type can only be 0 or 1.

v_limit (optional): (float) New velocity limit, in rad/s (revolute) or m/s (prismatic), of the axis.
v_limit must be positive.

a_limit (optional): (float) New acceleration limit, in rad/s^2 (revolute) or m/s^2 (prismatic), of the axis.
a_limit must be positive.

q_limits (optional): (float[]) New position limits, in rad (revolute) or m (prismatic), of the axis.

The size of the q_limits can only be 0 or 2. The limits are set to practically infinite, if the size is 0. The lower limit must be less than the upper limit.

axis_index (optional): (integer) New index of this axis in the RTDE target positions array and actual positions array.

axis_index must be in range of [0, 5].
This function will fail, if axis_index is already occupied by an existing axis.

Return: n/a

Example

axis_group_add("AxisGroup1", p[x,x,x,x,x,x]) # adds "AxisGroup1"
axis_group_add_axis("AxisGroup1", "Axis1", "", p[x,x,x,x,x,x], 0, 1, 1, q_limits=[-1,1]) # adds "Axis1" with position limits [-1, 1]

axis_group_update_axis("Axis1", q_limits=[-1,2]) # updates position limits of "Axis1" to [-1, 2]

axis_group_get_axis_index

axis_group_get_axis_index(axis_name)

Returns the index of the axis with given axis_name in the RTDE target positions and actual positions arrays.

Parameters

axis_name: (string) Name of the axis in query.
Axis with such name must exist.

Return:

integer: Index of the axis in the RTDE target positions and actual positions arrays.

Example

axis_group_add("AxisGroup1", p[x,x,x,x,x,x]) # adds "AxisGroup1"
axis_group_add_axis("AxisGroup1", "Axis1", "", p[x,x,x,x,x,x], 0, 1, 1, q_limits=[-1,1], axis_index=3) # adds "Axis1" with index 3

index = axis_group_get_axis_index("Axis1") # returns 3

axis_group_get_axis_name

axis_group_get_axis_name(axis_index)

Returns the name of the axis with the given axis_index.

Parameters

axis_index: (integer) Index of the axis in query.
Axis with such index must exist.

Return:

string: Name of the axis.

Example

axis_group_add("AxisGroup1", p[x,x,x,x,x,x]) # adds "AxisGroup1"
axis_group_add_axis("AxisGroup1", "Axis1", "", p[x,x,x,x,x,x], 0, 1, 1, q_limits=[-1,1], axis_index=3) # adds "Axis1" with index 3

name = axis_group_get_axis_name(3) # returns "Axis1"

axis_group_get_target_positions

axis_group_get_target_positions(group_name="")

Returns the current target positions of the axis group with group_name. If group_name is not provided, the target positions of all external axes will be returned.

This function will fail, if the external axis bus is disabled.

Important

As of Polyscope 5.16, only a single axis can be configured at a time.

Parameters

group_name (optional): (string) Name of the axis group in query.
Axis group with such name must REALLY exist.

Return

Double[]: Target positions of the involved axes, in the order of their external axis indices.

Example

axis_group_add("AxisGroup1", p[x,x,x,x,x,x]) # adds "AxisGroup1"
axis_group_add_axis("AxisGroup1", "Axis1", parent_name="", p[x,x,x,x,x,x], 0, 1, 1, [-1,1], axis_index=2) # adds "Axis1" at index 2
axis_group_add_axis("AxisGroup1", "Axis2", parent_name="", p[x,x,x,x,x,x], 0, 1, 1, [-1,1]) # adds "Axis2" at index 0 (automatically assigned)
axis_group_add_axis("AxisGroup1", "Axis3", parent_name="", p[x,x,x,x,x,x], 0, 1, 1, [-1,1]) # adds "Axis3" at index 1 (automatically assigned)
axis_group_add_axis("AxisGroup1", "Axis4", parent_name="", p[x,x,x,x,x,x], 0, 1, 1, [-1,1]) # adds "Axis4" at index 3 (automatically assigned)

positions = axis_group_get_target_positions("AxisGroup1") # returns an array of axis target positions in the order [Axis2, Axis3, Axis1, Axis4] (index ordered)

axis_group_get_actual_positions

axis_group_get_actual_positions(group_name="")

Returns the current actual positions of the axis group with group_name. If group_name is not provided, the actual positions of all external axes will be returned.

This function will fail, if the external axis bus is disabled.

Important

As of Polyscope 5.16, only a single axis can be configured at a time.

Parameters

group_name (optional): (string) Name of the axis group in query.
Axis group with such name must exist.

Return:

Double[]: Actual positions of the involved axes, in the order of their external axis indices.

Example

axis_group_add("AxisGroup1", p[x,x,x,x,x,x]) # adds "AxisGroup1"
axis_group_add_axis("AxisGroup1", "Axis1", parent_name="", p[x,x,x,x,x,x], 0, 1, 1, [-1,1], axis_index=2) # adds "Axis1" at index 2
axis_group_add_axis("AxisGroup1", "Axis2", parent_name="", p[x,x,x,x,x,x], 0, 1, 1, [-1,1]) # adds "Axis2" at index 0 (automatically assigned) 
axis_group_add_axis("AxisGroup1", "Axis3", parent_name="", p[x,x,x,x,x,x], 0, 1, 1, [-1,1]) # adds "Axis3" at index 1 (automatically assigned)  
axis_group_add_axis("AxisGroup1", "Axis4", parent_name="", p[x,x,x,x,x,x], 0, 1, 1, [-1,1]) # adds "Axis4" at index 3 (automatically assigned)  

positions = axis_group_get_actual_positions("AxisGroup1") # returns an array of axis actual positions in the order [Axis2, Axis3, Axis1, Axis4] (index ordered)

axis_group_offset_positions

axis_group_offset_positions(group_name, offset)

Shifts the target and actual positions of the axis group group_name by the given offset.

This is a software shift that happens in the controller only, it does not affect external axis drives. The shift is also applied to any streamed target and actual positions published on RTDE.

Parameters

group_name: (string) Name of the axis group to apply the offset positions to.
Axis group with such name must exist.

offset: (float[]) Offsets that the target and actual positions should be shifted by.
The size of offset must match the number of axes attached to the given group.

Return: n/a

Example

# Assume the axis group "AxisGroup1" has only one axis.

# Example 1
# The target position for an axis is currently 9*pi/4 and the user wants to shift the position so that it becomes 0:

current_targets = axis_group_get_target_positions("AxisGroup1") # returns [9*pi/4]
current_actuals = axis_group_get_actual_positions("AxisGroup1") # returns [9*pi/4]

desired_offset = - current_targets # equals [-9*pi/4]
axis_group_offset_positions("AxisGroup1", [desired_offset])

current_targets = axis_group_get_target_positions("AxisGroup1") # returns [0]
current_actuals = axis_group_get_actual_positions("AxisGroup1") # returns [0]

# Example 2
# The target position for an axis is currently 9*pi/4 and the user wants to shift the position so that it is within one revolution of zero and on the lower side of zero (so that a subsequent move to zero would move the axis in the positive direction):

two_pi = 2.0 * 3.1415
current_targets = axis_group_get_target_positions("AxisGroup1") # returns [9*pi/4]
current_actuals = axis_group_get_actual_positions("AxisGroup1") # returns [9*pi/4]

desired_offset = -ceil(current_targets[0] / two_pi) * two_pi # equals –4*pi
axis_group_offset_positions("AxisGroup1", [desired_offset])

current_targets = axis_group_get_target_positions("AxisGroup1") # returns [-7*pi/4]
current_actuals = axis_group_get_actual_positions("AxisGroup1") # returns [-7*pi/4]

# Example 3
# The target position for an axis is currently 9*pi/4 and the user wants to shift the position so that it is within one revolution of zero and on the upper side of zero (so that a subsequent move to zero would move the axis in the negative direction):

two_pi = 2.0 * 3.1415
current_targets = axis_group_get_target_positions("AxisGroup1") # returns [9*pi/4]
current_actuals = axis_group_get_actual_positions("AxisGroup1") # returns [9*pi/4]

desired_offset = -floor(current_targets[0] / two_pi) * two_pi # equals –2*pi
axis_group_offset_positions("AxisGroup1", [desired_offset])

current_targets = axis_group_get_target_positions("AxisGroup1") # returns [pi/4]
current_actuals = axis_group_get_actual_positions("AxisGroup1") # returns [pi/4]

axis_group_movej

axis_group_movej(group_name, q, a, v)

Moves the axes of axis group named group_name to new positions q, using a trapezoidal velocity profile. Factor a specifying the percentage of the max profile accelerations out of the acceleration limits of each axes. Factor v specifying the percentage of the max profile velocities out of the velocity limits of each axes.

The actual accelerations and velocities are determined by the most constraining axis, so that all the axes complete the acceleration, cruise, and deceleration phases at the same time.

Important

As of Polyscope 5.16, only a single axis can be configured at a time.

Parameters

group_name: (string) Name of the axis group to move.
Axis group with such name must exist.

q: (float[]) Target positions in rad (revolute) or in m (prismatic). If the target exceeds the position limits, then it is set to the nearest limit. The involved axes are ordered increasingly by their axis indices.
The size of q must match the number of axes attached to the given group.

a: (float) Factor specifying the max accelerations of this move out of the acceleration limits.
a must be in range of (0,1].

v: (float) Factor specifying the max velocities of this move out of the velocity limits.
v must be in range of (0,1].

Return: n/a

Example

In the target array of axis_group_movej(), “Axis2” comes before “Axis1”, since “Axis2” has a smaller index (1) than “Axis1” (3).

axis_group_add("AxisGroup1", p[x,x,x,x,x,x]) # adds "AxisGroup1"
axis_group_add_axis("AxisGroup1", "Axis1", "", p[x,x,x,x,x,x], 0, 1, 1, [-3,3], 3) # adds "Axis1" at index 3
axis_group_add_axis("AxisGroup1", "Axis2", "", p[x,x,x,x,x,x], 0, 1, 1, [-3,3], 1) # adds "Axis2" at index 1

axis_group_movej("AxisGroup1", [2, -1], 1, 1) # moves "Axis1" to -1 rad and "Axis2" to 0 rad at full speed/acceleration

axis_group_speedj

axis_group_speedj(group_name, qd, a, t=-1)

Accelerates the axes of axis group named group_name up to the target velocities qd. Factor a specifying the percentage of the max accelerations out of the acceleration limits of each axes. The function will run for a period of t seconds.

Important

As of Polyscope 5.16, only a single axis can be configured at a time.

Parameters

group_name: (string) Name of the external axis group to control.
Axis group with such name must exist.

qd: (float[]) Target velocities for the axes in the axis group. If the target exceeds the velocity limits, then it is set to the limit. The involved axes are ordered increasingly by their axis indices.
The size of qd must match the number of axes attached to the given group.

a: (float) Factor specifying the max accelerations of this move out of the acceleration limits.
a must be in range of (0,1].

t (optional): (float) Duration in seconds before the function returns.
If t < 0, then the function will return when the target velocities are reached. if t 0, then the function will return after this duration, regardless of what the achieved axes velocities are.

Return: n/a

Example

In the target array of axis_group_speedj(), “Axis2” comes before “Axis1”, since “Axis2” has a smaller index (1) than “Axis1” (3).

axis_group_add("AxisGroup1", p[x,x,x,x,x,x]) # adds "AxisGroup1"
axis_group_add_axis("AxisGroup1", "Axis1", "", p[x,x,x,x,x,x], 0, 1, 1, [-3,3], 3) # adds "Axis1" at index 3
axis_group_add_axis("AxisGroup1", "Axis2", "", p[x,x,x,x,x,x], 0, 1, 1, [-3,3], 1) # adds "Axis2" at index 1

axis_group_speedj("AxisGroup1", [-.5, .5], 1) # speeds "Axis1" to .5 rad/s and "Axis2" to -.5 rad/s at full acceleration

movep_with_axis_group

movep_with_axis_group(
    goal, a=1.2, v=0.25, r=0, 
    name={}, axis_target={}
    )

Synchronizes a movep motion, defined by goal, a, v, and r as in regular movep function, and an axis group motion, defined by group name and axis_target. The trajectory profile (acceleration, cruise, deceleration, etc.) of the axes matches the trajectory profile of the TCP except during blends.

Important

This command does not respect the axis velocity or acceleration limits. When the velocity limits are exceeded, a protective stop is issued that allows the user to adjust the Polyscope speed slider and then resume to keep the velocity within limits.

  • Some motion blends are not supported, when frame tracking is enabled to track an external axis:

  • Blends from movej() or movej_with_axis_group() to movep_with_axis_group().

Parameters

goal: (float[], pose, struct{pose, frame}, string) Target pose for the TCP motion. The goal could be defined in different ways:

  • By a (float[]) as robot joint positions. The goal pose will be calculated by forward kinematics.

  • By a (pose) as a pose in robot base coordinate frame.

  • By a (struct{pose, frame}) as a pose and the name of a reference coordinate frame. The goal will be set to this pose in this reference coordinate frame.

  • By a (string) as the name of a world model object. The goal will be set to this object’s pose.

a (optional): (float) Tool acceleration in m/s^2.

v (optional): (float) Tool speed in m/s.

r (optional): (float) Tool blend radius in m.

name: (string) Name of the axis group that will synchronize with the movep motion.
Axis group with such name must exist.

axis_target: (float[]) Target positions for the axis group in rad (revolute) or m (prismatic). The involved axes are ordered increasingly by their axis indices.
The size of the array must match the number of axes attached to the axis group.

Return: n/a

Example Further examples can be found here.

axis_group_add("AxisGroup1", p[x,x,x,x,x,x]) # adds "AxisGroup1" 
axis_group_add_axis("AxisGroup1", "Axis1", "", p[x,x,x,x,x,x], 0, 1, 1, [-3,3], 3) # add "Axis1" at index 3
 
tcp_goal = p[1,2,3,4,5,6] # goal pose of the robot's tcp
axis_goal = [0.1] # goal position of Axis1

# Performs a movep command on the robot TCP, and Axis1 is timed to reach its goal at the same time. The default TCP acceleration and velocity are used.
movep_with_axis_group(tcp_goal, name="AxisGroup1", axis_target=axis_goal)

movec_with_axis_group

movec_with_axis_group(
    pose_via, pose_to, a=1.2, v=0.25, r=0, 
    mode=0, name={}, axis_target={}
    )

Synchronizes a movec motion, defined by pose_via, pose_to, a, v, r, and mode as in regular movec function, and an axis group motion, defined by group name and axis_target. The trajectory profile (acceleration, cruise, deceleration, etc.) of the axes matches the trajectory profile of the TCP except during blends.

Important

This command does not currently respect the axis velocity or acceleration limits. When the velocity limits are exceeded, a protective stop is issued that allows the user to adjust the Polyscope speed slider and then resume to keep the velocity within limits.

Some motion blends are not supported, when frame tracking is enabled to track an external axis:

  • Blends from movej() or movej_with_axis_group() to movec_with_axis_group().

Parameters

pose_via: (float[], pose, struct{pose, frame}, string) Path pose for the TCP motion, only the position part is actually used. It could be defined in different ways:

  • By a (float[]) as robot joint positions. The goal pose will be calculated by forward kinematics.

  • By a (pose) as a pose in robot base coordinate frame.

  • By a (struct{pose, frame}) of a pose and the name of a reference coordinate frame. The goal will be set to this pose in this reference coordinate frame.

  • By a (string) as the name of a world model object. The goal will be set to this object’s pose.

pose_to: (float[], pose, struct{pose, frame}, string) Target pose for the TCP motion. It could be defined in different ways:

  • By a (float[]) as robot joint positions. The goal pose will be calculated by forward kinematics.

  • By a (pose) as a pose in robot base coordinate frame.

  • By a (struct{pose, frame}) as a pose and the name of a reference coordinate frame. The goal will be set to this pose in this reference coordinate frame.

  • By a (string) as the name of a world model object. The goal will be set to this object’s pose.

a (optional): (float) Tool acceleration in m/s^2.

v (optional): (float) Tool speed in m/s.

r (optional): (float) Tool blend radius in m.

mode (optional): (integer) Mode of the circular motion, can only be one of the following:
0: Unconstrained mode. Interpolate orientation from current pose to target pose (pose_to)
1: Fixed mode. Keep orientation constant relative to the tangent of the circular arc (starting from current pose)

name: (string) Name of the axis group that will synchronize with the movec motion.
Axis group with such name must exist.

axis_target: (float[]) Target positions for the axis group in rad (revolute) or m (prismatic). The involved axes are ordered increasingly by their axis indices.
The size of the array must match the number of axes attached to the axis group.

Return: n/a

Example

axis_group_add("AxisGroup1", p[x,x,x,x,x,x]) # adds "AxisGroup1" 
axis_group_add_axis("AxisGroup1", "Axis1", "", p[x,x,x,x,x,x], 0, 1, 1, [-3,3], 3) # add "Axis1" at index 3
 
tcp_via = p[1,2,3,4,5,6] # via pose of the robot's tcp
tcp_goal = p[1,2,3,4,5,6] # goal pose of the robot's tcp
axis_goal = [0.1] # goal position of Axis1

# Performs a movec command on the robot TCP, and Axis1 is timed to reach its goal at the same time. The default TCP acceleration, velocity, and mode are used.
movec_with_axis_group(tcp_via, tcp_goal, name="AxisGroup1", axis_target=axis_goal)

movej_with_axis_group

movej_with_axis_group(
    goal, a=1.4, v=1.05, t=0, 
    r=0, name={}, axis_target={}
)

Synchronizes a movej motion, defined by goal, a, v, t, and r as in regular movej function, and an axis group motion, defined by group name and axis_target. The trajectory profile (acceleration, cruise, deceleration, etc.) of the axes matches the trajectory profile of the TCP except during blends.

Important

This command does not respect the axis velocity or acceleration limits. When the velocity limits are exceeded, a protective stop is issued that allows the user to adjust the Polyscope speed slider and then resume to keep the velocity within limits.

Some motion blends are not supported, when frame tracking is enabled to track an external axis:

  • Blends from movel() or movel_with_axis_group() to movej_with_axis_group().

  • Blends from movej_with_axis_group() to movel() or movel_with_axis_group().

  • Blends from movej_with_axis_group() to movep() or movep_with_axis_group().

  • Blends from movej_with_axis_group() to movec() or movec_with_axis_group().

Parameters

goal: (float[], pose, struct{pose, frame}, string) Target for the TCP motion. It could be defined in different ways:

  • By a (float[]) as robot joint positions. The target pose will be calculated by forward kinematics.

  • By a (pose) as a pose in robot base coordinate frame. The target joint positions will be calculated by inverse kinematics.

  • By a (struct{pose, frame}) as a pose and the name of a reference coordinate frame. The goal will be set to this pose in this reference coordinate frame.

  • By a (string) as the name of a world model object. The goal will be set to this object’s pose.

a (optional): (float) Joint acceleration in rad/s^2.
a must be positive.

v (optional): (float) Joint speed in rad/s.
v must be positive.

t (optional): (float) Time constraint in s. If used, a, v, and r are ignored.
t must not be negative.

r (optional): (float) Blend radius in m.

name: (string) Name of the axis group that will synchronize with the movej motion.
Axis group with such name must exist.

axis_target: (float[]) Target positions for the axis group in rad (revolute) or m (prismatic). The involved axes are ordered increasingly by their axis indices.
The size of the array must match the number of axes attached to the axis group.

Return: n/a

Example

axis_group_add("AxisGroup1", p[x,x,x,x,x,x]) # adds "AxisGroup1" 
axis_group_add_axis("AxisGroup1", "Axis1", "", p[x,x,x,x,x,x], 0, 1, 1, [-3,3], 3) # add "Axis1" at index 3
 
joint_goal = p[1,2,3,4,5,6] # goal of the robot joints
axis_goal = [0.1] # goal position of Axis1

# Performs a movej command on the robot joints, and Axis1 is timed to reach its goal at the same time. The default joint acceleration and velocity.
movej_with_axis_group(joint_goal, name="AxisGroup1", axis_target=axis_goal)

movel_with_axis_group

movel_with_axis_group(
    goal, a=1.2, v=0.25, t=0, r=0, 
    name={}, axis_target={}
)

Synchronizes a movel motion, defined by goal, a, v, t, and r as in regular movel function, and an axis group motion, defined by group name and axis_target. The trajectory profile (acceleration, cruise, deceleration, etc.) of the axes matches the trajectory profile of the TCP except during blends.

Important

This command does not respect the axis velocity or acceleration limits. When the velocity limits are exceeded, a protective stop is issued that allows the user to adjust the Polyscope speed slider and then resume to keep the velocity within limits.

Some motion blends are not supported, when frame tracking is enabled to track an external axis:

  • Blends from movel_with_axis_group() to movej() or movej_with_axis_group().

  • Blends from movej() or movej_with_axis_group() to movel_with_axis_group().

Parameters

goal: (float[], pose, struct{pose, frame}, string) Target pose for the TCP motion. It could be defined in different ways:

  • By a (float[]) as robot joint positions. The goal pose will be calculated by forward kinematics.

  • By a (pose) as a pose in robot base coordinate frame.

  • By a (struct{pose, frame}) of a pose and the name of a reference coordinate frame. The goal will be set to this pose in this reference coordinate frame.

  • By a (string) as the name of a world model object. The goal will be set to this object’s pose.

a (optional): (float) Tool acceleration in m/s^2.
a must be positive.

v (optional): (float) Tool speed in m/s.
v must be positive.

t (optional): (float) Time constraint in s. If used, a, v, and r are ignored.

t must not be negative.

r (optional): Tool blend radius in m.

name: (string) Name of the axis group that will synchronize with the movej motion.
Axis group with such name must exist.

axis_target: (float[]) Target positions for the axis group in rad (revolute) or m (prismatic). The involved axes are ordered increasingly by their axis indices.
The size of the array must match the number of axes attached to the axis group.

Return: n/a

Example

axis_group_add("AxisGroup1", p[x,x,x,x,x,x]) # adds "AxisGroup1" 
axis_group_add_axis("AxisGroup1", "Axis1", "", p[x,x,x,x,x,x], 0, 1, 1, [-3,3], 3) # add "Axis1" at index 3
 
tcp_goal = p[1,2,3,4,5,6] # goal pose of the robot's tcp
axis_goal = [0.1] # goal position of Axis1

# Performs a movel command on the robot TCP, and Axis1 is timed to reach its goal at the same time. The default TCP acceleration and velocity are used.
movel_with_axis_group(tcp_goal, name="AxisGroup1", axis_target= axis_goal)

servoj_with_axis_group

servoj_with_axis_group(
   q, a=1.4, v=1.05, t=0.002, 
   lookahead_time=0.1,  
   gain=300, group_name={}, 
   axes_q={}, 
   axes_lookahead_time={}, 
   axes_gain={}
)

Synchronizes an online realtime control of the robot, defined by q, a, v, t, lookahead_time, and gain as in regular servoj function, and an online realtime control of axes, defined by group group_ame and axis_q, axes_lookahead_time, and axes_gain. The behavior of for the axes is similar to that of the robot. Just like the servoj function, this function can also blend to/from another servoj or servoj_with_axis_group.

Important

This function respects the axis acceleration and velocity limits for the external axes. The actual acceleration and velocities for the axes are determined by the most constraining axis so that the progress for all the axes remains the same.

Warning

Known Limitations: This function expects the argument t to be a multiple of the robot timestep (0.002s). An exception will be thrown otherwise.

Parameters

q: (float[]) Target joint positions for the robot.

a (optional): (float) Not used.

v (optional): (float) Not used.

t (optional): (float) Duration in s, the robot and axes are controlled. Must be multiple of 0.002s.

lookahead_time (optional): (float) Look ahead time in s, clamped to [0.03, 0.2].

gain (optional): (float) Proportional gain for following target position, clamped to [100.0, 2000.0].

group_name: (string) Name of the axis group.
Axis group with such name must exist.

axes_q: (float[]) Target joint positions for the axis group.
The size of the array must match the number of axes attached to the axis group.

axes_lookahead_time: (float) Lookahead time for external axes similar to lookahead_time parameter for the robot in servoj.

axes_gain: (float) Proportional gain for the external axes similar to gain parameter for the robot in servoj.

Return: n/a

Example

Here’s an example of adding a new axis and driving the axis and robot together using servoj_with_axis_group. After adding an axis group and an axis in the program, the robot base joint and the external axis are moved together by -1 radians and then back immediately (with servoj blending) to starting positions. After that, they are both moved again to the same target positions. However, this time they are stopped before every move to disable blending by issuing stopj for the robot and axis_group_speedj for the axis group:

def servoj_with_axis_group_example():
  reset_world_model()
  axis_group_add("groupA", p[0,-1,0,0,0,0])
  axis_group_add_axis("groupA", "axis1", "", p[0,0,0,d2r(90),0,0], 0, 10, 10)
  q=get_actual_joint_positions()
  q1 = q
  q1[0] = q1[0] + 1
  servoj_with_axis_group(q1, t=5, group_name="groupA", axes_q=[-1], axes_lookahead_time=0.03, axes_gain=1000)
  servoj_with_axis_group(q, t=5, group_name="groupA", axes_q=[0], axes_lookahead_time=0.03, axes_gain=1000)
  stopj(10)
  axis_group_speedj("groupA", [0], 1)
  servoj_with_axis_group(q1, t=5, group_name="groupA", axes_q=[-1], axes_lookahead_time=0.03, axes_gain=1000)
  stopj(10)
  axis_group_speedj("groupA", [0], 1)
  servoj_with_axis_group(q, t=5, group_name="groupA", axes_q=[0], axes_lookahead_time=0.03, axes_gain=1000)
 end

calibrate_rotary_axis

calibrate_rotary_axis(headstock, tailstock=[])

Finds the coordinate frame of a rotary axis, given the poses sampled in circle around the headstock, and optional poses sampled in circle around the tailstock.

The origin of the frame locates at the center of the headstock, with x axis pointing to the first sample of headstock, and z axis pointing to the direction of rotation form the first sample of headstock to the second.

Parameters

headstock: (pose[]) Poses sampled around the headstock in a circle.

  • The size of headstock must be larger than 2.

tailstock (optional): (pose[]) Poses sample around the tailstock in a circle.

  • The size of tailstock must be larger than 2, if provided.

Return:

struct:

  • .pose: (pose) Fitted coordinate frame of the rotary axis.

  • .radius: (float) Radius of the fitted circle.

  • .max_error: (float) Maximum distance from headstock to the fitted circle.

  • .mean_error: (float) Average distance from headstock to the fitted circle.

Example

The following example uses headstock samples only. The points are exactly on a circle centered at p[0, 0, 0.001, 0, 0, 0] with radius 0.1. The result will be struct(pose = p[0, 0, 0.001, 0, 0, 0], radius = 0.1, max_error = 0, mean_error = 0).

result = calibrate_rotary_axis([p[0.1, 0.0, 0.001, 0, 0, 0], p[0.0, 0.1, 0.001, 0, 0, 0], p[-0.1, 0.0, 0.001, 0, 0, 0]])

The following example also uses tailstock samples, which are exactly on a circle centered at p[0, 0, 1, 0, 0, 0] with radius 0.2. The result will be struct(pose = p[0, 0, 0.001, 0, 0, 0], radius = 0.1, max_error = 0, mean_error = 0).

result = calibrate_rotary_axis([p[0.1, 0.0, 0.001, 0, 0, 0], p[0.0, 0.1, 0.001, 0, 0, 0], p[-0.1, 0.0, 0.001, 0, 0, 0]],
                               [p[0.0, 0.2, 0.1, 0, 0, 0], p[-0.2, 0.0, 0.1, 0, 0, 0], p[0.0, -0.2, 0.1, 0, 0, 0]])

calibrate_linear_axis

calibrate_linear_axis(origin, z_points, x_dir)

Finds the coordinate frame of a linear axis, given the sample poses of the origin, z_points (along z axis), and x_dir (towards x direction).

Parameters

origin: (pose) Sample pose of the origin.

z_points: (pose[], pose) Sample poses along the z axis.

  • The size of z_points must be positive, if provided as an array.

x_dir: (pose) Sample pose of the x direction.

Return:

struct:

  • .pose: (pose)Fitted coordinate frame of the linear axis.

  • .max_error: (float) Maximum distance from the origin and z_points to the fitted z-axis.

  • .mean_error: (float) Average distance from the origin and z_points to the fitted z-axis.

Example

The following example uses samples exactly on pose p[0, 0, 0.1, -1.5708, 0, 0]. The result will be struct(pose = p[0, 0, 0.1, -1.5708, 0, 0], max_error = 0, mean_error = 0).

result = calibrate_linear_axis(p[0, 0, 0.1, 0, 0, 0], p[0, 0.1, 0.1, 0, 0, 0], p[0.1, 0, 0.1, 0, 0, 0]) # z_points is a single pose

result = calibrate_linear_axis(p[0, 0, 0.1, 0, 0, 0], [p[0, 0.1, 0.1, 0, 0, 0], p[0, 0.1, 0.2, 0, 0, 0]], p[0.1, 0, 0.1, 0, 0, 0]) # z_points is an array of poses

World Model - URScript Functions

frame_tracking_enable

frame_tracking_enable(frame_name)

When enabled, frame tracking updates the robot’s motion so that it performs its trajectory in the tracked world model frame even while the frame moves in time, provided the frame’s motion is smooth and continuous. Any robot motion commands that occur after this call and before frame_tracking_disable() will be performed in the tracked frame. Frame tracking can be used at the same time as the “path offset” functionality. If path offset is turned on while frame tracking is enabled, the path offset will also be performed in the tracked frame.

Important: there are some motion blends that are currently not supported when frame tracking is enabled to track an external axis:

    • Blends from movel or movel_with_axis_group to movej or movej_with_axis_group.

    • Blends from movej or movej_with_axis_group to movel or movel_with_axis_group.

    • Blends from movej or movej_with_axis_group to movep or movep_with_axis_group.

    • Blends from movej or movej_with_axis_group to movec or movec_with_axis_group.

Parameters

frame_name: (string) Name of the frame in the world model to track. This can also be the name of an axis added with the axis_group_add_axis() command.

  • A runtime error will be reported if the tracked frame is attached to the robot’s TCP.

Return: n/a

Example

This shows an example of adding a new axis and then driving the axis using a thread. In the main program, the robot’s TCP is commanded to move from one pose to another in the moving frame of the axis. Further examples can be found here, here, and here.


axis_group_add("PartPositioner", p[x,x,x,x,x,x]) # adds an axis group 

axis_group_add_axis("PartPositioner", axis_name="Axis1", parent_name="", 
                    pose=p[x,x,x,x,x], type=0, v_limit=1, a_limit=1, 
                    q_limits=[-3,3], axis_index=3) # add an axis at index 3

thread moveAxis1Thread():
  axis_group_movej("PartPositioner", [d2r(45)], 1, 1)
end

thrd = run moveAxis1Thread() # start the axis moving

frame_tracking_enable("Axis1") # any robot motion commands after this point will be performed in the "Axis1" frame

movel(struct(pose=p[x,x,x,x,x,x],frame="Axis1")) # move to first pose in Axis1 frame
movel(struct(pose=p[x,x,x,x,x,x],frame="Axis1")) # move to second pose in Axis1 frame

frame_tracking_disable() # any robot motion commands will be performed in the robot base frame

join thrd # wait until the axis has completed motion

frame_tracking_disable

frame_tracking_disable()

Disables frame tracking, if it’s enabled. Any robot commands that are performed after this call will be executed in the robot base frame.

Parameters n/a

Return: n/a

Example

See the example here.