Script Manual G5
Script Manual G5
for SW5
5.14
The information contained herein is the property of Universal Robots A/S and shall not be
reproduced in whole or in part without prior written approval of Universal Robots A/S. The
information herein is subject to change without notice and should not be construed as a
commitment by Universal Robots A/S. This document is periodically reviewed and revised.
Universal Robots A/S assumes no responsibility for any errors or omissions in this document.
Copyright © 2009–2023 by Universal Robots A/S.
The Universal Robots logo is a registered trademark of Universal Robots A/S.
Contents
1. Introduction 1
2. Connecting to URControl 2
3. Numbers, Variables, and Types 3
4. Matrix and Array Expressions 4
5. Flow of Control 6
5.1. Special keywords 6
6. Function 7
7. Remote Procedure Call (RPC) 9
7.1. closeXMLRPCClientConnection() 10
13.1.19. get_target_tcp_pose_along_path() 32
13.1.20. get_target_tcp_speed_along_path() 32
13.1.21. movec(pose_via, pose_to, a=1.2, v=0.25, r =0, mode=0) 32
13.1.22. movej(q, a=1.4, v=1.05, t=0, r =0) 33
13.1.23. movel(pose, a=1.2, v=0.25, t=0, r=0) 34
13.1.24. movep(pose, a=1.2, v=0.25, r=0) 35
13.1.25. path_offset_disable(a=20) 35
13.1.26. path_offset_enable() 35
13.1.27. path_offset_get(type) 36
13.1.28. path_offset_set(offset, type) 36
13.1.29. path_offset_set_alpha_filter(alpha) 37
13.1.30. path_offset_set_max_offset(transLimit, rotLimit) 38
13.1.31. pause_on_error_code(code, argument) 38
13.1.32. position_deviation_warning(enabled, threshold=0.8) 38
13.1.33. reset_revolution_counter(qNear=[0.0, 0.0, 0.0, 0.0, 0.0, 0.0]) 39
13.1.34. screw_driving(f, v_limit) 39
13.1.35. servoc(pose, a=1.2, v=0.25, r=0) 40
13.1.36. servoj(q, a, v, t=0.002, lookahead_time=0.1, gain=300) 41
13.1.37. set_conveyor_tick_count(tick_count, absolute_encoder_resolution=0) 42
13.1.38. set_pos(q) 43
13.1.39. set_safety_mode_transition_hardness(type) 43
13.1.40. speedj(qd, a, t) 43
13.1.41. speedl(xd, a, t, aRot=’a’) 44
13.1.42. stop_conveyor_tracking(a=20) 44
13.1.43. stopj(a) 45
13.1.44. stopl(a, aRot=’a’) 45
1. Introduction
The Universal Robot can be controlled at two levels:
• The PolyScope or the Graphical User Interface Level
• Script Level
At the Script Level, the URScript is the programming language that controls the robot.
The URScript includes variables, types, and the flow control statements. There are also built-in
variables and functions that monitor and control I/O and robot movements.
2. Connecting to URControl
URControl is the low-level robot controller running on the Embedded PC in the Control Box cabinet.
When the PC boots up, the URControl starts up as a daemon (i.e., a service) and the PolyScope or
Graphical User Interface connects as a client using a local TCP/IP connection.
Programming a robot at the Script Level is done by writing a client application (running at another
PC) and connecting to URControl using a TCP/IP socket.
Hostname: ur-<serial number> (or the IP address found in the About Dialog-Box in PolyScope if the
robot is not in DNS).
• port: 30002
When a connection has been established URScript programs or commands are sent in clear text on
the socket. Each line is terminated by “\n”. Note that the text can only consist of extended ASCII
characters.
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
The following conditions must be met to ensure that the URControl correctly recognizes the script:
• The script must start from a function definition or a secondary function definition (either
"def" or "sec" keywords) in the first column
• All other script lines must be indented by at least one white space
• The last line of script must be an "end" keyword starting in the first column
Important:
It is recommended to always read data from the socket. At least 79 bytes have to be read from
socket before closing to ensure that underlying TCP protocol closes socket orderly. Otherwise data
sent from client may be discarded before script is executed.
It is especially important in cases when socket is opened just to send single script, and closed
immediately.
It is recommended to keep sockets open instead of opening end closing for each and every
request.
A pose is given as p[x,y,z,ax,ay,az], where x,y,z is the position of the TCP, and ax,ay,az
is the orientation of the TCP, given in axis-angle notation.
Note that strings are fundamentally byte arrays without knowledge of the encoding used for the
characters it contains. Therefore some string functions that may appear to operate on characters
(e.g. str_len), actually operates on bytes and the result may not correspond to the expected one
in case of string containing sequences of multi-byte or variable-length characters. Refer to the
description of the single function for more details.
matrix = [[1,2],[3,4],[5,6]]
b = matrix[0,0]
matrix[2,1] = 20
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
add1 = [1,2,3] + 10
add2 = 10 + [1,2,3]
sub1 = [10,20,30] - 5
sub2 = 5 - [[10,20],[30,40]]
mod1 = [11,22,33] % 5
mod2 = 121 % [[10,20],[30,40]]
5. Flow of Control
The flow of control of a program is changed by if-statements:
if a > 3:
a = a + 1
elif b < 7:
b = b * a
else:
a = a + b
end
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
and while-loops:
l = [1,2,3,4,5]
i = 0
while i < 5:
l[i] = l[i]*2
i = i + 1
end
You can use break to stop a loop prematurely and continue to pass control to the next iteration
of the nearest enclosing loop.
return returns from a function. When no value is returned, the keyword None must follow the
keyword return.
6. Function
A function is declared as follows:
return a+b
end
def add(a=0,b=0):
return a+b
If default values are given in the declaration, arguments can be either input or skipped as below:
result = add(0,0)
result = add()
When calling a function, it is important to comply with the declared order of the ar- guments. If the
order is different from its definition, the function does not work as ex- pected.
Arguments can only be passed by value (including arrays). This means that any modi- fication done
to the content of the argument within the scope of the function will not be reflected outside that
scope.
def myProg()
a = [50,100]
fun(a)
def fun(p1):
p1[0] = 25
assert(p1[0] == 25)
...
end
assert(a[0] == 50)
...
end
if (! camera.initialize("RGB")):
target = camera.getTarget()
camera.closeXMLRPCClientConnection()
...
First the rpc_factory (see Interfaces section) creates an XMLRPC connection to the
specified remote server. The camera variable is the handle for the remote function calls. You must
initialize the camera and therefore call camera.initialize("RGB").
The function returns a boolean value to indicate if the request was successful. In order to find a
target position, the camera first takes a picture, hence the camera.takeSnapshot() call. Once
the snapshot is taken, the image analysis in the remote site calculates the location of the target.
Then the program asks for the exact target location with the function call target =
camera.getTarget(). On return the target variable is as- signed the result. The
camera.initialize("RGB"), takeSnapshot() and getTarget() functions are the
responsibility of the RPC server.
The closeXMLRPCClientConnection is closing the XMLRPC connection created by the rpc_
factory. It is recommended to close the connection periodically, or when it's not used for a
longer time. Some server implementations by default have a limit of rpc requests or inactivity
watchdog timers.
NOTE: The RPC handle does not automatically close the connecetion.
The technical support website: http://www.universal-robots.com/support contains more examples
of XMLRPC servers.
7.1. closeXMLRPCClientConnection()
8. Scoping rules
A URScript program is declared as a function without parameters:
def myProg():
end
Every variable declared inside a program has a scope. The scope is the textual region where the
variable is directly accessible. Two qualifiers are available to modify this visibility:
• local qualifier tells the controller to treat a variable inside a function, as being truly local,
even if a global variable with the same name exists.
• global qualifier forces a variable declared inside a function, to be globally accessible.
For each variable the controller determines the scope binding, i.e. whether the variable is global or
local. In case no local or global qualifier is specified (also called a free variable), the controller will
def myProg():
global a = 0
def myFun():
local a = 1
...
end
...
end
Beware that the global variable is no longer accessible from within the function, as the local
variable masks the global variable of the same name.
In the following example, the first a is a global variable, so the variable inside the function is the
same variable declared in the program:
def myProg():
global a = 0
def myFun():
a = 1
...
end
...
end
For each nested function the same scope binding rules hold. In the following example, the first a is
global defined, the second local and the third implicitly global again:
def myProg():
global a = 0
def myFun():
local a = 1
def myFun2():
a = 2
...
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
end
...
end
...
end
The first and third a are one and the same, the second a is independent.
Variables on the first scope level (first indentation) are treated as global, even if the global
qualifier is missing or the local qualifier is used:
def myProg():
a = 0
def myFun():
a = 1
...
end
...
end
9. Threads
Threads are supported by a number of special commands.
To declare a new thread a syntax similar to the declaration of functions are used:
thread myThread():
# Do some stuff
return False
end
A couple of things should be noted. First of all, a thread cannot take any parameters, and so the
parentheses in the declaration must be empty. Second, although a return statement is allowed in
the thread, the value returned is discarded, and cannot be accessed from outside the thread.
A thread can contain other threads, the same way a function can contain other functions. Threads
thread myThread():
# Do some stuff
return False
end
The value returned by the run command is a handle to the running thread. This handle can be used
to interact with a running thread. The run command spawns from the new thread, and then
executes the instruction following the run instruction.
A thread can only wait for a running thread spawned by itself. To wait for a running thread to finish,
use the join command:
thread myThread():
# Do some stuff
return False
end
join thrd
This halts the calling threads execution, until the specified thread finishes its execution. If the
thread is already finished, the statement has no effect.
To kill a running thread, use the kill command:
thread myThread():
# Do some stuff
return False
end
kill thrd
After the call to kill, the thread is stopped, and the thread handle is no longer valid. If the thread has
children, these are killed as well.
To protect against race conditions and other thread-related issues, support for critical sections is
provided. A critical section ensures the enclosed code can finish running before another thread can
start running. The previous statement is always true, unless a time-demanding command is
present within the scope of the critical section. In such a case, another thread will be allowed to
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
thread myThread():
enter_critical
# Do some stuff
exit_critical
return False
end
1Before the start of each frame the threads are sorted, such that the thread with the largest
remaining time slice is to be scheduled first.
Each time a thread is scheduled, it can use a piece of its time slice (by executing instructions that
control the robot), or it can execute instructions that do not control the robot, and therefore do not
use any “physical” time. If a thread uses up its entire time slice, either by use of “physical” time or
by computational heavy instructions (such as an infinite loop that do not control the robot) it is
placed in a non-runnable state, and is not allowed to run until the next frame starts. If a thread does
not use its time slice within a frame, it is expected to switch to a non-runnable state before the end
of 1. The reason for this state switching can be a join instruction or simply because the thread
terminates.
It should be noted that even though the sleep instruction does not control the robot, it still uses
“physical” time. The same is true for the sync instruction. Inserting sync or sleep will allow time
for other threads to be executed and is therefore recommended to use next to computational
heavy instructions or inside infinite loops that do not control the robot, otherwise an exception like
"Lost communication with Controller" can be raised with a consequent protective stop.
$ 2 "var_1= True"
set_digital_out(1,True)
end
When the last statement received is executed, the interpreter thread will be idle until new
statements are received.
Interpreter mode can be stopped by calling end_interpreter() over the interpreter mode
socket, or by calling it from a thread in the main program. Interpreter mode also stops when the
program is stopped.
Each statement should be sent in a single line, so the following statement:
def myFun():
mystring = "Hello Interpreter"
textmsg(mystring)
end
Should be formatted like below:
def myFun(): mystring = "Hello Interpreter" textmsg(mystring) end
With a newline character to end the statement. Multiple statements can be sent on a single line,
and will only be accepted if all can be compiled.
Note: There exists an upper limit to the size of the interpreted statements per interpreter mode. To
avoid reaching that limit clear_interpreter() can be called to clear up everything interpreted
into the current interpreter mode.
Important: It is important to remember that every time a statement is interpreted the size and the
complexity of the program will grow if interpreter mode is not cleared either on exit or with clear_
interpreter(). Too large programs should be avoided.
Ends the interpreter mode, and causes the interpreter_mode() function to return. This
function can be compiled into the program by sending it to the interpreter socket(30020) as any
other statement, or can be called from anywhere else in the program.
By default everything interpreted will be cleared when ending, though the state of the robot, the
modifications to local variables from the enclosing scope, and the global variables will remain
affected by any changes made. The interpreter thread will be idle after this call.
Clears all interpreted statements, objects, functions, threads, etc. generated in the current
interpreter mode. Threads started in current interpreter session will be stopped, and deleted.
Variables defined outside of the current interpreter mode will not be affected by a call to this
function.
Only statements interpreted before the clear_interpreter() function will be cleared.
Statements sent after clear_interpreter() will be queued. When cleaning is done, any
statements queued are interpreted and responded to. Note that commands such as abort,
skipbuffer and state commands are executed as soon as they are received.
Note: This function can only be called from an interpreter mode.
Tip: To expedite the clean, skipbuffer can be sent right before clear_interpreter().
The interpreter mode offers a mechanism to abort limited number of script functions, even if
they are called from the main program. Currently only movej and movel can be aborted.
Aborting a movement will result in a controlled stop if no blend radius is defined.
If a blend radius is defined then a blend with the next movement will be initiated right away if
not already in an initial blend, otherwise the command is ignored.
Return value should be ignored
Note: abort must be sent in a line by itself, and thus cannot be combined with other
commands or statements.
The interpreter mode furthermore supports the opportunity to skip already sent but not
executed statements. The interpreter thread will then (after finishing the currently executing
statement) skip all received but not executed statements.
After the skip, the interpreter thread will idle until new statements are received. skipbuffer
will only skip already received statements, new statements can therefore be send right away.
Return value should be ignored
Note: skipbuffer must be sent in a line by itself, and thus cannot be combined with other
commands or statements.
statelastexecuted
Replies with the largest id of a statement that has started being executed.
state: <id>: statelastexecuted
statelastinterpreted
Replies with the latest interpreted id, i.e. the highest number of interpreted statement so far.
state: <id>: statelastinterpreted
statelastcleared
Replies with the id for the latest statement to be cleared from the interpreter mode. This clear
can happen when ending interpreter mode, or by calls to clear_interpreter()
state: <id>: statelastcleared
stateunexecuted
Replies with the number of non executed statements, i.e. the number of statements that would
have be skipped if skipbuffer was called instead.
state: <#unexecuted>: stateunexecuted
<statement> with id <id_a> was compiled into the program. To avoid filling the memory of the
robot, the logfile is cleaned up according to the following rules:
1. If the interpreter mode was entered with the parameter clearOnEnd=False, all statements in
the interpreter mode are appended to the file
/tmp/log/urcontrol/interpreter.saved.log when end_interpreter() is called.
2. Any other call to end_interpreter() or clear_interpreter() will cause the log to be moved to
/tmp/log/urcontrol/interpreter.0.log overwriting any data previously stored
there.
All interpreter mode log files are included in failure report files.
13.1. Functions
Deprecated: Tells the robot controller to treat digital inputs number A and B as pulses for a
conveyor encoder. Only digital input 0, 1, 2 or 3 can be used.
Parameters
type:
An integer determining how to treat the inputs on A and B
0 is no encoder, pulse decoding is disabled.
1 is quadrature encoder, input A and B must be square waves with 90 degree offset. Direction
of the conveyor can be determined.
2 is rising and falling edge on single input (A).
3 is rising edge on single input (A).
4 is falling edge on single input (A).
The controller can decode inputs at up to 40kHz
A:
Encoder input A, values of 0-3 are the digital inputs 0-3.
B:
Encoder input B, values of 0-3 are the digital inputs 0-3.
Deprecated: This function is replaced by encoder_enable_pulse_decode and it should
therefore not be used moving forward.
>>> conveyor_pulse_decode(1,0,1)
This example shows how to set up quadrature pulse decoding with input A = digital_in[0] and
input B = digital_in[1]
>>> conveyor_pulse_decode(2,3)
This example shows how to set up rising and falling edge pulse decoding with input A = digital_
in[3]. Note that you do not have to set parameter B (as it is not used anyway).
Example command: conveyor_pulse_decode(1, 2, 3)
• Example Parameters:
• type = 1→ is quadrature encoder, input A and B must be square waves with 90
degree offset. Direction of the conveyor can be determined.
• A = 2 → Encoder output A is connected to digital input 2
• B = 3 → Encoder output B is connected to digital input 3
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
Sets up an encoder expecting to be updated with tick counts via the function encoder_set_
tick_count.
>>> encoder_enable_set_tick_count(0,0)
This example shows how to set up encoder 0 to expect counts in the range of [-2147483648 ;
2147483647].
Parameters
encoder_index:
Index of the encoder to define. Must be either 0 or 1.
range_id:
decoder_index: Range of the encoder
Tells the robot controller the tick count of the encoder. This function is useful for absolute
encoders (e.g. MODBUS).
>>> encoder_set_tick_count(0, 1234)
This example sets the tick count of encoder 0 to 1234. Assumes that the encoder is enabled
using encoder_enable_set_tick_count first.
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
Parameters
encoder_index: Index of the encoder to define. Must be either 0 or 1.
count: The tick count to set. Must be within the range of the encoder.
Returns the delta_tick_count. Unwinds in case encoder wraps around the range. If no wrapping
has happened the given delta_tick_count is returned without any modification.
Consider the following situation: You are using an encoder with a UINT16 range, meaning the
tick count is always in the [0; 65536[ range. When the encoder is ticking, it may cross either end
of the range, which causes the tick count to wrap around to the other end. During your program,
the current tick count is assigned to a variable (start:=encoder_get_tick_count(...)). Later, the
tick count is assigned to another variable (current:=encoder_get_tick_count(...)). To calculate
the distance the conveyor has traveled between the two sample points, the two tick counts are
subtracted from each other.
For example, the first sample point is near the end of the range (e.g., start:=65530). When the
conveyor arrives at the second point, the encoder may have crossed the end of its range,
wrapped around, and reached a value near the beginning of the range (e.g., current:=864).
Subtracting the two samples to calculate the motion of the conveyor is not robust, and may
result in an incorrect result
(delta=current-start=-64666).
Conveyor tracking applications rely on these kinds of encoder calculations. Unless special care
is taken to compensate the encoder wrapping around, the application will not be robust and
may produce weird behaviors (e.g., singularities or exceeded speed limits) which are difficult to
explain and to reproduce.
This heuristic function checks that a given delta_tick_count value is reasonable. If the encoder
wrapped around the end of the range, it compensates (i.e., unwinds) and returns the adjusted
result. If a delta_tick_count is larger than half the range of the encoder, wrapping is assumed
and is compensated. As a consequence, this function only works when the range of the
encoder is explicitly known, and therefore the designated encoder must be enabled. If not, this
function will always return nil.
Parameters
encoder_index: Index of the encoder to query. Must be either 0 or 1.
delta_tick_count: The delta (difference between two) tick count to unwind (float)
13.1.7. end_force_mode()
13.1.8. end_freedrive_mode()
Set robot back in normal position control mode after freedrive mode.
13.1.9. end_screw_driving()
13.1.10. end_teach_mode()
Deprecated:
Set robot back in normal position control mode after teach mode.
position along/about compliant axis in order to achieve the specified force/torque. Values
have no effect for non-compliant axes.
Actual wrench applied may be lower than requested due to joint safety limits. Actual forces and
torques can be read using get_tcp_force function in a separate thread.
type:
An integer [1;3] specifying how the robot interprets the force frame.
1: The force frame is transformed in a way such that its y-axis is aligned with a vector pointing
from the robot tcp towards the origin of the force frame.
2: The force frame is not transformed.
3: The force frame is transformed in a way such that its x-axis is the projection of the robot tcp
velocity vector onto the x-y plane of the force frame.
limits: (Float) 6d vector. For compliant axes, these values are the maximum allowed tcp
speed along/about the axis. For non-compliant axes, these values are the maximum allowed
deviation along/about an axis between the actual tcp position and the one set by the program.
Note: Avoid movements parallel to compliant axes and high deceleration (consider inserting a
short sleep command of at least 0.02s) just before entering force mode. Avoid high
acceleration in force mode as this decreases the force control accuracy.
13.1.12. force_mode_example()
• Task frame = p[0.1,0,0,0,0.785] ! This frame is offset from the base frame 100 mm in the
x direction and rotated 45 degrees
• in the rz direction
• Selection Vector = [1,0,0,0,0,0] ! The robot is compliant in the x direction of the Task
frame above.
• Wrench = [20,0,40,0,0,0] ! The robot apples 20N in the x direction. It also accounts for a
40N external force in the z direction.
• Type = 2 ! The force frame is not transformed.
• Limits = [.1,.1,.1,.785,.785,1.57] ! max x velocity is 100 mm/s, max y deviation is 100 mm,
max z deviation is 100 mm, max rx deviation is 45 deg, max ry deviation is 45 deg, max rz
deviation is 90 deg.
13.1.14. force_mode_set_gain_scaling(scaling)
Set robot in freedrive mode. In this mode the robot can be moved around by hand in the same
way as by pressing the "freedrive" button.
The robot will not be able to follow a trajectory (eg. a movej) in this mode.
The default parameters enables the robot to move freely in all directions. It is possible to
enable Constrained Freedrive by providing user specific parameters.
Parameters
freeAxes: A 6 dimensional vector that contains 0’s and 1’s, these indicates in which axes
movement is allowed. The first three values represents the cartesian directions along x, y, z,
and the last three defines the rotation axis, rx, ry, rz. All relative to the selected feature.
feature: A pose vector that defines a freedrive frame relative to the base frame. For base
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
and tool reference frames predefined constants "base", and "tool" can be used in place of pose
vectors.
Example commands:
• freedrive_mode()
• Robot can move freely in all directions.
• freedrive_mode(freeAxes=[1,0,0,0,0,0], feature=p
[0.1,0,0,0,0.785])
• Example Parameters:
• freeAxes = [1,0,0,0,0,0] -> The robot is compliant in the x direction
relative to the feature.
• feature = p[0.1,0,0,0,0.785] -> This feature is offset from the base
frame with 100 mm in the x direction and rotated 45 degrees in the rz
direction.
• freedrive_mode(freeAxes=[0,1,0,0,0,0], feature="tool")
• Example Parameters:
• freeAxes = [0,1,0,0,0,0] -> The robot is compliant in the y direction
relative to the "tool" feature.
• feature = "tool" -> The "tool" feature is located in the active TCP.
High acceleration and deceleration can both decrease the control accuracy and cause
protective stops.
13.1.16. freedrive_mode_no_incorrect_payload_check()
This method, like teach_mode() and freedrive_mode(), changes the robot mode to teach mode,
but this function does not check for an incorrect payload during the initial state change, nor if
the payload is updated during freedrive. For this reason, it is exceedingly important for users to
be certain the payload is correct.
It is possible for the user to exit teach mode/freedrive in the usual manner, using: end_teach_
mode() or end_freedrive_mode()
Deprecated:Tells the tick count of the encoder, note that the controller interpolates tick counts
to get more accurate movements with low resolution encoders
Return Value
The conveyor encoder tick count
Deprecated: This function is replaced by encoder_get_tick_count and it should therefore
not be used moving forward.
13.1.18. get_freedrive_status()
13.1.19. get_target_tcp_pose_along_path()
Query the target TCP pose as given by the trajectory being followed.
This script function is useful in conjunction with conveyor tracking to know what the target
pose of the TCP would be if no offset was applied.
Return Value
Target TCP pose
13.1.20. get_target_tcp_speed_along_path()
Query the target TCP speed as given by the trajectory being followed.
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
This script function is useful in conjunction with conveyor tracking to know what the target
speed of the TCP would be if no offset was applied.
Return Value
Target TCP speed as a vector
• Example Parameters:
• q = [0,1.57,-1.57,3.14,-1.57,1.57] base is at 0 deg rotation, shoulder is at 90 deg
rotation, elbow is at -90 deg rotation, wrist 1 is at 180 deg rotation, wrist 2 is at -90
deg rotation, wrist 3 is at 90 deg rotation. Note: joint positions (q can also be
specified as a pose, then inverse kinematics is used to calculate the corresponding
joint positions)
• a = 1.4 → acceleration is 1.4 rad/s/s
• v = 1.05 → velocity is 1.05 rad/s
• t = 0 the time (seconds) to make move is not specified. If it were specified the
command would ignore the a and v values.
• r = 0 → the blend radius is zero meters.
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
Move Process
Blend circular (in tool-space) and move linear (in tool-space) to position. Accelerates to and
moves with constant tool speed v.
Parameters
pose: target pose (pose can also be specified as joint positions, then forward kinematics is
used to calculate the corresponding pose)
a: tool acceleration [m/s^2]
v: tool speed [m/s]
r: blend radius [m]
Example command: movep(pose, a=1.2, v=0.25, r=0)
13.1.25. path_offset_disable(a=20)
Disable the path offsetting and decelerate all joints to zero speed.
Uses the stopj functionality to bring all joints to a rest. Therefore, all joints will decelerate at
different rates but reach stand-still at the same time.
Use the script function path_offset_enable to enable path offsetting
Parameters
a: joint acceleration [rad/s^2] (optional)
13.1.26. path_offset_enable()
Path offsets can be applied in various frames of reference and in various ways. Please refer to
the script function path_offset_set for further explanation.
Enabling path offsetting doesn’t cancel the effects of previous calls to the script functions
path_offset_set_max_offset and path_offset_set_alpha_filter. Path offset
configuration will persist through cycles of enable and disable.
Using Path offset at the same time as Conveyor Tracking and/or Force can lead to program
conflict. Do not use this function togther with Conveyor Tracking and/or Force.
13.1.27. path_offset_get(type)
type: Specifies the frame of reference of the returned offset. Please refer to the path_
offset_set script function for a definition of the possible values and their meaning.
Return Value
Pose specifying the translational and rotational offset. Units are meters and radians.
path_offset_set(offset, type)
Specify the Cartesian path offset to be applied.
Use the script function path_offset_enable beforehand to enable offsetting. The calculated
offset is applied during each cycle at 500Hz.
Discontinuous or jerky offsets are likely to cause protective stops. If offsets are not smooth the
function path_offset_set_alpha_filter can be used to engage a simple filter.
The following example uses a harmonic wave (cosine) to offset the position of the TCP along
the Z-axis of the robot base:
>>> 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
>>> path_offset_set([0,0,x,0,0,0], 1)
>>> sync()
>>> end
>>> end
Parameters
offset: Pose specifying the translational and rotational offset.
type: Specifies how to apply the given offset. Options are:
1: (BASE) Use robot base coordinates when applying.
2: (TCP) Use robot TCP coordinates when applying.
3: (MOTION) Use a coordinate system following the un-offset trajectory when applying. This
coordinate system is defined as follows. X-axis along the tangent of the translational part of
the un-offset trajectory (rotation not relevant here). Y-axis perpendicular to the X-axis above
and the Z-axis of the tool (X cross Z). Z-axis given from the X and Y axes by observing the right-
hand rule. This is useful for instance for superimposing a weaving pattern onto the trajectory
when welding.
13.1.29. path_offset_set_alpha_filter(alpha)
Engage offset filtering using a simple alpha filter (EWMA) and set the filter coefficient.
When applying an offset, it must have a smooth velocity profile in order for the robot to be able
to follow the offset trajectory. This can potentially be cumbersome to obtain, not least as offset
application starts, unless filtering is applied.
The alpha filter is a very simple 1st order IIR filter using a weighted sum of the commanded
offset and the previously applied offset: filtered_offset= alpha*offset+ (1-alpha)*filtered_offset.
See more details and examples in the UR Support Site: Modify Robot Trajectory
Parameters
alpha: The filter coefficient to be used - must be between 0 and 1.
A value of 1 is equivalent to no filtering.
For welding; experiments have shown that a value around 0.1 is a good compromise between
robustness and offsetting accuracy.
The necessary alpha value will depend on robot calibration, robot mounting, payload mass,
payload center of gravity, TCP offset, robot position in workspace, path offset rate of change
and underlying motion.
Makes the robot pause if the specified error code occurs. The robot will only pause during
program execution.
This setting is reset when the program is stopped. Call the command again before/during
program execution to re-enable it.
>>> pause_on_error_code(173, 3)
In the above example, the robot will pause on errors with code 173 if its argument equals 3
(corresponding to ’C173A3’ in the log).
>>> pause_on_error_code(173)
In the above example, the robot will pause on error code 173 for any argument value.
Parameters
code: The code of the error for which the robot should pause (int)
argument: The argument of the error. If this parameter is omitted the robot will pause on any
argument for the specified error code (int)
Notes:
• This script command currently only supports error codes 173 and 174.
• Error codes appear in the log as CxAy where 'x' is the code and 'y' is the argument.
When enabled, this function generates warning messages to the log when the robot deviates
from the target position. This function can be called at any point in the execution of a program.
It has no return value.
>>> position_deviation_warning(True)
In the above example, the function has been enabled. This means that log messages will be
generated whenever a position deviation occurs. The optional "threshold" parameter can be
used to specify the level of position deviation that triggers a log message.
Parameters
enabled: (Boolean) Enable or disable position deviation log messages.
threshold: (Float) Optional value in the range [0;1], where 0 is no position deviation and 1 is the
maximum position deviation (equivalent to the amount of position deviation that causes a
protective stop of the robot). If no threshold is specified by the user, a default value of 0.8 is
used.
Example command: position_deviation_warning(True, 0.8)
• Example Parameters:
• Enabled = True → Logging of warning is turned on
Reset the revolution counter, if no offset is specified. This is applied on joints which safety
limits are set to "Unlimited" and are only applied when new safety settings are applied with
limitted joint angles.
>>> reset_revolution_counter()
Parameters
qNear: Optional parameter, reset the revolution counter to one close to the given qNear joint
vector. If not defined, the joint’s actual number of revolutions are used.
Example command: reset_revolution_counter(qNear=[0.0, 0.0, 0.0, 0.0,
0.0, 0.0])
• Example Parameters:
• qNear = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] -> Optional parameter, resets the revolution
counter of wrist 3 to zero on UR3 robots to the nearest zero location to joint
rotations represented by qNear.
Enter screw driving mode. The robot will exert a force in the TCP Z-axis direction at limited
speed. This allows the robot to follow the screw during tightening/loosening operations.
Parameters
f: The amount of force the robot will exert along the TCP Z-axis (Newtons).
v_limit: Maximum TCP velocity along the Z axis (m/s).
Notes:
Zero the F/T sensor without the screw driver pushing against the screw.
Call end_screw_driving when the screw driving operation has completed.
>>> def testScrewDriver():
>>> # Zero F/T sensor
>>> zero_ftsensor()
>>> sleep(0.02)
>>>
>>> # Move the robot to the tightening position
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
Servo Circular
Servo to position (circular in tool space). Accelerates to, and moves with, constant tool speed
v.
Parameters
pose: target pose (pose can also be specified as joint positions, then
forward kinematics is used to calculate the corresponding pose)
a: tool acceleration [m/s^2]
v: tool speed [m/s]
• Example Parameters:
• q = [0.0,1.57,-1.57,0,0,3.14] joint angles in radians representing rotations of base,
shoulder, elbow, wrist1, wrist2 and wrist3
• a = 0 → not used in current version
• v = 0 → not used in current version
• t = 0.002 time where the command is controlling the robot. The function is
blocking for time t [S].
• lookahead time = .1 time [S], range [0.03,0.2] smoothens the trajectory with this
lookahead time
• gain = 300 proportional gain for following target position, range [100,2000]
resolution=0)
Deprecated:Tells the robot controller the tick count of the encoder. This function is useful for
absolute encoders, use conveyor_pulse_decode() for setting up an incremental encoder. For
circular conveyors, the value must be between 0 and the number of ticks per revolution.
Parameters
tick_count:
Tick count of the conveyor (Integer)
absolute_encoder_resolution:
Resolution of the encoder, needed to handle wrapping nicely. (Integer)
0 is a 32 bit signed encoder, range [-2147483648 ; 2147483647] (default)
1 is a 8 bit unsigned encoder, range [0 ; 255]
2 is a 16 bit unsigned encoder, range [0 ; 65535]
3 is a 24 bit unsigned encoder, range [0 ; 16777215]
4 is a 32 bit unsigned encoder, range [0 ; 4294967295]
Deprecated: This function is replaced by encoder_set_tick_count and it should therefore not be
used moving forward.
Example command: set_conveyor_tick_count(24543, 0)
• Example Parameters:
• Tick_count = 24543 a value read from e.g. a MODBUS register being updated by
the absolute encoder
• Absolute_encoder_resolution = 0 0 is a 32 bit signed encoder, range [-
2147483648 ;2147483647] (default)
13.1.38. set_pos(q)
13.1.39. set_safety_mode_transition_hardness(type)
13.1.40. speedj(qd, a, t)
Joint speed
Accelerate linearly in joint space and continue with constant joint speed. The time t is optional;
if provided the function will return after time t, regardless of the target speed has been reached.
If the time t is not provided, the function will return when the target speed is reached.
Parameters
qd: joint speeds [rad/s]
a: joint acceleration [rad/s^2] (of leading axis)
t: time [s] before the function returns (optional)
Example command: speedj([0.2,0.3,0.1,0.05,0,0], 0.5, 0.5)
• Example Parameters:
• qd -> Joint speeds of: base=0.2 rad/s, shoulder=0.3 rad/s, elbow=0.1 rad/s,
wrist1=0.05 rad/s, wrist2 and wrist3=0 rad/s
• a = 0.5 rad/s^2 -> acceleration of the leading axis (shoulder in this case)
• t = 0.5 s -> time before the function returns
Parameters
xd: tool speed [m/s] (spatial vector)
a: tool positional acceleration [m/s^2]
t: time [s] before function returns (optional)
aRot: tool rotational acceleration [rad/s^2] (optional), if not defined a, position acceleration, is
used
Example command: speedl([0.5,0.4,0,1.57,0,0], 0.5, 0.5)
• Example Parameters:
• xd -> Tool speeds of: x=500 mm/s, y=400 mm/s, rx=90 deg/s, ry and rz=0 mm/s
• a = 0.5 m/s^2 -> acceleration of the tool
• t = 0.5 s -> time before the function returns
13.1.42. stop_conveyor_tracking(a=20)
13.1.43. stopj(a)
13.1.45. teach_mode()
Deprecated:
Set robot in freedrive mode. In this mode the robot can be moved around by hand in the same
way as by pressing the "freedrive" button.
The robot will not be able to follow a trajectory (eg. a movej) in this mode.
Deprecated:
This function is replaced by freedrive_mode and it should therefore not be used moving
forward.
rotate_tool: Should the tool rotate with the coneyor or stay in the orientation specified by
the trajectory (movel() etc.).
encoder_index: The index of the encoder to associate with the conveyor tracking. Must be
either 0 or 1. This is an optional argument, and please note the default of 0. The ability to omit
this argument will allow existing programs to keep working. Also, in use cases where there is
just one conveyor to track consider leaving this argument out.
Example command: track_conveyor_circular(p[0.5,0.5,0,0,0,0], 500.0,
false)
• Example Parameters:
• center = p[0.5,0.5,0,0,0,0] location of the center of the conveyor
• ticks_per_revolution = 500 the number of ticks the encoder sees when the
conveyor moves one revolution
• rotate_tool = false the tool should not rotate with the conveyor, but stay in the
orientation specified by the trajectory (movel() etc.).
direction: Pose vector that determines the direction of the conveyor in the base coordinate
system of the robot
ticks_per_meter: How many ticks the encoder sees when the conveyor moves one meter
encoder_index: The index of the encoder to associate with the conveyor tracking. Must be
either 0 or 1. This is an optional argument, and please note the default of 0. The ability to omit
this argument will allow existing programs to keep working. Also, in use cases where there is
just one conveyor to track consider leaving this argument out.
Example command: track_conveyor_linear(p[1,0,0,0,0,0], 1000.0)
• Example Parameters:
• direction = p[1,0,0,0,0,0] Pose vector that determines the direction of the conveyor
in the base coordinate system of the robot
• ticks_per_meter = 1000. How many ticks the encoder sees when the conveyor
moves one meter.
14.1.2. get_actual_joint_positions()
14.1.3. get_actual_joint_positions_history(steps=0)
The joint angular position vector in rad : [Base, Shoulder, Elbow, Wrist1, Wrist2, Wrist3] that was
actual at the provided number of steps before the current time step.
14.1.4. get_actual_joint_speeds()
14.1.6. get_actual_tcp_speed()
14.1.7. get_actual_tool_flange_pose()
Returns the 6d pose representing the tool flange position and orientation specified in the base
frame, without the Tool Center Point offset. The calculation of this pose is based on the actual
robot encoder readings.
Return Value
The current actual tool flange vector: [X, Y, Z, Rx, Ry, Rz]
Note: See get_actual_tcp_pose for the actual 6d pose including TCP offset.
14.1.8. get_controller_temp()
Return Value
A temperature in degrees Celcius (float)
Calculate the forward kinematic transformation (joint space -> tool space) using the calibrated
robot kinematics. If no joint position vector is provided the current joint angles of the robot arm
will be used. If no tcp is provided the currently active tcp of the controller will be used.
Parameters
q: joint position vector (Optional)
tcp: tcp offset pose (Optional)
Return Value
tool pose
Example command: get_forward_kin([0.,3.14,1.57,.785,0,0], p
[0,0,0.01,0,0,0])
• Example Parameters:
• q = [0.,3.14,1.57,.785,0,0] -> joint angles of j0=0 deg, j1=180 deg, j2=90 deg, j3=45
deg, j4=0 deg, j5=0 deg.
• tcp = p[0,0,0.01,0,0,0] -> tcp offset of x=0mm, y=0mm, z=10mm and rotation vector
of rx=0 deg., ry=0 deg, rz=0 deg.
Calculate the inverse kinematic transformation (tool space -> joint space). If qnear is defined,
the solution closest to qnear is returned.
Otherwise, the solution closest to the current joint positions is returned. If no tcp is provided the
currently active tcp of the controller is used.
Parameters
x: tool pose
qnear: list of joint positions (Optional)
maxPositionError: the maximum allowed position error (Optional)
maxOrientationError: the maximum allowed orientation error (Optional)
14.1.12. get_joint_temp(j)
14.1.13. get_joint_torques()
14.1.14. get_steptime()
14.1.15. get_target_joint_positions()
14.1.16. get_target_joint_speeds()
14.1.17. get_target_payload()
14.1.18. get_target_payload_cog()
14.1.19. get_target_payload_inertia()
14.1.20. get_target_tcp_pose()
Returns the 6d pose representing the tool position and orientation specified in the base frame.
The calculation of this pose is based on the current target joint positions.
Return Value
The current target TCP vector [X, Y, Z, Rx, Ry, Rz]
14.1.21. get_target_tcp_speed()
14.1.22. get_target_waypoint()
Return Value
The desired waypoint TCP vector [X, Y, Z, Rx, Ry, Rz]
14.1.23. get_tcp_force()
= pose_trans(get_target_tcp_pose(), pose_inv(get_tcp_offset()))
flange_rot = pose_inv(p[0, 0, 0, t_flange_in_base[3], t_flange_in_base
[4], t_flange_in_base[5]])
f = pose_trans(flange_rot, p[ft[0], ft[1], ft[2], 0, 0, 0])
end
def get_wrench_at_tcp():
return wrench_trans(get_tcp_offset(), get_wrench_at_tool_flange
())
end
14.1.24. get_tcp_offset()
Gets the active tcp offset, i.e. the transformation from the output flange coordinate system to
the TCP as a pose.
Return Value
tcp offset pose
14.1.25. get_tool_accelerometer_reading()
14.1.26. get_tool_current()
14.1.27. is_steady()
The function will return true when the robot has been standing still with zero target velocity for
500ms
When the function returns true, the robot is able to adapt to large external forces and torques,
e.g. from screwdrivers, without issuing a protective stop.
Return Value
True when the robot able to adapt to external forces, false otherwise (bool)
Checks if the given pose or q is reachable and within the current safety limits of the robot.
This check considers joint limits (if the target pose is specified as joint positions), TCP
orientation limit and range of the robot.
If a solution is found when applying the inverse kinematics to the given target TCP pose, this
pose is considered reachable.
Parameters
pose: Target pose or joint position
qnear: list of joint positions (Optional) Only used when target is a pose
Return Value
True if within limits, false otherwise (bool)
Deprecated: This function is deprecated, since it does not apply the same algorithm as get_
inverse_kin. It is recommended to use get_inverse_kin_has_solution instead.
14.1.30. powerdown()
Shut down the robot, and power off the robot and controller.
14.1.31. set_gravity(d)
Set the direction of the acceleration experienced by the robot. When the robot mounting is
fixed, this corresponds to an accleration of g away from the earth’s centre.
>>> set_gravity([0, 9.82*sin(theta), 9.82*cos(theta)])
will set the acceleration for a robot that is rotated "theta" radians around the x-axis of the robot
base coordinate system
Parameters
d: 3D vector, describing the direction of the gravity, relative to the base of the robot.
Example command: set_gravity[(0,9.82,0)]
• Example Parameters:
• d is vector with a direction of y (direction of the robot cable) and a magnitude of
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
Parameters
m: mass in kilograms
cog: Center of Gravity, a vector [CoGx, CoGy, CoGz] specifying the displacement (in meters)
from the toolmount.
Deprecated: See set_target_payload to set mass, CoG and payload inertia matrix at the same
time.
Set payload mass and center of gravity while resetting payload inertia matrix
Sets the mass and center of gravity (abbr. CoG) of the payload.
This function must be called, when the payload mass or mass CoG offset changes - i.e. when
the robot picks up or puts down a workpiece.
Note: The force torque measurements are automatically zeroed when setting the payload. That
ensures the readings are compensated for the payload. This is similar to the behavior of zero_
ftsensor()
Warnings:
• This script is deprecated since SW 5.10.0 because of the risk of inconsistent payload
parameters. Use the set_target_payload instead to set mass, CoG and inertia
matrix.
• Omitting the cog parameter is not recommended. The Tool Center Point (TCP) will be
used if the cog parameter is missing with the side effect that later calls to set_tcp will
change also the CoG to the new TCP. Use the set_payload_mass function to change
only the mass or use the get_target_payload_cog as second argument to not
change the CoG.
• Using this script function to modify payload parameters will reset the payload inertia
matrix.
Example command:
• set_payload(3., [0,0,.3])
• Example Parameters:
• m = 3 → mass is set to 3 kg payload
• cog = [0,0,.3] Center of Gravity is set to x=0 mm, y=0 mm, z=300 mm from
14.1.33. set_payload_cog(CoG)
Deprecated: See set_target_payload to set mass, CoG and payload inertia matrix at the
same time.
Set the Center of Gravity (CoG) and reset payload inertia matrix
Warning: Using this script function to modify payload parameters will reset the payload inertia
matrix.
Note: The force torque measurements are automatically zeroed when setting the payload. That
ensures the readings are compensated for the payload. This is similar to the behavior of zero_
ftsensor()
14.1.34. set_payload_mass(m)
Parameters
m: mass in kilograms
Deprecated: See set_target_payload to set mass, CoG and payload inertia matrix at the
same time.
Sets the mass, CoG (center of gravity), the inertia matrix of the active payload and the transition
time for applying new settings.
This function must be called when the payload mass, the mass displacement (CoG) or the
inertia matrix changes - (i.e. when the robot picks up or puts down a workpiece).
Parameters
m: mass in kilograms.
cog: Center of Gravity, a vector with three elements [CoGx, CoGy, CoGz] specifying the offset
(in meters) from the tool mount.
inertia: payload 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 tool flange axes.
transition_time: the duration of the payload property changes in seconds
Notes:
• This script should be used instead of the deprecated set_payload, set_payload_
mass, and set_payload_cog.
• The payload mass and CoG are required, the inertia matrix and transition time are
optional.
14.1.36. set_tcp(pose)
Sets the active tcp offset, i.e. the transformation from the output flange coordinate system to
the TCP as a pose.
Parameters
pose: A pose describing the transformation.
Example command: set_tcp(p[0.,.2,.3,0.,3.14,0.])
• Example Parameters:
• – pose = p[0.,.2,.3,0.,3.14,0.] -> tool center point is set to x=0mm, y=200mm,
z=300mm, rotation vector is rx=0 deg, ry=180 deg, rz=0 deg. In tool coordinates
14.1.37. sleep(t)
• Example Parameters:
• t = 3. -> time to sleep
String concatenation
This script returns a string that is the concatenation of the two operands given as input. Both
operands can be one of the following types: String, Boolean, Integer, Float, Pose, List of
Boolean / Integer / Float / Pose. Any other type will raise an exception.
The resulting string cannot exceed 1023 characters, an exception is thrown otherwise.
Float numbers will be formatted with 6 decimals, and trailing zeros will be removed.
The function can be nested to create complex strings (see last example).
Parameters
op1: first operand
op2: second operand
Return Value
String concatenation of op1 and op2
Example command:
• str_cat("Hello", " World!")
• returns "Hello World!"
• str_cat("Integer ", 1)
• returns "Integer 1"
14.1.40. str_empty(str)
Return Value
The index of the first occurrence of target in src, -1 if target is not found in src.
Example command:
• str_find("Hello World!", "o")
• returns 4
• str_find("Hello World!", "lo")
• returns 3
• str_find("Hello World!", "o", 5)
• returns 7
• str_find("abc", "z")
• returns -1
14.1.42. str_len(str)
Example command:
• str_len("Hello")
• returns 5
• str_len("")
• returns 0
14.1.44. sync()
Uses up the remaining "physical" time a thread has in the current frame.
s1: message string, variables of other types (int, bool poses etc.) can also be sent
s2: message string, variables of other types (int, bool poses etc.) can also be sent
Example command: textmsg("value=", 3)
• Example Parameters:
• s1 set first part of message to "value="
• s2 set second part of message to 3
• message in the log is "value=3"
14.1.46. to_num(str )
Runtime exceptions are raised if the source string doesn’t contain a valid number or the result
is out of range for the resulting type.
Parameters
str: string to convert
Return Value
Integer or float number according to the input string.
Example command:
• to_num("10")
• returns 10 //integer
• to_num("3.14")
• returns 3.14 //float
14.1.47. to_str(val)
• to_str(10)
• returns "10"
• to_str(2.123456123456)
• returns "2.123456"
• to_str(p[1.0, 2.0, 3.0, 4.0, 5.0, 6.0])
• returns "p[1, 2, 3, 4, 5, 6]"
• to_str([True, False, True])
• returns "[True, False, True]"
14.1.48. tool_contact(direction)
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
14.1.49. tool_contact_examples()
tool_contact(direction = [1,0,0,0,0,0])
• Example Parameters:
• direction=[1,0,0,0,0,0] will detect contacts in the direction robot base X
Return Value
the arc cosine of f.
Example command: acos(0.707)
• Example Parameters:
• f is the cos of 45 deg. (.785 rad)
• Returns .785
15.1.2. asin(f )
15.1.3. atan(f )
15.1.4. atan2(x, y)
15.1.5. binary_list_to_integer(l)
Returns the integer value represented by the bools contained in the list l when evaluated as a
signed binary number.
Parameters
l: The list of bools to be converted to an integer. The bool at index 0 is evaluated as the least
significant bit. False represents a zero and True represents a one. If the list is empty this
function returns 0. If the list contains more than 32 bools, the function returns the signed
integer value of the first 32 bools in the list.
Return Value
The integer value of the binary list content.
Example command: binary_list_to_integer([True,False,False,True])
• Example Parameters:
• l represents the binary values 1001
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
• Returns 9
15.1.6. ceil(f )
15.1.7. cos(f )
15.1.8. d2r(d)
Returns degrees-to-radians of d
Returns the radian value of ’d’ degrees. Actually: (d/180)*MATH_PI
Parameters
d: The angle in degrees
15.1.9. floor(f )
15.1.10. get_list_length(v)
• Returns 5
15.1.11. integer_to_binary_list(x)
Parameters
p_from: tool pose (pose)
p_to: tool pose (pose)
alpha: Floating point number
Return Value
interpolated pose (pose)
Example command: interpolate_pose(p[.2,.2,.4,0,0,0], p[.2,.2,.6,0,0,0],
.5)
• Example Parameters:
• p_from = p[.2,.2,.4,0,0,0]
• p_to = p[.2,.2,.6,0,0,0]
15.1.13. inv(m)
15.1.14. length(v)
Return Value
An integer specifying the length of the given list or string
Example command: length("here I am")
• Example Parameters:
• v equals string "here I am"
• Returns 9
15.1.15. log(b, f )
Parameters
b: floating point value
f: floating point value
Return Value
the logarithm of f to the base of b.
Example command: log(10.,4.)
• Example Parameters:
• b is base 10
• f is log of 4
• Returns 0.60206
15.1.16. norm(a)
norm of a
Example command:
• norm(-5.3) -> Returns 5.3
• norm(-8) -> Returns 8
• norm(p[-.2,.2,-.2,-1.57,0,3.14]) -> Returns 3.52768
15.1.17. normalize(v)
Point distance
Parameters
p_from: tool pose (pose)
p_to: tool pose (pose)
Return Value
Distance between the two tool positions (without considering rotations)
Example command: point_dist(p[.2,.5,.1,1.57,0,3.14], p
[.2,.5,.6,0,1.57,3.14])
• Example Parameters:
• p_from = p[.2,.5,.1,1.57,0,3.14] -> The first point
• p_to = p[.2,.5,.6,0,1.57,3.14] -> The second point
• Returns distance between the points regardless of rotation
Pose addition
Both arguments contain three position parameters (x, y, z) jointly called P, and three rotation
parameters (R_x, R_y, R_z) jointly called R. This function calculates the result x_3 as the
addition of the given poses as follows:
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
Pose distance
Parameters
p_from: tool pose (pose)
p_to: tool pose (pose)
Return Value
distance
15.1.21. pose_inv(p_from)
Pose subtraction
Parameters
p_to: tool pose (spatial vector)
p_from: tool pose (spatial vector)
Return Value
tool pose transformation (spatial vector)
Example command: pose_sub(p[.2,.5,.1,1.57,0,0], p[.2,.5,.6,1.57,0,0])
• Example Parameters:
• p_1 = p[.2,.5,.1,1.57,0,0] -> The first point
• p_2 = p[.2,.5,.6,1.57,0,0] -> The second point
• Returns p[0.0,0.0,-0.5,0.0,.0.,0.0]
Pose transformation
The first argument, p_from, is used to transform the second argument, p_from_to, and the
result is then returned. This means that the result is the resulting pose, when starting at the
coordinate system of p_from, and then in that coordinate system moving p_from_to.
This function can be seen in two different views. Either the function transforms, that is
translates and rotates, p_from_to by the parameters of p_from. Or the function is used to get
the resulting pose, when first making a move of p_from and then from there, a move of p_from_
to.
If the poses were regarded as transformation matrices, it would look like:
T_world->to = T_world->from * T_from->to T_x->to = T_x->from * T_from->to
Parameters
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
• Example Parameters:
• Base = 5
• Exponent = 3
• Returns 125.
15.1.25. r2d(r)
Returns radians-to-degrees of r
Returns the degree value of ’r’ radians.
Parameters
r: The angle in radians
15.1.26. random()
Random Number
Return Value
pseudo-random number between 0 and 1 (float)
15.1.27. rotvec2rpy(rotation_vector)
15.1.28. rpy2rotvec(rpy_vector)
Returns the rotation vector corresponding to ’rpy_vector’ where the RPY (roll-pitch-yaw)
rotations are extrinsic rotations about the X-Y-Z axes (corresponding to intrinsic rotations
about the Z-Y’-X” axes).
Parameters
rpy_vector: The RPY vector (Vector3d) in radians, describing a roll-pitch-yaw sequence of
extrinsic rotations about the X-Y-Z axes, (corresponding to intrinsic rotations about the Z-Y’-X”
axes). In matrix form the RPY vector is defined as Rrpy = Rz(yaw)Ry(pitch)Rx(roll).
Return Value
The rotation vector (Vector3d) in radians, also called the Axis-Angle vector (unit-axis of rotation
multiplied by the rotation angle in radians).
Example command: rpy2rotvec([3.14,1.57,0])
• Example Parameters:
• rpy_vector = [3.14,1.57,0] -> roll=3.14, pitch=1.57, yaw=0
• Returns [2.22153, 0.00177, -2.21976] -> rx=2.22153, ry=0.00177, rz=-2.21976
15.1.29. sin(f )
• Example Parameters:
• f is angle of 1.57 rad (90 deg)
• Returns 1.0
15.1.30. size(v)
Returns the size of a matrix variable, the length of a list or string variable
Parameters
v: A matrix, list or string variable
Return Value
Given a list or a string the length is returned as an integer. Given a matrix the size is returned as
15.1.31. sqrt(f )
15.1.32. tan(f)
Returns the tangent of f
15.1.33. transpose(m)
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
Wrench transformation
Move the point of view of a wrench.
Note: Transforming wrenches is not as trivial as transforming poses as the torque scales with
the length of the translation.
w_to = T_from->to * w_from
Parameters
T_from_to: The transformation to the new point of view (Pose)
w_from: wrench to transform in list format [F_x, F_y, F_z, M_x, M_y, M_z]
Return Value
resulting wrench, w_to in list format [F_x, F_y, F_z, M_x, M_y, M_z]
Deprecated:
This function is used for enabling and disabling the use of external F/T measurements in the
controller. Be aware that the following function is impacted:
• force_mode
• screw_driving
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
• freedrive_mode
The RTDE interface shall be used for feeding F/T measurements into the real-time control loop
of the robot using input variable external_force_torque of type VECTOR6D. If no other
RTDE watchdog has been configured (using script function rtde_set_watchdog), a default
watchdog will be set to a 10Hz minimum update frequency when the external F/T sensor
functionality is enabled. If the update frequency is not met the robot program will pause.
Parameters
enable: enable or disable feature (bool)
sensor_mass: mass of the sensor in kilograms (float)
sensor_measuring_offset: [x, y, z] measuring offset of the sensor in meters relative to the
tool flange frame
sensor_cog: [x, y, z] center of gravity of the sensor in meters relative to the tool flange frame
Deprecated
When using this function, the sensor position is applied such that the resulting torques are
computed with opposite sign. New programs should use ft_rtde_input_enable in place of this.
Notes:
• The TCP Configuration in the installation must also include the weight and offset
contribution of the sensor.
• Only the enable parameter is required, sensor mass, offset and center of gravity are
optional (zero if not provided).
This function is used for enabling and disabling the use of external F/T measurements in the
controller. Be aware that the following function is impacted:
• force_mode
• screw_driving
• freedrive_mode
The RTDE interface shall be used for feeding F/T measurements into the real-time control loop
of the robot using input variable external_force_torque of type VECTOR6D. If no other
RTDE watchdog has been configured (using script function rtde_set_watchdog), a default
watchdog will be set to a 10Hz minimum update frequency when the external F/T sensor
functionality is enabled. If the update frequency is not met the robot program will pause.
• ft_rtde_input_enable(True, 0.5)
• Example Parameters:
• enable S{rarr} Enabling the feed of an external F/T measurements in
the controller.
• sensor_mass S{rarr} mass of F/T sensor is set to 0.5 Kg.
• Both sensor measuring offset and sensor's center of gravity are zero.
• @example:
• C{ft_rtde_input_enable(False)}
• Disable the feed of external F/T measurements in the controller (no
other parameters required)
16.1.3. get_analog_in(n)
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
16.1.4. get_analog_out(n)
16.1.5. get_configurable_digital_in(n)
16.1.6. get_configurable_digital_out(n)
16.1.7. get_digital_in(n)
• Example Parameters:
• n is digital input 1
• Returns True or False
16.1.8. get_digital_out(n)
16.1.9. get_flag(n)
Flags behave like internal digital outputs. They keep information between program runs.
Parameters
n: The number (id) of the flag, integer: [0:31]
Return Value
Boolean, The stored bit.
Example command: get_flag(1)
• Example Parameters:
• n is flag number 1
• Returns True or False
16.1.11. get_standard_analog_out(n)
• Example Parameters:
• n is standard analog output 1
• Returns value of standard analog output #1
16.1.12. get_standard_digital_in(n)
16.1.13. get_standard_digital_out(n)
16.1.14. get_tool_analog_in(n)
16.1.15. get_tool_digital_in(n)
16.1.16. get_tool_digital_out(n)
Adds a new modbus signal for the controller to supervise. Expects no response. If the signal is
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
an output type, then until the first set_output_signal/register() command the function code will
be 2/3, after the call it will switch to 15/16.
Matrix of function codes used for accessing coils or discrete inputs:
Read Write
Signal type Single Multiple Single Multiple
Coil Coils Coil Coils
0 = Digital input 2 2 - -
1 = Digital output 1 1 15 15
15 = Multiple digital 1 1 15 15
outputs
Read Write
Signal type Single Multiple Single Multiple
register registers register registers
2 = Register input 4 4 - -
3 = Register output 3 3 6 16
16 = Multiple register 3 3 16 16
outputs
slave_number: An integer normally not used and set to 255, but is a free choice between 0
and 255.
signal_address: An integer specifying the address of the either the coil or the register that
this new signal should reflect. Consult the configuration of the modbus unit for this
information. The value must be greater or equal to 0.
signal_type: An integer specifying the type of signal to add. 0 = digital input, 1 = digital
output, 2 = register input, 3 = register output, 15 = multiple digital output, 16 = multiple register
output. Note: this function does not accept 23 = multiple read-write signal type.
signal_name: A string uniquely identifying the signal. If a string is supplied which is equal to
an already added signal, the new signal will replace the old one. The length of the string can not
exceed 20 characters. The signal name cannot be empty.
sequential_mode: Setting to True forces the modbus client to wait for a response before
sending the next request. This mode is required by some fieldbus units (Optional).
Adds a new modbus signal for the controller to supervise. This function will use the function
code 23. The read and write addresses can overlap. Until the first set_output_register()
command the function code will be 3, after the call it will switch to 23.
>>> modbus_add_rw_signal("172.140.17.11", 255, 5, 10, 15, 10,
"output1")
Parameters
IP: A string specifying the IP address of the modbus unit to which the modbus signal is
connected. The IP can not be empty.
slave_number: An integer normally not used and set to 255, but is a free choice between 0
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
and 255.
read_address: An integer specifying the address of the first register that this new signal
should read from.
read_register_count: Number of registers to read [1-123].
write_address: An integer specifying the address of the first register that this new signal
should write to.
write_register_count: Number of registers to write [1-123].
signal_name: A string uniquely identifying the signal. If a string is supplied which is equal to
an already added signal, the new signal will replace the old one. The length of the string can not
exceed 20 characters. The signal name cannot be empty.
sequential_mode: Setting to True forces the modbus client to wait for a response before
sending the next request. This mode is required by some fieldbus units (Optional).
Example command: modbus_add_rw_signal("172.140.17.11", 255, 5, 10, 15,
10 "output1")
This example will create a signal that cyclically reads 10 registers from addresses 5-14, an
writes 10 registers to addresses 10-19 Signal will use Function Code 3 to read register until first
time modbus_set_register_output(...) is called. Afterwards Function Code 23 will be used to
both read and write registers in remote device.
• Example Parameters:
• IP address = 172.140.17.11
• Slave number = 255
• Signal read address = 5
• Signal read register count = 10
16.1.19. modbus_delete_signal(signal_name)
Reads the current value(s) of a specific signal. If the modbus watchdog is active, this will return
the last valid value(s). No error will be thrown within the watchdog time. If needed, the modus_
get_error() or the modbus_get_time_since_signal_invalid() can be used to detected that the
signal is in an error state before the watchdog expires.
>>> modbus_get_signal_status("output1",False)
Parameters
signal_name: A string equal to the name of the signal for which the value should be gotten.
Can not be empty.
is_secondary_program: A boolean for internal use only. Must be set to False. (Optional,
default is False)
Return Value
An integer or a boolean. For digital signals: True or False. For register signals: The register
value expressed as an unsigned integer. If the signal was declared to have access for multiple
registers/coild, then the return value will be an array of unsigned integers / booleans. The
length of the returned array is equal to the register_count of the signal.
Example command: modbus_get_signal_status("output1")
Example Parameters:
>>> [17,32,2,88])
The above example sets the watchdog timeout on a Beckhoff BK9050 to 600 ms. That is done
using the modbus function code 6 (preset single register) and then supplying the register address
in the first two bytes of the data array ([17,32] = [0x1120]) and the desired register content in the
last two bytes ([2,88] = [0x0258] = dec 600).
Parameters
IP: A string specifying the IP address locating the modbus unit to which the custom command
should be send.
slave_number: An integer specifying the slave number to use for the custom command.
function_code: An integer specifying the function code for the custom command.
data: An array of integers in which each entry must be a valid byte (0-255) value.
Example command: modbus_send_custom_command("172.140.17.11", 103, 6,
[17,32,2,88])
• Example Parameters:
• IP address = 172.140.17.11
• Slave number = 103
• Function code = 6
• Data = [17,32,2,88]
• Function code and data are specified by the manufacturer of the slave Modbus
device connected to the UR controller
Sets the selected digital input signal to either a "default" or "freedrive" action.
Sets the output digital signal identified by the given name to the given value.
>>> modbus_set_output_signal("output2",True,False)
Parameters
signal_name: A string identifying an output digital signal that in advance has been added.
digital_value: A boolean to which value the signal will be set.
is_secondary_program: A boolean for interal use only. Must be set to False.
16.1.25. modbus_set_signal_update_frequency(signal_name,
update_frequency)
Sets the frequency with which the robot will send requests to the Modbus controller to either
read or write the signal value.
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
>>> modbus_set_signal_update_frequency("output2",20)
Parameters
signal_name: A string identifying an output digital signal that in advance has been added.
update_frequency: An integer in the range 0-125 specifying the update frequency in Hz.
Example command: modbus_set_signal_update_frequency("output2", 20)
• Example Parameters:
• Signal name = output2
• Signal update frequency = 20 Hz
16.1.26. modbus_get_error(signal_name)
NOTICE
If combined errors are requested, then the returned value's upper 2 bytes will
16.1.27. modbus_get_time_since_signal_invalid(signal_name)
Returns the time in seconds since the signal is invalid (has communication or device error).For
input signals function tells how long ago was last time when signal value was successfully
read from remote device. For output signals function tells how long ago was last time when
signal value was successfully written to remote device.
>>> modbus_get_time_since_signal_invalid("output1")
Parameters
signal_name: A string equal to the name of the signal. The signal name can not be empty.
Return Value
A float number representing the time in seconds since the signal is in a communication or
device error.
Example command: modbus_get_time_since_signal_invalid("output1")
• Example Parameters:
• Signal name = output1
16.1.28. modbus_request_update_signal_value(signal_name)
Tear down, and reconnect all signals to remote device. By default it will block as long as there
are errors in the connection.
>>> modbus_reset_connection("172.140.17.11")
Parameters
connection_id: A string specifying the IP address of the modbus unit to which the modbus
signal is connected. The IP can not be empty.
Example command: modbus_reset_connection("172.140.17.11")
Example Parameters:
• connection_id = 172.140.17.11
• is_blocking = True
Set tolerance for modbus errors (both communication, and device exceptions) as minimum
time between valid device responses. No error will be thrown within the watchdog time. If
needed, the modus_get_error() or the modbus_get_time_since_signal_invalid() can be used to
detected that the signal is in an error state before the watchdog expires.Default signal timeout
is 2 seconds.
>>> modbus_set_signal_watchdog("signal1", 5)
Parameters
signal_name: A string identifying an output digital signal that in advance has been added.
Can not be empty.
new_timeout_in_sec: A number in range 0-300 representing seconds.
Example command: modbus_set_signal_watchdog("signal1", 10.5)
Example Parameters:
• signal_name = signal1
• new_timeout_in_sec = 10.5 seconds
16.1.31. read_input_boolean_register(address)
Reads the boolean from one of the input registers, which can also be accessed by a Field bus.
16.1.32. read_input_float_register(address)
Reads the float from one of the input registers, which can also be accessed by a Field bus.
Note, uses it’s own memory space.
Parameters
address: Address of the register (0:47)
Return Value
The value held by the register (float)
Note: The lower range of the float input registers [0:23] is reserved for FieldBus/PLC interface
usage. The upper range [24:47] cannot be accessed by FieldBus/PLC interfaces, since it is
reserved for external RTDE clients.
>>> float_val = read_input_float_register(3)
Example command: read_input_float_register(3)
• Example Parameters:
• Address = input float register 3
16.1.33. read_input_integer_register(address)
Reads the integer from one of the input registers, which can also be accessed by a Field bus.
Note, uses it’s own memory space.
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
Parameters
address: Address of the register (0:47)
Return Value
The value held by the register [-2,147,483,648 : 2,147,483,647]
Note: The lower range of the integer input registers [0:23] is reserved for FieldBus/PLC
interface usage. The upper range [24:47] cannot be accessed by FieldBus/PLC interfaces, since
it is reserved for external RTDE clients.
>>> int_val = read_input_integer_register(3)
Example command: read_input_integer_register(3)
• Example Parameters:
• Address = input integer register 3
16.1.34. read_output_boolean_register(address)
Reads the boolean from one of the output registers, which can also be accessed by a Field bus.
Note, uses it’s own memory space.
Parameters
address: Address of the register (0:127)
Return Value
The boolean value held by the register (True, False)
Note: The lower range of the boolean output registers [0:63] is reserved for FieldBus/PLC
interface usage. The upper range [64:127] cannot be accessed by FieldBus/PLC interfaces,
since it is reserved for external RTDE clients.
16.1.35. read_output_float_register(address)
Reads the float from one of the output registers, which can also be accessed by a Field bus.
Note, uses it’s own memory space.
Parameters
address: Address of the register (0:47)
16.1.36. read_output_integer_register(address)
Reads the integer from one of the output registers, which can also be accessed by a Field bus.
Note, uses it’s own memory space.
Parameters
address: Address of the register (0:47)
Return Value
The int value held by the register [-2,147,483,648 : 2,147,483,647]
Note: The lower range of the integer output registers [0:23] is reserved for FieldBus/PLC
interface usage. The upper range [24:47] cannot be accessed by FieldBus/PLC interfaces, since
it is reserved for external RTDE clients.
>>> int_val = read_output_integer_register(3)
Example command: read_output_integer_register(3)
• Example Parameters:
• Address = output integer register 3
16.1.37. read_port_bit(address)
Reads one of the ports, which can also be accessed by Modbus clients
>>> boolval = read_port_bit(3)
Parameters
address: Address of the port (See port map on Support site, page "Modbus Server" )
Return Value
The value held by the port (True, False)
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
16.1.38. read_port_register(address)
Reads one of the ports, which can also be accessed by Modbus clients
>>> intval = read_port_register(3)
Parameters
address: Address of the port (See port map on Support site, page "Modbus Server" )
Return Value
The signed integer value held by the port (-32768 : 32767)
Example command: read_port_register(3)
Example Parameters:
Address = port register 3
Creates a new Remote Procedure Call (RPC) handle. Please read the subsection ef{Remote
Procedure Call (RPC)} for a more detailed description of RPCs.
>>> proxy = rpc_factory("xmlrpc", "http://127.0.0.1:8080/RPC2")
Parameters
type: The type of RPC backed to use. Currently only the "xmlrpc" protocol is available.
url: The URL to the RPC server. Currently two protocols are supported: pstream and http.
The pstream URL looks like "<ip-address>:<port>", for instance "127.0.0.1:8080" to make a local
connection on port 8080. A http URL generally looks like "http://<ip-address>:<port>/<path>",
whereby the <path> depends on the setup of the http server. In the example given above a
connection to a local Python webserver on port 8080 is made, which expects XMLRPC calls to
come in on the path "RPC2".
Return Value
A RPC handle with a connection to the specified server using the designated RPC backend. If
the server is not available the function and program will fail. Any function that is made available
on the server can be called using this instance. For example "bool isTargetAvailable(int number,
...)" would be "proxy.isTargetAvailable(var_1, ...)", whereby any number of arguments are
supported (denoted by the ...).
This function will activate a watchdog for a particular input variable to the RTDE. When the
watchdog did not receive an input update for the specified variable in the time period specified
by min_frequency (Hz), the corresponding action will be taken. All watchdogs are removed on
program stop.
>>> rtde_set_watchdog("input_int_register_0", 10, "stop")
Parameters
variable_name: Input variable name (string), as specified by the RTDE interface
min_frequency: The minimum frequency (float) an input update is expected to arrive.
action: Optional: Either "ignore", "pause" or "stop" the program on a violation of the minimum
frequency. The default action is "pause".
Return Value
None
Note: Only one watchdog is necessary per RTDE input package to guarantee the specified
action on missing updates.
Example command: rtde set watchdog( "input int register 0" , 10, "stop"
)
• Example Parameters:
• variable name = input int register 0
• min frequency = 10 hz
• action = stop the program
Parameters
port: analog input port number, 0,1 = controller, 2,3 = tool
range: Controller analog input range 0: 0-5V (maps automatically onto range 2) and range 2:
0-10V.
range: Tool analog input range 0: 0-5V (maps automatically onto range 1), 1: 0-10V and 2: 4-
20mA.
Deprecated: The set_standard_analog_input_domain and set_tool_analog_input_
domain replace this function. Ports 2-3 should be changed to 0-1 for the latter function. This
function might be removed in the next major release.
Note: For Controller inputs ranges 1: -5-5V and 3: -10-10V are no longer supported and will
show an exception in the GUI.
16.1.42. set_analog_out(n, f )
• Example Parameters:
• n is standard analog output port 1
• f = 0.5, that corresponds to 5V (or 12mA depending on domain setting) on the
output port
16.1.43. set_configurable_digital_out(n, b)
16.1.44. set_digital_out(n, b)
16.1.45. set_flag(n, b)
Flags behave like internal digital outputs. They keep information between program runs.
Parameters
n: The number (id) of the flag, integer: [0:31]
b: The stored bit. (boolean)
Example command: set_flag(1,True)
• Example Parameters:
• n is flag number 1
• b = True will set the bit to True
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
16.1.46. set_standard_analog_out(n, f)
16.1.47. set_standard_digital_out(n, b)
• Example Parameters:
• n is standard digital output 1
• f = True
16.1.48. set_tool_digital_out(n, b)
This function will activate or deactivate the ’Tool Communication Interface’ (TCI). The TCI will
enable communication with a external tool via the robots analog inputs hereby avoiding
external wiring.
>>> set_tool_communication(True, 115200, 1, 2, 1.0, 3.5)
Parameters
enabled: Boolean to enable or disable the TCI (string). Valid values: True (enable), False
(disable)
baud_rate: The used baud rate (int). Valid values: 9600, 19200, 38400, 57600, 115200,
1000000, 2000000, 5000000.
parity: The used parity (int). Valid values: 0 (none), 1 (odd), 2 (even).
stop_bits: The number of stop bits (int). Valid values: 1, 2.
rx_idle_chars: Amount of chars the RX unit in the tool should wait before marking a
message as over / sending it to the PC (float). Valid values: min=1.0 max=40.0.
tx_idle_chars: Amount of chars the TX unit in the tool should wait before starting a new
transmission since last activity on bus (float). Valid values: min=0.0 max=40.0.
Return Value
None
Note:
Enabling this feature will disable the robot tool analog inputs.
Example command:
set_tool_communication(True, 115200, 1, 2, 1.0, 3.5)
• Example Parameters:
• enabled = True
• baud rate = 115200
• parity = ODD
• stop bits = 2
• rx idle time = 1.0
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
Parameters
Mode: 1=power (dual pin) mode.
Example command: set_tool_output_mode(1)
• Example Parameters:
• 1 is the power (dual pin) mode.
The digital outputs are used as extra supply
16.1.52. set_tool_voltage(voltage)
Sets the voltage level for the power supply that delivers power to the connector plug in the tool
flange of the robot. The votage can be 0, 12 or 24 volts.
16.1.53. socket_close(socket_name=’socket_0’)
Parameters
name: Variable name (string)
socket_name: Name of socket (string)
Return Value
an integer from the server (int), 0 is the timeout value
Example command: x_pos = socket_get_var("POS_X")
Sends: GET POS_X\n to socket_0, and expects response within 2s
• Example Parameters:
• name = POS_X -> name of variable
• socket_name = default: socket_0
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
Reads a number of ascii formatted floats from the socket. A maximum of 30 values can be
read in one command.
The format of the numbers should be in parantheses, and seperated by ",". An example list of
four numbers could look like "( 1.414 , 3.14159, 1.616, 0.0 )".
The returned list contains the total numbers read, and then each number in succession. For
example a read_ascii_float on the example above would return [4, 1.414, 3.14159, 1.616, 0.0].
A failed read or timeout will return the list with 0 as first element and then "Not a number (nan)"
in the following elements (ex. [0, nan, nan, nan] for a read of three numbers).
Parameters
number: The number of variables to read (int)
Reads a number of 32 bit integers from the socket. Bytes are in network byte order. A
maximum of 30 values can be read in one command.
Returns (for example) [3,100,2000,30000], if there is a timeout or the reply is invalid, [0,-1,-1,-1]
is returned, indicating that 0 integers have been read
Parameters
number: The number of variables to read (int)
socket_name: Name of socket (string)
timeout: The number of seconds until the read action times out (float). A timeout of 0 or
negative number indicates that the function should not return until a read is completed.
Return Value
A list of numbers read (length=number+1, list of ints)
Example command: list_of_ints = socket_read_binary_integer(4,"socket_
10")
• Example Parameters:
• number = 4 -> Number of integers to read
• socket_name = socket_10
Reads a number of bytes from the socket. A maximum of 30 values can be read in one
command.
Returns (for example) [3,100,200,44], if there is a timeout or the reply is invalid, [0,-1,-1,-1] is
returned, indicating that 0 bytes have been read
Parameters
number: The number of bytes to read (int)
socket_name: Name of socket (string)
timeout: The number of seconds until the read action times out (float). A timeout of 0 or
negative number indicates that the function should not return until a read is completed.
Return Value
A list of numbers read (length=number+1, list of ints)
Example command: list_of_bytes = socket_read_byte_list(4,"socket_10")
• Example Parameters:
• number = 4 -> Number of byte variables to read
• socket_name = socket_10
Deprecated: Reads the socket buffer until the first "\r\n" (carriage return and newline)
characters or just the "\n" (newline) character, and returns the data as a string. The returned
string will not contain the "\n" nor the "\r\n" characters.
Returns (for example) "reply from the server:", if there is a timeout or the reply is invalid, an
empty line is returned (""). You can test if the line is empty with an if-statement.
>>> if(line_from_server) :
>>> popup("the line is not empty")
>>> end
Parameters
socket_name: Name of socket (string)
timeout: The number of seconds until the read action times out (float). A timeout of 0 or
negative number indicates that the function should not return until a read is completed.
Return Value
One line string
Reads all data from the socket and returns the data as a string.
Returns (for example) "reply from the server:\n Hello World". if there is a timeout or the reply is
invalid, an empty string is returned (""). You can test if the string is empty with an if-statement.
>>> if(string_from_server) :
>>> popup("the string is not empty")
>>> end
The optional parameters "prefix" and "suffix", can be used to express what is extracted from the
socket. The "prefix" specifies the start of the substring (message) extracted from the socket.
The data up to the end of the "prefix" will be ignored and removed from the socket. The "suffix"
specifies the end of the substring (message) extracted from the socket. Any remaining data on
the socket, after the "suffix", will be preserved.
By using the "prefix" and "suffix" it is also possible send multiple string to the controller at once,
because the suffix defines where the message ends. E.g. sending ">hello<>world<" and calling
this script function with the prefix=">" and suffix="<".
Note that leading spaces in the prefix and suffix strings are ignored in the current software and
may cause communication errors in future releases.
The optional parameter "interpret_escape" can be used to allow the use of escape sequences
"\n", "\t" and "\r" as part of the prefix or suffix.
Parameters
socket_name: Name of socket (string)
prefix: Defines a prefix (string)
suffix: Defines a suffix (string)
interpret_escape: Enables the interpretation of escape sequences (bool)
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
timeout: The number of seconds until the read action times out (float). A timeout of 0 or
negative number indicates that the function should not return until a read is completed.
Return Value
String
Example command: string_from_server = socket_read_string("socket_
10",prefix=">",suffix="<")
Sends a string with a newline character to the server - useful for communicating with the UR
dashboard server
Sends the string <str> through the socket in ASCII coding. Expects no response.
Parameters
str: The string to send (ascii)
socket_name: Name of socket (string)
Return Value
a boolean value indicating whether the send operation was successful
Example command: socket_send_line("hello","socket_10")
Sends: hello\n to socket_10
• Example Parameters:
• str = hello
• socket_name = socket_10
• Returns True or False (sent or not sent)
• Example Parameters:
• str = hello
• socket_name = socket_10
• Returns True or False (sent or not sent)
Writes the boolean value into one of the output registers, which can also be accessed by a Field
bus. Note, uses it’s own memory space.
Parameters
address: Address of the register (0:127)
value: Value to set in the register (True, False)
Note: The lower range of the boolean output registers [0:63] is reserved for FieldBus/PLC
interface usage. The upper range [64:127] cannot be accessed by FieldBus/PLC interfaces,
since it is reserved for external RTDE clients.
>>> write_output_boolean_register(3, True)
Example command: write_output_boolean_register(3,True)
Writes the float value into one of the output registers, which can also be accessed by a Field
bus. Note, uses it’s own memory space.
Parameters
address: Address of the register (0:47)
value: Value to set in the register (float)
Note: The lower part of the float output registers [0:23] is reserved for FieldBus/PLC interface
usage. The upper range [24:47] cannot be accessed by FieldBus/PLC interfaces, since it is
reserved for external RTDE clients.
>>> write_output_float_register(3, 37.68)
Example command: write_output_float_register(3,37.68)
• Example Parameters:
• address = 3
• value = 37.68
Writes the integer value into one of the output registers, which can also be accessed by a Field
bus. Note, uses it’s own memory space.
Parameters
address: Address of the register (0:47)
value: Value to set in the register [-2,147,483,648 : 2,147,483,647]
Note: The lower range of the integer output registers [0:23] is reserved for FieldBus/PLC
interface usage. The upper range [24:47] cannot be accessed by FieldBus/PLC interfaces, since
it is reserved for external RTDE clients.
>>> write_output_integer_register(3, 12)
Example command: write_output_integer_register(3,12)
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
• Example Parameters:
• address = 3
• value = 12
Writes one of the ports, which can also be accessed by Modbus clients
>>> write_port_bit(3,True)
Parameters
address: Address of the port (See port map on Support site, page "Modbus Server" )
value: Value to be set in the register (True, False)
Example command: write_port_bit(3,True)
• Example Parameters:
• Address = 3
• Value = True
Writes one of the ports, which can also be accessed by Modbus clients
>>> write_port_register(3,100)
Parameters
address: Address of the port (See port map on Support site, page "Modbus Server" )
16.1.71. zero_ftsensor()
Zeroes the TCP force/torque measurement from the builtin force/torque sensor by subtracting
the current measurement from the subsequent.
17.1. Functions
17.1.1. modbus_set_runstate_dependent_choice(signal_name,
runstate_choice)
Sets the output signal levels depending on the state of the program.
Parameters
signal_name:
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
A string identifying a digital or register output signal that in advance has been added.
state:
0: Preserve signal state,
1: Set signal Low when program is not running,
2: Set signal High when program is not running,
3: Set signal High when program is running and low when it is stopped,
4: Set signal Low when program terminates unscheduled,
5: Set signal High from the moment a program is started and Low when a program terminates
unscheduled.
Note: An unscheduled program termination is caused when a Protective stop, Fault, Violation or
Runtime exception occurs.
Example command:
modbus_set_runstate_dependent_choice("output2", 3)
• Example Parameters:
• Signal name = output2
• Runstate dependent choice = 3 ! set Low when a program is stopped and High
when a program is running
Using this method sets the selected configurable digital input register to either a "default" or
"freedrive" action.
See also:
Parameters
port: The configurable digital input port number. (integer)
action: The type of action. The action can either be "default" or "freedrive". (string)
Example command: set_configurable_digital_input_action(0, "freedrive")
• Example Parameters:
• n is the configurable digital input register 0
• f is set to "freedrive" action
Using this method sets the selected gp boolean input register to either a "default" or "freedrive"
action.
Parameters
port: The gp boolean input port number. integer: [0:127]
action: The type of action. The action can either be "default" or "freedrive". (string)
Note: The lower range of the boolean input registers [0:63] is reserved for FieldBus/PLC
interface usage. The upper range [64:127] cannot be accessed by FieldBus/PLC interfaces,
since it is reserved for external RTDE clients.
See also:
set_input_actions_to_default
set_standard_digital_input_action
set_configurable_digital_input_action
set_tool_digital_input_action
Example command: set_gp_boolean_input_action(64, "freedrive")
• Example Parameters:
• n is the gp boolean input register 0
• f is set to "freedrive" action
17.1.5. set_input_actions_to_default()
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
Using this method sets the input actions of all standard, configurable, tool, and gp_boolean
input registers to "default" action.
See also:
set_standard_digital_input_action
set_configurable_digital_input_action
set_tool_digital_input_action
set_gp_boolean_input_action
Example command: set_input_actions_to_default()
17.1.6. set_runstate_configurable_digital_output_to_value(outputId,
state)
Sets the output signal levels depending on the state of the program (running or stopped).
Example: Set configurable digital output 5 to high when program is not running.
>>> set_runstate_configurable_digital_output_to_value(5, 2)
Parameters
outputId:
The output signal number (id), integer: [0:7]
state:
0: Preserve signal state,
1: Set signal Low when program is not running,
2: Set signal High when program is not running,
3: Set signal High when program is running and low when it is stopped,
4: Set signal Low when program terminates unscheduled,
5: Set signal High from the moment a program is started and Low when a program terminates
unscheduled.
Note: An unscheduled program termination is caused when a Protective stop, Fault, Violation or
Runtime exception occurs.
Example command:
set_runstate_configurable_digital_output_to_value(5, 2)
• Example Parameters:
• outputid = configurable digital output on port 5
• Runstate choice = 4 ! configurable digital output on port 5 goes low when a
program is terminated unscheduled.
Sets the output value depending on the state of the program (running or stopped).
Parameters
outputId: The output signal number (id), integer: [0:127]
state:
0: Preserve signal state,
1: Set signal to False when program is not running,
2: Set signal to True when program is not running,
3: Set signal to True when program is running and False when it is stopped,
4: Set signal to False when program terminates unscheduled,
5: Set signal to True from the moment a program is started and False when a program
terminates unscheduled.
Notes:
• The lower range of the boolean output registers [0:63] is reserved for FieldBus/PLC
interface usage. The upper range [64:127] cannot be accessed by FieldBus/PLC
interfaces, since it is reserved for external RTDE clients.
• An unscheduled program termination is caused when a Protective stop, Fault, Violation
or Runtime exception occurs.
Example command:
set_runstate_gp_boolean_output_to_value(64, 2)
• Example Parameters:
• outputid = output on port 64
• Runstate choice = 2 ! sets signal on port 64 to True when program is not running
17.1.8. set_runstate_standard_analog_output_to_value(outputId,
state)
Sets the output signal levels depending on the state of the program (running or stopped).
Example: Set standard analog output 1 to high when program is not running.
>>> set_runstate_standard_analog_output_to_value(1, 2)
Parameters
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
17.1.9. set_runstate_standard_digital_output_to_value(outputId,
state)
Sets the output signal level depending on the state of the program (running or stopped).
Example: Set standard digital output 5 to high when program is not running.
>>> set_runstate_standard_digital_output_to_value(5, 2)
Parameters
outputId: The output signal number (id), integer: [0:7]
state:
0: Preserve signal state,
1: Set signal Low when program is not running,
2: Set signal High when program is not running,
3: Set signal High when program is running and low when it is stopped,
4: Set signal Low when program terminates unscheduled,
5: Set signal High from the moment a program is started and Low when a program terminates
unscheduled.
Sets the output signal level depending on the state of the program (running or stopped).
Example: Set tool digital output 1 to high when program is not running.
>>> set_runstate_tool_digital_output_to_value(1, 2)
Parameters
outputId:
The output signal number (id), integer: [0:1]
state:
0: Preserve signal state,
1: Set signal Low when program is not running,
2: Set signal High when program is not running,
3: Set signal High when program is running and low when it is stopped,
4: Set signal Low when program terminates unscheduled,
5: Set signal High from the moment a program is started and Low when a program terminates
unscheduled.
Note: An unscheduled program termination is caused when a Protective stop, Fault, Violation or
Runtime exception occurs.
Example command:
set_runstate_tool_digital_output_to_value(1, 2)
• Example Parameters:
• outputid = tool digital output on port 1
• Runstate choice = 2 ! digital output on port 1 goes High when program is not
running
Using this method sets the selected standard digital input register to either a "default" or
"freedrive" action.
See also:
• set_input_actions_to_default
• set_configurable_digital_input_action
• set_tool_digital_input_action
• set_gp_boolean_input_action
Parameters
port: The standard digital input port number. (integer)
action: The type of action. The action can either be "default" or "freedrive". (string)
Example command: set_standard_digital_input_action(0, "freedrive")
• Example Parameters:
• n is the standard digital input register 0
• f is set to "freedrive" action
Using this method sets the selected tool digital input register to either a "default" or "freedrive"
action.
See also:
• set_input_actions_to_default
• set_standard_digital_input_action
• set_configurable_digital_input_action
• set_gp_boolean_input_action
Parameters
port: The tool digital input port number. (integer)
action: The type of action. The action can either be "default" or "freedrive". (string)
Example command: set_tool_digital_input_action(0, "freedrive")
• Example Parameters:
• n is the tool digital input register 0
• f is set to "freedrive" action
17.1.15. set_baselight_off()
NOTICE
Only applies to UR20
17.1.16. set_baselight_iec()
NOTICE
Only applies to UR20
Make the baselight comply to the IEC 60204-1 standard and indicate whether the robot is in a
safety stop, in freedrive as well as the operational mode. Further details of the colors can be
seen in the UR20 manual.
17.1.17. set_baselight_solid(r,g,b)
NOTICE
Only applies to UR20
Set a color on the entire baselight ring as specified by the given RGB values in the range 0-255.
18.2. Functions
18.2.1. mc_add_circular(pose_via, pose_to, a, v, r, mode=0)
18.2.2. mc_add_linear(pose, a, v, r)
18.2.3. mc_add_path(path_id, a, v, r)
18.2.4. mc_get_target_rtcp_speed()
This command returns the target linear speed of a Remote TCP. To get the target linear speed
of a regular TCP, please use get_target_tcp_speed_along_path().
Return Value
Remote TCP speed in m/s. This is a scalar without any indication of travel direction.
Example command: rtcpSpeed = mc_get_target_rtcp_speed()
mode:
0: Initialize regular TCP motion.
1: Initialize remote TCP motion.
tcp:
If mode = 0, the regular TCP offset, i.e. the transformation from the output flange coordinate
system to the TCP as a pose.
If mode = 1, the remote TCP offset, i.e. the transformation from the robot base to the remote
TCP as a pose.
doc:
degree of constraints
6: Constrain all 6-Degree of Freedom (DOF) of the tool.
5: Constrain 5-DOF of the tool. The rotation about z-axis is not constrained.
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
Load a .nc toolpath file. This function returns a path id which is to be used with the subsequent
mc_add_path call. This function has to be called for the same nc_file if it is to be executed with
different speed and acceleration values.
Parameters
nc_file: the .nc file on the disk
useFeedRate: specify whether to use feedrate mentioned in the NC file
Return Value
The path ID
Example command: path_id = mc_load_path("/programs/path.nc",
useFeedRate=True)
• Example Parameters:
• nc_file = /programs/path.nc → the file that contains GCode is /programs/path.nc
• useFeedRate = True → use the feedrate from .nc file
18.2.7. mc_run_motion(id=-1)
18.2.8. mc_set_pcs(pcs)
18.2.9. mc_set_speed_factor(s)
Set speed factor in range [0, 1]. The tool speed will be v × s, where v is the commanded tool
speed in each motion.
This command only affect motions in this module (such as mc_add_linear). The command
can be used on a separate thread during motion to dynamically change tool speed.
Example command: mc_set_speed_factor(s=0.1)
• Example Parameters:
• s = 0.1 → speed factor is 0.1
18.3. Examples
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
18.4. myToolPathFile.nc
%PM0
N10 G74 Z-5. L1
N20 G7
N30 G54
N40 ; Operation 1
N50 S1000 T1 M6 ; (Bull Mill, Diameter: 10, Flute Length: 25,
; Shoulder Length: 40, Overall Length: 40, Length including Holder: 40,
; Corner Radius: 2, Corner Radius Type: Corner)
N60 M3
N70 G74 Z-5. L1
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
N80 G54 I0
N90 G7
N100 M8
N110 G01 X-39.5178 Y-0.0003 Z24.9995 C0.0000 B0.0000 F1500
N120 G01 X-38.2246 Y-1.9469 Z24.9995 C0.0000 B0.0000 F1500
N130 G01 X-36.9313 Y-3.8934 Z24.9995 C0.0000 B0.0000 F1500
N140 G01 X-35.6381 Y-5.8400 Z24.9995 C0.0000 B0.0000 F1500
N150 G01 X-34.3448 Y-7.7866 Z24.9995 C0.0000 B0.0000 F1500
N160 G01 X-33.0515 Y-9.7332 Z24.9995 C0.0000 B0.0000 F1500
N170 G01 X-31.7583 Y-11.6798 Z24.9995 C0.0000 B0.0000 F1500
N180 G01 X-30.4650 Y-13.6264 Z24.9995 C0.0000 B0.0000 F1500
N190 G01 X-29.1718 Y-15.5729 Z24.9995 C0.0000 B0.0000 F1500
N200 G01 X-27.8785 Y-17.5195 Z24.9995 C0.0000 B0.0000 F1500
N210 G01 X-26.5853 Y-19.4661 Z24.9995 C0.0000 B0.0000 F1500
N220 G01 X-25.2920 Y-21.4127 Z24.9995 C0.0000 B0.0000 F1500
N230 G01 X-23.9988 Y-23.3593 Z24.9995 C0.0000 B0.0000 F1500
N240 G01 X-22.7055 Y-25.3059 Z24.9995 C0.0000 B0.0000 F1500
N250 G01 X-21.4123 Y-27.2524 Z24.9995 C0.0000 B0.0000 F1500
N260 G01 X-20.1190 Y-29.1990 Z24.9995 C0.0000 B0.0000 F1500
N270 G01 X-18.8258 Y-31.1456 Z24.9995 C0.0000 B0.0000 F1500
N280 G01 X-17.5325 Y-33.0922 Z24.9995 C0.0000 B0.0000 F1500
N290 G01 X-16.2393 Y-35.0388 Z24.9995 C0.0000 B0.0000 F1500
N300 G01 X-14.9460 Y-36.9854 Z24.9995 C0.0000 B0.0000 F1500
152
e-Series
Copyright © 2009–2023 by Universal Robots A/S. All rights reserved.
19. Glossary
19. Glossary
My Term
My definition