In some cases, it can be beneficial to be able to control a UR robot through python, if for instance you wish to control the robot based on a web interface or calculations outside of the polyscope interface.
If you want to control your robot through a python script, this can be done via the RTDE (Real Time Data Exchange) port of the robot controller. RTDE is running in the background of the robot and is not accessible through the polyscope interface. Through RTDE you are able to get information about the robot, including current TCP pose, input and output statuses etc. You are also able to control the robot through move or servo commands and control the IO of the robot controller and the end-effector.
Installation
To communicate with RTDE from python you need to install the ur_rtde library from SDU (University of Southern Denmark). To install the library, head to your python environment in the terminal and activate it. If you are using anaconda you can use this command:
conda activate <your_environment_name>
After activating your environment, run the following command to install the library to your environment:
pip install ur_rtde
The official installation guide can be found here: Installation β ur_rtde 1.6.0 documentation
Import
To use the RTDE library in python you need to import it to your python script. This is done like this:
import rtde_control # For controlling the robot
import rtde_receive # For receiving data from the robot
import rtde_io # For robot IO
For easy use of the RTDE libraries you use can definitions like this:
rtde_ctrl = rtde_control.RTDEControlInterface(robot_ip)
rtde_rec = rtde_receive.RTDEReceiveInterface(robot_ip)
rtde_inout = rtde_io.RTDEIOInterface(robot_ip)
robot_ip = β192.168.0.xxxβ
To get the IP of the UR robot, click on the UR logo in the top left corner of the polyscope interface.
Setup on Robot
On the robot some settings have to be configured to make the RTDE control via python work.
Step 1: Press the β‘ icon at the top right off the screen, then go to Settings β System β Remote control and enable remote control.
Step 2: Go to Installation β Fieldbus. Disable Ethernet, disable profinet and disable MODBUS. Otherwise, RTDE will fail to connect with the robot. Save the configuration on the robot.
Step 3: Press the remote/local button at the top right of the screen. Put the robot in remote mode to control the robot with RTDE. Use local mode to move the robot via the polyscope interface.
Use the library
The RTDE libraries uses approximately the same syntax as URscripts.
Here is a few examples of how to use the RTDE libraries:
Set a standard digital output
rtde_inout.setStandardDigitalOut(7, False)
This method can also be used to set safety, tool or configurable outputs.
Read a digital input
rtde_rec.getDigitalInState(7)
This method can also be used to read safety, tool or configurable inputs.
0-7
: Standard digital inputs
8-15
: Configurable inputs
16-17
: Tool inputs
Make a move
rtde_ctrl.moveJ([x, y, z, rx, ry, rz], speed, acceleration)
Move commands also work for other types of movement like moveL
and moveP
.
Notice that the x, y and z coordinates
should be entered as [m] in RTDE commands, while the polyscope interface displays positions as [mm]. rx, ry and rz
should be entered as [rad], the same as in the polyscope interface. Blend radius and move time is not supported via RTDE for single movements. For a blend radius, you need to use move path: API Reference β ur_rtde 1.6.0 documentation.
Blend radius can be applied to a movement path like this:
pos_1 = [x_1, y_1, z_1, rx_1, ry_1, rz_1, speed_1, acceleration_1, blend radius_1]
pos_2 = [x_2, y_2, z_2, rx_2, ry_2, rz_2, speed_2, acceleration_2, blend radius_2]
path = [pos_1, pos_2]
rtde_ctrl.moveL(path)
The blend radius can only be applied to movements defined as a path, not to a single move followed by another single move.
If you want to define a set of specific joint rotations for a position, that can be done like this:import math
joint_rotation = [
math.radians(base rotation),
math.radians(shoulder rotation),
math.radians(elbow rotation),
math.radians(wrist 1 rotation),
math.radians(wrist 2 rotation),
math.radians(wrist 3 rotation)
]
rtde_ctrl.moveJ(joint_rotation)
The rotation values should be entered as [Β°] like displayed in the polyscope interface.
Note that move
commands are blocking per default, meaning the python program will wait for the movement to finish before continuing execution of the remaining code.
Get actual TCP pose
rtde_rec.getActualTCPPose()
This returns the TCP position as a list.
Get actual TCP force
This only works on e-models.
rtde_rec.getActualTCPForce()
This returns the TCP forces as a list.
Jogging
Jogging performs a linear movement. jog
is non-blocking, as opposed to normal move
.
To start jogging:
rtde_ctrl.jogStart(speed, feature, acceleration)
The speed
argument can be input as a list; an example jog_speed_down_z = [0.0, 0.0, -0.1, 0.0, 0.0, 0.0] # m/s for translation (downward)
The feature
argument could also be called frame
. Enter 0
to use the default base feature.
The acceleration
argument should be entered as [m/s^2]
To stop jogging:
rtde_ctrl.jogStop()
Stop script
rtde_ctrl.stopScript()
This command makes sure the RTDE communication is stopped correctly, and not leaving the RTDE occupied.
Be aware that the RTDE libraries are designed for C++ but most functions have been translated to python. It is also possible to send custom scripts via RTDE for not supported functions. Check the documention for this. Keep in mind, the most used functions will work.
It is also possible to compile and edit the C++ libraries yourself to add functionality. For information about that, see the examples page which also includes more examples of use in C++ and python: Examples β ur_rtde 1.6.0 documentation
Make a custom RTDE control class
For easier robot control, creating a Python class can be very helpful. An example is shown below. Most common functions are integrated, and you can add more functions as needed. For example, RTDE doesnβt have a pose_trans
function. This function has been added to the URControl
class to replicate the same result as the pose_trans
from the Polyscope programming.
With this class, controlling the robot becomes easier, as error messages and the connection to the robot are handled within the class. This makes your code easier to read and simplifies the usage of the robot.
import rtde_control # For controlling the robot
import rtde_receive # For receiving data from the robot
import rtde_io # For robot IO
import time
import logging
import numpy as np
logging.basicConfig(
level=logging.DEBUG,
format="%(asctime)s - %(levelname)s - %(message)s",
datefmt="%Y-%m-%d %H:%M:%S",
)
##########################
#class for controlling UR robot with UR_RDTE. gives easy way to use the library.
# you need to enter the robot ip. us connect() for connecting etc.
##########################
class URControl:
def __init__(self, robot_ip):
self.robot_ip = robot_ip
self.rtde_ctrl = None
self.rtde_rec = None
self.rtde_inout = None
# Connect to robot with retry logic
def connect(self):
max_retries = 10
retry_delay = 0.5 # Delay in seconds between retries
for attempt in range(1, max_retries + 1):
try:
self.rtde_ctrl = rtde_control.RTDEControlInterface(self.robot_ip)
self.rtde_rec = rtde_receive.RTDEReceiveInterface(self.robot_ip)
self.rtde_inout = rtde_io.RTDEIOInterface(self.robot_ip)
logging.info(f"Connected to robot: {self.robot_ip} on attempt {attempt}")
return # Exit the method upon successful connection
except Exception as e:
logging.error(f"Attempt {attempt} failed: {e}")
if attempt < max_retries:
time.sleep(retry_delay) # Wait before retrying
else:
logging.error("Max retries reached. Unable to connect to the robot.")
raise
#stop connection to robot
def stop_robot_control(self):
self.rtde_ctrl.stopScript()
logging.info("stopped connection with robot")
#set tool frame (TCP frame)
def set_tool_frame(self, tool_frame):
try:
self.rtde_ctrl.setTcp(tool_frame)
#logging.info(f"succesfully setted toolframe: {self.rtde_ctrl.getTCPOffset()}")
except Exception as e:
logging.error(f"error setting toolframe: {e}")
def set_tcp(self, tool_frame):
self.set_tool_frame(tool_frame)
#set payload (not tested). needs payload(kg), center of gravity (CoGx, CoGy, CoGz)
def set_payload(self, payload, cog):
try:
self.rtde_ctrl.setPayLoad(payload, cog)
except Exception as e:
logging.error(f"can not set COG or/and payload: {e}")
#set digital output
def set_digital_output(self, output_id, state):
try:
self.rtde_inout.setStandardDigitalOut(output_id, state)
logging.info(f"digital output {output_id} is {state}")
except Exception as e:
logging.error(f"Eror setting digital output {output_id}: {e}")
#pulse digital output. duration in seconds
def pulse_digital_output(self, output_id, duration):
self.set_digital_output(output_id=output_id, state=True)
time.sleep(duration)
self.set_digital_output(output_id=output_id, state=False)
#move L
def move_l(self, pos, speed=0.5, acceleration=0.5):
try:
self.rtde_ctrl.moveL(pos, speed, acceleration)
except Exception as e:
logging.error(f"can not move: {e}")
#move L path
def move_l_path(self, path):
try:
self.rtde_ctrl.moveL(path)
except Exception as e:
logging.error(f"can not move: {e}")
#move j (not tested yet)
def move_j(self, pos, speed=0.5, acceleration=0.5):
try:
self.rtde_ctrl.moveJ(pos, speed, acceleration)
except Exception as e:
logging.error(f"can not move: {e}")
#move add (relative movement based of current position
def move_add_l(self, relative_move, speed=0.5, acceleration=0.5):
try:
current_tcp_pos = self.get_tcp_pos()
new_linear_move = [current_tcp_pos[i] + relative_move[i] for i in range(6)]
self.move_l(new_linear_move, speed, acceleration)
except Exception as e:
logging.error(f"cannot do relative move: {e}")
#move add j (relative movement based of current position
def move_add_j(self, relative_move, speed=0.5, acceleration=0.5):
try:
current_tcp_pos = self.get_tcp_pos()
new_linear_move = [current_tcp_pos[i] + relative_move[i] for i in range(6)]
self.move_j(new_linear_move, speed, acceleration)
except Exception as e:
logging.error(f"cannot do relative move: {e}")
#help functions for pose_trans
def rodrigues_to_rotation_matrix(self,r):
"""Converteer een rodrigues-vector naar een rotatiematrix."""
theta = np.linalg.norm(r)
if theta < 1e-6: # Geen rotatie
return np.eye(3)
k = r / theta
K = np.array([
[0, -k[2], k[1]],
[k[2], 0, -k[0]],
[-k[1], k[0], 0]
])
return np.eye(3) + np.sin(theta) * K + (1 - np.cos(theta)) * np.dot(K, K)
def pose_to_matrix(self,pose):
"""Converteer een 6D-pose naar een 4x4 transformatie-matrix."""
R = self.rodrigues_to_rotation_matrix(pose[3:]) # Rotatie
t = np.array(pose[:3]) # Translatie
T = np.eye(4)
T[:3, :3] = R
T[:3, 3] = t
return T
def matrix_to_pose(self,matrix):
"""Converteer een 4x4 transformatie-matrix terug naar een 6D-pose."""
R = matrix[:3, :3]
t = matrix[:3, 3]
theta = np.arccos((np.trace(R) - 1) / 2)
if theta < 1e-6:
r = np.zeros(3)
else:
r = theta / (2 * np.sin(theta)) * np.array([
R[2, 1] - R[1, 2],
R[0, 2] - R[2, 0],
R[1, 0] - R[0, 1]
])
return np.concatenate((t, r))
def pose_trans(self,pose1, pose2):
"""Combineer twee poses met behulp van matrixvermenigvuldiging."""
T1 = self.pose_to_matrix(pose1)
T2 = self.pose_to_matrix(pose2)
T_result = np.dot(T1, T2)
return self.matrix_to_pose(T_result)
#return actual TCP position
def get_tcp_pos(self):
try:
return self.rtde_rec.getActualTCPPose()
except Exception as e:
logging.error(f"cannot return actual tcp pose: {e}")
#return actual joint pos
def get_joint_pos(self):
try:
return self.rtde_rec.getActualQ()
except Exception as e:
logging.error(f"cannot return actual joint pose: {e}")
def set_tcp_rotation(self,rx, ry, rz,speed=0.1,acc=0.1):
"""
Sets the rotation of the tool center point (TCP).
Args:
rx (float): Rotation around the X-axis in degrees.
ry (float): Rotation around the Y-axis in degrees.
rz (float): Rotation around the Z-axis in degrees.
Returns:
None
"""
# Get the current TCP pose
current_pose = self.get_tcp_pose() # Assume this returns [x, y, z, rx, ry, rz]
# Update the rotation components
current_pose[3] = rx # Set rotation around X-axis
current_pose[4] = ry # Set rotation around Y-axis
current_pose[5] = rz # Set rotation around Z-axis
# Move the robot to the new rotation
self.move_l(current_pose, speed, acc) # Execute a linear move to the updated pose
if __name__ == '__main__':
robot = URControl('192.168.0.1')
robot.connect()
robot.stop_robot_control()