or run

npx @tessl/cli init
Log in

Version

Tile

Overview

Evals

Files

Files

docs

collision-detection.mdconnection-simulation.mdindex.mdinverse-kinematics-dynamics.mdjoint-motor-control.mdmathematical-utilities.mdobject-loading.mdphysics-configuration.mdrendering-visualization.mdstate-management-logging.mdvr-input-handling.md

index.mddocs/

0

# PyBullet

1

2

A 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.

3

4

## Package Information

5

6

- **Package Name**: pybullet

7

- **Language**: Python

8

- **Installation**: `pip install pybullet`

9

10

## Core Imports

11

12

```python

13

import pybullet as p

14

```

15

16

For data and example assets:

17

18

```python

19

import pybullet_data

20

```

21

22

## Basic Usage

23

24

```python

25

import pybullet as p

26

import pybullet_data

27

28

# Connect to physics server

29

physicsClient = p.connect(p.GUI) # or p.DIRECT for non-graphical version

30

p.setAdditionalSearchPath(pybullet_data.getDataPath()) # access to data files

31

32

# Set up the simulation environment

33

p.setGravity(0, 0, -10)

34

planeId = p.loadURDF("plane.urdf")

35

36

# Load a robot from URDF

37

startPos = [0, 0, 1]

38

startOrientation = p.getQuaternionFromEuler([0, 0, 0])

39

boxId = p.loadURDF("r2d2.urdf", startPos, startOrientation)

40

41

# Run simulation

42

for i in range(1000):

43

p.stepSimulation()

44

time.sleep(1./240.)

45

46

# Get object position and orientation

47

cubePos, cubeOrn = p.getBasePositionAndOrientation(boxId)

48

print(f"Position: {cubePos}")

49

print(f"Orientation: {cubeOrn}")

50

51

p.disconnect()

52

```

53

54

## Architecture

55

56

PyBullet operates through a client-server architecture that supports multiple connection modes:

57

58

- **Physics Server**: Handles simulation, collision detection, and dynamics computation

59

- **Client Interface**: Python API for sending commands and receiving data

60

- **Rendering Pipeline**: Software and hardware-accelerated rendering with OpenGL support

61

- **Data Management**: Comprehensive asset loading for URDF, SDF, MJCF, and various 3D formats

62

63

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.

64

65

## Capabilities

66

67

### Connection and Simulation Management

68

69

Essential functions for establishing connections to the physics server, controlling simulation execution, and managing the simulation lifecycle.

70

71

```python { .api }

72

def connect(method, *args, **kwargs):

73

"""

74

Connect to physics server.

75

76

Args:

77

method: Connection method (p.GUI, p.DIRECT, p.SHARED_MEMORY, p.TCP, p.UDP)

78

key: Shared memory key (optional)

79

hostName: Host name for TCP/UDP (optional)

80

port: Port number for TCP/UDP (optional)

81

82

Returns:

83

int: Physics client ID

84

"""

85

86

def disconnect(physicsClientId=0):

87

"""Disconnect from physics server."""

88

89

def isConnected(physicsClientId=0):

90

"""Check if client is connected to server."""

91

92

def resetSimulation(physicsClientId=0):

93

"""Reset simulation and remove all objects."""

94

95

def stepSimulation(physicsClientId=0):

96

"""Step simulation forward by one time step."""

97

98

def setRealTimeSimulation(enableRealTimeSimulation, physicsClientId=0):

99

"""Enable or disable real-time simulation."""

100

```

101

102

[Connection and Simulation](./connection-simulation.md)

103

104

### Object Loading and Creation

105

106

Functions for loading robots, objects, and environments from various file formats, as well as creating collision and visual shapes programmatically.

107

108

```python { .api }

109

def loadURDF(fileName, basePosition=None, baseOrientation=None, **kwargs):

110

"""

111

Load multibody from URDF file.

112

113

Args:

114

fileName: Path to URDF file

115

basePosition: Initial position [x, y, z]

116

baseOrientation: Initial orientation as quaternion [x, y, z, w]

117

useMaximalCoordinates: Use maximal coordinates (default False)

118

useFixedBase: Fix base to world (default False)

119

flags: Loading flags (URDF_USE_INERTIA_FROM_FILE, etc.)

120

121

Returns:

122

int: Unique body ID

123

"""

124

125

def loadSDF(fileName, physicsClientId=0):

126

"""Load objects from SDF file."""

127

128

def createCollisionShape(shapeType, **kwargs):

129

"""Create collision shape."""

130

131

def createVisualShape(shapeType, **kwargs):

132

"""Create visual shape."""

133

134

def createMultiBody(baseMass, baseCollisionShapeIndex, **kwargs):

135

"""Create multibody from components."""

136

```

137

138

[Object Loading and Creation](./object-loading.md)

139

140

### Joint and Motor Control

141

142

Comprehensive joint control including position, velocity, and torque control with PD controllers and multi-DOF joint support.

143

144

```python { .api }

145

def getJointInfo(bodyUniqueId, jointIndex, physicsClientId=0):

146

"""

147

Get joint information.

148

149

Returns:

150

tuple: (jointIndex, jointName, jointType, qIndex, uIndex, flags,

151

jointDamping, jointFriction, jointLowerLimit, jointUpperLimit,

152

jointMaxForce, jointMaxVelocity, linkName, jointAxis,

153

parentFramePos, parentFrameOrn, parentIndex)

154

"""

155

156

def setJointMotorControl2(bodyUniqueId, jointIndex, controlMode, **kwargs):

157

"""

158

Set joint motor control.

159

160

Args:

161

bodyUniqueId: Body ID

162

jointIndex: Joint index

163

controlMode: Control mode (POSITION_CONTROL, VELOCITY_CONTROL, TORQUE_CONTROL)

164

targetPosition: Target position (position control)

165

targetVelocity: Target velocity (velocity/position control)

166

force: Maximum force/torque

167

positionGain: Position gain (Kp)

168

velocityGain: Velocity gain (Kd)

169

"""

170

171

def getJointState(bodyUniqueId, jointIndex, physicsClientId=0):

172

"""Get joint state (position, velocity, reaction forces)."""

173

```

174

175

[Joint and Motor Control](./joint-motor-control.md)

176

177

### Collision Detection and Ray Casting

178

179

Advanced collision queries, contact point analysis, and ray intersection testing for sensor simulation and collision avoidance.

180

181

```python { .api }

182

def getContactPoints(bodyA=None, bodyB=None, linkIndexA=-1, linkIndexB=-1, physicsClientId=0):

183

"""

184

Get contact points between objects.

185

186

Returns:

187

list: Contact points with position, normal, distance, force, etc.

188

"""

189

190

def rayTestBatch(rayFromPositions, rayToPositions, **kwargs):

191

"""

192

Cast batch of rays for efficient collision testing.

193

194

Args:

195

rayFromPositions: List of ray start positions

196

rayToPositions: List of ray end positions

197

numThreads: Number of threads for parallel processing

198

199

Returns:

200

list: Ray hit results with objectId, linkIndex, hitFraction, hitPosition, hitNormal

201

"""

202

```

203

204

[Collision Detection](./collision-detection.md)

205

206

### Inverse Kinematics and Dynamics

207

208

Compute inverse kinematics solutions for robotic manipulation and inverse dynamics for force computation and control.

209

210

```python { .api }

211

def calculateInverseKinematics(bodyUniqueId, endEffectorLinkIndex, targetPosition, **kwargs):

212

"""

213

Calculate inverse kinematics.

214

215

Args:

216

bodyUniqueId: Robot body ID

217

endEffectorLinkIndex: End effector link index

218

targetPosition: Target position [x, y, z]

219

targetOrientation: Target orientation quaternion (optional)

220

lowerLimits: Joint lower limits (optional)

221

upperLimits: Joint upper limits (optional)

222

jointRanges: Joint ranges (optional)

223

restPoses: Rest pose joint angles (optional)

224

225

Returns:

226

list: Joint angles for target pose

227

"""

228

229

def calculateInverseDynamics(bodyUniqueId, objPositions, objVelocities, objAccelerations, physicsClientId=0):

230

"""Calculate joint forces using inverse dynamics."""

231

```

232

233

[Inverse Kinematics and Dynamics](./inverse-kinematics-dynamics.md)

234

235

### Rendering and Visualization

236

237

Camera control, image rendering, and debug visualization tools for simulation analysis and data collection.

238

239

```python { .api }

240

def getCameraImage(width, height, viewMatrix, projectionMatrix, **kwargs):

241

"""

242

Render camera image.

243

244

Args:

245

width: Image width in pixels

246

height: Image height in pixels

247

viewMatrix: 4x4 view matrix

248

projectionMatrix: 4x4 projection matrix

249

renderer: Renderer type (ER_BULLET_HARDWARE_OPENGL, ER_TINY_RENDERER)

250

251

Returns:

252

tuple: (width, height, rgbPixels, depthPixels, segmentationMaskBuffer)

253

"""

254

255

def computeViewMatrix(cameraEyePosition, cameraTargetPosition, cameraUpVector):

256

"""Compute camera view matrix."""

257

258

def computeProjectionMatrixFOV(fov, aspect, nearVal, farVal):

259

"""Compute projection matrix from field of view."""

260

```

261

262

[Rendering and Visualization](./rendering-visualization.md)

263

264

### Physics Configuration

265

266

Configure simulation parameters, gravity, time stepping, and advanced physics engine settings for optimal performance.

267

268

```python { .api }

269

def setGravity(gravX, gravY, gravZ, physicsClientId=0):

270

"""Set gravity acceleration vector."""

271

272

def setTimeStep(timeStep, physicsClientId=0):

273

"""Set simulation time step."""

274

275

def setPhysicsEngineParameter(**kwargs):

276

"""

277

Set physics engine parameters.

278

279

Args:

280

fixedTimeStep: Fixed time step size

281

numSolverIterations: Number of constraint solver iterations

282

useSplitImpulse: Use split impulse for penetration recovery

283

splitImpulsePenetrationThreshold: Penetration threshold for split impulse

284

numSubSteps: Number of sub-steps per simulation step

285

collisionFilterMode: Collision filtering mode

286

contactBreakingThreshold: Contact breaking threshold

287

maxNumCmdPer1ms: Maximum commands per millisecond

288

"""

289

```

290

291

[Physics Configuration](./physics-configuration.md)

292

293

### Mathematical Utilities

294

295

Quaternion operations, coordinate transformations, and mathematical utilities for robotics and 3D graphics applications.

296

297

```python { .api }

298

def getQuaternionFromEuler(eulerAngles):

299

"""Convert Euler angles (roll, pitch, yaw) to quaternion."""

300

301

def getEulerFromQuaternion(quaternion):

302

"""Convert quaternion to Euler angles."""

303

304

def multiplyTransforms(positionA, orientationA, positionB, orientationB):

305

"""Multiply two transforms (position, orientation)."""

306

307

def invertTransform(position, orientation):

308

"""Invert transform (position, orientation)."""

309

```

310

311

[Mathematical Utilities](./mathematical-utilities.md)

312

313

### State Management and Data Logging

314

315

Save and restore simulation states, log data for analysis, and manage user-defined data attachments.

316

317

```python { .api }

318

def saveState():

319

"""Save complete world state to memory."""

320

321

def restoreState(stateId):

322

"""Restore world state from memory."""

323

324

def startStateLogging(loggingType, fileName, **kwargs):

325

"""

326

Start logging simulation data.

327

328

Args:

329

loggingType: Type of logging (STATE_LOGGING_VIDEO_MP4, STATE_LOGGING_GENERIC_ROBOT, etc.)

330

fileName: Output file name

331

objectUniqueIds: Objects to log (optional)

332

maxLogDof: Maximum degrees of freedom to log

333

334

Returns:

335

int: Logging unique ID

336

"""

337

```

338

339

[State Management and Logging](./state-management-logging.md)

340

341

### VR and Input Handling

342

343

Virtual reality support, keyboard and mouse input handling for interactive simulations and teleoperation.

344

345

```python { .api }

346

def getVREvents(deviceTypeFilter=None, physicsClientId=0):

347

"""Get VR controller events and state."""

348

349

def getKeyboardEvents(physicsClientId=0):

350

"""Get keyboard input events."""

351

352

def getMouseEvents(physicsClientId=0):

353

"""Get mouse input events."""

354

```

355

356

[VR and Input Handling](./vr-input-handling.md)

357

358

## Constants and Enums

359

360

### Connection Methods

361

362

```python { .api }

363

# Connection types

364

p.GUI # Graphical interface

365

p.DIRECT # Direct in-process

366

p.SHARED_MEMORY # Shared memory

367

p.TCP # TCP network connection

368

p.UDP # UDP network connection

369

```

370

371

### Joint Types and Control Modes

372

373

```python { .api }

374

# Joint types

375

p.JOINT_REVOLUTE # Revolute (hinge) joint

376

p.JOINT_PRISMATIC # Prismatic (slider) joint

377

p.JOINT_SPHERICAL # Spherical joint

378

p.JOINT_FIXED # Fixed joint

379

380

# Control modes

381

p.POSITION_CONTROL # Position control with PD

382

p.VELOCITY_CONTROL # Velocity control

383

p.TORQUE_CONTROL # Direct torque control

384

p.PD_CONTROL # Pure PD control

385

p.STABLE_PD_CONTROL # Stable PD control

386

```

387

388

### Geometry Types

389

390

```python { .api }

391

# Collision shape types

392

p.GEOM_SPHERE # Sphere primitive

393

p.GEOM_BOX # Box primitive

394

p.GEOM_CYLINDER # Cylinder primitive

395

p.GEOM_MESH # Triangle mesh

396

p.GEOM_PLANE # Infinite plane

397

p.GEOM_CAPSULE # Capsule primitive

398

p.GEOM_HEIGHTFIELD # Height field terrain

399

```

400

401

### URDF Loading Flags

402

403

```python { .api }

404

# URDF loading options

405

p.URDF_USE_INERTIA_FROM_FILE # Use inertia from URDF

406

p.URDF_USE_SELF_COLLISION # Enable self collision

407

p.URDF_USE_MATERIAL_COLORS_FROM_MTL # Use MTL material colors

408

p.URDF_ENABLE_SLEEPING # Enable object sleeping

409

p.URDF_MERGE_FIXED_LINKS # Merge fixed links for performance

410

```

411

412

### Visualization and Rendering

413

414

```python { .api }

415

# Renderer types

416

p.ER_TINY_RENDERER # Software renderer

417

p.ER_BULLET_HARDWARE_OPENGL # Hardware OpenGL renderer

418

419

# Debug visualizer options

420

p.COV_ENABLE_GUI # Enable/disable GUI

421

p.COV_ENABLE_SHADOWS # Enable/disable shadows

422

p.COV_ENABLE_WIREFRAME # Enable/disable wireframe

423

p.COV_ENABLE_RENDERING # Enable/disable rendering

424

```

425

426

### Coordinate Frames

427

428

```python { .api }

429

# Reference frames

430

p.WORLD_FRAME # World coordinate frame

431

p.LINK_FRAME # Link local coordinate frame

432

```

433

434

## Error Handling

435

436

PyBullet functions may raise exceptions for invalid parameters or failed operations. Common exception scenarios include:

437

438

- **Connection errors**: Server not available or connection lost

439

- **Invalid IDs**: Non-existent body, joint, or constraint IDs

440

- **File errors**: URDF/SDF files not found or malformed

441

- **Parameter errors**: Invalid ranges or incompatible options

442

443

Always check return values and handle potential exceptions in production code.

444

445

## Performance Considerations

446

447

For optimal performance:

448

449

- Use `p.DIRECT` mode for headless simulation

450

- Enable `p.URDF_MERGE_FIXED_LINKS` for complex robots

451

- Use batch operations (`rayTestBatch`, `setJointMotorControlArray`)

452

- Minimize visualization updates in tight loops

453

- Consider multi-threading for parallel simulations

454

455

## Common Patterns

456

457

### Robot Simulation Loop

458

459

```python

460

# Load robot and set up environment

461

robotId = p.loadURDF("robot.urdf")

462

p.setGravity(0, 0, -9.81)

463

464

# Control loop

465

for step in range(simulation_steps):

466

# Set joint targets

467

p.setJointMotorControlArray(robotId, jointIndices, p.POSITION_CONTROL, targetPositions)

468

469

# Step simulation

470

p.stepSimulation()

471

472

# Get feedback

473

joint_states = p.getJointStates(robotId, jointIndices)

474

475

time.sleep(1./240.) # Real-time simulation

476

```

477

478

### Camera Simulation

479

480

```python

481

# Set up camera

482

width, height = 640, 480

483

fov, aspect, nearplane, farplane = 60, width/height, 0.01, 100

484

projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, nearplane, farplane)

485

486

# Render images in loop

487

for i in range(num_frames):

488

view_matrix = p.computeViewMatrix(eye_pos, target_pos, up_vector)

489

490

# Get camera image

491

_, _, rgb_img, depth_img, seg_img = p.getCameraImage(

492

width, height, view_matrix, projection_matrix

493

)

494

495

# Process images...

496

```