MotionPlus Introduction

The MotionPlus product aims to provide a simple and accurate way for customers to integrate external axes with their UR robots. This work is limited to external axes that maneuver a part which the robot is performing some operation on.

This product will enable our customers to create programs that perform coordinated motion with external axis. This is critical for part positioners used in welding, which is our main focus application.

Target Application

This introduction is focused on part positioners for welding applications where the part being welded is placed on a positioning system that maneuvers the part while it is being welded.

Target Customer

This product is aimed at OEMs to incorporate into their existing URCaps.

Components

The product is divided into two components:

  1. Controller URScript API

  2. EtherCAT URCap. (The EtherCAT URCap also contains an EtherCAT-specific URScript API.)

Controller URScript API

The controller provides a URScript API that enables customers to:

  • build the kinematics of a group of external axes (we loosely follow nomenclature from the PLCOpen standard)

  • jog external axes with desired target positions or velocities

  • perform frame tracking with a moving axis

  • synchronize the timing of the robot and external axes

  • perform coordinated motion with external axes by combining frame tracking and timing synchronization

  • calibrate axis relative to the robot

  • integrate with new World Model & Kinematic Tree features

On its own, the controller only generates and publishes target setpoints for the external axes. The setpoints are also published over RTDE an internal non-public (for now) message bus. The controller relies on other components to perform the lower level communication with hardware using the published target setpoints. For this product, we created an EtherCAT URCap that implements lower level EtherCAT communication of the controller’s target setpoints. The EtherCAT component utilizes the non-public message bus.

More details can be found in this document and the URScript manual here: MotionPlus URScript Manual

EtherCAT URCap

The URCap handles the lower-level communication with EtherCAT hardware. The URCap include three sub-components:

  1. A Polyscope installation page GUI for setting up/starting EtherCAT communication.

  2. A daemon that runs alongside the UR controller and handles low-level EtherCAT communication.

  3. A URScript API that enables programmers to manage EtherCAT communication with external axes in their own applications.

More details can be found in this document and the EtherCAT URCap manual here: MotionPlus EtherCAT URCap Manual

Background & Terminology

World Model & Kinematic Tree

A new set of features as of Polyscope 5.16 that adds a URScript API for manipulating coordinate frames as objects. New capabilities include the ability to attach coordinated frames together, move them, and perform robot motion relative to them in real-time. MotionPlus is designed to work seamlessly with the world model feature. See the world model page for details and descriptions of poses, coordinate frames, and reference coordinated frames.

External Axis

A mechanical component that can produce motion. It has a motor controller that can accept position/velocity commands. An axis is “external” if it is not one of the robot’s native joints. In the controller’s world model, an external axis has properties that include:

  • unique string name identifier

  • parent axis or axis group

  • a pose relative to th fAxise parent

  • type (rotary or linear) - please see limitations for additional info on supported types

  • acceleration limits

  • velocity limits

  • position limits

  • a unique integer index

Axis Group

A set of related axes that are commanded together.

Note

We are loosely following the terminology used the PLCopen Motion Control Part 4 standard available for free download here. In practice, an axis group will likely constitute a physical system. For example, a two-axis welding part positioner would typically be defined as a single axis group that contains two axes. However, an axis group can also be an abstract concept where multiple axes from separate physical systems could be incorporated into an axis group for the purpose of controlling them together. In the controller’s world model, an axis group has properties that include:

  • a unique string name identifier

  • child axes - please see limitations for additional info on supported number of axes

  • a pose

Time Synchronization

The robot and axis group move simultaneously and complete their desired motions at the same time. For example, the TCP of a robot’s welding torch must reach its programmed waypoint at the same time as the programmed pose of a welding part positioner. Synchronizing the timing of the part positioner is accomplished by varying its axes velocities. See more details here.

Frame Tracking

The robot adjusts its trajectory at each timestep based on the instantaneous joint positions of the axis group. For example, the TCP of the robot’s welding torch needs to follow a trajectory in the moving frame of a welding part positioner. This is accomplished with frame tracking. See more details here.

Coordinated Motion

The combination of Time Synchronization and Frame Tracking defines coordinated motion. The TCP moving within the part frame, with the robot and external axis reaching the targeted position(s) simultaneously. See more details here.

Axis Index

The axis index is a unique identifier that specifies where an axis’ data is placed in the target position and actual position vectors streamed over RTDE.

Overview of What’s New

As of Polyscope 5.16, programmers will be able to control external axes natively in URScript programs. The new feature set will enable programmers to easily write programs that do time synchronization, frame tracking, and coordinated motion with external axes.

Setting Up External Axis Kinematics

The URScript API lets programmers create their external axis system by adding axes to the controller’s world model and organizing them into axis groups.

Note

Please see limitations for additional info on supported external axis types and the number of supported axes that can be controlled.

The API supports:

  • Configuring axes a tree kinematics that does not create a closed kinematic chain - see limitations.

  • Giving axes unique string name identifiers that can be used throughout URScript programs

  • Configuring axes as rotary (e.g., a welding part positioner) or linear (e.g., a linear rail) - see limitations.

  • Setting axis position, velocity, and acceleration limits

  • Set the pose of the axes in their “zero-configuration” when their joint positions are 0. In practice, these poses would be calibrated from a physical system.

  • Configure the axes into named axis groups

  • Delete an axis group from the controller’s world model. This is useful if an axis needs to be placed into a different axis group so that it can move in concert with a different combination of axes. The supported process is to delete axis group and then construct a new one with the relevant axes.

  • Update the properties of an axis in the controller’s world model. This is useful if a calibration needs to be adjusted or the range of motion needs to be changed in the middle of a program.

Relevant commands from the URScript API include:

  • axis_group_add

  • axis_group_delete

  • axis_group_add_axis

  • axis_group_update_axis

Relevant examples include:

Configuring an Axis For EtherCAT

EtherCAT functionality is enabled through the EtherCAT URCap. The URCap contains a daemon that handles the low-level communication with the EtherCAT axes. While a program is running, the controller and daemon communicate “behind the scenes” to pass the computed axis target positions and actual positions back and forth. The only responsibility of the customer developer is to call the appropriate URScript functions to start/stop ethercat communication, configure created axes as EtherCAT axes, and enable them when it is time for them to move.

Relevant commands from the URScript API include:

  • ethercat_start

  • ethercat_stop

  • ethercat_config_axis

  • ethercat_enable_axis

  • ethercat_disable_axis

Relevant examples include:

Jogging an External Axis

The URScript API provides two functions to implement jogging:

  • axis_group_movej drives the axes that are part of a group to the desired joint positions. It generates trapezoidal velocity profiles where the joint accelerations and velocities are scaled so that the desired axis targets are reached simultaneously (the axis with the most constraining acceleration/velocity limits governs the scaling factors for the rest of the axes in the group).

  • axis_group_speedj commands the axes to accelerate to target velocities. It generates trapezoidal velocity profiles and scales the accelerations so that the desired axis velocities of the group are all reached simultaneously.

Both functions can be safely called in URScript threads to implement simultaneous motion of the robot and any axis groups that are part of the world model. If a thread is killed (e.g. using the kill URScript command) while an axis_group_movej or axis_group_speedj is still in motion, the controller will stop any moving axes with their maximum allowable deceleration unless another URScript function immediately takes control over them (e.g., another call to axis_group_movej or *axis_group_speedj*).

Relevant commands from the URScript API include:

  • axis_group_movej

  • axis_group_speedj

Relevant examples include:

Frame Tracking with External Axes

Frame tracking is a mode that we implemented to command the robot to perform motion trajectories defined in a moving frame. It’s enabled and disabled in URScript using:

  • frame_tracking_enable

  • frame_tracking_disable

The frame_tracking_enable call accepts the name of the frame to track, which can be the name of an axis, the name of a frame attached to an axis, or any frame in the world model. All robot motions performed after the call to frame_tracking_enable and before the call to frame_tracking_disable will be performed in the frame provided in the call to frame_tracking_enable. As an example

frame_tracking_enable("axis1")
movel(struct(pose=p[1,0,0,0,0,0], frame="axis1"), ...)
frame_tracking_disable()

would move the TCP to 1m in the x direction of the “axis1” frame and track the “axis1” frame if it moves.

Relevant examples include:

Time Synchronization with External Axes

We have implemented variants of the UR robot motion commands (movep, movec, etc.) that execute robot motion and drive an axis group to target positions so that the axes’ reach their targets at the same time as the robot reaches its target. These commands are

  • movep_with_axis_group

  • movec_with_axis_group

  • movel_with_axis_group

  • movej_with_axis_group

  • servoj_with_axis_group

Note

These commands only synchronize robot and axes motion in time. We have also implemented full coordinated motion as described here.

Relevant examples include:

Coordinated Motion with External Axes

Coordinated motion can be achieved with the simultaneous use of frame tracking and our time synchronized motion commands together. For example, this script:

frame_tracking_enable("axis1")

movep_with_axis_group(struct(pose=p[1,0,0,0,0,0], frame="axis1"), ..., group="mygroup", axis_targets=[3.1415])

frame_tracking_disable()

would move the TCP to a position 1m in the x direction of the “axis1” frame while rotating the axis (assuming “axis1” is the only axis added to the axis group “mygroup”) 180 degrees. The axis would arrive at its goal of 180 degrees at the same time as the TCP arriving at it’s goal and the TCP would simultaneously track with the “axis1” frame rotation motion.

Relevant examples include:

Streamed Axis Targets and Actuals

The target and actual axes positions are streamed via RTDE. Here is a description of the new RTDE fields:

name

type

comment

target_external_q

VECTOR6D

this stores the target position commands that the controller generates for the external axes

actual_external_q

VECTOR6D

this stores the actual positions of the external axes as reported by the encoders

The VECTOR6D structure contains a position for each axis. If axes are not used, the VECTOR6D contains zero for that index.

Integration with World Model & Kinematic Tree

We are working to fully integrate the part positioner and kinematic tree products so they work seamlessly together. This work is not fully complete.

Attaching Axes and Groups to the Kinematic Tree: There are some important limitations of the current integration that are important to know. The first is that world model frames (created using the add_frame command) can be attached to axes and groups, but not vice versa. Here is a table showing what can be attached to one another.

World Model & Axis Group Attachment Policy

frame

group

axis

can attach frame to

yes, with attach_frame

yes, with attach_frame

yes, with attach_frame

can attach group to

no, except groups are attached to “world” during construction

no

no

can attach axis to

no

yes, by construction with axis_group_add_axis

yes, by construction with axis_group_add_axis

Using Axes and Groups in World Model Functions: Many world model functions have been expanded to take names of axes and groups as arguments. Here is a list of world model functions that can take either an axis or group name in arguments:

  • get_pose: any of the arguments can be an axis or group name

  • convert_pose: any of the arguments can be an axis or group name

  • add_frame: the ref_frame argument can be an axis or group name

  • attach_frame: the parent argument can be an axis or group name

  • move_frame: the ref_frame argument can be an axis or group name

  • movec: if providing structs as arguments for pose_via or pose_to, the “frame” struct member can be an axis or group name. If providing string names for pose_via or pose_to, the string names can also be axes or group names.

  • movej: if providing a struct for the goal argument, the “frame” struct member can be an axis or group name. If providing a string name for goal, the string name can be an axis or group name.

  • movel: if providing a struct for the goal argument, the “frame” struct member can be an axis or group name. If providing a string name for goal, the string name can be an axis or group name.

  • movep: if providing a struct for the goal argument, the “frame” struct member can be an axis or group name. If providing a string name for goal, the string name can be an axis or group name.

  • speedl: if providing a struct for the xd argument, the “frame” struct member can be an axis or group name.

Relevant examples include:

Known Limitations

Ethernet Adapters

We no longer recommend using an USB-Ethernet adapter for EtherCAT due to communication stability problems. Only the use of the control box primary ethernet port is supported for EtherCAT. See here for more info and details on integrating into applications that also require TCP/IP communication with the robot.

Axis Quantity and Type

Motion Plus V1.1 supports only rotational (i.e., type=0 when calling axis_group_add_axis()) and up to four axes can be configured. A beta version of the product includes up to six axes that can be rotational or linear.

Axis Kinematics

Motion Plus V1.1 supports a serial kinematic structure that is at most two axes deep. For example, a multi-axis welding part positioner with two axes connected to one another (e.g., a L-type skyhook, pan-tilt positioner, etc.) is supported. Whereas a multi-axis positioner with three axes connected in series would not be supported. A beta version of the product supports kinematic structures of any arrangement provided they contain no kinematic loops (e.g., an axis connects to another that connects back to the first).

Axis Group Motion

Motion Plus V1.1 supports only one axis group moving at a time. A beta version of the product supports any number.

Frame Tracking

Kinematic Singularities

When frame tracking has been turned on (see frame_tracking_enable), moving the robot through a kinematic singularity using any move command (e.g., movej, servoj, etc.) can cause unexpected jumps in acceleration. These can cause a protective stop if large enough or they may cause an audible noise. Guidance on avoiding kinematic singularities can be found here.

Motion Blends

When frame tracking has been turned on to track an external axis (see frame_tracking_enable), the following blends are not yet implemented:

  • movej or movej_with_axis_group to movep, movep_with_axis_group, movec, or movec_with_axis_group

  • movel or movel_with_axis_group to movep, movep_with_axis_group, movec, or movec_with_axis_group

ServoJ with Axis Group

The servoj_with_axis_command cannot currently accept a time duration argument t that is not a multiple of the controller’s timestep (0.002s)

Calling MotionPlus EtherCAT URScript API Functions by Third-Party URCaps

The functions provided by the EtherCAT URScript API can be called by third-party URCaps with some considerations. Please see here for details.

Calls to EtherCAT URScript API over the secondary interface are not supported.