Fixed Position Recording and Replay for AgileX PIPER Robotic Arm

We recently implemented a fixed position recording and replay function for the AgileX PIPER robotic arm using the official Python SDK. This feature allows recording specific arm positions and replaying them repeatedly, which is useful for teaching demonstrations and automated operations.

In this post, I will share the detailed setup steps, code implementation, usage instructions, and a demonstration video to help you get started.

Tags

Position recording, Python SDK, teaching demonstration, position reproduction, AgileX PIPER

Code Repository

GitHub link: https://github.com/agilexrobotics/Agilex-College.git

Function Demonstration

Preparation Before Use

Hardware Preparation for PIPER Robotic Arm

  • There are no obstacles in the workspace to provide sufficient movement space for the robotic arm.
  • Confirm that the power supply of the robotic arm is normal and all indicator lights are in the normal state.
  • The lighting conditions are good for observation of the position and state of the robotic arm.
  • If equipped with a gripper, check whether the gripper actions are normal.
  • The ground is stable to avoid vibration affecting recording accuracy.
  • The teach button functions normally.

Environment Configuration

  • Operating system: Ubuntu (Ubuntu 18.04 or higher is recommended)
  • Python environment: Python 3.6 or higher
  • git code management tool: used to clone remote code repositories
sudo apt install git
  • pip package manager: used to install Python dependency packages
sudo apt install python3-pip
  • Install CAN tools
sudo apt install can-utils ethtool
  • Install the official Python SDK package, among which1_0_0_betais the version with API
git clone -b 1_0_0_beta https://github.com/agilexrobotics/piper_sdk.git
cd piper_sdk
pip3 install .

Operation Steps for Fixed Position Recording and Replay Function

  1. Power on the robotic arm and connect the USB-to-CAN module to the computer (ensure that only one CAN module is connected)
  2. Open the terminal and activate the CAN module

sudo ip link set can0 up type can bitrate 1000000

  1. Clone the remote code repository

git clone https://github.com/agilexrobotics/Agilex-College.git

  1. Switch to therecordAndPlayPosdirectory

cd Agilex-College/piper/recordAndPlayPos/

  1. Run the recording program

python3 recordPos_en.py

  1. Short-press the teach button to enter the teaching mode

  2. Place the position of the robotic arm well, press Enter in the terminal to record the position, and input ‘q’ to end the recording.

  3. After recording, short-press the teach button again to exit the teaching mode

  1. Notes before replay: When exiting the teaching mode for the first time, a specific initialization process is required to switch from the teaching mode to the CAN mode. Therefore, the replay program will automatically perform a reset operation to return joints 2, 3, and 5 to safe positions (zero points) to prevent the robotic arm from suddenly falling due to gravity and causing damage. In special cases, manual assistance may be required to return joints 2, 3, and 5 to zero points.
  2. Run the replay program

python3 playPos_en.py

  1. After successful enabling, press Enter in the terminal to play the positions

Problems and Solutions

Problem 1: There is no Piper class.

image

Reason: The currently installed SDK is not the version with API.

Solution: Execute pip3 uninstall piper_sdkto uninstall the current SDK, then install the 1_0_0_beta version of the SDK according to the method in 1.2. Environment Configuration.

Problem 2: The robotic arm does not move, and the terminal outputs as follows.

Reason: The teach button was short-pressed during the operation of the program.

Solution: Check whether the indicator light of the teach button is off. If yes, re-run the program; if not, short-press the teach button to exit the teaching mode first and then run the program.

Code/Principle and Parameter Description

Implementation of Position Recording Program

The position recording program is the data collection module of the system, which is responsible for capturing the joint position information of the robotic arm in the teaching mode.

Program Initialization and Configuration

Parameter Configuration Design

#  Whether there is a gripper
have_gripper = True
# Timeout for teaching mode detection, unit: second
timeout = 10.0
# CSV file path for saving positions
CSV_path = os.path.join(os.path.dirname(__file__), "pos.csv")

Analysis of configuration parameters:

Thehave_gripperparameter is of boolean type, and True means there is a gripper.

Thetimeoutparameter sets the timeout for teaching mode detection. After starting the program, if the teaching mode is not entered within 10s, the program will exit.

TheCSV_pathparameter sets the save path of the trajectory file, which defaults to the same path as the program, and the file name is pos.csv

Robotic Arm Connection and Initialization

# Initialize and connect the robotic arm
piper = Piper("can0")
interface = piper.init()
piper.connect()
time.sleep(0.1)

Analysis of connection mechanism:

Piper()is the core class of the API, which simplifies some common methods on the basis of the interface.

init()will create and return an interface instance, which can be used to call some special methods of Piper.

connect()will start a thread to connect to the CAN port and process CAN data.

time.sleep(0.1)is added to ensure that the connection is fully established. In embedded systems, hardware initialization usually takes a certain amount of time, and this short delay ensures the reliability of subsequent operations.

Position Acquisition and Data Storage

Implementation of Position Acquisition Function

def get_pos():
    '''Get the current joint radians of the robotic arm and the gripper opening distance'''
    joint_state = piper.get_joint_states()[0]
    if have_gripper:
        return joint_state + (piper.get_gripper_states()[0][0], )
    return joint_state

Mode Detection and Switching

print("INFO: Please click the teach button to enter the teaching mode")
over_time = time.time() + timeout
while interface.GetArmStatus().arm_status.ctrl_mode != 2:
    if over_time < time.time():
        print("ERROR: Teaching mode detection timeout, please check whether the teaching mode is enabled")
        exit()
    time.sleep(0.01)

Status polling strategy
The program uses polling to detect the control mode, and this method has the following characteristics:

  • Simple implementation and clear logic
  • Low requirements on system resources

Timeout protection mechanism:
The 10-second timeout setting takes into account the needs of actual operations:

  • Time for users to understand prompt information
  • Time to find and press the teach button
  • Time for system response and state switching
  • Fault tolerance handling in abnormal situations

Safety features of teaching mode:

  • Joint torque is released, allowing manual operation
  • Maintain position feedback and monitor position changes in real time

Data Recording and Storage

count = 1
csv = open(CSV_path, "w")
while input("INPUT: Input q to exit, press Enter directly to record:") != "q":
    current_pos = get_pos()
    print(f"INFO: {count}th position, recorded position:  {current_pos}")
    csv.write(",".join(map(str, current_pos)) + "\n")
    count += 1
csv.close()
print("INFO: Recording ends, click the teach button again to exit the teaching mode")

Data integrity guarantee:
After each recording, the data is immediately written to the file and the buffer is refreshed to ensure that the data will not be lost due to abnormal exit of the program.

Data Format Selection
Reasons for choosing CSV format for data storage:

  • High versatility, almost all data processing tools support CSV format
  • Strong human readability, easy for debugging and verification
  • Simple structure and high parsing efficiency
  • Widely supported, easy to integrate with other tools

Data column attributes:

  • Columns 1-6: Joint motor radians
  • Column 7: Gripper opening distance, unit: m

Complete Code Implementation of Position Recording Program

#!/usr/bin/env python3
# -*-coding:utf8-*-
# Record positions
import os, time
from piper_sdk import *

if __name__ == "__main__":
    # Whether there is a gripper
    have_gripper = True
    # Timeout for teaching mode detection, unit: second
    timeout = 10.0
    # CSV file path for saving positions
    CSV_path = os.path.join(os.path.dirname(__file__), "pos.csv")
    # Initialize and connect the robotic arm
    piper = Piper("can0")
    interface = piper.init()
    piper.connect()
    time.sleep(0.1)

    def get_pos():
        '''Get the current joint radians of the robotic arm and the gripper opening distance'''
        joint_state = piper.get_joint_states()[0]
        if have_gripper:
            return joint_state + (piper.get_gripper_states()[0][0], )
        return joint_state
    
    print("INFO: Please click the teach button to enter the teaching mode")
    over_time = time.time() + timeout
    while interface.GetArmStatus().arm_status.ctrl_mode != 2:
        if over_time < time.time():
            print("ERROR:Teaching mode detection timeout, please check whether the teaching mode is enabled")
            exit()
        time.sleep(0.01)

    count = 1
    csv = open(CSV_path, "w")
    while input("INPUT: Enter q to exit, press Enter directly to record:  ") != "q":
        current_pos = get_pos()
        print(f"INFO:  {count}th position, recorded position: {current_pos}")
        csv.write(",".join(map(str, current_pos)) + "\n")
        count += 1
    csv.close()
    print("INFO: Recording ends, click the teach button again to exit the teaching mode")

Implementation of Position Replay Program

The position replay program is the execution module of the system, responsible for reading the recorded position data and controlling the robotic arm to reproduce these positions.

Parameter Configuration and Data Loading

replay Parameter Configuration

# Number of replays, 0 means infinite loop
play_times = 1
# replay interval, unit: second, negative value means manual key control
play_interval = 0
# Movement speed percentage, recommended range: 10-100
move_spd_rate_ctrl = 100

Analysis of parameter design:

Theplay_timesparameter supports three replay modes:

  • Single replay(play_times = 1):Suitable for demonstration and testing
  • Multiple replay (play_times > 1): Suitable for repetitive tasks
  • Infinite loop(play_times = 0): Suitable for continuous operations

The negative value design ofplay_intervalis an ingenious user interface design:

  • Positive value: Automatic replay mode, the system executes automatically at the set interval
  • Zero value: Continuous replay mode, no delay between positions
  • Negative value: Manual control mode, users control the replay rhythm through keys.

Themove_spd_rate_ctrlparameter provides a speed control function, which is very important for different application scenarios:

  • High-speed mode (80-100%): Suitable for no-load fast movement
  • Medium-speed mode (50-80%): Suitable for general operation tasks
  • Low-speed mode (10-50%): Suitable for precision operations and scenarios with high safety requirements

Data File Reading

try:
    with open(CSV_path, 'r', encoding='utf-8') as f:
        track = list(csv.reader(f))
        if not track:
            print("ERROR: The position file is empty")
            exit()
        track = [[float(j) for j in i] for i in track]    # Convert to a list of floating-point numbers
except FileNotFoundError:
    print("ERROR: The position file does not exist")
    exit()

Exception handling strategies:

  • FileNotFoundError:Handle the case where the file does not exist
  • Empty file check: Prevent reading empty data files
  • Data format verification: Ensure that the data can be correctly converted to numerical types

Data type conversion:
In the process of converting string data to floating-point numbers, the program uses list comprehensions.

Safety Stop Function

def stop():
    '''Stop the robotic arm; when exiting the teaching mode for the first time, this function must be called first to control the robotic arm in CAN mode'''
    interface.EmergencyStop(0x01)
    time.sleep(1.0)
    limit_angle = [0.1745, 0.7854, 0.2094]  # The robotic arm can be restored only when the angles of joints 2, 3, and 5 are within the limit range to prevent damage caused by falling from a large angle
    pos = get_pos()
    while not (abs(pos[1]) < limit_angle[0] and abs(pos[2]) < limit_angle[0] and pos[4] < limit_angle[1] and pos[4] > limit_angle[2]):
        time.sleep(0.01)
        pos = get_pos()
    # Restore the robotic arm
    piper.disable_arm()
    time.sleep(1.0)

Staged stop strategy:
The stop function adopts a staged safety stop strategy:

  1. Emergency stop stage: EmergencyStop(0x01) sends an emergency stop command to immediately stop all joint movements (joints with impedance)
  2. Safe position waiting: Wait for key joints (joints 2, 3, and 5) to move within the safe range
  3. System recovery stage: Send a recovery command to reactivate the control system

Safety range design:
The program pays special attention to the positions of joints 2, 3, and 5, which is based on the mechanical structure characteristics of the PIPER robotic arm:

  • Joint 2 (shoulder joint): Controls the pitching movement of the upper arm, affecting the overall stability
  • Joint 3 (elbow joint): Controls the angle of the forearm, directly affecting the end position
  • Joint 5 (wrist joint): Controls the end posture, affecting the direction of the gripper

The setting of the safe angle range (10°, 45°, 12°) is based on the following considerations:

  • Avoid the robotic arm from falling quickly under gravity
  • Ensure that the joints will not collide with mechanical limits
  • Provide sufficient operating space for subsequent movements

Real-time monitoring mechanism: The program uses real-time polling to monitor the joint positions to ensure that the next step is performed only when the safety conditions are met.

System Enable Function

def enable():
    '''Enable the robotic arm and gripper'''
    while not piper.enable_arm():
        time.sleep(0.01)
    if have_gripper:
        time.sleep(0.01)
        piper.enable_gripper()
    interface.ModeCtrl(0x01, 0x01, move_spd_rate_ctrl, 0x00)
    print("INFO: Enable successful")

Robotic arm enabling:enable_arm()

Gripper enabling:enable_gripper()

Control mode setting:
ModeCtrl(0x01, 0x01, move_spd_rate_ctrl, 0x00)Control mode parameters:

  • The first parameter (0x01): Set to CAN command control mode
  • The second parameter (0x01): Set to joint movement mode
  • The third parameter (0 to 100): Set the movement speed percentage
  • The fourth parameter (0x00): Set to position-speed mode

Replay Control Logic

count = 0
input("step 2: Press Enter to start playing positions")
while play_times == 0 or abs(play_times) != count:
    for n, pos in enumerate(track):
        while True:
            piper.move_j(pos[:-1], move_spd_rate_ctrl)
            time.sleep(0.01)
            current_pos = get_pos()
            print(f"INFO: {count + 1}th playback, {n + 1}th position, current position: {current_pos}, target position: {pos}")
            if all(abs(current_pos[i] - pos[i]) < 0.0698 for i in range(6)):
                break
        if have_gripper and len(pos) == 7:
            piper.move_gripper(pos[-1], 1)
            time.sleep(0.5)
        if play_interval < 0:
            if n != len(track) - 1 and input("Enter q to exit, press Enter directly to play:  ") == 'q':
                exit()
        else:
            time.sleep(play_interval)
    count += 1

Joint control: move_j()

  • The first parameter: A tuple containing the radians of the six joint motors
  • The second parameter: Movement speed percentage, range 0-100

Gripper control: move_gripper()

  • The first parameter: Gripper opening distance, unit: m
  • The second parameter: Gripper torque, unit: N/m

Position control closed-loop system:

  1. Target setting: Send target position commands to each joint through themove_j()function
  2. Status feedback: Obtain the current actual position through theget_pos()function
  3. Error calculation: Compare the difference between the target position and the actual position
  4. Convergence judgment: Consider reaching the target when the error is less than the threshold

Multi-joint coordinated control:
all(abs(current_pos[i] - pos[i]) < 0.0698 for i in range(6))ensures that the next step is performed only after all six joints reach the target position.

Gripper control strategy:
The gripper control adopts an independent control logic:

  • Execute gripper control only when the data contains gripper information
  • The gripper action is executed after the joint movement is completed to avoid interference
  • A 0.5-second delay ensures that the gripper action is fully completed

replay rhythm control:
The program supports three replay rhythms:

  • Automatic continuous replay: play_interval >= 0
  • Manual step-by-step replay: play_interval < 0
  • Real-time adjustment: Users can interrupt replay at any time

Complete Code Implementation of Position replay Program

#!/usr/bin/env python3
# -*-coding:utf8-*-
# Play positions
import os, time, csv
from piper_sdk import Piper

if __name__ == "__main__":
    # Whether there is a gripper
    have_gripper = True
    # Number of playbacks, 0 means infinite loop
    play_times = 1
    # Playback interval, unit: second; negative value means manual key control
    play_interval = 0
    # Movement speed percentage, recommended range: 10-100
    move_spd_rate_ctrl = 100
    # Timeout for switching to CAN mode, unit: second
    timeout = 5.0
    # CSV file path for saving positions
    CSV_path = os.path.join(os.path.dirname(__file__), "pos.csv")
    # Read the position file
    try:
        with open(CSV_path, 'r', encoding='utf-8') as f:
            track = list(csv.reader(f))
            if not track:
                print("ERROR: Position file is empty")
                exit()
            track = [[float(j) for j in i] for i in track]    # Convert to a list of floating-point numbers
    except FileNotFoundError:
        print("ERROR: Position file does not exist")
        exit()

    # Initialize and connect the robotic arm
    piper = Piper("can0")
    interface = piper.init()
    piper.connect()
    time.sleep(0.1)

    def get_pos():
        '''Get the current joint radians of the robotic arm and the gripper opening distance'''
        joint_state = piper.get_joint_states()[0]
        if have_gripper:
            return joint_state + (piper.get_gripper_states()[0][0], )
        return joint_state    

    def stop():
        '''Stop the robotic arm; this function must be called first when exiting the teaching mode for the first time to control the robotic arm in CAN mode'''
        interface.EmergencyStop(0x01)
        time.sleep(1.0)
        limit_angle = [0.1745, 0.7854, 0.2094]  # The robotic arm can be restored only when the radians of joints 2, 3, and 5 are within the limit range to prevent damage caused by falling from a large radian
        pos = get_pos()
        while not (abs(pos[1]) < limit_angle[0] and abs(pos[2]) < limit_angle[0] and pos[4] < limit_angle[1] and pos[4] > limit_angle[2]):
            time.sleep(0.01)
            pos = get_pos()
        # Restore the robotic arm
        piper.disable_arm()
        time.sleep(1.0)
    
    def enable():
        '''Enable the robotic arm and gripper'''
        while not piper.enable_arm():
            time.sleep(0.01)
        if have_gripper:
            time.sleep(0.01)
            piper.enable_gripper()
        interface.ModeCtrl(0x01, 0x01, move_spd_rate_ctrl, 0x00)
        print("INFO: Enable successful")

    print("step 1:  Please ensure the robotic arm has exited the teaching mode before playback")
    if interface.GetArmStatus().arm_status.ctrl_mode != 1:
        stop()  # This function must be called first when exiting the teaching mode for the first time to switch to CAN mode
    over_time = time.time() + timeout
    while interface.GetArmStatus().arm_status.ctrl_mode != 1:
        if over_time < time.time():
            print("ERROR: Failed to switch to CAN mode, please check if the teaching mode is exited")
            exit()
        interface.ModeCtrl(0x01, 0x01, move_spd_rate_ctrl, 0x00)
        time.sleep(0.01)
    
    enable()
    count = 0
    input("step 2: Press Enter to start playing positions")
    while play_times == 0 or abs(play_times) != count:
        for n, pos in enumerate(track):
            while True:
                piper.move_j(pos[:-1], move_spd_rate_ctrl)
                time.sleep(0.01)
                current_pos = get_pos()
                print(f"INFO: {count + 1}th playback, {n + 1}th position, current position: {current_pos}, target position: {pos}")
                if all(abs(current_pos[i] - pos[i]) < 0.0698 for i in range(6)):
                    break
            if have_gripper and len(pos) == 7:
                piper.move_gripper(pos[-1], 1)
                time.sleep(0.5)
            if play_interval < 0:
                if n != len(track) - 1 and input("INPUT: Enter 'q' to exit, press Enter directly to play:  ") == 'q':
                    exit()
            else:
                time.sleep(play_interval)
        count += 1

Summary

The above implements the fixed position recording and replay function based on the AgileX PIPER robotic arm. By applying the Python SDK, it is possible to record and repeatedly execute specific positions of the robotic arm, providing strong technical support for teaching demonstrations and automated operations.

If you have any questions regarding the use, please feel free to contact us at support@agilex.ai.