0
# Object Loading and Creation
1
2
Functions for loading robots, objects, and environments from various file formats (URDF, SDF, MJCF), as well as creating collision and visual shapes programmatically. These functions form the foundation for building simulation environments and populating them with objects.
3
4
## Capabilities
5
6
### URDF Loading
7
8
Load robots and objects from Unified Robot Description Format (URDF) files with extensive configuration options.
9
10
```python { .api }
11
def loadURDF(fileName, basePosition=None, baseOrientation=None, useMaximalCoordinates=0, useFixedBase=0, flags=0, globalScaling=1.0, physicsClientId=0):
12
"""
13
Load multibody from URDF file.
14
15
Args:
16
fileName (str): Path to URDF file (relative to search path or absolute)
17
basePosition (list, optional): Initial position [x, y, z]. Defaults to [0, 0, 0].
18
baseOrientation (list, optional): Initial orientation as quaternion [x, y, z, w].
19
Defaults to [0, 0, 0, 1].
20
useMaximalCoordinates (int, optional): Use maximal coordinates (0=multibody, 1=rigid body).
21
Defaults to 0.
22
useFixedBase (int, optional): Fix base to world (1) or allow movement (0). Defaults to 0.
23
flags (int, optional): Bitwise combination of URDF loading flags. Defaults to 0.
24
globalScaling (float, optional): Global scaling factor for all dimensions. Defaults to 1.0.
25
physicsClientId (int, optional): Physics client ID. Defaults to 0.
26
27
Returns:
28
int: Unique body ID for the loaded object
29
30
Raises:
31
Exception: If file not found or parsing fails
32
"""
33
34
def loadSDF(fileName, useMaximalCoordinates=0, globalScaling=1.0, physicsClientId=0):
35
"""
36
Load objects from Simulation Description Format (SDF) file.
37
38
Args:
39
fileName (str): Path to SDF file
40
useMaximalCoordinates (int, optional): Use maximal coordinates. Defaults to 0.
41
globalScaling (float, optional): Global scaling factor. Defaults to 1.0.
42
physicsClientId (int, optional): Physics client ID. Defaults to 0.
43
44
Returns:
45
list: List of unique body IDs for all loaded objects
46
"""
47
48
def loadMJCF(fileName, flags=0, physicsClientId=0):
49
"""
50
Load objects from MuJoCo XML format (MJCF) file.
51
52
Args:
53
fileName (str): Path to MJCF file
54
flags (int, optional): Loading flags. Defaults to 0.
55
physicsClientId (int, optional): Physics client ID. Defaults to 0.
56
57
Returns:
58
list: List of unique body IDs for all loaded objects
59
"""
60
61
def loadBullet(fileName, physicsClientId=0):
62
"""
63
Load world state from .bullet file (PyBullet's binary format).
64
65
Args:
66
fileName (str): Path to .bullet file
67
physicsClientId (int, optional): Physics client ID. Defaults to 0.
68
69
Returns:
70
list: List of unique body IDs for all loaded objects
71
"""
72
```
73
74
### Soft Body Loading
75
76
```python { .api }
77
def loadSoftBody(fileName, basePosition=None, baseOrientation=None, scale=1.0, mass=1.0, useNeoHookean=0, useBendingSprings=1, useMassSpring=1, springElasticStiffness=0.45, springDampingStiffness=0.1, springDampingAllDirections=1, useSelfCollision=1, frictionCoeff=0.5, useFaceContact=1, physicsClientId=0):
78
"""
79
Load soft body from OBJ mesh file.
80
81
Args:
82
fileName (str): Path to OBJ file containing triangle mesh
83
basePosition (list, optional): Initial position [x, y, z]. Defaults to [0, 0, 0].
84
baseOrientation (list, optional): Initial orientation quaternion. Defaults to [0, 0, 0, 1].
85
scale (float, optional): Scaling factor for mesh. Defaults to 1.0.
86
mass (float, optional): Total mass of soft body. Defaults to 1.0.
87
useNeoHookean (int, optional): Use Neo-Hookean material model. Defaults to 0.
88
useBendingSprings (int, optional): Add bending springs. Defaults to 1.
89
useMassSpring (int, optional): Use mass-spring model. Defaults to 1.
90
springElasticStiffness (float, optional): Elastic stiffness. Defaults to 0.45.
91
springDampingStiffness (float, optional): Damping stiffness. Defaults to 0.1.
92
springDampingAllDirections (int, optional): Apply damping in all directions. Defaults to 1.
93
useSelfCollision (int, optional): Enable self collision. Defaults to 1.
94
frictionCoeff (float, optional): Friction coefficient. Defaults to 0.5.
95
useFaceContact (int, optional): Use face-based contact. Defaults to 1.
96
physicsClientId (int, optional): Physics client ID. Defaults to 0.
97
98
Returns:
99
int: Unique body ID for the soft body
100
"""
101
```
102
103
### Shape Creation
104
105
Create collision and visual shapes programmatically for custom objects.
106
107
```python { .api }
108
def createCollisionShape(shapeType, radius=0.5, halfExtents=None, height=1.0, fileName=None, meshScale=None, planeNormal=None, flags=0, physicsClientId=0):
109
"""
110
Create collision shape.
111
112
Args:
113
shapeType (int): Shape type constant (p.GEOM_SPHERE, p.GEOM_BOX, etc.)
114
radius (float, optional): Radius for sphere, cylinder, capsule. Defaults to 0.5.
115
halfExtents (list, optional): Half extents [x, y, z] for box. Required for p.GEOM_BOX.
116
height (float, optional): Height for cylinder, capsule. Defaults to 1.0.
117
fileName (str, optional): Mesh file path for p.GEOM_MESH. Required for mesh shapes.
118
meshScale (list, optional): Mesh scaling [x, y, z]. Defaults to [1, 1, 1].
119
planeNormal (list, optional): Plane normal [x, y, z] for p.GEOM_PLANE. Defaults to [0, 0, 1].
120
flags (int, optional): Shape creation flags. Defaults to 0.
121
physicsClientId (int, optional): Physics client ID. Defaults to 0.
122
123
Returns:
124
int: Collision shape unique ID
125
"""
126
127
def createCollisionShapeArray(shapeTypes, radii=None, halfExtents=None, heights=None, fileNames=None, meshScales=None, planeNormals=None, flags=None, physicsClientId=0):
128
"""
129
Create array of collision shapes efficiently.
130
131
Args:
132
shapeTypes (list): List of shape type constants
133
radii (list, optional): List of radii for spherical shapes
134
halfExtents (list, optional): List of half extents for box shapes
135
heights (list, optional): List of heights for cylindrical shapes
136
fileNames (list, optional): List of mesh file paths
137
meshScales (list, optional): List of mesh scales
138
planeNormals (list, optional): List of plane normals
139
flags (list, optional): List of shape flags
140
physicsClientId (int, optional): Physics client ID. Defaults to 0.
141
142
Returns:
143
list: List of collision shape unique IDs
144
"""
145
146
def createVisualShape(shapeType, radius=0.5, halfExtents=None, height=1.0, fileName=None, meshScale=None, planeNormal=None, rgbaColor=None, specularColor=None, physicsClientId=0):
147
"""
148
Create visual shape for rendering.
149
150
Args:
151
shapeType (int): Shape type constant
152
radius (float, optional): Radius for spherical shapes. Defaults to 0.5.
153
halfExtents (list, optional): Half extents for box shapes
154
height (float, optional): Height for cylindrical shapes. Defaults to 1.0.
155
fileName (str, optional): Mesh file path for visual meshes
156
meshScale (list, optional): Mesh scaling factors. Defaults to [1, 1, 1].
157
planeNormal (list, optional): Plane normal for plane shapes
158
rgbaColor (list, optional): RGBA color [r, g, b, a]. Values 0-1.
159
specularColor (list, optional): Specular color [r, g, b]. Values 0-1.
160
physicsClientId (int, optional): Physics client ID. Defaults to 0.
161
162
Returns:
163
int: Visual shape unique ID
164
"""
165
166
def createVisualShapeArray(shapeTypes, radii=None, halfExtents=None, heights=None, fileNames=None, meshScales=None, planeNormals=None, rgbaColors=None, specularColors=None, physicsClientId=0):
167
"""
168
Create array of visual shapes efficiently.
169
170
Returns:
171
list: List of visual shape unique IDs
172
"""
173
```
174
175
### Multi-Body Creation
176
177
Assemble complex objects from collision shapes, visual shapes, and link hierarchy.
178
179
```python { .api }
180
def createMultiBody(baseMass, baseCollisionShapeIndex, baseVisualShapeIndex=-1, basePosition=None, baseOrientation=None, baseInertialFramePosition=None, baseInertialFrameOrientation=None, linkMasses=None, linkCollisionShapeIndices=None, linkVisualShapeIndices=None, linkPositions=None, linkOrientations=None, linkInertialFramePositions=None, linkInertialFrameOrientations=None, linkParentIndices=None, linkJointTypes=None, linkJointAxis=None, physicsClientId=0):
181
"""
182
Create multibody from collision and visual shape components.
183
184
Args:
185
baseMass (float): Mass of base link
186
baseCollisionShapeIndex (int): Collision shape ID for base (-1 for none)
187
baseVisualShapeIndex (int, optional): Visual shape ID for base. Defaults to -1.
188
basePosition (list, optional): Base position [x, y, z]. Defaults to [0, 0, 0].
189
baseOrientation (list, optional): Base orientation quaternion. Defaults to [0, 0, 0, 1].
190
baseInertialFramePosition (list, optional): Inertial frame position offset
191
baseInertialFrameOrientation (list, optional): Inertial frame orientation offset
192
linkMasses (list, optional): List of link masses
193
linkCollisionShapeIndices (list, optional): List of collision shape IDs for links
194
linkVisualShapeIndices (list, optional): List of visual shape IDs for links
195
linkPositions (list, optional): List of link positions relative to parent
196
linkOrientations (list, optional): List of link orientations relative to parent
197
linkInertialFramePositions (list, optional): List of inertial frame positions
198
linkInertialFrameOrientations (list, optional): List of inertial frame orientations
199
linkParentIndices (list, optional): List of parent link indices
200
linkJointTypes (list, optional): List of joint type constants
201
linkJointAxis (list, optional): List of joint axes
202
physicsClientId (int, optional): Physics client ID. Defaults to 0.
203
204
Returns:
205
int: Unique body ID for created multibody
206
"""
207
```
208
209
### Object Removal
210
211
```python { .api }
212
def removeBody(bodyUniqueId, physicsClientId=0):
213
"""
214
Remove body from simulation.
215
216
Args:
217
bodyUniqueId (int): Body unique ID to remove
218
physicsClientId (int, optional): Physics client ID. Defaults to 0.
219
"""
220
221
def removeCollisionShape(collisionShapeId, physicsClientId=0):
222
"""
223
Remove collision shape (if not used by any body).
224
225
Args:
226
collisionShapeId (int): Collision shape ID to remove
227
physicsClientId (int, optional): Physics client ID. Defaults to 0.
228
"""
229
```
230
231
## URDF Loading Flags
232
233
Use these flags with loadURDF() to control loading behavior:
234
235
```python { .api }
236
# Inertia and dynamics
237
p.URDF_USE_INERTIA_FROM_FILE # Use inertia tensor from URDF file
238
p.URDF_USE_IMPLICIT_CYLINDER # Use implicit cylinder for collision
239
240
# Collision and physics
241
p.URDF_USE_SELF_COLLISION # Enable self-collision detection
242
p.URDF_USE_SELF_COLLISION_EXCLUDE_PARENT # Self collision but exclude parent links
243
p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS # Self collision but exclude all parent links
244
245
# Visual and materials
246
p.URDF_USE_MATERIAL_COLORS_FROM_MTL # Use colors from MTL material files
247
p.URDF_USE_MATERIAL_TRANSPARANCY_FROM_MTL # Use transparency from MTL files
248
249
# Performance optimizations
250
p.URDF_MERGE_FIXED_LINKS # Merge fixed joints for better performance
251
p.URDF_ENABLE_CACHED_GRAPHICS_SHAPES # Cache graphics shapes for reuse
252
p.URDF_ENABLE_SLEEPING # Enable object sleeping for inactive bodies
253
254
# Behavior control
255
p.URDF_MAINTAIN_LINK_ORDER # Preserve link order from URDF
256
p.URDF_IGNORE_VISUAL_SHAPES # Skip loading visual shapes
257
p.URDF_IGNORE_COLLISION_SHAPES # Skip loading collision shapes
258
p.URDF_PRINT_URDF_INFO # Print URDF parsing information
259
260
# Advanced features
261
p.URDF_GLOBAL_VELOCITIES_MB # Use global velocities for multibody
262
p.URDF_INITIALIZE_SAT_FEATURES # Initialize SAT collision features
263
p.URDF_ENABLE_WAKEUP # Enable automatic wakeup for sleeping bodies
264
```
265
266
## Usage Examples
267
268
### Basic Object Loading
269
270
```python
271
import pybullet as p
272
import pybullet_data
273
274
p.connect(p.GUI)
275
p.setAdditionalSearchPath(pybullet_data.getDataPath())
276
277
# Load ground plane
278
planeId = p.loadURDF("plane.urdf")
279
280
# Load robot at specific position and orientation
281
startPos = [0, 0, 1]
282
startOrientation = p.getQuaternionFromEuler([0, 0, 0])
283
robotId = p.loadURDF("r2d2.urdf", startPos, startOrientation)
284
285
# Load with specific flags for performance
286
robotId2 = p.loadURDF("pr2_gripper.urdf",
287
basePosition=[2, 0, 1],
288
flags=p.URDF_MERGE_FIXED_LINKS | p.URDF_USE_INERTIA_FROM_FILE)
289
```
290
291
### Creating Custom Primitives
292
293
```python
294
import pybullet as p
295
296
p.connect(p.GUI)
297
298
# Create collision shapes
299
sphereCol = p.createCollisionShape(p.GEOM_SPHERE, radius=0.5)
300
boxCol = p.createCollisionShape(p.GEOM_BOX, halfExtents=[0.5, 0.5, 0.5])
301
cylinderCol = p.createCollisionShape(p.GEOM_CYLINDER, radius=0.3, height=1.0)
302
303
# Create visual shapes with colors
304
sphereVis = p.createVisualShape(p.GEOM_SPHERE, radius=0.5, rgbaColor=[1, 0, 0, 1])
305
boxVis = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.5, 0.5, 0.5], rgbaColor=[0, 1, 0, 1])
306
cylinderVis = p.createVisualShape(p.GEOM_CYLINDER, radius=0.3, height=1.0, rgbaColor=[0, 0, 1, 1])
307
308
# Create multibodies
309
sphereId = p.createMultiBody(baseMass=1.0,
310
baseCollisionShapeIndex=sphereCol,
311
baseVisualShapeIndex=sphereVis,
312
basePosition=[0, 0, 2])
313
314
boxId = p.createMultiBody(baseMass=1.0,
315
baseCollisionShapeIndex=boxCol,
316
baseVisualShapeIndex=boxVis,
317
basePosition=[2, 0, 2])
318
319
cylinderId = p.createMultiBody(baseMass=1.0,
320
baseCollisionShapeIndex=cylinderCol,
321
baseVisualShapeIndex=cylinderVis,
322
basePosition=[-2, 0, 2])
323
```
324
325
### Loading Mesh Objects
326
327
```python
328
import pybullet as p
329
330
p.connect(p.GUI)
331
332
# Create collision shape from mesh file
333
meshCol = p.createCollisionShape(p.GEOM_MESH,
334
fileName="path/to/mesh.obj",
335
meshScale=[1, 1, 1])
336
337
# Create visual shape from same or different mesh
338
meshVis = p.createVisualShape(p.GEOM_MESH,
339
fileName="path/to/visual_mesh.obj",
340
meshScale=[1, 1, 1],
341
rgbaColor=[0.5, 0.5, 0.5, 1])
342
343
# Create object from mesh
344
meshId = p.createMultiBody(baseMass=0, # Static object
345
baseCollisionShapeIndex=meshCol,
346
baseVisualShapeIndex=meshVis,
347
basePosition=[0, 0, 0])
348
```
349
350
### Complex Multi-Link Object
351
352
```python
353
import pybullet as p
354
355
p.connect(p.GUI)
356
357
# Create shapes for base and links
358
baseCol = p.createCollisionShape(p.GEOM_BOX, halfExtents=[0.5, 0.5, 0.1])
359
linkCol = p.createCollisionShape(p.GEOM_CYLINDER, radius=0.1, height=0.5)
360
361
baseVis = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.5, 0.5, 0.1], rgbaColor=[0.2, 0.2, 0.8, 1])
362
linkVis = p.createVisualShape(p.GEOM_CYLINDER, radius=0.1, height=0.5, rgbaColor=[0.8, 0.2, 0.2, 1])
363
364
# Create 2-link object
365
multiBodyId = p.createMultiBody(
366
baseMass=1.0,
367
baseCollisionShapeIndex=baseCol,
368
baseVisualShapeIndex=baseVis,
369
basePosition=[0, 0, 1],
370
linkMasses=[0.5, 0.5],
371
linkCollisionShapeIndices=[linkCol, linkCol],
372
linkVisualShapeIndices=[linkVis, linkVis],
373
linkPositions=[[0, 0, 0.3], [0, 0, 0.6]],
374
linkOrientations=[[0, 0, 0, 1], [0, 0, 0, 1]],
375
linkParentIndices=[0, 1],
376
linkJointTypes=[p.JOINT_REVOLUTE, p.JOINT_REVOLUTE],
377
linkJointAxis=[[1, 0, 0], [1, 0, 0]]
378
)
379
```
380
381
### Soft Body Creation
382
383
```python
384
import pybullet as p
385
386
p.connect(p.GUI)
387
388
# Load soft body from mesh
389
softBodyId = p.loadSoftBody("path/to/cloth.obj",
390
basePosition=[0, 0, 2],
391
mass=1.0,
392
useNeoHookean=1,
393
springElasticStiffness=0.45,
394
springDampingStiffness=0.1,
395
useSelfCollision=1,
396
frictionCoeff=0.5)
397
```
398
399
## Best Practices
400
401
1. **Use appropriate loading flags** - p.URDF_MERGE_FIXED_LINKS for better performance
402
2. **Set search paths** - Use p.setAdditionalSearchPath() for asset directories
403
3. **Batch shape creation** - Use createCollisionShapeArray() for multiple similar shapes
404
4. **Consider memory usage** - Remove unused bodies and shapes to free memory
405
5. **Validate file paths** - Check file existence before loading to handle errors gracefully
406
6. **Use global scaling** - Scale objects uniformly rather than modifying source files