| Crates.io | piper-sdk |
| lib.rs | piper-sdk |
| version | 0.0.2 |
| created_at | 2026-01-17 21:16:55.709445+00 |
| updated_at | 2026-01-21 08:21:29.983018+00 |
| description | High-performance cross-platform (Linux/Windows/macOS) Rust SDK for AgileX Piper Robot Arm with support for high-frequency force control |
| homepage | |
| repository | https://github.com/vivym/piper-sdk-rs |
| max_upload_size | |
| id | 2051182 |
| size | 1,263,043 |
High-performance, cross-platform (Linux/Windows/macOS), zero-abstraction-overhead Rust SDK for AgileX Piper Robot Arm with support for high-frequency force control (500Hz).
ArcSwap, nanosecond-level responsebilge, compile-time data correctness guaranteesrusb (driver-free/universal)| Module | Crates | Purpose |
|---|---|---|
| CAN Interface | Custom CanAdapter |
Lightweight CAN adapter Trait (no embedded burden) |
| Linux Backend | socketcan |
Native Linux CAN support (SocketCAN interface) |
| USB Backend | rusb |
USB device operations on all platforms, implementing GS-USB protocol |
| Protocol Parsing | bilge |
Bit operations, unaligned data processing, alternative to serde |
| Concurrency Model | crossbeam-channel |
High-performance MPSC channel for sending control commands |
| State Sharing | arc-swap |
RCU mechanism for lock-free reading of latest state |
| Error Handling | thiserror |
Precise error enumeration within SDK |
| Logging | tracing |
Structured logging |
Add the dependency to your Cargo.toml:
[dependencies]
piper-sdk = "0.0.1"
For high-frequency control scenarios (500Hz-1kHz), you can enable the realtime feature to set RX thread to maximum priority:
[dependencies]
piper-sdk = { version = "0.0.1", features = ["realtime"] }
Note: On Linux, setting thread priority requires appropriate permissions:
CAP_SYS_NICE capability: sudo setcap cap_sys_nice+ep /path/to/your/binaryrtkit (RealtimeKit) for user-space priority elevationIf permission is insufficient, the SDK will log a warning but continue to function normally.
See Real-time Configuration Guide for detailed setup instructions.
use piper_sdk::PiperBuilder;
fn main() -> Result<(), Box<dyn std::error::Error>> {
// Create Piper instance
let robot = PiperBuilder::new()
.interface("can0")? // Linux: SocketCAN interface name (or GS-USB device serial)
.baud_rate(1_000_000)? // CAN baud rate
.build()?;
// Get current state (lock-free, nanosecond-level response)
let joint_pos = robot.get_joint_position();
println!("Joint positions: {:?}", joint_pos.joint_pos);
let end_pose = robot.get_end_pose();
println!("End pose: {:?}", end_pose.end_pose);
let joint_dynamic = robot.get_joint_dynamic();
println!("Joint velocities: {:?}", joint_dynamic.joint_vel);
// Send control frame
let frame = piper_sdk::PiperFrame::new_standard(0x1A1, &[0x01, 0x02, 0x03]);
robot.send_frame(frame)?;
Ok(())
}
For performance optimization, state data is divided into two categories:
High-frequency Data (200Hz):
JointPositionState: Joint positions (6 joints)EndPoseState: End-effector pose (position and orientation)JointDynamicState: Joint dynamic state (joint velocities, currents)RobotControlState: Robot control status (control mode, robot status, fault codes, etc.)GripperState: Gripper status (travel, torque, status codes, etc.)ArcSwap for lock-free reading, optimized for high-frequency control loopsLow-frequency Data (40Hz):
JointDriverLowSpeedState: Joint driver diagnostic state (temperatures, voltages, currents, driver status)CollisionProtectionState: Collision protection levels (on-demand)JointLimitConfigState: Joint angle and velocity limits (on-demand)JointAccelConfigState: Joint acceleration limits (on-demand)EndLimitConfigState: End-effector velocity and acceleration limits (on-demand)ArcSwap for diagnostic data, RwLock for configuration datapiper-rs/
βββ src/
β βββ lib.rs # Library entry, module exports
β βββ can/ # CAN communication adapter layer
β β βββ mod.rs # CAN adapter Trait and common types
β β βββ gs_usb/ # [Win/Mac] GS-USB protocol implementation
β β βββ mod.rs # GS-USB CAN adapter
β β βββ device.rs # USB device operations
β β βββ protocol.rs # GS-USB protocol definitions
β β βββ frame.rs # GS-USB frame structure
β βββ protocol/ # Protocol definitions (business-agnostic, pure data)
β β βββ ids.rs # CAN ID constants/enums
β β βββ feedback.rs # Robot arm feedback frames (bilge)
β β βββ control.rs # Control command frames (bilge)
β β βββ config.rs # Configuration frames (bilge)
β βββ robot/ # Core business logic
β βββ mod.rs # Robot module entry
β βββ robot_impl.rs # High-level Piper object (API)
β βββ pipeline.rs # IO Loop, ArcSwap update logic
β βββ state.rs # State structure definitions (hot/cold data splitting)
β βββ builder.rs # PiperBuilder (fluent construction)
β βββ error.rs # RobotError (error types)
Adopts asynchronous IO concepts but implemented with synchronous threads (ensuring deterministic latency):
ArcSwap, sending commands via crossbeam-channelCheck the examples/ directory for more examples:
Note: Example code is under development. See examples/ directory for more examples.
Available examples:
state_api_demo.rs - Simple state reading and printingrealtime_control_demo.rs - Real-time control with dual-threaded architecturerobot_monitor.rs - Robot state monitoringtimestamp_verification.rs - Timestamp synchronization verificationPlanned examples:
torque_control.rs - Force control demonstrationconfigure_can.rs - CAN baud rate configuration toolContributions are welcome! Please see CONTRIBUTING.md for details.
This project is licensed under the MIT License. See the LICENSE file for details.
For detailed design documentation, see:
Note: This project is under active development. APIs may change. Please test carefully before using in production.