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

physics-configuration.mddocs/

0

# Physics Configuration

1

2

Configure simulation parameters, gravity, time stepping, and advanced physics engine settings for optimal performance and realistic behavior. Essential for tuning simulations for specific applications and achieving desired accuracy-performance trade-offs.

3

4

## Capabilities

5

6

### Gravity and Global Forces

7

8

Set global forces that affect all objects in the simulation.

9

10

```python { .api }

11

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

12

"""

13

Set gravity acceleration vector for the simulation.

14

15

Args:

16

gravX (float): Gravity acceleration in X direction (m/s²)

17

gravY (float): Gravity acceleration in Y direction (m/s²)

18

gravZ (float): Gravity acceleration in Z direction (m/s²)

19

physicsClientId (int, optional): Physics client ID. Defaults to 0.

20

21

Note:

22

Earth gravity: [0, 0, -9.81]

23

Moon gravity: [0, 0, -1.62]

24

Zero gravity: [0, 0, 0]

25

Custom directions: e.g., [0, -9.81, 0] for Y-up coordinate system

26

"""

27

```

28

29

### Time Stepping

30

31

Control simulation timing and temporal resolution.

32

33

```python { .api }

34

def setTimeStep(timeStep, physicsClientId=0):

35

"""

36

Set simulation time step size.

37

38

Args:

39

timeStep (float): Time step in seconds (typically 1/240 to 1/60)

40

physicsClientId (int, optional): Physics client ID. Defaults to 0.

41

42

Note:

43

Smaller time steps provide higher accuracy but slower simulation.

44

Common values:

45

- 1/240 (0.00416s): High precision, good for complex simulations

46

- 1/120 (0.00833s): Good balance of speed and accuracy

47

- 1/60 (0.01667s): Fast simulation, lower accuracy

48

"""

49

```

50

51

### Contact Parameters

52

53

Configure contact behavior and error correction.

54

55

```python { .api }

56

def setDefaultContactERP(defaultContactERP, physicsClientId=0):

57

"""

58

Set default Error Recovery Parameter for contact constraints.

59

60

Args:

61

defaultContactERP (float): ERP value (0.0 to 1.0)

62

physicsClientId (int, optional): Physics client ID. Defaults to 0.

63

64

Note:

65

ERP controls how quickly interpenetration is resolved.

66

Higher values = faster resolution but less stability.

67

Typical range: 0.1 to 0.8

68

"""

69

```

70

71

### Advanced Physics Engine Parameters

72

73

Fine-tune internal physics engine behavior for performance and accuracy.

74

75

```python { .api }

76

def setPhysicsEngineParameter(fixedTimeStep=None, numSolverIterations=None, useSplitImpulse=None, splitImpulsePenetrationThreshold=None, numSubSteps=None, collisionFilterMode=None, contactBreakingThreshold=None, maxNumCmdPer1ms=None, enableFileCaching=None, restitutionVelocityThreshold=None, erp=None, contactERP=None, frictionERP=None, enableConeFriction=None, deterministicOverlappingPairs=None, allowedCcdPenetration=None, jointFeedbackMode=None, solverResidualThreshold=None, contactSlop=None, enableSAT=None, constraintSolverType=None, minimumSolverIslandSize=None, reportSolverAnalytics=None, warmStartingFactor=None, articulatedWarmStartingFactor=None, physicsClientId=0):

77

"""

78

Set advanced physics engine parameters for fine-tuning performance and behavior.

79

80

Args:

81

fixedTimeStep (float, optional): Fixed time step size override

82

numSolverIterations (int, optional): Number of constraint solver iterations (default: 50)

83

useSplitImpulse (int, optional): Use split impulse for penetration recovery (0/1)

84

splitImpulsePenetrationThreshold (float, optional): Threshold for split impulse activation

85

numSubSteps (int, optional): Number of sub-steps per simulation step (default: 1)

86

collisionFilterMode (int, optional): Collision filtering mode

87

contactBreakingThreshold (float, optional): Distance threshold for contact breaking

88

maxNumCmdPer1ms (int, optional): Maximum commands processed per millisecond

89

enableFileCaching (int, optional): Enable file caching for faster loading (0/1)

90

restitutionVelocityThreshold (float, optional): Velocity threshold for restitution

91

erp (float, optional): Global error recovery parameter

92

contactERP (float, optional): Contact-specific ERP

93

frictionERP (float, optional): Friction-specific ERP

94

enableConeFriction (int, optional): Enable cone friction model (0/1)

95

deterministicOverlappingPairs (int, optional): Deterministic overlapping pair handling (0/1)

96

allowedCcdPenetration (float, optional): Allowed penetration for CCD

97

jointFeedbackMode (int, optional): Joint feedback computation mode

98

solverResidualThreshold (float, optional): Solver convergence threshold

99

contactSlop (float, optional): Contact slop parameter for stability

100

enableSAT (int, optional): Enable Separating Axis Theorem (0/1)

101

constraintSolverType (int, optional): Constraint solver algorithm type

102

minimumSolverIslandSize (int, optional): Minimum size for solver islands

103

reportSolverAnalytics (int, optional): Enable solver analytics reporting (0/1)

104

warmStartingFactor (float, optional): Warm starting factor for solver

105

articulatedWarmStartingFactor (float, optional): Warm starting for articulated bodies

106

physicsClientId (int, optional): Physics client ID. Defaults to 0.

107

108

Note:

109

These parameters significantly affect simulation behavior and performance.

110

Modify carefully and test thoroughly. Default values work well for most applications.

111

"""

112

113

def getPhysicsEngineParameters(physicsClientId=0):

114

"""

115

Get current physics engine parameters.

116

117

Args:

118

physicsClientId (int, optional): Physics client ID. Defaults to 0.

119

120

Returns:

121

dict: Dictionary containing all current physics engine parameters

122

"""

123

```

124

125

### Internal Simulation Flags

126

127

Control experimental and advanced simulation features.

128

129

```python { .api }

130

def setInternalSimFlags(flags, physicsClientId=0):

131

"""

132

Set internal simulation flags (experimental features).

133

134

Args:

135

flags (int): Bitwise combination of internal simulation flags

136

physicsClientId (int, optional): Physics client ID. Defaults to 0.

137

138

Warning:

139

These are experimental features that may change or be removed.

140

Use with caution in production code.

141

"""

142

```

143

144

## Configuration Presets

145

146

### High Precision Configuration

147

148

```python

149

import pybullet as p

150

151

def setupHighPrecisionPhysics():

152

"""Configure physics for maximum accuracy."""

153

p.setTimeStep(1./240.) # Small time step

154

p.setGravity(0, 0, -9.81)

155

156

p.setPhysicsEngineParameter(

157

numSolverIterations=100, # More solver iterations

158

useSplitImpulse=1,

159

splitImpulsePenetrationThreshold=-0.001,

160

contactBreakingThreshold=0.001,

161

solverResidualThreshold=1e-7,

162

numSubSteps=1

163

)

164

```

165

166

### High Performance Configuration

167

168

```python

169

import pybullet as p

170

171

def setupHighPerformancePhysics():

172

"""Configure physics for maximum speed."""

173

p.setTimeStep(1./60.) # Larger time step

174

p.setGravity(0, 0, -9.81)

175

176

p.setPhysicsEngineParameter(

177

numSolverIterations=20, # Fewer iterations

178

useSplitImpulse=0,

179

enableFileCaching=1,

180

numSubSteps=1,

181

deterministicOverlappingPairs=0

182

)

183

```

184

185

### Robotics Configuration

186

187

```python

188

import pybullet as p

189

190

def setupRoboticsPhysics():

191

"""Configure physics optimized for robotics applications."""

192

p.setTimeStep(1./240.)

193

p.setGravity(0, 0, -9.81)

194

195

p.setPhysicsEngineParameter(

196

numSolverIterations=50,

197

useSplitImpulse=1,

198

splitImpulsePenetrationThreshold=-0.004,

199

contactBreakingThreshold=0.001,

200

restitutionVelocityThreshold=0.2,

201

enableConeFriction=1,

202

warmStartingFactor=0.85

203

)

204

```

205

206

### Soft Body Configuration

207

208

```python

209

import pybullet as p

210

211

def setupSoftBodyPhysics():

212

"""Configure physics for soft body simulation."""

213

p.setTimeStep(1./240.)

214

p.setGravity(0, 0, -9.81)

215

216

p.setPhysicsEngineParameter(

217

numSolverIterations=150, # More iterations for soft bodies

218

useSplitImpulse=1,

219

numSubSteps=4, # More sub-steps for stability

220

contactBreakingThreshold=0.0001,

221

solverResidualThreshold=1e-6

222

)

223

```

224

225

## Usage Examples

226

227

### Basic Physics Setup

228

229

```python

230

import pybullet as p

231

232

p.connect(p.GUI)

233

234

# Standard Earth-like physics

235

p.setGravity(0, 0, -9.81)

236

p.setTimeStep(1./240.)

237

238

# Load objects and run simulation

239

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

240

241

for step in range(1000):

242

p.stepSimulation()

243

```

244

245

### Custom Gravity Environment

246

247

```python

248

import pybullet as p

249

250

p.connect(p.GUI)

251

252

# Simulate low gravity environment (Moon-like)

253

p.setGravity(0, 0, -1.62) # Moon gravity

254

p.setTimeStep(1./240.)

255

256

# Or simulate microgravity

257

# p.setGravity(0, 0, -0.01)

258

259

# Load objects - they will fall slowly

260

cubeId = p.loadURDF("cube.urdf", [0, 0, 2])

261

262

for step in range(2000): # Longer simulation to see slow motion

263

p.stepSimulation()

264

```

265

266

### Performance Optimization Example

267

268

```python

269

import pybullet as p

270

import time

271

272

p.connect(p.DIRECT) # No GUI for maximum performance

273

274

# Performance-optimized settings

275

p.setTimeStep(1./60.) # Larger time step

276

p.setGravity(0, 0, -9.81)

277

278

# Optimize physics engine

279

p.setPhysicsEngineParameter(

280

numSolverIterations=20, # Reduce solver iterations

281

enableFileCaching=1, # Enable caching

282

deterministicOverlappingPairs=0, # Faster collision detection

283

useSplitImpulse=0 # Disable for speed

284

)

285

286

# Load many objects for stress test

287

objects = []

288

for i in range(100):

289

x = (i % 10) * 0.5

290

y = (i // 10) * 0.5

291

objId = p.loadURDF("cube.urdf", [x, y, 1])

292

objects.append(objId)

293

294

# Measure performance

295

start_time = time.time()

296

num_steps = 1000

297

298

for step in range(num_steps):

299

p.stepSimulation()

300

301

end_time = time.time()

302

elapsed = end_time - start_time

303

fps = num_steps / elapsed

304

305

print(f"Simulation FPS: {fps:.1f}")

306

print(f"Simulated time: {num_steps * (1./60.):.2f} seconds")

307

print(f"Real time: {elapsed:.2f} seconds")

308

print(f"Speed ratio: {(num_steps * (1./60.)) / elapsed:.1f}x real-time")

309

```

310

311

### Precision Testing and Tuning

312

313

```python

314

import pybullet as p

315

import numpy as np

316

317

def testPhysicsAccuracy(timeStep, solverIterations):

318

"""Test physics accuracy with different parameters."""

319

p.resetSimulation()

320

p.setTimeStep(timeStep)

321

p.setGravity(0, 0, -9.81)

322

323

p.setPhysicsEngineParameter(numSolverIterations=solverIterations)

324

325

# Drop object from known height

326

cubeId = p.loadURDF("cube.urdf", [0, 0, 5])

327

328

# Theoretical time to fall: t = sqrt(2h/g) = sqrt(10/9.81) ≈ 1.01s

329

theoretical_time = np.sqrt(10 / 9.81)

330

331

positions = []

332

times = []

333

334

for step in range(int(theoretical_time * 1.5 / timeStep)):

335

p.stepSimulation()

336

pos, _ = p.getBasePositionAndOrientation(cubeId)

337

positions.append(pos[2])

338

times.append(step * timeStep)

339

340

# Stop when object hits ground

341

if pos[2] < 0.05:

342

actual_time = step * timeStep

343

break

344

345

error = abs(actual_time - theoretical_time)

346

return actual_time, theoretical_time, error

347

348

# Test different configurations

349

configs = [

350

(1./240., 50), # Standard

351

(1./120., 50), # Faster time step

352

(1./240., 20), # Fewer iterations

353

(1./240., 100), # More iterations

354

]

355

356

print("TimeStep | Iterations | Actual | Theoretical | Error")

357

print("-" * 50)

358

359

for timeStep, iterations in configs:

360

p.connect(p.DIRECT)

361

actual, theoretical, error = testPhysicsAccuracy(timeStep, iterations)

362

print(f"{timeStep:8.5f} | {iterations:10d} | {actual:6.3f} | {theoretical:11.3f} | {error:5.3f}")

363

p.disconnect()

364

```

365

366

### Dynamic Parameter Adjustment

367

368

```python

369

import pybullet as p

370

371

p.connect(p.GUI)

372

p.setGravity(0, 0, -9.81)

373

374

# Start with standard settings

375

p.setTimeStep(1./240.)

376

p.setPhysicsEngineParameter(numSolverIterations=50)

377

378

robotId = p.loadURDF("kuka_iiwa/model.urdf")

379

380

simulation_phase = 0

381

step_count = 0

382

383

for total_step in range(3000):

384

# Change physics parameters during simulation

385

if total_step == 1000:

386

print("Switching to high precision mode...")

387

p.setPhysicsEngineParameter(

388

numSolverIterations=100,

389

solverResidualThreshold=1e-7

390

)

391

simulation_phase = 1

392

393

elif total_step == 2000:

394

print("Switching to high performance mode...")

395

p.setTimeStep(1./120.)

396

p.setPhysicsEngineParameter(

397

numSolverIterations=20,

398

solverResidualThreshold=1e-4

399

)

400

simulation_phase = 2

401

402

p.stepSimulation()

403

404

# Monitor performance impact

405

if total_step % 500 == 0:

406

print(f"Step {total_step}, Phase {simulation_phase}")

407

```

408

409

### Contact Parameter Tuning

410

411

```python

412

import pybullet as p

413

414

p.connect(p.GUI)

415

p.setGravity(0, 0, -9.81)

416

417

# Load objects for contact testing

418

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

419

cubeId = p.loadURDF("cube.urdf", [0, 0, 2])

420

421

# Experiment with different contact parameters

422

contact_configs = [

423

{"erp": 0.2, "description": "Soft contacts"},

424

{"erp": 0.8, "description": "Stiff contacts"},

425

{"contactBreakingThreshold": 0.001, "description": "Precise contacts"},

426

{"restitutionVelocityThreshold": 0.1, "description": "Low restitution threshold"}

427

]

428

429

for i, config in enumerate(contact_configs):

430

p.resetSimulation()

431

p.setGravity(0, 0, -9.81)

432

433

# Apply configuration

434

p.setPhysicsEngineParameter(**{k: v for k, v in config.items() if k != "description"})

435

436

# Reload objects

437

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

438

cubeId = p.loadURDF("cube.urdf", [0, 0, 2])

439

440

print(f"\nTesting: {config['description']}")

441

442

# Run simulation and monitor contacts

443

max_force = 0

444

for step in range(500):

445

p.stepSimulation()

446

447

contacts = p.getContactPoints(cubeId, planeId)

448

if contacts:

449

force = contacts[0][9] # Normal force

450

max_force = max(max_force, force)

451

452

print(f"Maximum contact force: {max_force:.2f} N")

453

```

454

455

## Performance Guidelines

456

457

### Time Step Selection

458

459

- **1/240s (0.0042s)**: High precision, complex robots, soft bodies

460

- **1/120s (0.0083s)**: Good balance for most robotics applications

461

- **1/60s (0.0167s)**: Fast simulation, simple rigid bodies

462

- **> 1/60s**: Use with caution, may cause instability

463

464

### Solver Iterations

465

466

- **20-30**: Fast simulation, simple scenes

467

- **50**: Default, good for most applications

468

- **100+**: High precision, complex constraints, soft bodies

469

470

### Memory and Performance

471

472

- **enableFileCaching=1**: Faster subsequent loads

473

- **deterministicOverlappingPairs=0**: Faster collision detection

474

- **numSubSteps=1**: Standard, increase for soft bodies or small time steps

475

- **useSplitImpulse=1**: Better stability, slightly slower

476

477

## Best Practices

478

479

1. **Start with defaults** - PyBullet's default parameters work well for most applications

480

2. **Profile before optimizing** - Measure performance impact of parameter changes

481

3. **Test stability** - Ensure parameter changes don't introduce instabilities

482

4. **Match time step to application** - Real-time applications need appropriate time steps

483

5. **Consider trade-offs** - Accuracy vs. performance is always a balance

484

6. **Use presets** - Start with configuration presets for your application domain

485

7. **Monitor solver convergence** - Watch for solver warnings in complex simulations

486

8. **Validate physics** - Test against known physical behaviors when tuning parameters