Skip to content

PyBullet Simulator

Simulation

Physics simulation for games, visual effects, robotics and reinforcement learning.

Install

Dowload git

#run
pip install -e .

Demo

hello.py
import pybullet as p
import pybullet_data
import time

# Connect to PyBullet with GUI
p.connect(p.GUI, options="--opengl2 --egl")

# Set search path to PyBullet’s default data
p.setAdditionalSearchPath(pybullet_data.getDataPath())

# Load a simple plane and a cube
plane_id = p.loadURDF("plane.urdf")
cube_id = p.loadURDF("r2d2.urdf", [0, 0, 1])

# Add gravity
p.setGravity(0, 0, -9.8)

# Run simulation loop
while True:
    p.stepSimulation()
    time.sleep(1./240.)
force opengl run on nvidia
__NV_PRIME_RENDER_OFFLOAD=1 __GLX_VENDOR_LIBRARY_NAME=nvidia python3 hello.py

Change ground texture

tarmac.png

import pybullet as p
import pybullet_data
import time

# Initialize PyBullet
physicsClient = p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())

# Create ground plane
planeId = p.loadURDF("plane.urdf")

# Add texture to the ground
textureId = p.loadTexture("tarmac.png")
p.changeVisualShape(planeId, -1, textureUniqueId=textureId)

# Set gravity and run simulation
p.setGravity(0, 0, -9.81)

while True:
    p.stepSimulation()
    time.sleep(1./240.)

Camera

camera
import pybullet as p
import pybullet_data
import time

# Initialize PyBullet
physicsClient = p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())

# Create ground plane
planeId = p.loadURDF("plane.urdf")

# Add texture to the ground
textureId = p.loadTexture("tarmac.png")
p.changeVisualShape(planeId, -1, textureUniqueId=textureId)

# Set gravity and run simulation
p.setGravity(0, 0, -9.81)

camera_pos = [0, 0, 10]  # Start at x=0, y=0, z=10m
velocity = 5.0  # 5 m/s in x-direction
width, height = 640, 480
fov, aspect, near, far = 60, width/height, 0.1, 100.0
projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far)
target_pos = [camera_pos[0], camera_pos[1], 0]  # Look downward

while True:
    p.stepSimulation()
    view_matrix = p.computeViewMatrix(camera_pos, target_pos, [0, 1, 0])  # Up vector: y-axis
    _, _, rgb, _, _ = p.getCameraImage(width, height, view_matrix, projection_matrix,
                                    renderer=p.ER_BULLET_HARDWARE_OPENGL)
    time.sleep(1./30.)

computeProjectionMatrixFOV

projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far)

Creates a projection matrix for a virtual camera using a perspective (field-of-view) projection.
Parameters:

  • fov: Field of view in degrees (vertical angle).
  • aspect: Aspect ratio (width/height).
  • near: Near clipping plane distance.
  • far: Far clipping plane distance.

Result: Returns a 4x4 matrix that transforms 3D points into 2D camera space, simulating a real camera lens.

getCameraImage

_, _, rgb, _, _ = p.getCameraImage(width, height, view_matrix, projection_matrix, renderer=p.ER_BULLET_HARDWARE_OPENGL)

Renders an image from the simulation as seen by the virtual camera. Parameters:

  • width, height: Output image size.
  • view_matrix: Defines the camera’s position and orientation (where it looks from and to).
  • projection_matrix: Defines how the 3D scene is projected onto the 2D image (from computeProjectionMatrixFOV).
  • renderer: Rendering backend (here, OpenGL).

Returns: A tuple containing image data, including the RGB image (rgb), depth, and segmentation masks.

alt text

opencv view
import cv2
import numpy as np
import pybullet as p
import pybullet_data
import time

# Initialize PyBullet
physicsClient = p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())

# Create ground plane
planeId = p.loadURDF("plane.urdf")

# Add texture to the ground
textureId = p.loadTexture("tarmac.png")
p.changeVisualShape(planeId, -1, textureUniqueId=textureId)

# Set gravity and run simulation
p.setGravity(0, 0, -9.81)

camera_pos = [0, 0, 10]  # Start at x=0, y=0, z=10m
velocity = 5.0  # 5 m/s in x-direction
width, height = 640, 480
fov, aspect, near, far = 60, width/height, 0.1, 100.0
projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far)
target_pos = [camera_pos[0], camera_pos[1], 0]  # Look downward

while True:
    p.stepSimulation()
    view_matrix = p.computeViewMatrix(camera_pos, target_pos, [0, 1, 0])  # Up vector: y-axis
    _, _, rgb, _, _ = p.getCameraImage(width, height, view_matrix, projection_matrix,
                                    renderer=p.ER_BULLET_HARDWARE_OPENGL)

    rgb = np.reshape(rgb, (height, width, 4))[:, :, :3]  # Remove alpha channel
    rgb = cv2.cvtColor(rgb, cv2.COLOR_RGBA2BGR)

    # Write to video
    cv2.imshow('Camera Feed', rgb)
    key = cv2.waitKey(1)

    if key == ord('q'):
        break

    time.sleep(1./30.)
cv2.destroyAllWindows()
p.disconnect()