Piperlib is a library for AgileX Piper arms. It implements a minimal hardware interface layer and a joint controller. Piperlib is written purely in C++ (with Python bindings) with only Pinocchio dependency for gravity compensation and Ruckig for trajectory generation.
- Simple interface with Piper without ROS and piper_sdk
- Joint stiffness controller implemented through the MIT control mode
- Velocity, acceleration and jerk limits with Ruckig on-the-go trajectory generation.
- Python bindings
- Gripper control
- piper-cli for easier state management
Piperlib is a C++ library that has Python bindings. It has a few C++ dependencies that unfortunately cannot be handled only through uv.
C++ dependencies are installed using conda. However, conda is ONLY used for these dependencies. Piperlib Python package uses the uv Python and venv. uv is a superior tool and this makes Piperlib easier to use as a dependency in other projects. Follow these steps to install dependencies:
- Install the conda environment:
mamba env create -f environment.yml. - If your conda environment is not installed in the default path:
$HOME/miniforge3/envs/piperlib, set PIPERLIB_CONDA_ENV environment variable.
- You can now use pip to build and install the C++ library and Python bindings:
pip install -e . - or you can do
uv syncto create a virtual environment and install the package.
If you want to use the C++ library or test your developments in C++:
mkdir -p build && cd build
cmake ..
make -jYou can use Piperlib directly in C++ or through its Python bindings. Here is a very simple example that moves the robot to a desired joint position:
from piperlib import PiperController, ControllerConfig
controller_config = ControllerConfig()
controller_config.urdf_path = "" # set urdf path for gravity compensation, you can use the one in urdf/
piper_controller = PiperController(controller_config)
if not piper_controller.start(): # WARNING: this will power down the robot, and it will fall if not in neutral position.
raise RuntimeError("piper controller could not be started")
piper_controller.set_target(
new_target_pos=[0.0] * 6,
new_target_vel=[0.0] * 6,
new_target_acc=[0.0] * 6,
)
time.sleep(1)
piper_controller.stop() # WARNING: this puts the robot in damping mode, slowly lowering. Then, it prompts user to press Enter to disable motors after the arm is safe.Piper arms use CAN as communication protocol. piper_interface.h defines the hardware interface with the robot:
-
reset_arm(PiperInterface &interface)/reset_gripper(PiperInterface &interface): Disables and enables arm/gripper until they are active again in a timeout loop.PiperController.startuses these. -
enable_arm(PiperInterface &interface)/disable_arm(PiperInterface &interface): Used to enable/disable Piper actuators. Disable powers off the motors and the arms will fall down if not supported!!! -
enable_gripper(PiperInterface &interface)/disable_gripper(PiperInterface &interface): Used to enable/disable Piper gripper. -
PiperInterface::set_emergency_stop(EmergencyStop es): Emergency stop cancels the current command and puts the Piper actuators in a damping-only mode which allows the arm to slowly drop. -
PiperInterface::set_arm_mode(ControlMode ctrl_mode, MoveMode move_mode, uint8_t speed_rate, ArmController arm_controller): Piper supports two control modes: MIT mode for low level PD control of actuators and Joint Control mode that implements a joint controller in the firmware. Since we implement a compliant joint stiffness controller in Piperlib, we use MIT mode. This call allows you to change between modes. -
PiperInterface::set_joint_pos_vel_torque(JointState &joint_state, Gain& gain): Sends motor commands to all the actuators. Requires that the actuators are enabled and in MIT mode. You can command:desired_pos: raddesired_vel: rad/sfeedforward_torque: NmkpkdThe controller law here is:K_p * (desired_pos - current_pos) + K_d * (desired_vel - current_vel) + feedforward_torque
-
PiperInterface::get_current_state(): It gets the currentJointStatefrom piper. -
PiperInterface::get_driver_status(int motor_id):DriverStatusshows error status, overcurrent, enabled/disabled for arm motors. -
PiperInterface::get_arm_status(): CheckArmStatusenum for possible states. Expected to beNORMAL. -
PiperInterface::get_control_mode(): CheckControlModeenum. Expected to beSTANDBYorCAN_COMMAND -
PiperInterface::get_gripper_status():GripperStatusshows gripper error and enabled status. -
PiperInterface::get_move_mode(): CheckMoveModeenum. Expected to beMITin MIT mode orJOINTin joint control mode. -
PiperInterface::is_arm_enabled() -
PiperInterface::is_gripper_enabled()