Quick Reference
Axis Group Functions
Configuring Axis Groups and Kinematics
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. The 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 disabled (if live) and deleted.
This function will fail, if this axis group is under control by another URScript function.
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 when it axis position is 0. 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.
The pose parameter is typically obtained from a calibration process when the external axis is commissioned. See here for a guide on a basic routine for calibrating a single rotary axis.
This function will fail, if this axis group is under control of another URScript function.
This function will fail, if the kinematic chain created by the attachment forms a closed chain.
Note
As of MotionPlus 1.1, only type 0 (rotary) is supported and only four axes can be configured at a time. Please see limitations for more info.
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. The 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) the zero-position pose, in the parent coordinate frame, this axis will be placed and attached to. This is the pose the axis will be (relative to its parent) when its axis position is 0. If type is 0 (rotary), then the z axis of the frame corresponds to the axis of rotation. If type is 1 (linear), then the z axis is the axis of translation.
type: (integer) Type of the axis: 0 (rotary) or 1 (linear). The type can only be 0 or 1. (As of MotionPlus 1.1, only type 0 (rotary) is supported. See limitations for details.)
v_limit: (float) Maximum axis velocity in
rad/s
(rotary) orm/s
(linear). The v_limit must be positive.
a_limit: (float) Maximum axis acceleration in
rad/s^2
(rotary) orm/s^2
(linear). The a_limit must be positive.
q_limits (optional): (float[]) Lower and upper limits of the axis position in
rad
(rotary) orm
(linear). 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. The 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:
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. The pose parameter is typically obtained from a calibration process when the external axis is commissioned. See here for a guide on a basic routine for calibrating a single rotary axis.
This function will fail, if the axis group the axis attached to is already being controlled by another URScript command.
This function will fail, if any attached axis of the axis group is live and enabled.
Important
As of MotionPlus 1.1, only type 0 (rotary) is supported. See limitations for details.
Parameters
name: (string) Name of the axis to update. Axis with such name must exist.
pose (optional): (pose) New zero-position pose, in the coordinate frame of the parent axis (or axis group), of the axis. This is the pose of the axis when its axis position is 0.
type (optional): (integer) New type of the axis. The type can only be 0 (rotary) or 1 (linear). As of MotionPlus 1.1, only type 0 (rotary) is supported. See limitations for details.
v_limit (optional): (float) New velocity limit, in
rad/s
(rotary) orm/s
(linear), of the axis. The v_limit must be positive.
a_limit (optional): (float) New acceleration limit, in
rad/s^2
(rotary) orm/s^2
(linear), of the axis. a_limit must be positive.
q_limits (optional): (float[]) New position limits, in
rad
(rotary) orm
(linear), 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]
Getting Axis Group and Axis Properties
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.
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.
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)
Setting Software Axis Offsets
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]
Jogging External Axes
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.
Parameters
group_name: (string) Name of the axis group to move.
Axis group with such name must exist.
q: (float[]) Target positions in
rad
(rotary) or inm
(linear). 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.
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.
Ift < 0
, then the function will return when the target velocities are reached. ift ≥ 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
Time Synchronized Robot and Axis Motion
movep_with_axis_group
movep_with_axis_group(
goal, a=1.2, v=0.25, r=0,
name={}, axis_target={}
)
Synchronizes a robot 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. The axis group motion is synchronized with the robot motion so that the axis arrives at its target at the same time as the robot.
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. See limitations for details.
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
(rotary) orm
(linear). 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. The axis group motion is synchronized with the robot motion so that the axis arrives at its target at the same time as the robot.
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. See limitations for details.
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
(rotary) orm
(linear). 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. The axis group motion is synchronized with the robot motion so that the axis arrives at its target at the same time as the robot.
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. See limitations for details.
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
(rotary) orm
(linear). 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. The axis group motion is synchronized with the robot motion so that the axis arrives at its target at the same time as the robot.
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. See limitations for details.
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
(rotary) orm
(linear). 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
. The axis group motion is synchronized with the robot motion so that the axis arrives at its target at the same time as the robot.
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.
High gains or a short lookahead times may cause instability and vibrations. Especially if the target positions, q or axes_q, are noisy or updated at a low frequency.
Warning
Please see known issues for more limitations of this command.
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
Coordinated Axis and Robot Motion
Coordinated motion is accomplished by executing any of the time synchronized commands while having frame tracking enabled. The time synchronized commands include:
Frame tracking is controlled using:
See example here:
Axis Group Calibration
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. The z axis points in the direction of rotation from the first headstock sample to the second according to the right-hand rule.
Parameters
headstock: (pose[]) An array of poses sampled around the headstock in a circle.
The size of headstock must be larger than 2.
tailstock (optional): (pose[]) An array of 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
EtherCAT Functions
Configuring Axes on the EtherCAT Network
ethercat_config_axis
ethercat_config_axis(axis_name, station_address, counts_per_rev, gear_ratio, feed_constant, zero_offset_count, axis_index = -1, timeout = 2.0)
Description
Configures the axis with parameters of the corresponding hardware
This function must be called for each axis separately
This function will halt the program with an error, if the value of
axis_name
doesn’t match an axis name provided toaxis_group_add()
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
axis_name |
string |
N |
Name of the axis. This should match an axis name provided to axis_group_add(). |
station_address |
int |
N |
EtherCAT station address for the axis. The value must be greater than 0 and no larger than 65536. |
counts_per_rev |
int |
N |
Increment in encoder counts for each round the motor turns. The value must be greater than 0. |
gear_ratio |
float |
N |
Gear ratio for the axis. |
feed_constant |
float |
N |
Feed constant for the axis in radians. Usually, it’s 2*PI (PI=3.14159265359) for rotary positioners. |
zero_offset_count |
int |
N |
Encoder reading in counts when the axis is at 0 position. The joint angle = ((current encoder – offset) * feed_constant) / (counts_per_rev * gear_ratio). |
axis_index |
int |
Y |
Index for the axis in the joint positions vector. Defaults to |
timeout |
float |
Y |
Timeout in seconds to wait for the operation to finish. Defaults to |
Return
none
Examples
In this example, a new axis group and axis are added and the new axis is configured to be commanded with EtherCAT
Note: replace the values for <ENCODER>
and <GEAR>
to match your servo setup.
global PI = acos(-1)
AXIS_TYPE = 0 # 0:rotary, 1:linear
VELOCITY_LIMIT = 1 # rad/s
ACCELERATION_LIMIT = 10 # rad/s^2
ENCODER_RESOLUTION = <ENCODER> # Specify encoder ticks per revolution of the motor
GEAR_RATIO = <GEAR> # Specify gear after motor output
FEED_CONSTANT = 2 * PI # change sign to change motor direction
ZERO_OFFSET = 0
#create new axis group and axis
axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
# configure the axis to be controlled via ethercat
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
Using the EtherCAT Master
ethercat_start
ethercat_start(timeout = 5.0)
Description
Starts the EtherCAT Master communication with the slave axes configured through calls of ethercat_config_axis() and waits for the EtherCAT Master network state to be Operational (OP).
This function will halt the program and display an error popup on PolyScope, if it times out, or if an error is encountered (e.g., if initialization or configuration fails during startup)
This function requires one axis to be defined using ethercat_config_axis(), and the MotionPlus service running which can be checked using ethercat_is_service_responsive().
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
timeout |
float |
Y |
Timeout in seconds to wait for EtherCAT master state to be Operational (OP). Default: 5.0. |
Return
none
Example
In this example, a new axis group and axis are added and the new axis is configured to be commanded with EtherCAT. The EtherCAT master is then started using the default startup wait.
# create an axis group
axis_group_add("groupA", tf, "world")
# create a new axis
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
# configure the axis to be controlled via ethercat
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
# starts up ethercat master
ethercat_start()
ethercat_stop
ethercat_stop(reset = False, timeout = 5.0)
Description
Stops the EtherCAT Master and optionally removes all the axes (EtherCAT slaves) configured via ethercat_config_axis(). This option is useful to ensure the EtherCAT network begins in a clean, unconfigured state.
This function will halt the program and display an error popup on PolyScope, if it times out, or if an error is encountered
This function can be called whether or not the EtherCAT Master has already been started
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
reset |
bool |
Y |
Resets the axis configuration via ResetConfiguration XML-RPC method. Default: False |
timeout |
float |
Y |
Timeout in seconds to wait for EtherCAT master to finish stopping. Default: 5.0 |
server_port |
int |
Y |
TCP port for the XML-RPC server. Defaults to |
server_host |
string |
Y |
Hostname / IP address for the XML-RPC server. Defaults to “”, implying that |
Return
none
Example
ethercat_stop(True) # make sure the ethercat master is stopped and clear the configured ethercat slaves... this makes the program start with a clean slate
axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start() # starts up ethercat
# do stuff
ethercat_stop() # stop the ethercat master only... don't clear the ethercat slaves
ethercat_set_parameter
ethercat_set_parameter(key, value, timeout = 1.0)
Description
This sets advanced/custom EtherCAT Master parameters. This function will halt the program with an error, if the EtherCAT Master is already running, or if the key or the value is invalid.
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
key |
string |
N |
Name of EtherCAT Master parameter to set. |
value |
bool, int, float, or string |
N |
New value for the EtherCAT Master parameter. The type of this argument depends on the value of |
timeout |
float |
Y |
Timeout in seconds to wait for the operation to finish. Defaults to 1. |
The following EtherCAT Master parameters are supported by this function:
Key |
Value Type |
Default Value |
Description |
---|---|---|---|
dc_enable |
bool |
False |
Whether EtherCAT Distributed Clock should be enabled. ** Note: DC enabled is on by default.** |
Return
none
Example
In this example, the EtherCAT Distributed Clock is disabled
ethercat_set_parameter("dc_enable", False)
ethercat_is_master_running
ethercat_is_master_running(timeout = 2.0)
Description
Checks whether the EtherCAT Master is running
This function will halt the program with an error, if it times out, or if an error is encountered
This function requires the MotionPlus Service to be running
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
timeout |
float |
Y |
Seconds to wait for heartbeat (Status) before failing with error. Default: 2.0 |
Return
bool result indicating whether the EtherCAT Master is currently running
Example
# assuming ethercat start/stop is handled on a different thread
if ethercat_is_master_running():
# do stuff if master is running
else:
# do stuff if master is not running
end
ethercat_begin_status_monitor
ethercat_begin_status_monitor(period = 0.1, max_missed_messages = 3, timeout = 1.0)
Description
Starts background task to periodically call
GetStatus
XML-RPC method
This function will halt the program, if the responses stop or are never received
This function will halt the program, if any response contains a non-zero error code
This is useful for making a URScript program identify if the MotionPlus Service has prematurely quit or encountered a runtime error
Note: Runtime errors are those that prevent the MotionPlus Service from functioning properly. They do not include faults from the EtherCAT slaves
This function will halt the program, if another monitoring task is already running
Only one Status Monitor task may be running at any given time
Call ethercat_end_status_monitor() to stop the previous task, before starting a new one
Monitoring will automatically start when program
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
period |
float |
Y |
Rate (in seconds) at which to request Status messages. Default: 0.1 |
max_missed_messages |
int |
Y |
Maximum number of heartbeats that may be missed consecutively before a halt is triggered. Default: 3 |
timeout |
float |
Y |
Seconds to wait for response before considering it to be missed. Default: 1.0 |
server_port |
int |
Y |
TCP port for the XML-RPC server. Defaults to |
server_host |
string |
Y |
Hostname / IP address for the XML-RPC server. Defaults to “”, implying that |
Return
none
Example
ethercat_end_status_monitor() # end status monitor
ethercat_begin_status_monitor() # restart
ethercat_end_status_monitor
ethercat_end_status_monitor()
Description
Stops any Status Monitor task started with ethercat_begin_status_monitor()
Monitoring will automatically end when a program completes, but this command can be used to stop monitoring at any point in the program
Parameter
none
Return
none
Example
# end default status monitor first
ethercat_end_status_monitor()
# restart
ethercat_begin_status_monitor()
Enabling/Disabling External Axes
ethercat_enable_axis
ethercat_enable_axis(axis_name, timeout = 10, steady_time = 0.5)
Description
Enables the EtherCAT axis specified by axis_name
This function requires the EtherCAT Master to be running
This function blocks until either the axis is enabled or the timeout expires
This function returns True if it succeeded and False if it timed out
This function will halt the program with an error, if the value of the
axis_name
parameter is invalid
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
axis_name |
string |
N |
The name of the axis. This should match an axis name created by calling |
timeout |
float |
Y |
Maximum time in seconds to wait for axis to be enabled. Negative values indicate unlimited time. Default: 10 |
steady_time |
float |
Y |
Time to wait after enabling axis to verify that it stays in operation enabled state. Default: 0.5 |
Return
bool value where True indicates the axis was enabled and False if it timed out
Example
axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start()
ethercat_enable_axis("axis1") # enables the axis and waits 1s to verify the axis remains enabled before continuing
ethercat_disable_axis
ethercat_disable_axis(axis_name, timeout = 10)
Description
Disables the EtherCAT axis specified by axis_name
This function requires the EtherCAT Master to be running
This function blocks until either the axis is disabled or the timeout expires
This function returns True if it succeeded and False if it timed out
This function will halt the program with an error, if the value of the
axis_name
parameter is invalid
Note
A call to reset_world_model() will automatically disable any enabled EtherCAT axes.
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
axis_name |
string |
N |
The name of the axis. This should match an axis name created by calling |
timeout |
float |
Y |
Maximum time in seconds to wait for axis to be disabled. Negative values indicate unlimited time. Default: 10 |
Return
bool value where True indicates the axis was disabled and False if it timed out
Example
axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start()
ethercat_enable_axis("axis1") # enables the axis
# do stuff
ethercat_disable_axis("axis1") # disables the axis
ethercat_is_axis_enabled
ethercat_is_axis_enabled(axis_name)
Description
Checks whether the specified EtherCAT axis is enabled
This function requires the EtherCAT Master to be running. If the EtherCAT Master is not running, it will provide the last known status
This function will halt the program with an error, if the value of the
axis_name
parameter is invalidThis function requires one axis to be defined
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
axis_name |
string |
N |
The name of the axis. This should match an axis name created by calling |
Return
bool where True indicates that the axis is enabled
Example
axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start()
ethercat_enable_axis("axis1") # enables the axis and waits 1s to verify the axis remains enabled before continuing
enabled = ethercat_is_axis_enabled("axis1") # would be True if ethercat_enable_axis() succeeded
ethercat_is_axis_disabled
ethercat_is_axis_disabled(axis_name)
Description
Checks whether the specified EtherCAT axis is disabled
This function requires the EtherCAT Master to be running. If the EtherCAT Master is not running, it will provide the last known status
This function will halt the program with an error, if the value of the
axis_name
parameter is invalidThis function requires one axis to be defined
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
axis_name |
string |
N |
The name of the axis. This should match an axis name created by calling |
Return
bool value where True indicates the axis is disabled
Example
axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start()
ethercat_enable_axis("axis1") # enables the axis
# do stuff
ethercat_disable_axis("axis1") # disables the axis
disabled = ethercat_is_axis_disabled("axis1") # would be True if ethercat_disable_axis() succeeded
Handling Errors and Faults
ethercat_clear_error
ethercat_clear_error(timeout = 1.0)
Description
Clears the EtherCAT Master error
This function allows the user to clear the error on the EtherCAT Master using the ClearError XML-RPC method
This function will halt the program with a popup, if it times out, or if an error is encountered (e.g. if there is a configuration error on the EtherCAT Master)
If the EtherCAT Master halts on a runtime error, and the Status Monitoring is disabled, user will be unable to start the EtherCAT Master again until the error is cleared
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
timeout |
float |
Y |
Seconds to wait for operation to finish before failing with error. Default: 1.0 |
Return
none
Example
# Status Monitor (started by `ethercat_begin_status_monitor()`)
# has detected an EtherCAT Master runtime error and stopped the previous UR program.
ethercat_clear_error() # Clear current error
# Proceed to reconfigure and restart EtherCAT Master.
ethercat_is_axis_in_fault_state
ethercat_is_axis_in_fault_state(axis_name)
Description
Checks whether the specified axis has reported fault on EtherCAT network
This function requires the EtherCAT Master to be running by calling ethercat_start()
However, if the EtherCAT Master is not running, it will return the last known status
This function will halt the program with an error, if the value of the
axis_name
parameter is invalidThis function requires one axis to be defined
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
axis_name |
string |
N |
The name of the axis. This should match an axis name created by calling |
Return
bool value where True indicates the axis has a fault
Example
axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start() # starts up ethercat
# query whether or not "axis1" is in fault state
isAxis1Faulted = ethercat_is_axis_in_fault_state("axis1")
ethercat_get_axis_errors
ethercat_get_axis_errors(timeout = 1.0)
Description
Gets the axis error codes for all axes on the EtherCAT network
Returns a struct containing a list of drive (axis) indices and a corresponding list of error codes from those drives
If the EtherCAT master is not running, the return value may be invalid
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
timeout |
float |
Y |
Seconds to wait for method result before failing with error. Default: 1.0 |
Return
struct AxisErrors type structure containing the following:
timestamp.sec (int) whole seconds elapsed since the UNIX epoch (1970-01-01, 00:00:00) in local time zone
timestamp.nsec (int) nanoseconds elapsed in addition to timestamp.sec
axis_count (int) number of configured axis
axis_indices (int[]) list of axis indices EtherCAT Master is controlling
axis_errors (int[]) list of current error codes for the axes listed in axis_indices
Example
# make sure the ethercat master is stopped and clear the configured ethercat slaves...
# this makes the program start with a clean slate
ethercat_stop(True)
axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start() # starts up ethercat
# do stuff
msg = ethercat_get_axis_errors()
textmsg(str_cat("Current error code for axis1: ", to_str(msg.axis_errors[0])))
ethercat_stop(False) # stop the ethercat master only... don't clear the ethercat slaves
ethercat_reset_axis_fault
ethercat_reset_axis_fault(axis_name, timeout = 10)
Description
Resets fault status for the axis specified by axis_name
This function requires the EtherCAT Master to be running
This function blocks until either the fault is successfully reset or the timeout expires
This function returns True if it succeeded and False if it timed out while trying to reset the fault
This function will halt the program with an error, if the value of the
axis_name
parameter is invalidThis function requires one axis to be defined
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
axis_name |
string |
N |
The name of the axis. This should match an axis name created by calling |
timeout |
float |
Y |
Maximum time in seconds to wait for fault to be reset. Negative values indicate unlimited time. Default: 10 |
Return
bool value where True indicates the fault was successfully reset while False indicates it timed out
Example
axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start()
if ethercat_is_axis_in_fault_state("axis1"):
ethercat_reset_axis_fault("axis1") # reset fault of "axis1" if there is any
end
Homing External Axes
ethercat_home_axis_direct
ethercat_home_axis_direct(axis_name, timeout = 10.0)
Note
This method is deprecated as of MotionPlus 1.1 and is planned for removal in MotionPlus 2.0. Please use ethercat_home_axis() instead. The equivalent call is ethercat_home_axis(axis_name, 35, 0, [], [], timeout).
Description
Performs EtherCAT home-to-current homing method on the external axis specified by axis_name.
This function requires the EtherCAT Master to be running for it to succeed (see ethercat_start())
This function requires the axis to be enabled (see ethercat_enable_axis())
This function returns a boolean flag indicating whether the function exited due to timeout.
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
axis_name |
string |
N |
The name of the axis. This should match an axis name created by calling |
home_offset |
int |
N |
Moves the homed zero position by the given offset (given in [encoder counts]). ** Note:** This parameter is not supported and is ignored by the Mitsubishi J4 drive. |
timeout |
float |
Y |
Seconds to wait for method result before failing with error. Default: 10.0 |
Return
bool value where True indicates the axis was homed and False if it timed out
Example
ethercat_stop(True) # make sure the ethercat master is stopped and clear the configured ethercat slaves... this makes the program start with a clean slate
axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start() # starts up ethercat
# do stuff
positions = axis_group_get_target_positions("groupA")
textmsg(str_cat("Axis 1 position: ", to_str(positions[0])))
ethercat_home_axis_direct("axis1", 0)
positions = axis_group_get_target_positions("groupA")
textmsg(str_cat("Axis 1 position: ", to_str(positions[0]))) # axis has been homed and position is now 0.0
ethercat_stop(False) # stop the ethercat master only... don't clear the ethercat slaves
ethercat_home_axis
ethercat_home_axis(axis_name, homing_method, home_offset, homing_velocities, homing_accelerations, timeout = 10.0)
Description
Performs homing on the the external axis specified by axis_name using the specified EtherCAT CoE CiA402 homing method.
This function requires the EtherCAT Master to be running for it to succeed (see ethercat_start())
This function requires the axis to be enabled (see ethercat_enable_axis())
This function returns a boolean flag indicating whether the function exited due to timeout.
Name |
Type |
Optional |
Description |
---|---|---|---|
axis_name |
string |
N |
The name of the axis. This should match an axis name created by calling |
homing_method |
int |
N |
The EtherCAT CoE CiA402 homing method to use. Valid values are between -128 and 127 inclusive. The supported values vary between servo manufacturers. See servo manufacturer’s documentation for supported methods (refer to EtherCAT CoE CiA 402 object: 0x6098).
|
home_offset |
int |
N |
Moves the homed zero position by the given offset (given in [encoder counts]). Note: This parameter is not supported and is ignored by the Mitsubishi J4 drive. |
homing_velocities |
int[] |
N |
An integer array (max size 6) containing the velocity(ies) to use while homing (given in [encoder counts/s]). Typically [switch_search_speed, zero_search_speed]. Enter [] to use existing values stored in the servo. Note: This parameter is not supported and is ignored by the Mitsubishi J4 drive. |
homing_accelerations |
int[] |
N |
An integer array (max size 6) containing the acceleration(s) to use while homing (given in [encoder counts/s^2]). Typically [homing_acceleration]. Enter [] to use existing values stored in the servo. Note: This parameter is not supported and is ignored by the Mitsubishi J4 drive. |
timeout |
float |
Y |
Seconds to wait for method result before failing with error. Default: 10.0. |
Warning
Behavior and support varies by servo manufacturer. See manufacturer documentation for supported values of homing_method (refer to EtherCAT CoE CiA 402 object: 0x6098). For example, the Mitsubishi J4 drive does not support and ignores the values passed in the home_offset, homing_velocities, and homing_accelerations parameters.
Return
bool value where True indicates the axis was homed and False if it timed out
Example
ethercat_stop(True) # make sure the ethercat master is stopped and clear the configured ethercat slaves... this makes the program start with a clean slate
axis_group_add("groupA", tf, "world") # create an axis group
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], 0, 1, 10) # create a new axis
ethercat_config_axis("axis1", 1, 4194304, 120.460000, 6.280000, 0) # configure the axis to be controlled via ethercat
ethercat_start() # starts up ethercat
# do stuff
positions = axis_group_get_target_positions("groupA")
textmsg(str_cat("Axis 1 position: ", to_str(positions[0])))
# home the axis against the encoder index nearest to the positive limit switch
# use the servo-provided velocity and acceleration values
ethercat_home_axis("axis1", 2, 0, [], [])
# alternatively, set home to the current position
# ethercat_home_axis("axis1", 35, 0, [], [])
positions = axis_group_get_target_positions("groupA")
textmsg(str_cat("Axis 1 position: ", to_str(positions[0]))) # axis has been homed and position is now 0.0
ethercat_stop(False) # stop the ethercat master only... don't clear the ethercat slaves
Get External Axis Positions
ethercat_get_axis_positions
ethercat_get_axis_positions(timeout = 1.0)
Description
Gets the last known axis positions for all axes on the EtherCAT network
This function returns a struct with a timestamp, axis indices, target axis positions, actual axis positions, target axis position encoder counts and actual axis position encoder counts
This function requires the EtherCAT Master to be running for the returned data to be valid
This function will halt the program with an error, if the EtherCAT Master is not running
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
timeout |
float |
Y |
Seconds to wait for method result before failing with error. Default: 1.0 |
Return
struct structure containing the following:
timestamp.sec (int) whole seconds elapsed since the UNIX epoch (1970-01-01, 00:00:00) in local time zone
timestamp.nsec (int) nanoseconds elapsed in addition to timestamp.sec
axis_count (int) number of configured axis
axis_indices (int[]) list of axis indices EtherCAT Master is controlling
target_positions (float[]) list of target positions in metric units for the axes listed in axis_indices
actual_positions (float[]) list of current actual positions in metric units for the axes listed in axis_indices
target_position_counts (int[]) list of target positions in encoder counts for the axes listed in axis_indices
actual_position_counts (int[]) list of actual positions in encoder counts for the axes listed in axis_indices
Example
ethercat_stop(True) # make sure the ethercat master is stopped and clear the configured ethercat slaves... this makes the program start with a clean slate
axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start()
# do stuff
positions = ethercat_get_axis_positions()
textmsg(str_cat("Current actual encoder counts for axis1: ", to_str(positions.actual_position_counts[0])))
ethercat_stop(False) # stop the ethercat master only... don't clear the ethercat slaves
Getting MotionPlus Service Information
ethercat_is_service_responsive
ethercat_is_service_responsive(timeout = 0.5)
Description
Checks if the MotionPlus Service is responsive. This function returns True if the MotionPlus Service responds to a GetStatus XML-RPC call within the provided timeout
Parameter
Name |
Type |
Optional |
Description |
---|---|---|---|
timeout |
float |
Y |
Seconds to wait for method result before failing with error. Default: 0.5 |
Return
bool where True indicates the MotionPlus Service is responsive
Example
ret = ethercat_is_service_responsive() # would be True, if the service is responsive
Miscellaneous Utility Functions
time_sec()
Description: returns the current execution time of the UR Controller in seconds
Parameter: none
Return
float current execution time in seconds
Example
cur_time = time_sec()
textmsg(str_cat("Current time in seconds: ", to_str(cur_time)))
World Model Functions
Manipulate Coordinate Frames
add_frame
add_frame(name, pose, ref_frame="base")
Add a frame with the name name initialized at the specified pose expressed in the ref_frame coordinate frame. This command only adds a frame to the world, it does not attach it to the ref_frame coordinate frame. Use attach_frame() to attach the newly added frame to ref_frame if desired.
If being used with MotionPlus, the ref_frame argument can be the name of an external axis or axis group.
Parameters
name: name of the frame to be added. The name must not be the same as any existing world model object (frame, axis, or axis group), otherwise an exception is thrown
pose: initial pose of the new object
ref_frame: name of the world model object whose coordinate frame the pose is expressed in. If nothing is provided here, the default is the robot “base” frame.
attach_frame
attach_frame(child, parent)
Attaches the child frame to the parent world model object. The relative transform between the parent and child will be set such that the child does not move in the world when the attachment occurs.
The child cannot be “world”, “flange”, “tcp”, or the same as parent.
This will fail if child or parent is not an existing frame, or this makes the attachments form a closed chain.
If being used with the MotionPlus, the parent argument can be the name of an external axis or axis group.
Parameters
child: name of the frame to be attached. The name must not be “world”, “flange”, or “tcp”.
parent: name of the object that the child frame will be attached to.
Return: n/a
delete_all_frames
delete_all_frames()
Delete all frames that have been added to the world model.
The “world”, “base”, “flange”, and “tcp” frames cannot be deleted.
Any frames that are attached to the deleted frames will be attached to the “world” frame with new frame offsets set such that the detached frames do not move in the world.
delete_frame
delete_frame(name)
Delete the frame named frame from the world model.
The “world”, “base”, “flange”, and “tcp” frames cannot be deleted.
Any frames that are attached to the deleted frame will be attached to the “world” frame with new frame offsets set such that the detached frame does not move in the world.
This command will fail if the frame does not exist.
Parameters
name: name of the frame to be deleted
move_frame
move_frame(name, pose, ref_name)
Changes the placement of the coordinate frame named name to the new placement given by pose that is defined in the ref_name coordinate frame.
This will fail if name is “world”, “flange”, “tcp”, or if the frame does not exist. Note: to move the “tcp” frame, use the set_tcp() command instead.
If being used with the MotionPlus, the ref_name argument can be the name of an external axis or axis group.
Note
If used in conjunction with MotionPlus external axis and frame tracking, the move_frame() call will throw an exception and fail if the following is true: the frame being tracked is attached to the moving axis and the call to move_frame will change the tracked frame’s pose. This can occur if move_frame() is invoked on the tracked frame, or if the tracked frame is attached to another on which move_frame() is invoked. Here is an example of when move_frame would fail:
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,x], type=0, v_limit=1, a_limit=1, q_limits=[-1,1]) # add first axis
add_frame("AttachedFrame", p[0,0,0,0,0,0]) # add a new frame coincident with the robot base
attach_frame("AttachedFrame", "Axis1"), # attach the frame to the axis
frame_tracking_enable("AttachedFrame")
axis_group_movej("PartPositioner", [1]) # calling move_frame("AttachedFrame",...) during this call would fail
frame_tracking_disable()
Parameters
name: the name of the frame to move
pose: the new placement
ref_name: the coordinate frame that pose is expressed in. The default value is the robot’s “base” frame.
Example Commands:
*move_frame("frame1", p[0.2, 0.3, 0.1, 0, 0, 3.14])*
*move_frame("frame1", p[0.2, 0.3, 0.1, 0, 0, 3.14], ref_name="frame2")*
Get Coordinate Frame Properties
get_pose
get_pose(name, rel_frame="base", ref_frame=rel_frame)
Get the pose of the name frame relative to the rel_frame frame but expressed in the coordinates of the ref_frame frame. If ref_frame is not provided, then this returns the pose of the name frame relative to and expressed in the same frame as rel_frame.
This will fail if any arguments are not an existing frame.
If being used with MotionPlus, all three arguments can also be the names of external axes or axis groups.
Parameters
name: name of the frame to query.
rel_frame: short for “relative frame” is the frame where the pose is computed relative to
ref_frame: short for “reference frame” is the frame to express the coordinates of resulting relative pose in. If this is not provided, then it will default to match the value of rel_frame.
Return
The pose of the frame expressed in the ref_frame coordinates.
Example
Here is an example URScript:
# place the first frame 1m up in the "base" y axis and rotated -90 degrees around the "base" z axis.
add_frame("frame1", p[0, 1, 0, 0, 0, -pi/2], "base")
# place the second frame 1m in the "base" y axis, 1m in the "base" x axis and rotated -pi radians around the "base" z axis.
add_frame("frame2", p[1, 1, 0, 0, 0, -pi], "base")
# get the pose of frame2 relative to "frame1" and expressed in the "frame1" coordinates the return value is
# p[0, 1, 0, 0, 0, -pi/2] meaning that "frame2" is 1m in the "frame1" y axis and is rotated by -pi/2 radians about the "frame1"
# z axis.
p1to2in1 = get_pose("frame2", "frame1", "frame1")
# Get the pose of frame2 relative to frame1 but expressed in the coordinates of the "base" frame. The return value
# is p[1, 0, 0, 0, 0, -pi/2] meaning that "frame2" is 1m in the "base" frame x axis relative to "frame1" and is rotated
# -pi/2 radians in the "base" frame z axis relative to "frame1".
p1to2inbase = get_pose("frame2", "frame1", "base")
Here is a diagram that illustrates the frames in the prior example.
convert_pose
convert_pose(pose, from_frame, to_frame)
Convert pose from from_frame to to_frame.
This will fail if either coordinate system argument is not an existing frame.
If being used with MotionPlus, all three arguments can also be the names of external axes or axis groups.
Parameters
pose: pose to be converted
from_frame: name of reference frame at origin of old coordinate system
to_frame: name of reference frame at origin of new coordinate system
Return
Value of pose expressed in the coordinates of to_frame.
reset_world_model
Delete all frames, axis groups, and axes that were added to the world model. This also moves the robot’s base to the world origin.
Note
If any MotionPlus EtherCAT external axes are enabled, a call to reset_world_model() will automatically disable all axes.
is_frame
is_frame(name)
Queries for the existence of a frame by the given name.
Parameters
name: name of the frame to be queried.
Return: Returns true if there is a frame by the given name, false if not.
Example Commands:
add_frame(“frame1”, p[0.2, 0.3, 0.1, 0, 0, 3.14])
is_frame(“frame1”) # true
is_frame(“frame99”) # false
get_frame_parent
get_frame_parent(name)
Get the parent of the frame named name in the world model.
If the frame is not attached to another frame, then “world” is the parent.
Parameters
name: the frame being queried
Return
name of the parent as a string
get_children
get_children(name)
Returns a list of immediate child object frame names. Parent-child relationships are defined by wold model attachments. If being used with MotionPlus, the child objects may also be an axis group or an axis.
Parameters
name: the name of the parent object.
Example Commands:
get_children("world")
# ["base"]
attach_frame("user_frame1", "base")
attach_frame("user_frame2", "user_frame1")
get_children("base")
# ["flange", "user_frame1"]
Frame Tracking
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.
Warning
Important: there are some motion blends that are currently not supported when frame tracking is enabled to track an external axis. Please see known issues for more info.
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 tool flange in some way.
Return: n/a
Example
This shows a MotionPlus 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
Here is an example URScript which smoothly traces out a square which is rotating and translating:
global center = p[0.5, 0.0, 0.2, 3.14159, 0, 0]
length = 0.2
l = length / 2
global velocity = 0.005
global delta = velocity / (500)
add_frame("center", center)
add_frame("corner1", p[l, l, 0, 0, 0, 0], "center")
add_frame("corner2", p[-l, l, 0, 0, 0, 0], "center")
add_frame("corner3", p[-l, -l, 0, 0, 0, 0], "center")
add_frame("corner4", p[l, -l, 0, 0, 0, 0], "center")
attach_frame("center", "base")
attach_frame("corner1", "center")
attach_frame("corner2", "center")
attach_frame("corner3", "center")
attach_frame("corner4", "center")
global running = True
thread duration():
steps = 0
while (True):
if (steps > 10000):
running = False
break
end
steps = steps + 1
sync()
end
end
thread tracking():
dy = 0
dz = 0
rz = 0
frame_tracking_enable("center")
while (running):
dy = dy + delta
dz = dz + delta
rz = rz - 12 * delta
newCenter = p[center[0], center[1] + dy, center[2] + dz, center[3], center[4], center[5]]
move_frame("center", newCenter) # translate center within the world
move_frame("center", p[0, 0, 0, 0, 0, rz], "center") # rotate about itself
sync()
end
end
frame_tracking_enable("center")
looping = True
movel("center")
did = run duration()
tid = run tracking()
while (running):
vel = 0.1
movel("corner2", v=vel)
movel("corner3", v=vel)
movel("corner4", v=vel)
movel("corner1", v=vel)
end
frame_tracking_disable()
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.
Mass Properties
set_mass_properties
set_mass_properties(frame, m, cog, inertia)
Set mass properties (including mass m, center of gravity cog, and inertia matrix inertia) of the frame.
Parameters
frame: Name of the frame to set mass properties to
m: Mass (in kg)
cog: Center of Gravity, a vector with three elements [CoGx, CoGy, CoGz] specifying the offset (in meters) from the frame origin.
inertia: Inertia matrix (in kg*m^2), as a vector with six elements [Ixx, Iyy, Izz, Ixy, Ixz, Iyz] with origin in the CoG and the axes aligned with the frame axes
set_payload_from_attached_frames
set_payload_from_attached_frames()
Set the payload based on the attached frames. This will compute the effective mass and inertia from frames on an attachment chain to the TCP and set it as the payload. This is an alternative to manually computing the payload and using set_target_payload.
Changes to Existing URScript Functions
movec - new behavior
movec(pose_via, pose_to, a, v, r, mode)
new behavior added to: In addition to existing behavior, the pose_via and pose_to arguments can now also be provided as a frame, axis, or axis group name or a struct of the form struct(pose=p[…], frame=”…”) where the frame struct element indicates what reference frame, axis, or axis group the pose struct element is represented in. The robot will resolve the pose_via and pose_to arguments into the base frame of the robot at the time of the movec call.
Changes to Parameters
pose_via: target via position. Can now be provided as a frame, axis, or axis group name or a struct of the form struct(pose=p[…], frame=”…”) where the frame struct element indicates what reference frame, axis, or axis group the pose struct element is represented in.
pose_to: target end position. Can now be provided as a frame, axis, or axis group name or a struct of the form struct(pose=p[…], frame=”…”) where the frame struct element indicates what reference frame, axis, or axis group the pose struct element is represented in.
(All other arguments and their default parameters are unchanged.)
Example Command: using frame name as arguments
add_frame("frame_via", p[0.2, 0.3, 0.1, 0, 0, 3.14])
add_frame("frame_to", p[0.1, 0.1, 0.1, 0, 0, 0])
movec("frame_via", "frame_to") # uses the frame names as via and to arguments*
Example Command: using a struct as arguments
add_frame("ref_frame", p[0.1, 0.1, 0.1, 0, 0, 0])
pose_via_struct = struct(pose=p[0.1, 0, 0, 0, 0, 0], frame="ref_frame")
pose_to_struct = struct(pose=p[0.1, 0.1, 0.1, 0, 0, 0], frame="ref_frame")
movec(pose_via_struct , pose_to_struct) # uses poses defined in the "ref_frame" frame for pose_via and pose_to*
movej - new behavior
movej(goal, a, v, t, r)
In addition to existing behavior, the goal argument can now also be provided as a frame, axis, or axis group name or a struct of the form struct(pose=p[…], frame=”…”) where the frame struct element indicates what reference frame, axis, or axis group the pose struct element is represented in. When these new argument types are provided, their pose is resolved to the base frame of the robot at the time of the call and the movej joint angle goal is determined via inverse kinematics.
Changes to Parameters
goal: target position. Can now be provided as a frame, axis, or axis group name or a struct of the form struct(pose=p[…], frame=”…”) where the frame struct element indicates what reference frame, axis, or axis group the pose struct element is represented in.
(All other arguments and their default parameters are unchanged.)
Example Command: using frame name as arguments
add_frame(“frame”, p[0.2, 0.3, 0.1, 0, 0, 3.14])
movej(“frame”) # uses “frame” as the goal argument
Example Command: using a struct as arguments
goal_struct = struct(pose=p[0.1, 0, 0, 0, 0, 0], frame="frame")
movej(goal_struct)
movel - new behavior
movel(goal, a, v, t, r)
In addition to existing behavior, the goal argument can now also be provided as a frame, axis, or axis group name or a struct of the form struct(pose=p[…], frame=”…”) where the frame struct element indicates what reference frame, axis, or axis group the pose struct element is represented in. When these new argument types are provided, their pose is resolved to the base frame of the robot at the time of the call and used as the goal waypoint to the movel command.
Changes to Parameters
goal: target position. Can now be provided as a frame, axis, or axis group name or a struct of the form struct(pose=p[…], frame=”…”) where the frame struct element indicates what reference frame, axis, or axis group the pose struct element is represented in.
(All other arguments and their default parameters are unchanged.)
Example Command: using frame name as arguments
add_frame("newframe", p[0.2, 0.3, 0.1, 0, 0, 3.14])
movel("newframe")
Example Command: using a struct as arguments
add_frame("newframe", p[0.2, 0.3, 0.1, 0, 0, 3.14])
goal=struct(pose=p[1,0,0,0,0,0], frame="newframe")
movel(goal)
movep - new behavior
movep(goal, a, v, r)
In addition to existing behavior, the goal argument can now also be provided as a frame, axis, or axis group name or a struct of the form struct(pose=p[…], frame=”…”) where the frame struct element indicates what reference frame, axis, or axis group the pose struct element is represented in. When these new argument types are provided, their pose is resolved to the base frame of the robot at the time of the call and used as the goal waypoint to the movep command.
Changes to Parameters
goal: target position. Can now be provided as a frame, axis, or axis group name or a struct of the form struct(pose=p[…], frame=”…”) where the frame struct element indicates what reference frame, axis, or axis group the pose struct element is represented in.
(All other arguments and their default parameters are unchanged.)
Example Command: using frame name as arguments
add_frame("frame", p[0.2, 0.3, 0.1, 0, 0, 3.14])
movep("frame")
Example Command: using a struct as arguments
add_frame("newframe", p[0.2, 0.3, 0.1, 0, 0, 3.14])
goal=struct(pose=p[1,0,0,0,0,0], frame="newframe")
movep(goal)
path_offset_set - new behavior
path_offset_set(offset, type)
The path offset function is now aware of frame tracking external axes when MOTION type is selected and a new type called “WORLD MODEL” has been added.
Changes to Parameters
type: Specifies how to apply the given offset. Changes to options are:
3 - (MOTION) When used at the same time as frame tracking an external axis (see frame_tracking_enable()), the TCP velocity vector used to compute the motion frame is measured in the tracked frame.
5 - (WORLD MODEL) The offset argument is provided as a struct of the form struct(offset=[…], frame=”…”) where the offset struct element is an array (not a pose) and is defined in the coordinates of the provided reference frame given by the frame struct element. The pose of the frame element is resolved to the base frame of the robot at the time of the call.
(All other arguments and their default parameters are unchanged.)
Example Command:
The following example uses a harmonic wave (cosine) to offset the position of the TCP along the Z-axis of the specified frame named “waypoint” using the WORLD MODEL mode
thread OffsetThread():
while(True):
#2Hz cosine wave with an amplitude of 5mm
global x = 0.005*(cos(p) - 1)
global p = p + 4*3.14159/500
offset_type = 5 # WORLD MODEL mode
path_offset_set(struct(offset=[0, 0, x, 0, 0, 0], frame="waypoint"), offset_type)
sync()
end
end
speedl - new behavior
speedl(xd, a, t, aRot)
The tool speed xd can now be a struct of the form struct(vel=[…], frame=”…”) where the frame struct element indicates what reference frame, axis, or axis group the vel struct element is represented in. The pose of the frame element is resolved to the base frame of the robot at the time of the call.
Changes to Parameters
xd: tool speed. The argument can be a struct of the form struct(vel=[…], frame=”…”) where the frame struct element indicates what reference frame, axis, or axis group the vel struct element is represented in.
> (All other arguments and their default parameters are unchanged.)
Example Command:
add_frame("newframe", p[0.2, 0.3, 0.1, 0, 0, 3.14])
xd_struct=struct(vel=[1,0,0,0,0,0], frame="newframe")
speedl(xd_struct)