【PIKA】Achievement of PIKA SDK for Teleoperating UR Robotic Arm

Hi everyone! :waving_hand:

I’m excited to share our beginner-friendly guide on implementing teleoperation for UR robotic arms using PIKA Sense. This tutorial walks through the complete setup process, from environment configuration to running your first teleoperation session.

Check out the demo video to see it in action:
https://youtu.be/TNB1lPitM4Y?si=LIw0abAQMvbngZ4C

A Beginner’s Guide to PIKA Teleoperation (UR Edition)

Before starting, it is recommended to read Methods for Teleoperating Any Robotic Arm with PIKA first.

Now that you understand the principles, let’s start building a teleoperation program step by step. To quickly implement the teleoperation function, we will use the following tools:

  • PIKA SDK: It enables quick access to all data from PIKA Sense and easy control of the gripper.
  • Various conversion tools: Such as tools for converting XYZRPY (X/Y/Z coordinates + Roll/Pitch/Yaw angles) to a 4x4 homogeneous transformation matrix, converting XYZ coordinates and quaternions to a 4x4 homogeneous transformation matrix, and converting RPY angles (rotation around X/Y/Z axes) to a rotation vector.
  • UR robotic arm control interface: This interface mainly uses the ur-rtde library. It realizes real-time control by sending target poses (XYZ coordinates and rotation vectors), speed, acceleration, control interval cycle (frequency), look-ahead time, and proportional gain.

Environment Setup

1. 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. For teleoperation, we first need to create a proper control interface. For example, the original control interface of UR requires input of XYZ coordinates and a rotation vector, but the data we usually send in the teleoperation code is XYZRPY. This means we need to perform a conversion, which can be done either in the control interface or the main teleoperation program. Here, we choose to do the conversion in the main teleoperation program. The following is the control interface code for the UR robotic arm, and the code file 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 50Hz, 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("UR disconnected")

# 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)

This code defines a Python class named URCONTROL for communicating with and controlling the UR robot. The class encapsulates the functions of the rtde_control and rtde_receive libraries, and provides methods for connecting to the robot, disconnecting from it, sending servoL commands, and obtaining the TCP (Tool Center Point) pose.


Core Teleoperation Code

The teleoperation code is located at pika_remote_ur/teleop_ur.py.

From Methods for Teleoperating Any Robotic Arm with PIKA, we know that the principle of teleoperation can be generally divided into four steps:

  1. Acquire 6D pose data.
  2. Align coordinate systems.
  3. Implement incremental control.
  4. Map the 6D pose data to the robotic arm.

Acquiring Pose Data

The code is as follows:

# Get tracker device pose data
def get_tracker_pose(self):
    logger.info(f"Starting to get pose data from {self.target_device} 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 get pose data from {self.target_device}, waiting for next attempt...")

        time.sleep(0.02)  # Get data every 0.02 seconds (50Hz)

This code acquires the pose information of the tracker named “T20” every 0.02 seconds. There are two types of tracker names: one starts with “WM” and the other starts with “T”. When the tracker is connected to the computer with a wire, the first connected tracker is named “T20”, the second one is “T21”, and so on. When connected wirelessly, the first tracker connected to the computer is named “WM0”, the second one is “WM1”, and so on.

The acquired pose data needs to be processed further. The adjustment function is used to adjust the coordinates so that we match the coordinate system of the UR robotic arm’s end effector, achieving alignment between the two.


Coordinate System Alignment

The code is as follows:

# Adjustment matrix 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--->robot arm end

    transform = np.dot(transform, r_adj)

    x_,y_,z_,Rx_,Ry_,Rz_ = self.tools.mat2xyzrpy(transform)

    return x_,y_,z_,Rx_,Ry_,Rz_

The functions of this function are as follows:

  1. Convert the input pose (x, y, z, Rx, Ry, Rz) to a transformation matrix.
  2. Obtain the adjustment matrix that transforms the PIKA coordinate system to the robotic arm end-effector coordinate system.
  3. Combine the two transformations by matrix multiplication.
  4. Convert the final transformation matrix back to pose parameters and return them.

Through this function, we can obtain the pose information that has been converted to match the robotic arm’s coordinate system.


Incremental Control

In teleoperation, the pose data provided by PIKA Sense is an absolute pose. However, we do not want the robotic arm to jump directly to this absolute pose. Instead, we hope that the robotic arm can follow the relative movement of the operator, starting from its current position. In short words, it means converting the change in the absolute pose of the operating device into the relative pose command that the robotic arm needs to execute.

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 the operation rules of transformation matrices to implement incremental control. Let’s break down the code step by step:

Input Parameters

  • base_pose: This is the reference pose at the start of teleoperation. When teleoperation is triggered, the system records the pose of the operating device at that moment 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: This is the real-time pose data received from the operating device (PIKA Sense) at the current moment.

Matrix Conversion

The function first converts three key poses (represented in the [x, y, z, roll, pitch, yaw] format) into 4x4 homogeneous transformation matrices. This conversion is usually completed by the tools.xyzrpy2Mat function.

  • begin_matrix: Converted from base_pose, it represents the pose matrix of the operating device at the start of teleoperation, denoted as T_begin.
  • zero_matrix: Converted from self.initial_pose_rpy, it represents the pose matrix of the robotic arm’s end-effector at the start of teleoperation. This is the “starting point” of the robotic arm’s movement, denoted as T_zero.
  • end_matrix: Converted from pose_data, it represents the pose matrix of the operating device at the current moment, denoted as T_end.

Core Calculation

This is the most critical line of code:

result_matrix = np.dot(zero_matrix, np.dot(np.linalg.inv(begin_matrix), end_matrix))

We can analyze it using matrix multiplication:

The formula is 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 matrix of a transformation matrix represents the reverse transformation.
  • np.dot(np.linalg.inv(begin_matrix), end_matrix): This step calculates (T_begin)⁻¹ * T_end. The physical meaning of this operation is the transformation required to go from the begin coordinate system to the end coordinate system. In other words, it accurately describes the relative pose change (increment) of the operating device from the start of teleoperation to the current moment, denoted as ΔT.
  • np.dot(zero_matrix, ...): This step calculates T_zero * ΔT. Its physical meaning is to apply the previously calculated relative pose change (ΔT) to the initial pose (T_zero) of the robotic arm’s end-effector.

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 understand.
  • return xyzrpy: Returns the calculated target pose.

Teleoperation Trigger

In fact, there are many ways to trigger teleoperation:

  • Voice trigger: The operator can trigger teleoperation using a wake-up word.
  • Server request trigger: Teleoperation is triggered by sending a request.

However, neither of the above methods is very convenient to operate. For voice trigger, an additional voice input module is required, and there is the problem of inaccurate wake-up word recognition. Sometimes, you have to say the wake-up word many times to trigger teleoperation successfully, and your mouth may get dry before teleoperation even starts. For the server request trigger, you need to use a control computer to send the request. It works well if there are two people to cooperate, but it becomes a hassle when there is only one person.

The method we use is to trigger teleoperation by detecting the state change of PIKA Sense. The operator only needs to hold PIKA Sense and double-click it quickly to reverse its state, thereby triggering 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: # State change detected
        self.bool_trigger = not self.bool_trigger # Flip bool_trigger
        self.last_value =  current_value # Update last_value
        # Execute corresponding operations based on 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("Start teleoperation")

        elif not self.bool_trigger :
            self.flag = False

            #-------------------------------------------------Option 1: When teleoperation ends, robot stops at current pose, next teleoperation starts from current pose---------------------------------------------------

            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 # Target pose data
            print("Stop teleoperation")

            #-------------------------------------------------Option 2: When teleoperation ends, robot returns to initial pose, next teleoperation starts from initial pose---------------------------------------------------

            # # Get current robot arm pose
            # current_pose = self.ur_control.get_tcp_pose()

            # # Define interpolation steps
            # num_steps = 100  # Can adjust steps as needed, more steps = smoother transition

            # for i in range(1, num_steps + 1):
            #     # Calculate current interpolation point pose
            #     # Assumes 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)  # Small delay between interpolations to control speed

            # # Ensure final arrival at 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("Stop teleoperation")

This code continuously obtains the current state of PIKA Sense through self.sense.get_command_state(), which can only output two states: 0 or 1. When the program starts, bool_trigger is set to False by default. When the first state reversal occurs, bool_trigger is set to True. At this time, the pose of the tracker is set as the zero point, self.flag is set to True, and the control data is sent to the robotic arm to control it. To stop teleoperation, double-click quickly again to reverse the state. At this point, the robotic arm will stop at the current pose, and the next teleoperation will start from this pose. The above is the control method for the robotic arm when teleoperation stops in Option 1. In Option 2, when teleoperation stops, the robotic arm returns to the initial pose, and the next teleoperation starts from the initial pose. You can choose the appropriate teleoperation stop method according to your specific situation.


Mapping PIKA Pose Data to the Robotic Arm

The code for this part is as follows:

def start(self):
    self.tracker_thread.start() # Start 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 robot arm
        if self.flag:
            self.ur_control.sevol_l(increment_pose)

        time.sleep(0.02) # 50Hz update

In this part of the code, the increment_pose calculated through incremental control is used. The RPY rotation in increment_pose is converted to a rotation vector, and then the resulting data is sent to the robotic arm (the UR robotic arm is controlled by receiving XYZ coordinates and a rotation vector). Only when self.flag is True (i.e., teleoperation is enabled) will the control data be sent to the robotic arm.


Practical Operation

The teleoperation code is located in pika_remote_ur/teleop_ur.py.

Step-by-Step Guide

  1. Power on the UR robotic arm and enable the joint motors. If the end of the robotic arm is equipped with an actuator such as a gripper, enter the corresponding load parameters.

  2. Configure the robot IP address on the tablet.

  3. Set up the tool coordinate system.

    Important: It is crucial to set the end-effector coordinate system such that the Z-axis points forward, the X-axis points downward, and the Y-axis points to the left. In the code, we rotate the PIKA coordinate system 90° counterclockwise around the Y-axis. After this rotation, the PIKA coordinate system has the Z-axis forward, X-axis downward, and Y-axis to the left. Therefore, the end-effector (tool) coordinate system of the robotic arm must be set to match this; otherwise, the control will be chaotic.

  4. For the first use, adjust the speed to 20-30%, and then enable the remote control of the robotic arm.

  5. Connect the tracker to the computer using a USB cable, and calibrate the tracker and the base station.

    Navigate to the ~/pika_ros/scripts directory and run the following command:

    bash calibration.bash 
    

    After the positioning calibration is completed, close the program.

  6. Connect PIKA Sense and PIKA Gripper to the computer using a USB 3.0 cable.

    Note: First, plug in PIKA Sense, which should be recognized as the /dev/ttyUSB0 port. Then, plug in the gripper (the gripper requires 24V DC power supply), which should be recognized as the /dev/ttyUSB1 port.

  7. Run the code:

    cd pika_remote_ur
    python3 teleop_ur.py
    

    The terminal will output a lot of logs. Most of the initial logs will be:

    teleop_ur - WARNING - Failed to get pose data from T20, waiting for next attempt...
    

    Wait until the above log stops appearing and the following log is output:

    pika.vive_tracker - INFO - New device update detected: T20
    

    At this point, you can double-click PIKA Sense to start teleoperation.


Wrapping Up

That’s it! You should now have a working teleoperation setup for your UR arm. If you run into any issues or have questions, feel free to drop a comment below. I’d also love to hear about your experiences and any improvements you make to the code.

The full repository is available on GitHub – contributions and feedback are always welcome!

Happy teleoperating! :robot: