examples/pybullet/notebooks/HelloPyBullet.ipynb
<a href="https://colab.research.google.com/github/bulletphysics/bullet3/blob/master/examples/pybullet/notebooks/HelloPyBullet.ipynb" target="_parent"></a>
This notebook shows how to install and create a simple application on PyBullet.
First, let's install the PyBullet module.
# Install the PyBullet module.
!pip install -U pybullet
This is based on the PyBullet Quickstart Guide.
After importing the PyBullet module, the first thing to do is 'connecting' to the physics simulation. PyBullet is designed around a client-server driven API, with a client sending commands and a physics server returning the status.
PyBullet has some built-in physics servers: DIRECT and GUI.
Both GUI and DIRECT connections will execute the physics simulation and rendering in the same process as PyBullet.
In this example, we'll use the DIRECT mode to do the calculations independently of rendering.
import pybullet as p
p.connect(p.DIRECT)
We want to access the example
Bullet data
files.
Fortunately, we can specify a new search path in PyBullet and point it to the py_bullet_data.getDataPath().
import pybullet_data
p.setAdditionalSearchPath(pybullet_data.getDataPath())
Now, we can load models from the example data in the Unified Robot Description Format (URDF) format.
Let's load a plane to serve as our simulation floor plane,
and an R2D2 droid.
In Bullet Physics, you can use whatever units you want as long as you are consistent. For this example, we'll use the metric system.
# First, let's make sure we start with a fresh new simulation.
# Otherwise, we can keep adding objects by running this cell over again.
p.resetSimulation()
# Load our simulation floor plane at the origin (0, 0, 0).
p.loadURDF('plane.urdf')
# Load an R2D2 droid at the position at 0.5 meters height in the z-axis.
r2d2 = p.loadURDF('r2d2.urdf', [0, 0, 0.5])
# We can check the number of bodies we have in the simulation.
p.getNumBodies()
Now that we've populated our simulation with those two objects, we can analyze them to see what's inside.
The getJointInfo()
function returns a list of all the information from the selected joint.
# First let's define a class for the JointInfo.
from dataclasses import dataclass
@dataclass
class Joint:
index: int
name: str
type: int
gIndex: int
uIndex: int
flags: int
damping: float
friction: float
lowerLimit: float
upperLimit: float
maxForce: float
maxVelocity: float
linkName: str
axis: tuple
parentFramePosition: tuple
parentFrameOrientation: tuple
parentIndex: int
def __post_init__(self):
self.name = str(self.name, 'utf-8')
self.linkName = str(self.linkName, 'utf-8')
# Let's analyze the R2D2 droid!
print(f"r2d2 unique ID: {r2d2}")
for i in range(p.getNumJoints(r2d2)):
joint = Joint(*p.getJointInfo(r2d2, i))
print(joint)
To start the simulation, first we must set the gravity.
We'll use Earth's gravity for convenience, so we'll set it up to -9.807 m/s<sup>2</sup>.
# Set the gravity to Earth's gravity.
p.setGravity(0, 0, -9.807)
# Run the simulation for a fixed amount of steps.
for i in range(20):
position, orientation = p.getBasePositionAndOrientation(r2d2)
x, y, z = position
roll, pitch, yaw = p.getEulerFromQuaternion(orientation)
print(f"{i:3}: x={x:0.10f}, y={y:0.10f}, z={z:0.10f}), roll={roll:0.10f}, pitch={pitch:0.10f}, yaw={yaw:0.10f}")
p.stepSimulation()
The getCameraImage
API will return a RGB image, a depth buffer and a segmentation mask buffer with body unique ids of visible objects for each pixel
import numpy as np
from PIL import Image
from IPython.display import display
width = 320
height = 200
img_arr = p.getCameraImage(
width,
height,
viewMatrix=p.computeViewMatrixFromYawPitchRoll(
cameraTargetPosition=[0, 0, 0],
distance=4,
yaw=60,
pitch=-10,
roll=0,
upAxisIndex=2,
),
projectionMatrix=p.computeProjectionMatrixFOV(
fov=60,
aspect=width/height,
nearVal=0.01,
farVal=100,
),
shadow=True,
lightDirection=[1, 1, 1],
)
width, height, rgba, depth, mask = img_arr
print(f"rgba shape={rgba.shape}, dtype={rgba.dtype}")
display(Image.fromarray(rgba, 'RGBA'))
print(f"depth shape={depth.shape}, dtype={depth.dtype}, as values from 0.0 (near) to 1.0 (far)")
display(Image.fromarray((depth*255).astype('uint8')))
print(f"mask shape={mask.shape}, dtype={mask.dtype}, as unique values from 0 to N-1 entities, and -1 as None")
display(Image.fromarray(np.interp(mask, (-1, mask.max()), (0, 255)).astype('uint8')))