Introduction
Have you ever wanted to teach a robotic arm to perform repetitive tasks without complex programming? This project demonstrates how to implement a simple yet powerful position recording and replay system for the AgileX PIPER robotic arm using its Python SDK.
What It Does
This system allows you to:
- Enter teaching mode with a simple button press
- Manually guide the robotic arm to desired positions
- Record positions with a single keystroke
- Replay recorded positions automatically or step-by-step
- Control gripper actions during replay
- Perform infinite loops for continuous operations
Why It Matters
This implementation is valuable for:
- Industrial Automation: Repetitive pick-and-place operations
- Education: Teaching robotics concepts through hands…
Introduction
Have you ever wanted to teach a robotic arm to perform repetitive tasks without complex programming? This project demonstrates how to implement a simple yet powerful position recording and replay system for the AgileX PIPER robotic arm using its Python SDK.
What It Does
This system allows you to:
- Enter teaching mode with a simple button press
- Manually guide the robotic arm to desired positions
- Record positions with a single keystroke
- Replay recorded positions automatically or step-by-step
- Control gripper actions during replay
- Perform infinite loops for continuous operations
Why It Matters
This implementation is valuable for:
- Industrial Automation: Repetitive pick-and-place operations
- Education: Teaching robotics concepts through hands-on demonstration
- Prototyping: Quick testing of robotic workflows without complex programming
- Quality Control: Consistent positioning for inspection tasks
How It Works
Recording Phase:
-
The system initializes the robotic arm via CAN bus communication
-
User enters teaching mode by pressing the teach button (joints become freely movable)
-
User manually positions the arm and presses Enter to record each position
-
Joint angles and gripper positions are saved to a CSV file
-
Teaching mode is exited to lock the arm in place Replay Phase:
-
System reads recorded positions from CSV file
-
Arm is enabled in CAN control mode with safety checks
-
System moves through each recorded position using closed-loop control
-
Position accuracy is verified (within 4° tolerance) before proceeding
-
Gripper actions are executed at appropriate positions
-
Process repeats based on configured replay settings Safety Features:
-
Automatic reset operation when exiting teaching mode
-
Safe position verification for critical joints (2, 3, and 5)
-
Emergency stop capability
-
Timeout protection for mode switching
-
Real-time position monitoring
Technical Implementation
Key Technologies:
-
CAN bus communication for real-time control
-
Closed-loop position control with error checking
-
CSV-based trajectory storage for portability
-
Multi-threaded state monitoring
-
Position-speed control mode for smooth movements Control Parameters:
-
Position accuracy threshold: 0.0698 radians (≈4°)
-
Speed control: 10-100% adjustable
-
Teaching mode timeout: 10 seconds
-
CAN mode switch timeout: 5 seconds
-
Safe angle limits: 10°, 45°, 12° for joints 2, 3, 5
SCHEMATICS, DIAGRAMS, AND PHOTOS
System Architecture:
User Input → Teaching Mode → Position Recording → CSV File ↓Robotic Arm ← CAN Control ← Position Replay ← CSV File
Control Flow:
Initialize → Connect CAN → Enter Teaching Mode → Record Positions ↓Exit Teaching ← Verify Playback ← Enable Arm ← Read CSV
CODE
recordPos_en.py
#!/usr/bin/env python3# -*-coding:utf8-*-# Record positionsimport os, timefrom piper_sdk import *if __name__ == "__main__": # Configuration have_gripper = True timeout = 10.0 CSV_path = os.path.join(os.path.dirname(__file__), "pos.csv") # Initialize robotic arm piper = Piper("can0") interface = piper.init() piper.connect() time.sleep(0.1) def get_pos(): '''Get current joint radians and 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 # Wait for teaching mode print("INFO: Please click the teach button to enter 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") exit() time.sleep(0.01) # Record positions count = 1 csv = open(CSV_path, "w") while input("INPUT: Enter 'q' to exit, press Enter to record: ") != "q": current_pos = get_pos() print(f"INFO: {count}th position recorded: {current_pos}") csv.write(",".join(map(str, current_pos)) + "\n") count += 1 csv.close() print("INFO: Recording complete. Exit teaching mode.")
playPos_en.py
#!/usr/bin/env python3# -*-coding:utf8-*-# Play positionsimport os, time, csvfrom piper_sdk import Piperif __name__ == "__main__": # Configuration have_gripper = True play_times = 1 # 0 = infinite loop play_interval = 0 # negative = manual control move_spd_rate_ctrl = 100 timeout = 5.0 CSV_path = os.path.join(os.path.dirname(__file__), "pos.csv") # Read 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] except FileNotFoundError: print("ERROR: Position file does not exist") exit() # Initialize robotic arm piper = Piper("can0") interface = piper.init() piper.connect() time.sleep(0.1) def get_pos(): '''Get current joint radians and 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(): '''Emergency stop with safety position check''' interface.EmergencyStop(0x01) time.sleep(1.0) limit_angle = [0.1745, 0.7854, 0.2094] 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() piper.disable_arm() time.sleep(1.0) def enable(): '''Enable 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") # Ensure CAN mode print("Step 1: Ensure robotic arm has exited teaching mode") if interface.GetArmStatus().arm_status.ctrl_mode != 1: stop() 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") exit() interface.ModeCtrl(0x01, 0x01, move_spd_rate_ctrl, 0x00) time.sleep(0.01) # Execute replay 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): # Move to position with closed-loop control while True: piper.move_j(pos[:-1], move_spd_rate_ctrl) time.sleep(0.01) current_pos = get_pos() print(f"INFO: Playback {count + 1}, Position {n + 1}") print(f"Current: {current_pos}, Target: {pos}") if all(abs(current_pos[i] - pos[i]) < 0.0698 for i in range(6)): break # Control gripper if have_gripper and len(pos) == 7: piper.move_gripper(pos[-1], 1) time.sleep(0.5) # Handle replay interval if play_interval < 0: if n != len(track) - 1: if input("INPUT: Enter 'q' to exit, Enter to continue: ") == 'q': exit() else: time.sleep(play_interval) count += 1
INSTRUCTIONS
Step 1: Environment Setup
Install System Dependencies:
sudo apt install git python3-pip can-utils ethtool
Install PIPER SDK:
git clone -b 1_0_0_beta https://github.com/agilexrobotics/piper_sdk.gitcd piper_sdkpip3 install .
Step 2: Hardware Setup
- Power on the PIPER robotic arm
- Connect USB-to-CAN module to computer
- Ensure only one CAN module is connected
- Verify teach button functionality
- Clear workspace of obstacles
Step 3: Activate CAN Interface
sudo ip link set can0 up type can bitrate 1000000
Step 4: Download Project Code
git clone https://github.com/agilexrobotics/Agilex-College.gitcd Agilex-College/piper/recordAndPlayPos/
Step 5: Record Positions
- Run recording program:
python3 recordPos_en.py
Short-press teach button to enter teaching mode (indicator light turns on)
-
Short-press teach button to enter teaching mode (indicator light turns on) Manually move arm to desired position
-
Manually move arm to desired position Press Enter in terminal to record position
-
Press Enter in terminal to record position Repeat steps 3-4 for all desired positions
-
Repeat steps 3-4 for all desired positions Type ‘q’ and press Enter to finish recording
-
Type ‘q’ and press Enter to finish recording Short-press teach button again to exit teaching mode
-
Short-press teach button again to exit teaching mode
Step 6: Replay Positions
- Run replay program:
python3 playPos_en.py
System will perform safety reset (joints 2, 3, 5 return to zero)
-
System will perform safety reset (joints 2, 3, 5 return to zero) Press Enter when prompted to start replay
-
Press Enter when prompted to start replay Arm will execute all recorded positions in sequence
-
Arm will execute all recorded positions in sequence
Configuration Options
Modify these parameters in the code as needed:
have_gripper
: Set toFalse
if no gripper attachedplay_times
: Number of replay cycles (0 = infinite)play_interval
: Delay between positions (negative = manual control)move_spd_rate_ctrl
: Speed percentage (10-100)
TROUBLESHOOTING
Problem: “No Piper class” error
-
Cause: Wrong SDK version installed
-
Solution: Uninstall with
pip3 uninstall piper_sdk
, then reinstall 1_0_0_beta version Problem: Arm doesn’t move, timeout errors -
Cause: Teaching mode accidentally activated during replay
-
Solution: Check teach button LED. If on, press to exit teaching mode and restart program Problem: Arm falls when exiting teaching mode
-
Cause: Joints 2, 3, 5 not in safe positions
-
Solution: Manually assist moving these joints to near-zero positions before exiting Support Contact: support@agilex.ai