The URScript Programming Language
The URScript Programming Language
The URScript Programming Language
Version 1.7
February 1, 2013
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 manual is periodically
reviewed and revised.
Universal Robots A/S assumes no responsibility for any errors or omissions in this
document.
c
Copyright
2012
by Universal Robots A/S
The Universal Robots logo is a registered trademark of Universal Robots A/S.
URScript
CONTENTS
CONTENTS
Contents
Contents
1 The URScript Programming Language
1.1 Introduction . . . . . . . . . . . .
1.2 Connecting to URControl . . . .
1.3 Numbers, Variables and Types .
1.4 Flow of Control . . . . . . . . . .
1.5 Function . . . . . . . . . . . . . .
1.6 Scoping rules . . . . . . . . . . .
1.7 Threads . . . . . . . . . . . . . . .
1.7.1 Threads and scope . . . .
1.7.2 Thread scheduling . . . .
1.8 Program Label Messages . . . .
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
.
4
4
4
4
5
5
6
7
8
9
9
2 Module motion
9
2.1 Functions . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 10
2.2 Variables . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 15
3 Module internals
15
3.1 Functions . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 15
3.2 Variables . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 20
4 Module urmath
20
4.1 Functions . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 20
4.2 Variables . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 27
5 Module interfaces
28
5.1 Functions . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 28
5.2 Variables . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 39
URScript
1.1
Introduction
The Universal Robot can be controlled a three different levels: The Graphical UserInterface Level, the Script Level and the C-API Level. URScript is the robot programming
languange used to control the robot at the Script Level. Like any other programming
language URScript has variables, types, flow of control statements, function etc. In
addition URScript has a number of built-in variables and functions which monitors and
controls the I/O and the movements of the robot.
1.2
Connecting to URControl
URControl is the low-level robot controller running on the Mini-ITX PC in the controller
cabinet. When the PC boots up URControl starts up as a daemon (like a service) and
PolyScope 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-xx (or the ip-adresse found in the about dialog-box in PolyScope if
the robot is not in dns.)
port: 30002
When connected URScript programs or commands are sent i clear text on the socket.
Each line is terminated by \n.
1.3
42
False or True and not False
87-13/3.1415
= "Hello, World!"
4
URScript
Flow of Control
l = [1,2,4]
target = p[0.4,0.4,0.0,0.0,3.14159,0.0]
The fundamental type of a variable is deduced from the first assignment of the variable. In the example above foo is an int and bar is a bool. target is a pose, a
combination of a position and orientation.
The fundamental types are:
none
bool
number - either int or float
pose
string
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.
1.4
Flow of Control
1.5
Function
URScript
Scoping rules
1.6
Scoping rules
URScript
Threads
a = 0
def myFun():
local a = 1
return a
end
r = myFun()
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.
1.7
Threads
thread myThread():
# Do some stuff
return
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 can in other words be nested,
allowing for a thread hierarchy to be formed.
To run a thread use the following syntax:
thread myThread():
# Do some stuff
return
end
thrd = run myThread()
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 off the new
thread, and then goes off to execute the instruction following the run instruction.
To wait for a running thread to finish, use the join command:
7
URScript
Threads
thread myThread():
# Do some stuff
return
end
thrd = run myThread()
join thrd
This halts the calling threads execution, until the thread is finished
executing. 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
end
thrd = run myThread()
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 are provided. A critical section ensures that the code it encloses is allow to
finish, before another thread is allowed to run. It is therefore important that the critical
section is kept as short as possible. The syntax is as follows:
thread myThread():
enter_critical
# Do some stuff
exit_critical
return
end
1.7.1
The scoping rules for threads are exactly the same, as those used for functions. See
section 1.6 for a discussion of these rules.
URScript
1.7.2
Module motion
Thread scheduling
Because the primary purpose of the urscript scripting language is to control the robot,
the scheduling policy is largely based upon the realtime demands of this task.
The robot must be controlled a frequency of 125 Hz, or in other words, it must be told
what to do every 0.008 second (each 0.008 second period is called a frame). To
achieve this, each thread is given a physical (or robot) time slice of 0.008 seconds
to use, and all threads in a runnable state is then scheduled in a round robin1 fashion.
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 doesnt control
the robot, and therefor doesnt use any physical time. If a thread uses up its entire
time slice, 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 the frame2 . 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 doesnt control the robot,
it still uses physical time. The same is true for the sync instruction.
1.8
A special feature is added to the script code, to make it simple to keep track of which
lines are executed by the runtime machine. An example Program Label Message in
the script code looks as follows;
sleep(0.5)
$ 3 "AfterSleep"
digital_out[9] = True
After the the Runtime Machnie executes the sleep command, it will send a message
of type PROGRAM LABEL to the latest connected primary client. The message will hold
the number 3 and the text AfterSleep. This way the connected client can keep track
of which lines of codes are being executed by the Runtime Machine.
Module motion
This module contains functions and variables built into the URScript programming language.
URScript programs are executed in real-time in the URControl RuntimeMachine (RTMachine). The RuntimeMachine communicates with the robot with a frequency of 125hz.
1
Before the start of each frame the threads are sorted, such that the thread with the largest remaining
time slice is to be scheduled first.
2
If this expectation is not met, the program is stopped.
URScript
Functions
Module motion
Robot trajectories are generated online by calling the move functions movej, movel
and the speed functions speedj, speedl and speedj init.
Joint positions (q) and joint speeds (qd) are represented directly as lists of 6 Floats,
one for each robot joint. Tool poses (x) are represented as poses also consisting of 6
Floats. In a pose, the first 3 coordinates is a position vector and the last 3 an axis-angle
(http://en.wikipedia.org/wiki/Axis angle).
2.1
Functions
end force mode()
Resets the robot mode from force mode to normal operation.
This is also done when a program stops.
10
URScript
Functions
Module motion
type:
limits:
11
URScript
Functions
Module motion
a:
v:
r:
12
URScript
Functions
Module motion
v:
t:
time [S]
r:
v:
r:
v:
r:
13
URScript
Functions
Module motion
URScript
Module internals
stopj(a)
Stop (linear in joint space)
Decellerate joint speeds to zero
Parameters
a: joint acceleration [rad/s2] (of leading axis)
stopl(a)
Stop (linear in tool space)
Decellerate tool speed to zero
Parameters
a: tool accleration [m/s2]
2.2
Variables
Name
package
a joint default
a tool default
v joint default
v tool default
3
3.1
Value:
Value:
Value:
Value:
Value:
Description
Motion
3
1.2
0.75
0.3
Module internals
Functions
get actual joint positions()
Returns the actual angular positions of all joints
The angular actual positions are expressed in radians and returned as a
vector of length 6. Note that the output might differ from the output of
get target joint positions(), especially durring acceleration and heavy
loads.
Return Value
The current actual joint angular position vector in rad : [Base,
Shoulder, Elbow, Wrist1, Wrist2, Wrist3]
15
URScript
Functions
Module internals
16
URScript
Functions
Module internals
17
URScript
Functions
Module internals
message string
title string
error message?
powerdown()
Shutdown the robot, and power off the robot and controller.
18
URScript
Functions
Module internals
set gravity(d)
Set the direction of the gravity
Parameters
d: 3D vector, describing the direction of the gravity, relative to
the base of the robot.
set payload(m, CoG)
Set payload mass and center of gravity
Sets the mass and center of gravity (abbr. CoG) of the payload.
This function must be called, when the payload weight or weigh
distribution changes significantly - I.e when the robot picks up or puts
down a heavy workpiece.
The CoG argument is optional - If not provided, the Tool Center Point
(TCP) will be used as the Center of Gravity (CoG). If the CoG argument is
omitted, later calls to set tcp(pose) will change CoG to the new TCP.
The CoG is specified as a Vector, [CoGx, CoGy, CoGz], displacement,
from the toolmount.
Parameters
m:
mass in kilograms
CoG: Center of Gravity: [CoGx, CoGy, CoGz] in meters.
Optional.
set tcp(pose)
Set the Tool Center Point
Sets the transformation from the output flange coordinate system to the
TCP as a pose.
Parameters
pose: A pose describing the transformation.
sleep(t)
Sleep for an amount of time
Parameters
t: time [s]
sync()
Uses up the remaining physical time a thread has in the current frame.
19
URScript
Module urmath
textmsg(s)
Send text message
Send message to be shown on the GUI log-tab
Parameters
s: message string, variables of other types (int, bool poses
etc.) can also be sent
3.2
Variables
Name
package
4
4.1
Description
Value: None
Module urmath
Functions
acos(f )
Returns the arc cosine of f
Returns the principal value of the arc cosine of f, expressed in radians. A
runtime error is raised if f lies outside the range [-1, 1].
Parameters
f: floating point value
Return Value
the arc cosine of f.
asin(f )
Returns the arc sine of f
Returns the principal value of the arc sine of f, expressed in radians. A
runtime error is raised if f lies outside the range [-1, 1].
Parameters
f: floating point value
Return Value
the arc sine of f.
20
URScript
Functions
Module urmath
atan(f )
Returns the arc tangent of f
Returns the principal value of the arc tangent of f, expressed in radians.
Parameters
f: floating point value
Return Value
the arc tangent of f.
atan2(x, y)
Returns the arc tangent of x/y
Returns the principal value of the arc tangent of x/y, expressed in radians.
To compute the value, the function uses the sign of both arguments to
determine the quadrant.
Parameters
x: floating point value
y: floating point value
Return Value
the arc tangent of x/y.
binary list to integer(l)
Returns the value represented by the content of list 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.
21
URScript
Functions
Module urmath
ceil(f )
Returns the smallest integer value that is not less than f
Rounds floating point number to the smallest integer no greater than f.
Parameters
f: floating point value
Return Value
rounded integer
cos(f )
Returns the cosine of f
Returns the cosine of an angle of f radians.
Parameters
f: floating point value
Return Value
the cosine of f.
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
Return Value
The angle in radians
floor(f )
Returns largest integer not greater than f
Rounds floating point number to the largest integer no greater than f.
Parameters
f: floating point value
Return Value
rounded integer
force()
Returns the force exceted at the TCP
Return the current externally excerted force at the TCP. The force is the
lengt of the force vector calculated using get tcp force().
Return Value
The force in newtons (float)
22
URScript
Functions
Module urmath
alpha:
Return Value
interpolated pose (pose)
23
URScript
Functions
Module urmath
log(b, f )
Returns the logarithm of f to the base b
Returns the logarithm of f to the base b. If b or f are negative, or if b i 1 an
runtime error is raised.
Parameters
b: floating point value
f: floating point value
Return Value
the logarithm of f to the base of b.
norm(a)
Returns the norm of the argument
The argument can be one of three diffrent types:
Pose: In this case the euclidian norm of the pose is returned.
Float: In this case fabs(a) is returned.
Int: In this case abs(a) is returned.
Parameters
a: Pose, float or int
Return Value
norm of a
point dist(p from, p to)
Point distance
Parameters
p from: tool pose (pose)
p to:
Return Value
Distance between the two tool positions (without considering
rotations)
24
URScript
Functions
Module urmath
pose add(p 1, p 2)
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:
p 3.P = p 1.P + p 2.P
p 3.R = p 1.R * p 2.R
Parameters
p 1: tool pose 1(pose)
p 2: tool pose 2 (pose)
Return Value
Sum of position parts and product of rotation parts (pose)
pose dist(p from, p to)
Pose distance
Parameters
p from: tool pose (pose)
p to:
Return Value
distance
pose inv(p from)
Get the invers of a pose
Parameters
p from: tool pose (spatial vector)
Return Value
inverse tool pose transformation (spatial vector)
pose sub(p to, p from)
Pose subtraction
Parameters
p to:
25
URScript
Functions
Module urmath
26
URScript
Variables
Module urmath
sin(f )
Returns the sine of f
Returns the sine of an angle of f radians.
Parameters
f: floating point value
Return Value
the sine of f.
sqrt(f )
Returns the square root of f
Returns the square root of f. If f is negative, an runtime error is raised.
Parameters
f: floating point value
Return Value
the square root of f.
tan(f )
Returns the tangent of f
Returns the tangent of an angle of f radians.
Parameters
f: floating point value
Return Value
the tangent of f.
4.2
Variables
Name
package
Description
Value: None
27
URScript
Module interfaces
5
5.1
Module interfaces
Functions
get analog in(n)
Get analog input level
Parameters
n: The number (id) of the input. (int) @return float, The signal
level [0,1]
get analog out(n)
Get analog output level
Parameters
n: The number (id) of the input. (int)
Return Value
float, The signal level [0;1]
get digital in(n)
Get digital input signal level
Parameters
n: The number (id) of the input. (int)
Return Value
boolean, The signal level.
get digital out(n)
Get digital output signal level
Parameters
n: The number (id) of the output. (int)
Return Value
boolean, The signal level.
28
URScript
Functions
Module interfaces
Parameters
port number: An integer specifying one of the available
Euromap67 input signals.
Return Value
A boolean, either True or False
get euromap output(port number)
Reads the current value of a specific Euromap67 output signal. This
means the value that is sent from the robot to the injection moulding
machine. See http://support.universal-robots.com/Manuals/Euromap67
for signal specifications.
>>> var = get euromap output(3)
Parameters
port number: An integer specifying one of the available
Euromap67 output signals.
Return Value
A boolean, either True or False
get flag(n)
Flags behave like internal digital outputs. The keep information between
program runs.
Parameters
n: The number (id) of the flag [0;32]. (int)
Return Value
Boolean, The stored bit.
29
URScript
Functions
Module interfaces
Parameters
IP:
slave number:
signal name:
Parameters
signal name: A string equal to the name of the signal that
should be deleted.
30
URScript
Functions
Module interfaces
Parameters
signal name:
slave number:
31
URScript
Functions
Module interfaces
Parameters
signal name:
register value:
Parameters
signal name:
digital value:
Parameters
signal name:
32
URScript
Functions
Module interfaces
Parameters
signal name:
Parameters
address: Address of the port (See portmap on Support site,
page UsingModbusServer )
Return Value
The value held by the port (True, False)
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 portmap on Support site,
page UsingModbusServer )
Return Value
The signed integer value held by the port (-32768 : 32767)
set analog inputrange(port, range)
Set range of analog inputs
Port 0 and 1 is in the controller box, 2 and 3 is in the tool connector For the
ports in the tool connector, range code 2 is current input.
Parameters
port:
33
URScript
Functions
Module interfaces
Parameters
port number:
34
URScript
Functions
Module interfaces
Parameters
port number:
Parameters
socket name: Name of socket (string)
35
URScript
Functions
Module interfaces
Parameters
name:
URScript
Functions
Module interfaces
37
URScript
Functions
Module interfaces
38
URScript
Variables
Module interfaces
Parameters
name:
value:
Parameters
address: Address of the port (See portmap on Support site,
page UsingModbusServer )
value:
Parameters
address: Address of the port (See portmap on Support site,
page UsingModbusServer )
value:
5.2
Variables
Name
package
Description
Value: None
39
URScript