Files
bullet3/examples/pybullet/examples/shiftCenterOfMass.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

35 lines
1.2 KiB
Python

import pybullet as p
import time
import pybullet_data
p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.loadURDF("plane.urdf")
p.setGravity(0, 0, -10)
visualShift = [0, 0, 0]
collisionShift = [0, 0, 0]
inertiaShift = [0, 0, -0.5]
meshScale = [1, 1, 1]
visualShapeId = p.createVisualShape(shapeType=p.GEOM_MESH,
fileName="cube.obj",
rgbaColor=[1, 1, 1, 1],
specularColor=[0.4, .4, 0],
visualFramePosition=visualShift,
meshScale=meshScale)
collisionShapeId = p.createCollisionShape(shapeType=p.GEOM_MESH,
fileName="cube.obj",
collisionFramePosition=collisionShift,
meshScale=meshScale)
p.createMultiBody(baseMass=1,
baseInertialFramePosition=inertiaShift,
baseCollisionShapeIndex=collisionShapeId,
baseVisualShapeIndex=visualShapeId,
basePosition=[0, 0, 1],
useMaximalCoordinates=False)
while (1):
p.stepSimulation()
time.sleep(1. / 240.)