Get started with Python
Quickly develop a program in Python that communicates with your robot using this library. It is available on PyPI.
🚀 Why you will love it
- Instant connectivity. Speak RTDE, Primary Interface, SSH, sockets, and SFTP with a single API.
- Battle-tested. Powering automation stacks in factories, labs, and classrooms around the world.
- Friendly by design. Pythonic abstractions, rich events, and typed helpers for poses, registers, variables, and more.
🧠 What is inside?
The SDK wraps the Universal Robots communication stack so you can:
- Stream telemetry up to 500 Hz with RTDE (read & write registers, sync IO, monitor forces).
- Drive URScript over the Primary Interface, fetch installation & program variables, and react to robot state changes.
- Run custom socket servers that chat with UR scripts and external tools.
- Move files back and forth with SFTP, and run shell commands securely via SSH.
- Decode
.urpprograms and.installationfiles into editable XML. - Convert poses between rotation vectors and roll-pitch-yaw angles in one line.
📦 Install it
From PyPI
pip install UnderAutomation.UniversalRobots
From source
git clone https://github.com/underautomation/UniversalRobots.py.gitcd UniversalRobots.pypip install -e .
Import features :
from underautomation.universal_robots.ur import URfrom underautomation.universal_robots.connect_parameters import ConnectParametersfrom underautomation.universal_robots.common.pose import Posefrom underautomation.universal_robots.rtde.rtde_input_data import RtdeInputDatafrom underautomation.universal_robots.rtde.rtde_output_data import RtdeOutputDatafrom underautomation.universal_robots.rtde.rtde_input_values import RtdeInputValues# from underautomation.universal_robots... import ...# etc.
Features
RTDE and Primary Interface
Full support for :
- RTDE (Real-Time Data Exchange) : read and write registers up to 500Hz
- Primary Interface :
- Receive robot state data at 10Hz : Cartesian and angular position, robot status, inputs and outputs value, and 100+ more measurements ...
- Send URScript
- Get variables
# Create a robot instancerobot = UR()# Setup connection to th robotparam = ConnectParameters()param.ip = "192.168.0.1"# Enable primary interface to get variable valuesparam.primary_interface.enable = True# Enable rtde at 5Hz (500Hz possible)param.rtde.enable = Trueparam.rtde.frequency = 5# Ask the robot for permission to write these registersparam.rtde.input_setup.add(RtdeInputData.StandardAnalogOutput0)param.rtde.input_setup.add(RtdeInputData.InputBitRegisters, 64)# Ask the robot to send me this dataparam.rtde.output_setup.add(RtdeOutputData.ActualTcpPose)param.rtde.output_setup.add(RtdeOutputData.ActualTcpForce)# Connect to the robotrobot.connect(param)# Function called when new RTDE data is receiveddef on_output_data_received(o, e):### Display robot TCP posepose = robot.rtde.output_data_values.actual_tcp_pose# pose.X, pose.Y, pose.Z, pose.Rx, ...# Display robot TCP forceforce = robot.rtde.output_data_values.actual_tcp_force# Write data in robot controlerinputs = RtdeInputValues()inputs.standard_analog_output0 = 0.2inputs.input_bit_registers.x64 = Truerobot.rtde.write_inputs(inputs)### Event raised when data is receivedrobot.rtde.output_data_received(on_output_data_received)# Function called when any program or installation variable changes in the robotdef on_value_updated(p, e):### Display all program and installation variablesvariables = robot.primary_interface.global_variables.get_all()name = variables[0].namevalue = variables[0].to_pose()type = variables[0].type### Event raised when a program or installation variable changerobot.primary_interface.global_variables.values_updated(on_value_updated)# Function called when masterboard data is receiveddef on_masterboard_data_received(p, e):ai0 = robot.primary_interface.masterboard_data.analog_input0di2 = robot.primary_interface.masterboard_data.digital_inputs.digital2# Several other events are raised by primary interfacerobot.primary_interface.masterboard_data_received(on_masterboard_data_received)# Function called when cartesian data is receiveddef on_cartesian_info_received(p, e):x = e.XtcpOffsetX = e.TCPOffsetXrobot.primary_interface.cartesian_info_received(on_cartesian_info_received)# Function called when joint data is receiveddef on_joint_data_received(o,e):shoulderAngle = e.Shoulder.PositionelbowMode = e.Elbow.JointModewrist3Speed = e.Wrist3.ActualSpeedrobot.primary_interface.joint_data_received(on_joint_data_received)
Read variables
Read program and installation variables :
myVar = robot.primary_interface.global_variables.get_by_name("myVar")variables = robot.primary_interface.global_variables.get_all()
Dashboard Server
Remote control the robot : load, play, pause, and stop a robot program, power on and off, release brake, shutdown, ...
# Create a new robot instancerobot = UR()# Setup connection to th robotparam = ConnectParameters("192.168.0.56")param.dashboard.enable=True# Connect to the robotrobot.connect(param)# Display a popup on the pendantrobot.dashboard.show_popup("I just remote-controlled my robot!")# Power on the robot arm and release brakesrobot.dashboard.power_on()robot.dashboard.release_brake()# Load program file to polyscoperobot.dashboard.load_program("fast_bin_picking.urp")# Start the programrobot.dashboard.play()# Get program name and statestate = robot.dashboard.get_program_state()
XML-RPC
From your robot program, remote call a function implemented in your .NET program. For example, this allows you to request a position resulting from image processing.
Robot code (URScript) :
# Connect to the SDK and specifie the IP and port of the PCrpc:=rpc_factory("xmlrpc","http://192.168.0.10:50000")# Call method GetPose and wait for the reply. The replied pose will be assigned in variable "answer"answer:=rpc.GetPose(100)
Python code :
# XML-RPC server on port 50000parameters.xml_rpc.enable = Trueparameters.xml_rpc.port = 50000# Event callback :# robot.xml_rpc.xml_rpc_server_request
Socket communication
The library can start a communication. The robot can connect to your server and exchange custom data.
Robot code (URScript) :
# Connect to robot socket server in URScriptsocket_open("192.168.0.10", 50001)# Raise event SocketRequest is your appsocket_send_string("Hello from robot")# Raise event SocketGetVar is your appvar1 := socket_get_var("MY_VAR")
Python code :
robot = UR()# Setup connection to th robotparam = ConnectParameters("192.168.0.1")# Enable spcket server on port 50001param.socket_communication.enable = Trueparam.socket_communication.port = 50001# Connect to the robotrobot.connect(param)### Function called when robot connects with URScipt function socket_open()def on_socket_client_connection(o, e : SocketClientConnectionEventArgs):e.client.socket_write("Hello cobot <3")robot.socket_communication.socket_client_connection(on_socket_client_connection)# Function called when the robot sends a message with socket_write()def on_socket_request(o,e:SocketRequestEventArgs):# Get robot messagerobotMessage = e.Messagerobot.socket_communication.socket_request(on_socket_request)# Send a message to all connected clientsrobot.socket_communication.socket_write("123456")### List of all connected clientsconnectedClients = robot.socket_communication.connected_clients# IP address and remote port of a clientclientEndpoint = connectedClients[0].end_point# Send a message to a specific connected robotconnectedClients[0].socket_write("Hello robot [0]")# Handle client disconnectiondef on_socket_client_disconnection(o,e):passconnectedClients[0].socket_client_disconnection(on_socket_client_disconnection)
SFTP
Manipulate files and folders of the robot via SFTP (Secure File Transfer Protocol) : download to the robot, import from the robot, rename, delete, move, list files in a folder...
robot = UR()# Setup connection to th robotparam = ConnectParameters("192.168.0.1")# Enable SFTP file accessparam.ssh.enable_sftp = True# Connect to the robotrobot.connect(param)# Enumerates files and folderitems = robot.sftp.list_directory("/home/ur/ursim-current/programs/")# Download program file prg.urp to your local diskrobot.sftp.download_file("/home/ur/ursim-current/programs/prg.urp", "C:\\temp\\prg.urp")# Send a local file to the robotrobot.sftp.upload_file("C:\\temp\\prg.urp", "/home/ur/ursim-current/programs/prg.urp")# Manipulate files and directoriesrobot.sftp.rename_file("/home/ur/prg.urp", "/home/ur/prg2.urp")robot.sftp.delete("/home/ur/prg.urp")exists = robot.sftp.exists("/home/ur/prg.urp")robot.sftp.write_all_text("/home/ur/file.txt", "Hello robot !")
SSH
Open a SSH (Secure Shell) connection with the robot to execute Linux command lines, as in the terminal.
robot.ssh.run_command("echo Hello > /home/ur/Desktop/NewFile.txt");
Convert position types
Convert Rotation Vector to and from RPY.
# Create X, Y, Z, RX, RY, RZ posepose = Pose(0.1, 0.2, -0.1, 0, 0.05, 0.1)# Convert cartesian pose type to RPY or rotation vectorrpy = pose.from_rotation_vector_to_rpy()vectorPose = pose.from_rpy_to_rotation_vector()
Edit program and installation files
Open and edit program (.urp) and installation (.installation) files :
# Decompile program and installation files and access inner XMLinstallation = URInstallation.load("C:\\temp\\default.installation")prg = URProgram.load("C:\\temp\\prg.urp")internalXml = prg.xml