From 7669fc92c57b7e64951795f03c47267c3fe494ec Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Fri, 23 Nov 2018 18:01:00 -0800 Subject: [PATCH] add shiftCenterOfMass.py example. --- .../pybullet/examples/shiftCenterOfMass.py | 22 +++++++++++++++++++ 1 file changed, 22 insertions(+) create mode 100644 examples/pybullet/examples/shiftCenterOfMass.py diff --git a/examples/pybullet/examples/shiftCenterOfMass.py b/examples/pybullet/examples/shiftCenterOfMass.py new file mode 100644 index 000000000..c77629b32 --- /dev/null +++ b/examples/pybullet/examples/shiftCenterOfMass.py @@ -0,0 +1,22 @@ +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.) + \ No newline at end of file