Files
bullet3/examples/pybullet/examples/changeDynamicsMass.py
Erwin Coumans ef9570c315 add yapf style and apply yapf to format all Python files
This recreates pull request #2192
2019-04-27 07:31:15 -07:00

16 lines
384 B
Python

import pybullet as p
import time
p.connect(p.GUI)
cube2 = p.loadURDF("cube.urdf", [0, 0, 3], useFixedBase=True)
cube = p.loadURDF("cube.urdf", useFixedBase=True)
p.setGravity(0, 0, -10)
timeStep = 1. / 240.
p.setTimeStep(timeStep)
p.changeDynamics(cube2, -1, mass=1)
#now cube2 will have a floating base and move
while (p.isConnected()):
p.stepSimulation()
time.sleep(timeStep)