Getting Started with ManipulaPyο
Welcome to ManipulaPy! This guide will get you up and running with modern robotics programming in Python.
π Ready to Build Robots?
ManipulaPy makes robot programming accessible with GPU acceleration, computer vision, and a clean Python API. Let's get started!
Installationο
π§ Quick Install
The fastest way to get started:
pip install manipulapy
π Recommended Install (with GPU acceleration)
For the best performance:
pip install manipulapy[cuda]
π¦ Full Installation (all features)
To unlock all capabilities:
pip install manipulapy[all]
π οΈ Development Installation
If you want to contribute or modify the library:
git clone https://github.com/yourusername/ManipulaPy.git
cd ManipulaPy
pip install -e .[dev]
Note
System Requirements:
Python 3.8 or higher
NumPy, SciPy (automatically installed)
Optional: CUDA for GPU acceleration
Optional: PyBullet for simulation
Verify Your Installationο
Letβs make sure everything is working:
import ManipulaPy
print("π ManipulaPy installed successfully!")
print(f"Version: {ManipulaPy.__version__}")
Your First Robotο
π€ Load a Robot Model
ManipulaPy comes with built-in robot models. Letβs start with the xArm:
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
print("π Loading xArm robot model...")
urdf_processor = URDFToSerialManipulator(xarm_urdf_file)
robot = urdf_processor.serial_manipulator
dynamics = urdf_processor.dynamics
print(f"β
Robot loaded with {len(robot.S_list[0])} degrees of freedom")
π― Forward Kinematics
Calculate where the robotβs end-effector is:
# Robot at home position (all joints at 0Β°)
home_angles = np.zeros(6)
end_effector_pose = robot.forward_kinematics(home_angles, frame="space")
print("π Home position:")
print(f" Position: {end_effector_pose[:3, 3]}")
print(f" Orientation:\n{end_effector_pose[:3, :3]}")
π Inverse Kinematics
Find joint angles to reach a target position:
# Define a target pose
target_position = np.array([0.5, 0.3, 0.8, 0.0, 0.5, 0.0])
T_target = robot.forward_kinematics(target_position)
# Solve inverse kinematics
print("π― Solving inverse kinematics...")
solution, success, iterations = robot.iterative_inverse_kinematics(
T_desired=T_target,
thetalist0=np.zeros(6),
max_iterations=1000
)
if success:
print(f"β
Solution found in {iterations} iterations!")
print(f"π§ Joint angles: {np.degrees(solution):.2f}Β°")
else:
print("β No solution found")
Your First Trajectoryο
β‘ GPU-Accelerated Planning
Plan smooth robot motions with CUDA acceleration:
from ManipulaPy.path_planning import TrajectoryPlanning
# Set up trajectory planner
joint_limits = np.array([[-np.pi, np.pi]] * 6)
planner = TrajectoryPlanning(robot, xarm_urdf_file, dynamics, joint_limits)
# Plan a smooth trajectory
start_angles = np.zeros(6)
end_angles = np.array([0.5, -0.3, 0.8, 0.0, 0.5, 0.0])
print("π Planning trajectory...")
trajectory = planner.joint_trajectory(
thetastart=start_angles,
thetaend=end_angles,
Tf=5.0, # 5 seconds
N=100, # 100 waypoints
method=5 # Quintic (smooth) interpolation
)
print(f"β
Generated {trajectory['positions'].shape[0]} waypoints")
print(f"π Start velocity: {trajectory['velocities'][0]}")
print(f"π End velocity: {trajectory['velocities'][-1]}")
π Visualize the Trajectory
See your robotβs planned motion:
# Plot the trajectory
planner.plot_trajectory(trajectory, 5.0, title="My First Robot Trajectory")
Your First Simulationο
π¬ PyBullet Physics Simulation
Bring your robot to life with realistic physics:
from ManipulaPy.sim import Simulation
# Create physics simulation
print("π¬ Starting simulation...")
sim = Simulation(
urdf_file_path=xarm_urdf_file,
joint_limits=joint_limits,
torque_limits=np.array([[-50, 50]] * 6),
time_step=0.01
)
# Initialize robot and controllers
sim.initialize_robot()
sim.initialize_planner_and_controller()
# Execute the trajectory in simulation
waypoints = trajectory["positions"][::10] # Use every 10th point
print("π Running simulation...")
final_position = sim.run_trajectory(waypoints)
print(f"π Final end-effector position: {final_position}")
Your First Control Systemο
ποΈ Intelligent Robot Control
Control your robot with advanced algorithms:
from ManipulaPy.control import ManipulatorController
# Create smart controller
controller = ManipulatorController(dynamics)
# Current and desired robot states
current_pos = np.zeros(6)
current_vel = np.zeros(6)
desired_pos = np.array([0.2, -0.1, 0.3, 0.0, 0.2, 0.0])
desired_vel = np.zeros(6)
# Auto-tune controller gains
ultimate_gain = 50.0 # Experiment to find this
ultimate_period = 0.5 # Measure from oscillations
Kp, Ki, Kd = controller.tune_controller(ultimate_gain, ultimate_period, kind="PID")
print(f"ποΈ Auto-tuned gains:")
print(f" Kp: {Kp[0]:.2f}, Ki: {Ki[0]:.2f}, Kd: {Kd[0]:.2f}")
# Compute 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}")
Your First Vision Systemο
ποΈ Computer Vision & Perception
Add eyes to your robot:
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 vision system
print("ποΈ Setting up vision system...")
vision = Vision(camera_configs=[camera_config])
perception = Perception(vision_instance=vision)
# Detect objects in the workspace
obstacle_points, cluster_labels = perception.detect_and_cluster_obstacles(
camera_index=0,
depth_threshold=3.0, # Objects within 3m
eps=0.1, # 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 objects")
Whatβs Next?ο
π Congratulations! Youβve just built your first robot system with ManipulaPy.
Common Issues & Solutionsο
β οΈ Installation Problems
# If you get permission errors
pip install --user manipulapy
# If you need CUDA support
pip install manipulapy[cuda]
# Verify CUDA is available
python -c "import cupy; print('CUDA available!')"
β οΈ Import Errors
# If ManipulaPy modules aren't found
import sys
sys.path.append('/path/to/ManipulaPy')
import ManipulaPy
β οΈ Simulation Issues
# If PyBullet simulation fails
pip install pybullet
# Test PyBullet installation
import pybullet as p
p.connect(p.DIRECT)
print("PyBullet working!")
β οΈ Performance Issues
# Check if CUDA acceleration is working
try:
import cupy
print("π CUDA acceleration available")
except ImportError:
print("β οΈ Install CuPy for GPU acceleration")
π‘ Pro Tips
Begin with forward kinematics before inverse kinematics
Use the plotting functions to understand robot behavior
Install CUDA for 7x faster computations
Always define realistic joint limits for safety
π Need Help?
π Check the π§ API Reference Guide for detailed function documentation
π Report bugs on GitHub Issues
π¬ Join our community discussions
π§ Contact the maintainers for support