Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning
npx @tessl/cli install tessl/pypi-pybullet@3.2.0A comprehensive Python library for physics simulation, robotics, and reinforcement learning. PyBullet is the official Python interface for the Bullet Physics SDK, providing real-time collision detection, multi-physics simulation, forward and inverse dynamics, kinematics computations, and extensive rendering capabilities with support for virtual reality headsets.
pip install pybulletimport pybullet as pFor data and example assets:
import pybullet_dataimport pybullet as p
import pybullet_data
# Connect to physics server
physicsClient = p.connect(p.GUI) # or p.DIRECT for non-graphical version
p.setAdditionalSearchPath(pybullet_data.getDataPath()) # access to data files
# Set up the simulation environment
p.setGravity(0, 0, -10)
planeId = p.loadURDF("plane.urdf")
# Load a robot from URDF
startPos = [0, 0, 1]
startOrientation = p.getQuaternionFromEuler([0, 0, 0])
boxId = p.loadURDF("r2d2.urdf", startPos, startOrientation)
# Run simulation
for i in range(1000):
p.stepSimulation()
time.sleep(1./240.)
# Get object position and orientation
cubePos, cubeOrn = p.getBasePositionAndOrientation(boxId)
print(f"Position: {cubePos}")
print(f"Orientation: {cubeOrn}")
p.disconnect()PyBullet operates through a client-server architecture that supports multiple connection modes:
The library provides both direct in-process simulation (p.DIRECT) for maximum performance and GUI mode (p.GUI) for visualization and debugging. Network-based connections (TCP, UDP) enable distributed simulation setups.
Essential functions for establishing connections to the physics server, controlling simulation execution, and managing the simulation lifecycle.
def connect(method, *args, **kwargs):
"""
Connect to physics server.
Args:
method: Connection method (p.GUI, p.DIRECT, p.SHARED_MEMORY, p.TCP, p.UDP)
key: Shared memory key (optional)
hostName: Host name for TCP/UDP (optional)
port: Port number for TCP/UDP (optional)
Returns:
int: Physics client ID
"""
def disconnect(physicsClientId=0):
"""Disconnect from physics server."""
def isConnected(physicsClientId=0):
"""Check if client is connected to server."""
def resetSimulation(physicsClientId=0):
"""Reset simulation and remove all objects."""
def stepSimulation(physicsClientId=0):
"""Step simulation forward by one time step."""
def setRealTimeSimulation(enableRealTimeSimulation, physicsClientId=0):
"""Enable or disable real-time simulation."""Functions for loading robots, objects, and environments from various file formats, as well as creating collision and visual shapes programmatically.
def loadURDF(fileName, basePosition=None, baseOrientation=None, **kwargs):
"""
Load multibody from URDF file.
Args:
fileName: Path to URDF file
basePosition: Initial position [x, y, z]
baseOrientation: Initial orientation as quaternion [x, y, z, w]
useMaximalCoordinates: Use maximal coordinates (default False)
useFixedBase: Fix base to world (default False)
flags: Loading flags (URDF_USE_INERTIA_FROM_FILE, etc.)
Returns:
int: Unique body ID
"""
def loadSDF(fileName, physicsClientId=0):
"""Load objects from SDF file."""
def createCollisionShape(shapeType, **kwargs):
"""Create collision shape."""
def createVisualShape(shapeType, **kwargs):
"""Create visual shape."""
def createMultiBody(baseMass, baseCollisionShapeIndex, **kwargs):
"""Create multibody from components."""Comprehensive joint control including position, velocity, and torque control with PD controllers and multi-DOF joint support.
def getJointInfo(bodyUniqueId, jointIndex, physicsClientId=0):
"""
Get joint information.
Returns:
tuple: (jointIndex, jointName, jointType, qIndex, uIndex, flags,
jointDamping, jointFriction, jointLowerLimit, jointUpperLimit,
jointMaxForce, jointMaxVelocity, linkName, jointAxis,
parentFramePos, parentFrameOrn, parentIndex)
"""
def setJointMotorControl2(bodyUniqueId, jointIndex, controlMode, **kwargs):
"""
Set joint motor control.
Args:
bodyUniqueId: Body ID
jointIndex: Joint index
controlMode: Control mode (POSITION_CONTROL, VELOCITY_CONTROL, TORQUE_CONTROL)
targetPosition: Target position (position control)
targetVelocity: Target velocity (velocity/position control)
force: Maximum force/torque
positionGain: Position gain (Kp)
velocityGain: Velocity gain (Kd)
"""
def getJointState(bodyUniqueId, jointIndex, physicsClientId=0):
"""Get joint state (position, velocity, reaction forces)."""Advanced collision queries, contact point analysis, and ray intersection testing for sensor simulation and collision avoidance.
def getContactPoints(bodyA=None, bodyB=None, linkIndexA=-1, linkIndexB=-1, physicsClientId=0):
"""
Get contact points between objects.
Returns:
list: Contact points with position, normal, distance, force, etc.
"""
def rayTestBatch(rayFromPositions, rayToPositions, **kwargs):
"""
Cast batch of rays for efficient collision testing.
Args:
rayFromPositions: List of ray start positions
rayToPositions: List of ray end positions
numThreads: Number of threads for parallel processing
Returns:
list: Ray hit results with objectId, linkIndex, hitFraction, hitPosition, hitNormal
"""Compute inverse kinematics solutions for robotic manipulation and inverse dynamics for force computation and control.
def calculateInverseKinematics(bodyUniqueId, endEffectorLinkIndex, targetPosition, **kwargs):
"""
Calculate inverse kinematics.
Args:
bodyUniqueId: Robot body ID
endEffectorLinkIndex: End effector link index
targetPosition: Target position [x, y, z]
targetOrientation: Target orientation quaternion (optional)
lowerLimits: Joint lower limits (optional)
upperLimits: Joint upper limits (optional)
jointRanges: Joint ranges (optional)
restPoses: Rest pose joint angles (optional)
Returns:
list: Joint angles for target pose
"""
def calculateInverseDynamics(bodyUniqueId, objPositions, objVelocities, objAccelerations, physicsClientId=0):
"""Calculate joint forces using inverse dynamics."""Inverse Kinematics and Dynamics
Camera control, image rendering, and debug visualization tools for simulation analysis and data collection.
def getCameraImage(width, height, viewMatrix, projectionMatrix, **kwargs):
"""
Render camera image.
Args:
width: Image width in pixels
height: Image height in pixels
viewMatrix: 4x4 view matrix
projectionMatrix: 4x4 projection matrix
renderer: Renderer type (ER_BULLET_HARDWARE_OPENGL, ER_TINY_RENDERER)
Returns:
tuple: (width, height, rgbPixels, depthPixels, segmentationMaskBuffer)
"""
def computeViewMatrix(cameraEyePosition, cameraTargetPosition, cameraUpVector):
"""Compute camera view matrix."""
def computeProjectionMatrixFOV(fov, aspect, nearVal, farVal):
"""Compute projection matrix from field of view."""Configure simulation parameters, gravity, time stepping, and advanced physics engine settings for optimal performance.
def setGravity(gravX, gravY, gravZ, physicsClientId=0):
"""Set gravity acceleration vector."""
def setTimeStep(timeStep, physicsClientId=0):
"""Set simulation time step."""
def setPhysicsEngineParameter(**kwargs):
"""
Set physics engine parameters.
Args:
fixedTimeStep: Fixed time step size
numSolverIterations: Number of constraint solver iterations
useSplitImpulse: Use split impulse for penetration recovery
splitImpulsePenetrationThreshold: Penetration threshold for split impulse
numSubSteps: Number of sub-steps per simulation step
collisionFilterMode: Collision filtering mode
contactBreakingThreshold: Contact breaking threshold
maxNumCmdPer1ms: Maximum commands per millisecond
"""Quaternion operations, coordinate transformations, and mathematical utilities for robotics and 3D graphics applications.
def getQuaternionFromEuler(eulerAngles):
"""Convert Euler angles (roll, pitch, yaw) to quaternion."""
def getEulerFromQuaternion(quaternion):
"""Convert quaternion to Euler angles."""
def multiplyTransforms(positionA, orientationA, positionB, orientationB):
"""Multiply two transforms (position, orientation)."""
def invertTransform(position, orientation):
"""Invert transform (position, orientation)."""Save and restore simulation states, log data for analysis, and manage user-defined data attachments.
def saveState():
"""Save complete world state to memory."""
def restoreState(stateId):
"""Restore world state from memory."""
def startStateLogging(loggingType, fileName, **kwargs):
"""
Start logging simulation data.
Args:
loggingType: Type of logging (STATE_LOGGING_VIDEO_MP4, STATE_LOGGING_GENERIC_ROBOT, etc.)
fileName: Output file name
objectUniqueIds: Objects to log (optional)
maxLogDof: Maximum degrees of freedom to log
Returns:
int: Logging unique ID
"""Virtual reality support, keyboard and mouse input handling for interactive simulations and teleoperation.
def getVREvents(deviceTypeFilter=None, physicsClientId=0):
"""Get VR controller events and state."""
def getKeyboardEvents(physicsClientId=0):
"""Get keyboard input events."""
def getMouseEvents(physicsClientId=0):
"""Get mouse input events."""# Connection types
p.GUI # Graphical interface
p.DIRECT # Direct in-process
p.SHARED_MEMORY # Shared memory
p.TCP # TCP network connection
p.UDP # UDP network connection# Joint types
p.JOINT_REVOLUTE # Revolute (hinge) joint
p.JOINT_PRISMATIC # Prismatic (slider) joint
p.JOINT_SPHERICAL # Spherical joint
p.JOINT_FIXED # Fixed joint
# Control modes
p.POSITION_CONTROL # Position control with PD
p.VELOCITY_CONTROL # Velocity control
p.TORQUE_CONTROL # Direct torque control
p.PD_CONTROL # Pure PD control
p.STABLE_PD_CONTROL # Stable PD control# Collision shape types
p.GEOM_SPHERE # Sphere primitive
p.GEOM_BOX # Box primitive
p.GEOM_CYLINDER # Cylinder primitive
p.GEOM_MESH # Triangle mesh
p.GEOM_PLANE # Infinite plane
p.GEOM_CAPSULE # Capsule primitive
p.GEOM_HEIGHTFIELD # Height field terrain# URDF loading options
p.URDF_USE_INERTIA_FROM_FILE # Use inertia from URDF
p.URDF_USE_SELF_COLLISION # Enable self collision
p.URDF_USE_MATERIAL_COLORS_FROM_MTL # Use MTL material colors
p.URDF_ENABLE_SLEEPING # Enable object sleeping
p.URDF_MERGE_FIXED_LINKS # Merge fixed links for performance# Renderer types
p.ER_TINY_RENDERER # Software renderer
p.ER_BULLET_HARDWARE_OPENGL # Hardware OpenGL renderer
# Debug visualizer options
p.COV_ENABLE_GUI # Enable/disable GUI
p.COV_ENABLE_SHADOWS # Enable/disable shadows
p.COV_ENABLE_WIREFRAME # Enable/disable wireframe
p.COV_ENABLE_RENDERING # Enable/disable rendering# Reference frames
p.WORLD_FRAME # World coordinate frame
p.LINK_FRAME # Link local coordinate framePyBullet functions may raise exceptions for invalid parameters or failed operations. Common exception scenarios include:
Always check return values and handle potential exceptions in production code.
For optimal performance:
p.DIRECT mode for headless simulationp.URDF_MERGE_FIXED_LINKS for complex robotsrayTestBatch, setJointMotorControlArray)# Load robot and set up environment
robotId = p.loadURDF("robot.urdf")
p.setGravity(0, 0, -9.81)
# Control loop
for step in range(simulation_steps):
# Set joint targets
p.setJointMotorControlArray(robotId, jointIndices, p.POSITION_CONTROL, targetPositions)
# Step simulation
p.stepSimulation()
# Get feedback
joint_states = p.getJointStates(robotId, jointIndices)
time.sleep(1./240.) # Real-time simulation# Set up camera
width, height = 640, 480
fov, aspect, nearplane, farplane = 60, width/height, 0.01, 100
projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, nearplane, farplane)
# Render images in loop
for i in range(num_frames):
view_matrix = p.computeViewMatrix(eye_pos, target_pos, up_vector)
# Get camera image
_, _, rgb_img, depth_img, seg_img = p.getCameraImage(
width, height, view_matrix, projection_matrix
)
# Process images...