ManipulaPy Documentation#

A modern, GPU-accelerated Python toolbox for robot kinematics, dynamics, trajectory planning, perception and control.

๐Ÿค– Modern Robotics Made Simple

ManipulaPy brings cutting-edge robotics algorithms to your fingertips with GPU acceleration, computer vision integration, and a clean Python API.

โšก CUDA Accelerated
GPU-powered trajectory planning and dynamics
๐Ÿ‘๏ธ Computer Vision
YOLO detection and stereo perception
๐ŸŽฎ Real-time Control
PyBullet simulation and advanced controllers

Getting Started#

If youโ€™re in a hurry, install the package into a fresh virtual-env and try the examples below:

python -m pip install manipulapy[cuda]  # or just manipulapy
python -c "import ManipulaPy; print('๐ŸŽ‰ Installation successful!')"

Note

The docs youโ€™re reading are generated from the source in docs/; feel free to improve them and send a pull request.

๐Ÿš€ Quick Start Examples#

1. Your First Robot Analysis

import numpy as np
from ManipulaPy.urdf_processor import URDFToSerialManipulator
from ManipulaPy.ManipulaPy_data.xarm import urdf_file as xarm_urdf_file

# Load the built-in xArm robot model
urdf_processor = URDFToSerialManipulator(xarm_urdf_file)
robot = urdf_processor.serial_manipulator
dynamics = urdf_processor.dynamics

# Compute forward kinematics at home position
joint_angles = np.zeros(6)  # 6-DOF robot at home
end_effector_pose = robot.forward_kinematics(joint_angles, frame="space")

print("๐Ÿ  Home position:", end_effector_pose[:3, 3])
print("๐Ÿ“ Home orientation:\n", end_effector_pose[:3, :3])

2. Inverse Kinematics in Action

# Define a target pose for the end-effector
target_angles = np.array([0.5, -0.3, 0.8, 0.0, 0.5, 0.0])
T_target = robot.forward_kinematics(target_angles)

# Solve inverse kinematics
initial_guess = np.zeros(6)
solution, success, iterations = robot.iterative_inverse_kinematics(
    T_desired=T_target,
    thetalist0=initial_guess,
    max_iterations=1000
)

if success:
    print(f"โœ… IK solved in {iterations} iterations!")
    print(f"๐ŸŽฏ Solution: {np.degrees(solution):.2f} degrees")
else:
    print("โŒ IK solution not found")

3. CUDA-Accelerated Trajectory Planning

from ManipulaPy.path_planning import TrajectoryPlanning

# Setup trajectory planner with GPU acceleration
joint_limits = np.array([[-np.pi, np.pi]] * 6)
planner = TrajectoryPlanning(robot, xarm_urdf_file, dynamics, joint_limits)

# Plan smooth trajectory from start to end
start_angles = np.zeros(6)
end_angles = np.array([0.5, -0.3, 0.8, 0.0, 0.5, 0.0])

trajectory = planner.joint_trajectory(
    thetastart=start_angles,
    thetaend=end_angles,
    Tf=5.0,          # 5 second duration
    N=100,           # 100 waypoints
    method=5         # Quintic time scaling for smoothness
)

print(f"๐Ÿ“ˆ Generated trajectory with {trajectory['positions'].shape[0]} points")
print(f"๐ŸŽฏ Start velocity: {trajectory['velocities'][0]}")
print(f"๐Ÿ End velocity: {trajectory['velocities'][-1]}")

# Visualize the trajectory
planner.plot_trajectory(trajectory, 5.0, title="Smooth Joint Trajectory")

4. Advanced Control with Dynamics

from ManipulaPy.control import ManipulatorController

# Create intelligent controller
controller = ManipulatorController(dynamics)

# Current robot state
current_pos = np.zeros(6)
current_vel = np.zeros(6)

# Desired target state
desired_pos = np.array([0.2, -0.1, 0.3, 0.0, 0.2, 0.0])
desired_vel = np.zeros(6)

# Auto-tune PID gains using Ziegler-Nichols
ultimate_gain = 50.0  # Found experimentally
ultimate_period = 0.5
Kp, Ki, Kd = controller.tune_controller(ultimate_gain, ultimate_period, kind="PID")

print(f"๐ŸŽ›๏ธ  Auto-tuned gains - Kp: {Kp[0]:.2f}, Ki: {Ki[0]:.2f}, Kd: {Kd[0]:.2f}")

# Compute optimal control torques
control_torques = controller.computed_torque_control(
    thetalistd=desired_pos,
    dthetalistd=desired_vel,
    ddthetalistd=np.zeros(6),
    thetalist=current_pos,
    dthetalist=current_vel,
    g=np.array([0, 0, -9.81]),
    dt=0.01,
    Kp=Kp, Ki=Ki, Kd=Kd
)

print(f"โšก Control torques: {control_torques}")

5. PyBullet Simulation

from ManipulaPy.sim import Simulation

# Create realistic physics simulation
sim = Simulation(
    urdf_file_path=xarm_urdf_file,
    joint_limits=joint_limits,
    torque_limits=np.array([[-50, 50]] * 6),
    time_step=0.01,
    real_time_factor=1.0
)

# Initialize robot and planning systems
sim.initialize_robot()
sim.initialize_planner_and_controller()

# Execute the planned trajectory in simulation
waypoints = trajectory["positions"][::10]  # Subsample for demonstration

print("๐ŸŽฌ Running simulation...")
final_position = sim.run_trajectory(waypoints)
print(f"๐Ÿ Final end-effector position: {final_position}")

6. Computer Vision & Perception

from ManipulaPy.vision import Vision
from ManipulaPy.perception import Perception

# Setup camera system
camera_config = {
    "name": "workspace_camera",
    "translation": [0.0, 0.0, 1.0],  # 1m above workspace
    "rotation": [0, 45, 0],           # Look down at 45ยฐ
    "fov": 60,
    "intrinsic_matrix": np.array([
        [500, 0, 320],
        [0, 500, 240],
        [0, 0, 1]
    ], dtype=np.float32),
    "distortion_coeffs": np.zeros(5, dtype=np.float32)
}

# Create integrated vision system
vision = Vision(camera_configs=[camera_config])
perception = Perception(vision_instance=vision)

# Detect and analyze obstacles
obstacle_points, cluster_labels = perception.detect_and_cluster_obstacles(
    camera_index=0,
    depth_threshold=3.0,  # Objects within 3m
    eps=0.1,              # DBSCAN clustering parameter
    min_samples=3         # Minimum points per cluster
)

num_clusters = len(set(cluster_labels)) - (1 if -1 in cluster_labels else 0)
print(f"๐Ÿ‘๏ธ  Detected {len(obstacle_points)} obstacle points")
print(f"๐Ÿ” Found {num_clusters} distinct object clusters")

๐Ÿ’ก Pro Tips for Success

๐ŸŽฏ Start Simple
Begin with forward kinematics before tackling complex control
๐Ÿ”ง Use Built-ins
The xArm URDF model is perfect for learning and testing
๐Ÿ“Š Visualize Everything
Use plotting functions to understand robot behavior
โšก GPU Acceleration
Install CUDA for 7x faster trajectory computations

Key Features at a Glance#

๐Ÿ”ง Core Robotics

  • Kinematics: Forward/inverse with neural network acceleration
  • Dynamics: Mass matrices, inverse/forward dynamics with caching
  • Control: PID, computed torque, adaptive controllers
  • Planning: CUDA-accelerated trajectory generation

๐Ÿ‘๏ธ Perception & Vision

  • Vision: Monocular/stereo camera support
  • Detection: YOLO-based object detection
  • 3D Processing: Point cloud clustering
  • Integration: PyBullet camera debugging

โšก High Performance

  • CUDA Kernels: GPU-accelerated computations
  • Parallel Processing: Multi-robot trajectory planning
  • Optimized Algorithms: Cached mass matrices
  • Real-time: Sub-millisecond kinematics

Documentation Map#

Whatโ€™s New#

๐ŸŽ‰ Latest in v1.3.2

  • New: Modular optional extras โ€” [simulation], [urdf], [vision], [ml], [cuda], [all] โ€” default install is now lightweight
  • New: Native NumPy 2.0-compatible URDF parser (ManipulaPy.urdf.URDF) with PackageResolver for package:// and file:// URIs
  • New: PEP 561 py.typed marker โ€” mypy/pyright now see ManipulaPy as a typed package
  • New: Python 3.12 added to the supported matrix
  • Fixed: CUDA trajectory kernels โ€” corrected quintic acceleration, removed shared-memory and forward-dynamics races, added method=1 (linear) support, guarded Nโ‰ค1 against div-zero
  • Fixed: Repulsive-potential-gradient sign in fused_potential_gradient_kernel โ€” previous versions produced an attracting field
  • Fixed: Simulation methods now raise clear ImportError with pip install ManipulaPy[simulation] hint when PyBullet is missing
  • Fixed: Vision.detect_obstacles default depth_threshold raised from 0.0 โ†’ 5.0 m (the old default filtered every detection)

Installation Options#

# Lightweight default install โ€” kinematics, dynamics, control, native URDF parser
pip install manipulapy

# Add PyBullet-based simulation
pip install "manipulapy[simulation]"

# Add trimesh-based mesh loading
pip install "manipulapy[urdf]"

# Add OpenCV / ultralytics / torch for vision and perception
pip install "manipulapy[vision]"

# Add scikit-learn for ML clustering
pip install "manipulapy[ml]"

# Add CUDA acceleration (CUDA 12.x)
pip install "manipulapy[cuda]"

# Everything (sim + urdf + vision + ml + cuda)
pip install "manipulapy[all]"

# Development installation
git clone https://github.com/boelnasr/ManipulaPy.git
cd ManipulaPy
pip install -e ".[dev]"

Performance Showcase#

โšก CUDA Acceleration

7x faster trajectory planning
GPU vs CPU for 1000-point trajectories

๐Ÿง  Neural Network IK

10x faster convergence
Hybrid approach vs traditional methods

๐Ÿ’พ Smart Caching

3x faster dynamics
Cached mass matrices for repeated calls

๐Ÿ‘๏ธ Real-time Vision

30 FPS object detection
YOLO integration with 3D localization

Citing ManipulaPy#

If you use ManipulaPy in your research, please cite:

@software{manipulapy2026,
  title={ManipulaPy: A Modern Python Library for Robot Manipulation},
  author={Mohamed Aboelnasr},
  year={2026},
  url={https://github.com/boelnasr/ManipulaPy},
  version={1.3.2}
}

License#

ManipulaPy is released under the AGPL-3.0 License:

โœ… Open Source
Source code freely available
๐Ÿ”„ Copyleft
Derivative works must be open source
๐ŸŒ Network Use
Modified network services must provide source
๐Ÿ’ผ Commercial Use
Permitted with AGPL compliance

For commercial licensing options or AGPL compliance questions, please contact the maintainers.

Indices and tables#

  • Index - Complete index of all functions, classes, and methods

  • Module Index - Module index for quick navigation

  • Search Page - Search the documentation