Skip to content

Commit b3cf619

Browse files
Add a physics simulation example with PyBullet
1 parent 985878a commit b3cf619

File tree

2 files changed

+63
-0
lines changed

2 files changed

+63
-0
lines changed

CHANGELOG.md

+1
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@ All notable changes to this project will be documented in this file.
1111
### Fixed
1212

1313
- cache: Only call git checkout when it is not head of the working copy
14+
- Example: simulated loaded robot description in PyBullet
1415

1516
## [1.13.0] - 2024-10-30
1617

examples/simulate_in_pybullet.py

+62
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,62 @@
1+
#!/usr/bin/env python3
2+
# -*- coding: utf-8 -*-
3+
#
4+
# SPDX-License-Identifier: Apache-2.0
5+
# Copyright 2024 Inria
6+
7+
"""
8+
Load a robot description in a PyBullet physics simulation.
9+
10+
This example requires PyBullet, which can be installed with conda or pip.
11+
"""
12+
13+
import argparse
14+
import time
15+
16+
import pybullet
17+
import pybullet_data
18+
from robot_descriptions.loaders.pybullet import load_robot_description
19+
20+
if __name__ == "__main__":
21+
parser = argparse.ArgumentParser(description=__doc__)
22+
parser.add_argument("name", help="name of the robot description")
23+
parser.add_argument(
24+
"--duration",
25+
type=float,
26+
default=10.0,
27+
help="duration of the simulation in seconds",
28+
)
29+
parser.add_argument(
30+
"--timestep",
31+
type=float,
32+
default=0.01,
33+
help="duration of a simulation timestep in seconds",
34+
)
35+
args = parser.parse_args()
36+
37+
pybullet.connect(pybullet.GUI)
38+
pybullet.setGravity(0.0, 0.0, -9.81)
39+
pybullet.setTimeStep(args.timestep)
40+
pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_RENDERING, 0)
41+
pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_SHADOWS, 0)
42+
pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_GUI, 0)
43+
pybullet.setAdditionalSearchPath(pybullet_data.getDataPath())
44+
plane_id = pybullet.loadURDF("plane.urdf")
45+
46+
try:
47+
robot = load_robot_description(args.name)
48+
except ModuleNotFoundError:
49+
robot = load_robot_description(f"{args.name}_description")
50+
51+
initial_position = [0.0, 0.0, 1.0]
52+
initial_orientation = [0.0, 0.0, 0.0, 1.0]
53+
pybullet.resetBasePositionAndOrientation(
54+
robot, initial_position, initial_orientation
55+
)
56+
pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_RENDERING, 1)
57+
58+
for _ in range(int(args.duration / args.timestep)):
59+
pybullet.stepSimulation()
60+
time.sleep(args.timestep)
61+
62+
pybullet.disconnect()

0 commit comments

Comments
 (0)