Simulation API Reference#
This page documents ManipulaPy.sim, the module for PyBullet-based simulation capabilities with real-time visualization, physics simulation, and interactive control.
Note
All Simulation methods raise ImportError with the hint
pip install ManipulaPy[simulation] if PyBullet is not installed.
The [simulation] extra is required for any sim-related code.
Changed in version 1.3.2: Every public Simulation method that touches PyBullet now performs an
explicit availability check and raises ImportError with the
install hint above when PyBullet is missing. Previously, calling these
methods after constructing a Simulation via __new__ (or after
hot-swapping the module) surfaced an AttributeError on NoneType
instead. PyBullet >= 3.2.5 is now sufficient β quaternion construction
no longer depends on p.getQuaternionFromAxisAngle (added in 3.2.7) and
uses inline axis-angle math instead. Repeated Simulation()
instantiation also no longer duplicates log handlers on
SimulationLogger.
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, enable_self_collision=False, disable_pairs=None)[source]#
Bases:
objectPyBullet-backed simulation and visualization helper for manipulators.
Main class for PyBullet-based simulation of robotic manipulators with real-time physics, visualization, and interactive control capabilities.
Constructor
- Parameters:
- __init__(urdf_file_path, joint_limits, torque_limits=None, time_step=0.01, real_time_factor=1.0, physics_client=None, enable_self_collision=False, disable_pairs=None)[source]#
Initialize the simulation and set up the PyBullet world.
- Parameters:
urdf_file_path (str) β Path to the robotβs URDF file.
joint_limits (Sequence[Tuple[float, float]]) β Per-joint (lower, upper) position limits.
torque_limits (Sequence[Any] | None) β Optional per-joint torque limits.
time_step (float) β Simulation time step in seconds.
real_time_factor (float) β Real-time playback factor.
physics_client (int | None) β Existing PyBullet client id to reuse, if any.
enable_self_collision (bool) β Whether to enable self-collision checking.
disable_pairs (Sequence[Tuple[str, str]] | None) β Link name pairs to exclude from self-collision.
- Return type:
None
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
β
Simulation Management#
Environment Setup#
Robot Initialization#
- Simulation.initialize_robot()[source]#
Initializes the robot using the URDF processor.
- Return type:
None
- Simulation.initialize_planner_and_controller()[source]#
Initializes the trajectory planner and the manipulator controller.
- Return type:
None
β
Robot Control and State#
Joint Control#
- Simulation.set_joint_positions(joint_positions, forces=None)[source]#
Sets the joint positions of the robot.
Drives the non-fixed joints toward
joint_positionsusing PyBulletβsPOSITION_CONTROLmode.- Parameters:
joint_positions (Sequence[float]) β Target angles for the non-fixed joints, in radians, one entry per non-fixed joint.
forces (Sequence[float] | None) β Optional per-joint maximum motor force. When
None, forces are derived fromself.torque_limits(collapsing each (min, max) pair to its largest absolute magnitude) or default to1000.0for every joint when no torque limits are configured.
- Return type:
None
- Simulation.set_joint_positions(joint_positions, forces=None)[source]
- Parameters:
joint_positions (Sequence[float]) β Target joint positions, one per non-fixed joint.
forces (Sequence[float] | None) β Per-joint maximum motor force passed to PyBulletβs
POSITION_CONTROL. WhenNone(the default), the value is auto-derived fromself.torque_limits: iftorque_limitsis a list of(min, max)pairs, each pair is collapsed to itsmax(|min|, |max|)so the motor can both push and pull within the configured limits. Iftorque_limitsis unset, a default of1000.0 Nper joint is used.
- Return type:
None
Changed in version 1.3.2: Added the
forceskeyword argument and the auto-derivation of per-joint force magnitudes fromself.torque_limitswhenforces=None. Previously, position commands were issued without an explicitforces=array andtorque_limits(when shaped as(N, 2)) was passed straight through to PyBullet, which expects a flat scalar per joint.
Trajectory Execution#
- Simulation.run_trajectory(joint_trajectory)[source]#
Runs a joint trajectory in the simulation.
Iterates over each waypoint, commands position control, steps the simulation, records the end-effector position, and finally renders the traced end-effector path in the scene.
- Simulation.simulate_robot_motion(desired_angles_trajectory)[source]#
Simulates the robotβs motion using a given trajectory of desired joint angles.
Commands each configuration via position control, steps the simulation, collects the end-effector positions, and plots the traced path.
Controller Integration#
- Simulation.run_controller(desired_positions)[source]#
Drive the robot through
desired_positionsin open-loop position control, one configuration per simulation step.For real closed-loop torque control, drive PyBulletβs
p.TORQUE_CONTROLmode directly in your own loop. The previous signature accepted a controller object plus PID gains; those were removed in v1.3.2 because the loop body never produced honest closed-loop behavior. See CHANGELOG.- Parameters:
desired_positions (Sequence[Sequence[float]]) β Waypoints to track, shape
(N, DOF)where DOF must equal the number of non-fixed joints; joint angles in radians.- Returns:
The (x, y, z) world position of the end-effector at the final waypoint.
- Return type:
- Raises:
ValueError β If
desired_positionsis empty, is not 2-D, or its joint count does not match the number of non-fixed joints.
- Simulation.run_controller(desired_positions)[source]
Drive the robot through
desired_positionsin open-loop position control, one configuration per simulation step.- Parameters:
desired_positions (Sequence[Sequence[float]]) β Array-like with shape
(N, DOF)β one row per waypoint, one column per non-fixed joint. Empty input or a row width that does not matchlen(self.non_fixed_joints)raisesValueError.- Returns:
The end-effector world position after the final waypoint, as returned by
p.getLinkState(...)[4].- Return type:
Changed in version 1.3.2: The signature was reduced to a single positional argument. The previous multi-argument form
run_controller(thetalistd, dthetalistd, ddthetalistd, g, Ftip, Kp, Ki, Kd, dt)β which accepted dynamics, gravity, end-effector wrench, and PID gains β was removed because the loop body never produced honest closed-loop behavior (computed torques were applied as position deltas). For real closed-loop torque control, drive PyBulletβsp.TORQUE_CONTROLmode directly in your own loop and feed it the torques produced byManipulaPy.control.ManipulatorController.
β
Interactive Controls#
GUI Elements#
Manual Control#
- Simulation.manual_control()[source]#
Allows manual control of the robot through the PyBullet UI sliders.
- Return type:
None
- Simulation.update_simulation_parameters()[source]#
Updates simulation parameters from GUI controls.
- Return type:
None
β
Visualization and Analysis#
Trajectory Visualization#
- Simulation.plot_trajectory(ee_positions, line_width=3, color=None)[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:
- Returns:
Body IDs of created trajectory geometry (for cleanup)
- Return type:
- Simulation.plot_trajectory(ee_positions, line_width=3, color=None)[source]
- Parameters:
ee_positions (Sequence[Sequence[float]]) β List of end-effector positions
[[x, y, z], ...]to render as a 3D capsule spline.line_width (int) β Thickness factor for the trajectory; scales the underlying capsule radius and the number of parallel capsules drawn per segment.
color (List[float] | None) β RGB triplet
[r, g, b](values in0..1) for the trajectory. Defaults toNone, in which case a red colour ([1, 0, 0]) is selected at call time.
- Return type:
Changed in version 1.3.2: The default value of
colorchanged from a mutable list/tuple default (which leaked the same object across calls) toNone. The red default is now constructed fresh on each invocation whencolor is None.
- Simulation.plot_trajectory_in_scene(joint_trajectory, end_effector_trajectory)[source]#
Plots the trajectory in the simulation scene.
Renders the end-effector path as a 3-D Matplotlib line plot, then replays the joint trajectory in the PyBullet simulation.
- Parameters:
joint_trajectory (Sequence[Sequence[float]]) β Sequence of joint-angle configurations (one per simulation step) to replay, each a sequence of joint angles in radians.
end_effector_trajectory (Sequence[Sequence[float]]) β Sequence of end-effector positions to plot, each an (x, y, z) world-frame coordinate.
- Return type:
None
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.
- Return type:
None
β
Safety and Monitoring#
- Simulation.check_collisions()[source]#
Checks for self-collisions in the simulation and returns contacts.
- Simulation.step_simulation()[source]#
Steps the simulation forward by one time step.
- Return type:
None
β
Main Execution#
- Simulation.run(joint_trajectory)[source]#
Main loop for running the simulation.
Runs the given trajectory once, then waits for the GUI reset button and switches between trajectory, wait-for-reset, and manual control modes.
β
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()
Open-Loop Position Tracking#
import numpy as np
# Define joint configurations to visit
desired_positions = np.array([[0.1, 0.2, 0.3, 0.0, 0.0, 0.0]])
# Run open-loop position tracking
final_pos = sim.run_controller(desired_positions)
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"])
Open-Loop Tracking Integration#
import numpy as np
# Use positions generated by a planner or custom waypoint list
positions = np.array([
[0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
[0.1, 0.2, 0.1, 0.0, 0.1, 0.0],
])
# Execute open-loop position tracking
sim.run_controller(positions)
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