World Model API

URScript 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.

img


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)