piper-sdk 0.0.1

High-performance cross-platform (Linux/Windows/macOS) Rust SDK for AgileX Piper Robot Arm with support for high-frequency force control
Documentation

Piper SDK

Crates.io Documentation License

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

δΈ­ζ–‡η‰ˆ README

✨ Core Features

  • πŸš€ Zero Abstraction Overhead: Compile-time polymorphism, no virtual function table (vtable) overhead at runtime
  • ⚑ High-Performance Reads: Lock-free state reading based on ArcSwap, nanosecond-level response
  • πŸ”„ Lock-Free Concurrency: RCU (Read-Copy-Update) mechanism for efficient state sharing
  • 🎯 Type Safety: Bit-level protocol parsing using bilge, compile-time data correctness guarantees
  • 🌍 Cross-Platform Support (Linux/Windows/macOS):
    • Linux: Based on SocketCAN (kernel-level performance)
    • Windows/macOS: User-space GS-USB driver implementation using rusb (driver-free/universal)

πŸ› οΈ Tech Stack

Module Crates Purpose
CAN Interface Custom CanAdapter Lightweight CAN adapter Trait (no embedded burden)
Linux Backend socketcan Native Linux CAN support (planned)
USB Backend rusb USB device operations on Windows/macOS, 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

πŸ“¦ Installation

Add the dependency to your Cargo.toml:

[dependencies]
piper-sdk = "0.0.1"

πŸš€ Quick Start

Basic Usage

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
        .baud_rate(1_000_000)?  // CAN baud rate
        .build()?;

    // Get current state (lock-free, nanosecond-level response)
    let core_motion = robot.get_core_motion();
    println!("Joint positions: {:?}", core_motion.joint_pos);

    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(())
}

πŸ—οΈ Architecture Design

Hot/Cold Data Splitting

For performance optimization, state data is divided into three categories:

  • Hot Data (500Hz):

    • CoreMotionState: Core motion state (joint positions, end-effector pose)
    • JointDynamicState: Joint dynamic state (joint velocities, currents)
    • Uses ArcSwap for lock-free reading, Frame Commit mechanism ensures atomicity
  • Warm Data (100Hz):

    • ControlStatusState: Control status (control mode, robot status, fault codes, etc.)
    • Uses ArcSwap for read/write operations, medium update frequency
  • Cold Data (10Hz or on-demand):

    • DiagnosticState: Diagnostic information (motor temperature, bus voltage, error codes, etc.)
    • ConfigState: Configuration information (firmware version, joint limits, PID parameters, etc.)
    • Uses RwLock for read/write operations, low update frequency

Core Components

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

Concurrency Model

Adopts asynchronous IO concepts but implemented with synchronous threads (ensuring deterministic latency):

  1. IO Thread: Responsible for CAN frame transmission/reception and state updates
  2. Control Thread: Lock-free reading of latest state via ArcSwap, sending commands via crossbeam-channel
  3. Frame Commit Mechanism: Ensures the state read by control threads is a consistent snapshot at a specific time point

πŸ“š Examples

Check the examples/ directory for more examples:

Note: Example code is under development. See examples/ directory for more examples.

Planned examples:

  • read_state.rs - Simple state reading and printing
  • torque_control.rs - Force control demonstration
  • configure_can.rs - CAN baud rate configuration tool

🀝 Contributing

Contributions are welcome! Please see CONTRIBUTING.md for details.

πŸ“„ License

This project is licensed under the MIT License. See the LICENSE file for details.

πŸ“– Documentation

For detailed design documentation, see:

πŸ”— Related Links


Note: This project is under active development. APIs may change. Please test carefully before using in production.