Simulation API Referenceο
This page documents ManipulaPy.sim, the module for PyBullet-based simulation capabilities with real-time visualization, physics simulation, and interactive control.
Tip
For conceptual explanations, see Simulation Module User Guide.
β
Simulation Classο
- class ManipulaPy.sim.Simulation(urdf_file_path, joint_limits, torque_limits=None, time_step=0.01, real_time_factor=1.0, physics_client=None)[source]ο
Bases:
objectMain class for PyBullet-based simulation of robotic manipulators with real-time physics, visualization, and interactive control capabilities.
Constructor
- __init__(urdf_file_path, joint_limits, torque_limits=None, time_step=0.01, real_time_factor=1.0, physics_client=None)[source]ο
Parameters:
urdf_file_path (str) β Path to the URDF file describing the robot
joint_limits (list) β List of tuples representing joint angle limits
torque_limits (list, optional) β List of tuples representing torque limits
time_step (float, optional) β Simulation time step (default: 0.01)
real_time_factor (float, optional) β Real-time scaling factor (default: 1.0)
physics_client (int, optional) β PyBullet physics client ID
- set_robot_models(robot, dynamics)[source]ο
Set pre-existing robot models to avoid reprocessing.
- Parameters:
robot β SerialManipulator instance
dynamics β ManipulatorDynamics instance
- initialize_planner_and_controller()[source]ο
Initializes the trajectory planner and the manipulator controller.
- plot_trajectory(ee_positions, line_width=3, color=[1, 0, 0])[source]ο
Plots the end-effector trajectory in PyBullet using REAL GEOMETRY.
This method now creates actual 3D capsules that will appear in screenshots taken with getCameraImage(), unlike the previous addUserDebugLine() approach.
- Parameters:
ee_positions β List of end-effector positions [[x,y,z], β¦]
line_width β Width factor for trajectory visualization
color β RGB color as [r, g, b] where values are 0-1
- Returns:
Body IDs of created trajectory geometry (for cleanup)
- Return type:
- clear_trajectory_visualization()[source]ο
Clear all trajectory visualization bodies from the simulation.
- run_controller(controller, desired_positions, desired_velocities, desired_accelerations, g, Ftip, Kp, Ki, Kd)[source]ο
Runs the controller with the specified parameters.
- simulate_robot_motion(desired_angles_trajectory)[source]ο
Simulates the robotβs motion using a given trajectory of desired joint angles.
- simulate_robot_with_desired_angles(desired_angles)[source]ο
Simulates the robot using PyBullet with desired joint angles.
- Parameters:
desired_angles (np.ndarray) β Desired joint angles.
- add_additional_parameters()[source]ο
Adds additional GUI parameters for controlling physics properties like gravity and time step.
- save_joint_states(filename='joint_states.csv')[source]ο
Saves the joint states to a CSV file.
- Parameters:
filename (str) β The filename for the CSV file.
β
Simulation Managementο
Environment Setupο
Robot Initializationο
- Simulation.initialize_planner_and_controller()[source]ο
Initializes the trajectory planner and the manipulator controller.
β
Robot Control and Stateο
Joint Controlο
Trajectory Executionο
Controller Integrationο
- Simulation.run_controller(controller, desired_positions, desired_velocities, desired_accelerations, g, Ftip, Kp, Ki, Kd)[source]ο
Runs the controller with the specified parameters.
β
Interactive Controlsο
GUI Elementsο
Manual Controlο
- Simulation.manual_control()[source]ο
Allows manual control of the robot through the PyBullet UI sliders.
- Simulation.update_simulation_parameters()[source]ο
Updates simulation parameters from GUI controls.
β
Visualization and Analysisο
Trajectory Visualizationο
- Simulation.plot_trajectory(ee_positions, line_width=3, color=[1, 0, 0])[source]ο
Plots the end-effector trajectory in PyBullet using REAL GEOMETRY.
This method now creates actual 3D capsules that will appear in screenshots taken with getCameraImage(), unlike the previous addUserDebugLine() approach.
- Parameters:
ee_positions β List of end-effector positions [[x,y,z], β¦]
line_width β Width factor for trajectory visualization
color β RGB color as [r, g, b] where values are 0-1
- Returns:
Body IDs of created trajectory geometry (for cleanup)
- Return type:
Data Managementο
- Simulation.save_joint_states(filename='joint_states.csv')[source]ο
Saves the joint states to a CSV file.
- Parameters:
filename (str) β The filename for the CSV file.
β
Safety and Monitoringο
β
Main Executionο
β
Logging and Utilitiesο
β
Usage Examplesο
Basic Simulation Setupο
from ManipulaPy.sim import Simulation
import numpy as np
# Define joint limits for a 6-DOF robot
joint_limits = [(-np.pi, np.pi)] * 6
torque_limits = [(-50, 50)] * 6
# Create simulation instance
sim = Simulation(
urdf_file_path="robot.urdf",
joint_limits=joint_limits,
torque_limits=torque_limits,
time_step=0.01,
real_time_factor=1.0
)
# Initialize robot and components
sim.initialize_robot()
sim.initialize_planner_and_controller()
Running a Trajectoryο
# Define a simple trajectory
trajectory = [
[0.0, 0.0, 0.0, 0.0, 0.0, 0.0], # Start position
[0.5, 0.3, -0.2, 0.1, 0.4, 0.0], # Intermediate
[1.0, 0.5, -0.5, 0.2, 0.6, 0.1] # End position
]
# Run the trajectory
final_ee_pos = sim.run_trajectory(trajectory)
print(f"Final end-effector position: {final_ee_pos}")
Interactive Manual Controlο
# Add GUI controls
sim.add_joint_parameters()
sim.add_reset_button()
sim.add_additional_parameters()
# Start manual control mode
sim.manual_control()
Controller Integrationο
import cupy as cp
# Define control parameters
desired_positions = np.array([[0.1, 0.2, 0.3, 0.0, 0.0, 0.0]])
desired_velocities = np.zeros_like(desired_positions)
desired_accelerations = np.zeros_like(desired_positions)
# Control gains
Kp = np.array([100, 100, 100, 50, 50, 50])
Ki = np.array([1, 1, 1, 0.5, 0.5, 0.5])
Kd = np.array([10, 10, 10, 5, 5, 5])
# Gravity and external forces
g = [0, 0, -9.81]
Ftip = [0, 0, 0, 0, 0, 0]
# Run controller
final_pos = sim.run_controller(
sim.controller,
desired_positions,
desired_velocities,
desired_accelerations,
g, Ftip, Kp, Ki, Kd
)
Collision Monitoringο
# Enable collision checking during simulation
while True:
# Update robot state
joint_positions = sim.get_joint_parameters()
sim.set_joint_positions(joint_positions)
# Check for collisions
sim.check_collisions()
# Step simulation
sim.step_simulation()
Data Logging and Analysisο
# Save joint states during simulation
sim.save_joint_states("robot_states.csv")
# Visualize trajectory in 3D
joint_trajectory = [
[0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
[0.5, 0.5, 0.5, 0.0, 0.0, 0.0],
[1.0, 1.0, 1.0, 0.0, 0.0, 0.0]
]
ee_trajectory = []
for joints in joint_trajectory:
# Calculate end-effector position for each joint configuration
ee_pos = sim.robot.forward_kinematics(joints)[:3, 3]
ee_trajectory.append(ee_pos)
sim.plot_trajectory_in_scene(joint_trajectory, ee_trajectory)
Complete Simulation Loopο
# Complete example with trajectory execution and manual control
try:
# Generate trajectory using path planner
thetastart = np.zeros(6)
thetaend = np.array([0.5, 0.3, -0.2, 0.1, 0.4, 0.0])
trajectory_data = sim.trajectory_planner.joint_trajectory(
thetastart, thetaend, Tf=5.0, N=100, method=3
)
# Run the main simulation loop
sim.run(trajectory_data["positions"])
except KeyboardInterrupt:
print("Simulation interrupted by user")
finally:
sim.close_simulation()
β
Configuration Optionsο
Simulation Parametersο
The simulation can be configured with various parameters:
Parameter |
Default |
Description |
|---|---|---|
|
0.01 |
Physics simulation time step in seconds |
|
1.0 |
Speed multiplier for real-time simulation |
|
Required |
List of (min, max) tuples for each joint |
|
None |
Optional torque limits for each joint |
Physics Settingsο
The simulation uses PyBulletβs physics engine with the following default settings:
Gravity: [0, 0, -9.81] m/sΒ²
Solver iterations: PyBullet default
Contact breaking threshold: PyBullet default
Collision detection: Enabled for all robot links
GUI Controlsο
When using interactive mode, the following GUI elements are available:
Joint sliders: Individual control for each robot joint
Reset button: Return robot to home position
Gravity control: Adjust gravitational acceleration
Time step control: Modify simulation time step
β
Performance Considerationsο
GPU Accelerationο
The simulation module integrates with CuPy for GPU-accelerated computations:
Controller calculations use CuPy arrays for improved performance
Large trajectory computations benefit from GPU acceleration
Memory management is handled automatically
Real-time Performanceο
For optimal real-time performance:
Use appropriate
time_stepvalues (0.001-0.01 seconds)Adjust
real_time_factorbased on computational loadMonitor collision detection frequency for complex robots
Consider reducing visualization quality for faster simulation
β
Error Handlingο
Common Issues and Solutionsο
Note
The simulation module includes comprehensive error handling for common issues:
URDF Loading Errors
Verify URDF file path and format
Check for missing mesh files or textures
Ensure joint limits are properly defined
Physics Instability
Reduce time step for better numerical stability
Check for unrealistic joint limits or masses
Verify contact parameters are reasonable
GUI Issues
Ensure PyBullet GUI mode is properly initialized
Check for conflicting parameter names
Verify graphics drivers support OpenGL
Memory Issues
Monitor CuPy memory usage for large trajectories
Use batch processing for very long simulations
Clear visualization lines periodically
β
Integration with Other Modulesο
Path Planning Integrationο
# Using trajectory planner with simulation
from ManipulaPy.path_planning import TrajectoryPlanning
planner = TrajectoryPlanning(
sim.robot,
sim.urdf_file_path,
sim.dynamics,
sim.joint_limits,
sim.torque_limits
)
# Generate smooth trajectory
trajectory = planner.joint_trajectory(
thetastart, thetaend, Tf=3.0, N=150, method=5
)
# Execute in simulation
sim.run_trajectory(trajectory["positions"])
Control System Integrationο
# Advanced controller setup
from ManipulaPy.control import ManipulatorController
controller = ManipulatorController(sim.dynamics)
# Auto-tune controller gains
Ku, Tu = controller.find_ultimate_gain_and_period(
thetalist=np.zeros(6),
desired_joint_angles=np.array([0.1, 0.2, 0.1, 0.0, 0.1, 0.0]),
dt=sim.time_step
)
Kp, Ki, Kd = controller.tune_controller(Ku, Tu, kind="PID")
# Use tuned gains in simulation
sim.run_controller(controller, positions, velocities, accelerations,
g, Ftip, Kp, Ki, Kd)
Vision System Integrationο
# Camera-based simulation feedback
from ManipulaPy.vision import Vision
from ManipulaPy.perception import Perception
# Setup vision system (if available)
vision = Vision(use_pybullet_debug=True)
perception = Perception(vision_instance=vision)
# Use perception for obstacle avoidance in simulation
obstacles, labels = perception.detect_and_cluster_obstacles()
# Modify trajectory based on detected obstacles
# (Implementation depends on specific requirements)
β
See Alsoο
Control API Reference β Controller implementations for simulation
Path Planning API Reference β Trajectory generation for simulation
URDF Processor API Reference β URDF loading and robot model creation
Dynamics API Reference β Robot dynamics for physics simulation
Kinematics API Reference β Forward and inverse kinematics
Vision API Reference β Computer vision integration
Perception API Reference β Environmental perception capabilities