Implementation of UR Robotic Arm Teleoperation with PIKA SDK
Demo Demonstration
Pika Teleoperation of UR Robotic Arm Demo Video
Getting Started with PIKA Teleoperation (UR Edition)
We recommend reading [Methods for Teleoperating Any Robotic Arm with PIKA] before you begin.
Once you understand the underlying principles, let’s guide you through writing a teleoperation program step by step. To quickly implement teleoperation functionality, we will use the following tools:
- PIKA SDK: Enables fast access to all PIKA Sense data and out-of-the-box gripper control capabilities
- Various transformation tools: Such as converting XYZRPY to 4x4 homogeneous transformation matrices, converting XYZ and quaternions to 4x4 homogeneous transformation matrices, and converting RPY angles (rotations around X/Y/Z axes) to rotation vectors
- UR Robotic Arm Control Interface: This interface is primarily built on the ur-rtde library. It enables real-time control by sending target poses (XYZ and rotation vectors), speed, acceleration, control interval (frequency), lookahead time, and proportional gain
Environment Setup
- Clone the code
git clone --recursive https://github.com/RoboPPN/pika_remote_ur.git
2、Install Dependencies
cd pika_remote_ur/pika_sdk
pip3 install -r requirements.txt
pip3 install -e .
pip3 install ur-rtde
UR Control Interface
Let's start with the control interface. To implement teleoperation, you first need to develop a proper control interface. For instance, the native control interface of UR robots accepts XYZ coordinates and rotation vectors as inputs, while teleoperation code typically outputs XYZRPY data. This requires a coordinate transformation, which can be implemented either in the control interface or the main teleoperation program. Here, we perform the transformation in the main teleoperation program.
The UR robotic arm control interface code is located at pika_remote_ur/ur_control.py:
import rtde_control
import rtde_receive
class URCONTROL:
def __init__(self,robot_ip):
# Connect to the robot
self.rtde_c = rtde_control.RTDEControlInterface(robot_ip)
self.rtde_r = rtde_receive.RTDEReceiveInterface(robot_ip)
if not self.rtde_c.isConnected():
print("Failed to connect to the robot control interface.")
return
if not self.rtde_r.isConnected():
print("Failed to connect to the robot receive interface.")
return
print("Connected to the robot.")
# Define servoL parameters
self.speed = 0.15 # m/s
self.acceleration = 0.1 # m/s^2
self.dt = 1.0/50 # dt for 500Hz, or 1.0/125 for 125Hz
self.lookahead_time = 0.1 # s
self.gain = 300 # proportional gain
def sevol_l(self, target_pose):
self.rtde_c.servoL(target_pose, self.speed, self.acceleration, self.dt, self.lookahead_time, self.gain)
def get_tcp_pose(self):
return self.rtde_r.getActualTCPPose()
def disconnect(self):
if self.rtde_c:
self.rtde_c.disconnect()
if self.rtde_r:
self.rtde_r.disconnect()
print("Disconnected from UR robot")
# example
# if __name__ == "__main__":
# ur = URCONTROL("192.168.1.15")
# target_pose = [0.437, -0.1, 0.846, -0.11019068574221307, 1.59479642933605, 0.07061926626169934]
# ur.sevol_l(target_pose)
The code defines a Python class named URCONTROL for communicating and controlling UR robots. This class encapsulates the functionalities of the rtde_control and rtde_receive libraries, providing methods for connecting to the robot, disconnecting, sending servoL commands, and retrieving TCP poses.
Core Teleoperation Code
The teleoperation code is located at `pika_remote_ur/teleop_ur.py`
As outlined in [Methods for Teleoperating Any Robotic Arm with PIKA], the teleoperation principle can be summarized in four key steps:
- Obtain 6D Pose data
- Coordinate System Alignment
- Incremental Control
- Map 6D Pose data to the robotic arm
Obtaining Pose Data
The code is as follows:
# Get pose data of the tracker device
def get_tracker_pose(self):
logger.info(f"Starting to obtain pose data of {self.target_device}...")
while True:
# Get pose data
pose = self.sense.get_pose(self.target_device)
if pose:
# Extract position and rotation data for further processing
position = pose.position # [x, y, z]
rotation = self.tools.quaternion_to_rpy(pose.rotation[0],pose.rotation[1],pose.rotation[2],pose.rotation[3]) # [x, y, z, w] quaternion
self.x,self.y,self.z, self.roll, self.pitch, self.yaw = self.adjustment(position[0],position[1],position[2],
rotation[0],rotation[1],rotation[2])
else:
logger.warning(f"Failed to obtain pose data for {self.target_device}, retrying in the next cycle...")
time.sleep(0.02) # Obtain data every 0.02 seconds (50Hz)
This code retrieves the pose information of the tracker named “T20” every 0.02 seconds. There are two types of tracker device names: those starting with WM and those starting with T. When connecting trackers to the computer via a wired connection, the first connected tracker is named T20, the second T21, and so on. For wireless connections, the first connected tracker is named WM0, the second WM1, and so forth.
The acquired pose data requires further processing. The adjustment function is used to adjust the coordinates to match the coordinate system of the UR robotic arm’s end effector, achieving alignment between the two systems.
Coordinate System Alignment
The code is as follows:
# Coordinate transformation adjustment function
def adjustment(self,x,y,z,Rx,Ry,Rz):
transform = self.tools.xyzrpy2Mat(x,y,z, Rx, Ry, Rz)
r_adj = self.tools.xyzrpy2Mat(self.pika_to_arm[0],self.pika_to_arm[1],self.pika_to_arm[2],
self.pika_to_arm[3],self.pika_to_arm[4],self.pika_to_arm[5],) # Adjust coordinate axis direction: Pika ---> Robotic Arm End Effector
transform = np.dot(transform, r_adj)
x_,y_,z_,Rx_,Ry_,Rz_ = self.tools.mat2xyzrpy(transform)
return x_,y_,z_,Rx_,Ry_,Rz_
The function implements coordinate transformation and adjustment with the following steps:
- Convert the input pose (x,y,z,Rx,Ry,Rz) into a transformation matrix.
- Obtain the adjustment matrix for transforming the Pika coordinate system to the robotic arm’s end effector coordinate system.
- Combine the two transformations through matrix multiplication.
- Convert the final transformation matrix back to pose parameters and return the result.
The adjusted pose parameters matching the robotic arm’s coordinate system can be obtained through this function.
Incremental Control
In teleoperation, the pose data provided by Pika Sense is absolute. However, we do not want the robotic arm to jump directly to this absolute pose. Instead, we want the robotic arm to follow the relative movements of the operator starting from its current position. In simple terms, this involves converting the absolute pose changes of the control device into relative pose commands for the robotic arm.
The code is as follows:
# Incremental control
def calc_pose_incre(self,base_pose, pose_data):
begin_matrix = self.tools.xyzrpy2Mat(base_pose[0], base_pose[1], base_pose[2],
base_pose[3], base_pose[4], base_pose[5])
zero_matrix = self.tools.xyzrpy2Mat(self.initial_pose_rpy[0],self.initial_pose_rpy[1],self.initial_pose_rpy[2],
self.initial_pose_rpy[3],self.initial_pose_rpy[4],self.initial_pose_rpy[5])
end_matrix = self.tools.xyzrpy2Mat(pose_data[0], pose_data[1], pose_data[2],
pose_data[3], pose_data[4], pose_data[5])
result_matrix = np.dot(zero_matrix, np.dot(np.linalg.inv(begin_matrix), end_matrix))
xyzrpy = self.tools.mat2xyzrpy(result_matrix)
return xyzrpy
This function uses transformation matrix arithmetic to implement incremental control. Let’s break down the code step by step:
Input Parameters:
- base_pose: The reference pose at the start of teleoperation. When teleoperation is triggered, the system records the current pose of the control device and stores it as
self.base_pose. This pose serves as the “starting point” or “reference zero point” for calculating all subsequent increments.
- pose_data: The real-time pose data received from the control device (Pika Sense) at the current moment.
Matrix Transformation:The function first converts three key poses (represented in [x, y, z, roll, pitch, yaw] format) into 4x4 homogeneous transformation matrices, typically implemented by the tools.xyzrpy2Mat function.
- begin_matrix: Converted from
base_pose, representing the pose matrix of the control device at the start of teleoperation (denoted as T_begin).
- zero_matrix: Converted from
self.initial_pose_rpy, representing the pose matrix of the robotic arm’s end effector at the start of teleoperation. This is the “starting point” for the robotic arm’s movement (denoted as T_zero).
- end_matrix: Converted from
pose_data, representing the pose matrix of the control device at the current moment (denoted as T_end).
Core Calculation:This is the critical line of code:
result_matrix = np.dot(zero_matrix, np.dot(np.linalg.inv(begin_matrix), end_matrix))
Let’s analyze it using matrix multiplication:The formula can be expressed as: Result = T_zero * (T_begin)⁻¹ * T_end
np.linalg.inv(begin_matrix): Calculates the inverse matrix of begin_matrix, i.e., (T_begin)⁻¹. In robotics, the inverse of a transformation matrix represents the reverse transformation.
np.dot(np.linalg.inv(begin_matrix), end_matrix): This calculates (T_begin)⁻¹ * T_end, which physically represents the transformation required to convert from the begin coordinate system to the end coordinate system. In other words, it accurately describes the relative pose change (increment) of the control device from the start of teleoperation to the current moment (denoted as ΔT).
np.dot(zero_matrix, ...): This calculates T_zero * ΔT, which physically applies the calculated relative pose change (ΔT) to the initial pose of the robotic arm (T_zero).
Result Conversion and Return:
xyzrpy = tools.mat2xyzrpy(result_matrix): Converts the calculated 4x4 target pose matrix result_matrix back to the [x, y, z, roll, pitch, yaw] format that the robot controller can interpret.
return xyzrpy: Returns the calculated target pose.
Teleoperation Triggering
There are various ways to trigger teleoperation:
- Voice Trigger: The operator can trigger teleoperation using a wake word.
- Server Request Trigger: Teleoperation is triggered via a server request.
However, both methods have usability limitations. Voice triggering requires an additional voice input module and may suffer from low wake word recognition accuracy—you might have to repeat the wake word multiple times before successful triggering, leaving you frustrated before even starting teleoperation. Server request triggering requires sending a request from the control computer, which works well with two-person collaboration but becomes cumbersome when operating alone.
Instead, we use Pika Sense’s state transition detection to trigger teleoperation. The operator simply holds the Pika Sense and double-clicks it to reverse the state, thereby initiating teleoperation. The code is as follows:
# Teleoperation trigger
def handle_trigger(self):
current_value = self.sense.get_command_state()
if self.last_value is None:
self.last_value = current_value
if current_value != self.last_value: # Detect state change
self.bool_trigger = not self.bool_trigger # Reverse bool_trigger
self.last_value = current_value # Update last_value
# Perform corresponding operations based on the new bool_trigger value
if self.bool_trigger :
self.base_pose = [self.x, self.y, self.z, self.roll, self.pitch, self.yaw]
self.flag = True
print("Teleoperation started")
elif not self.bool_trigger :
self.flag = False
#-------------------------------------------------Option 1: Robotic arm stops at current pose after teleoperation ends; resumes from current pose in next teleoperation---------------------------------------------------
self.initial_pose_rotvec = self.ur_control.get_tcp_pose()
temp_rotvec = [self.initial_pose_rotvec[3], self.initial_pose_rotvec[4], self.initial_pose_rotvec[5]]
# Convert rotation vector to Euler angles
roll, pitch, yaw = self.tools.rotvec_to_rpy(temp_rotvec)
self.initial_pose_rpy = self.initial_pose_rotvec[:]
self.initial_pose_rpy[3] = roll
self.initial_pose_rpy[4] = pitch
self.initial_pose_rpy[5] = yaw
self.base_pose = self.initial_pose_rpy # Desired target pose data
print("Teleoperation stopped")
#-------------------------------------------------Option 2: Robotic arm returns to initial pose after teleoperation ends; starts from initial pose in next teleoperation---------------------------------------------------
# # Get current pose of the robotic arm
# current_pose = self.ur_control.get_tcp_pose()
# # Define interpolation steps
# num_steps = 100 # Adjust steps as needed; more steps result in smoother transition
# for i in range(1, num_steps + 1):
# # Calculate interpolated pose at current step
# # Assume initial_pose_rotvec and current_pose are both in [x, y, z, Rx, Ry, Rz] format
# interpolated_pose = [
# current_pose[j] + (self.initial_pose_rotvec[j] - current_pose[j]) * i / num_steps
# for j in range(6)
# ]
# self.ur_control.sevol_l(interpolated_pose)
# time.sleep(0.01) # Short delay between interpolations to control speed
# # Ensure the robotic arm reaches the initial position
# self.ur_control.sevol_l(self.initial_pose_rotvec)
# self.base_pose = [self.x, self.y, self.z, self.roll, self.pitch, self.yaw]
# print("Teleoperation stopped")
The code continuously retrieves the current state of Pika Sense using self.sense.get_command_state(), which outputs either 0 or 1. When the program starts, bool_trigger defaults to False. On the first state reversal, bool_trigger is set to True—the tracker’s pose is set as the zero point, self.flag is set to True, and control data is sent to the robotic arm for motion control.
To stop teleoperation, double-click the Pika Sense again to reverse the state. The robotic arm will then stop at its current pose and resume from this pose in the next teleoperation session (Option 1). Option 2 allows the robotic arm to return to its initial pose after teleoperation stops and start from there in subsequent sessions. You can choose the appropriate option based on your specific needs.
Mapping Pika Pose Data to the Robotic Arm
The code for this section is as follows:
def start(self):
self.tracker_thread.start() # Start the thread
# Main thread continues with other tasks
while self.running:
self.handle_trigger()
self.control_gripper()
current_pose = [self.x, self.y, self.z, self.roll, self.pitch, self.yaw]
increment_pose = self.calc_pose_incre(self.base_pose,current_pose)
finally_pose = self.tools.rpy_to_rotvec(increment_pose[3], increment_pose[4], increment_pose[5])
increment_pose[3:6] = finally_pose
# Send pose to robotic arm
if self.flag:
self.ur_control.sevol_l(increment_pose)
time.sleep(0.02) # Update at 50Hz
This section of code converts the RPY rotation data of the calculated increment_pose into a rotation vector and sends it to the robotic arm (UR robots accept XYZ coordinates and rotation vectors for control). Control data is only sent to the robotic arm when self.flag is set to True.
Practical Operation
The teleoperation code is located at: `pika_remote_ur/teleop_ur.py`
-
Power on the UR robotic arm and enable the joint motors. If the robotic arm’s end effector is equipped with a gripper or other actuators, enter the corresponding load parameters.
-
Configure the robotic arm’s IP address on the tablet.
3、Configure the Tool Coordinate System.
The end effector coordinate system must be set with the Z-axis pointing forward, X-axis pointing downward, and Y-axis pointing left. In the code, we rotate the Pika coordinate system 90° counterclockwise around the Y-axis, resulting in the Pika coordinate system having the Z-axis forward, X-axis downward, and Y-axis left. Therefore, the robotic arm’s end effector (tool) coordinate system must be aligned with this configuration; otherwise, the control will malfunction.
-
For first-time use, set the speed to 20-30% and enable remote control of the robotic arm.
-
Connect the tracker to the computer via a USB cable and calibrate the tracker and base station.
Navigate to the ~/pika_ros/scripts directory and run:
bash calibration.bash
Once positioning calibration is complete, close the program.
-
Connect Pika Sense and Pika Gripper to the computer using USB 3.0 cables. Note: Connect Pika Sense first (it should be assigned the port /dev/ttyUSB0), then connect the Pika Gripper (which requires 24V DC power supply, and should be assigned the port /dev/ttyUSB1).
-
Run the code:
cd pika_remote_ur
python3 teleop_ur.py
The terminal will output numerous logs, with the most common one being:
teleop_ur - WARNING - Failed to obtain pose data for T20, retrying in the next cycle...
Teleoperation can be initiated by double-clicking once the above log stops appearing and is replaced by:
pika.vive_tracker - INFO - Detected new device update: T20
Then you can start the remote operation by double-clicking.
1 post - 1 participant
Read full topic