Merge branch 'master' of https://github.com/erwincoumans/bullet3
This commit is contained in:
40
examples/pybullet/examples/biped2d_pybullet.py
Normal file
40
examples/pybullet/examples/biped2d_pybullet.py
Normal file
@@ -0,0 +1,40 @@
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
import os
|
||||
import time
|
||||
GRAVITY = -9.8
|
||||
dt = 1e-3
|
||||
iters=2000
|
||||
|
||||
physicsClient = p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.resetSimulation()
|
||||
#p.setRealTimeSimulation(True)
|
||||
p.setGravity(0,0,GRAVITY)
|
||||
p.setTimeStep(dt)
|
||||
planeId = p.loadURDF("plane.urdf")
|
||||
cubeStartPos = [0,0,1.13]
|
||||
cubeStartOrientation = p.getQuaternionFromEuler([0.,0,0])
|
||||
botId = p.loadURDF("biped/biped2d_pybullet.urdf",
|
||||
cubeStartPos,
|
||||
cubeStartOrientation)
|
||||
|
||||
#disable the default velocity motors
|
||||
#and set some position control with small force to emulate joint friction/return to a rest pose
|
||||
jointFrictionForce=1
|
||||
for joint in range (p.getNumJoints(botId)):
|
||||
p.setJointMotorControl2(botId,joint,p.POSITION_CONTROL,force=jointFrictionForce)
|
||||
|
||||
#for i in range(10000):
|
||||
# p.setJointMotorControl2(botId, 1, p.TORQUE_CONTROL, force=1098.0)
|
||||
# p.stepSimulation()
|
||||
#import ipdb
|
||||
#ipdb.set_trace()
|
||||
import time
|
||||
p.setRealTimeSimulation(1)
|
||||
while (1):
|
||||
#p.stepSimulation()
|
||||
#p.setJointMotorControl2(botId, 1, p.TORQUE_CONTROL, force=1098.0)
|
||||
p.setGravity(0,0,GRAVITY)
|
||||
time.sleep(1/240.)
|
||||
time.sleep(1000)
|
||||
32
examples/pybullet/examples/otherPhysicsEngine.py
Normal file
32
examples/pybullet/examples/otherPhysicsEngine.py
Normal file
@@ -0,0 +1,32 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
#p.connect(p.DIRECT)
|
||||
#p.connect(p.DART)
|
||||
p.connect(p.MuJoCo)
|
||||
|
||||
#p.connect(p.GUI)
|
||||
bodies = p.loadMJCF("mjcf/capsule.xml")
|
||||
print("bodies=",bodies)
|
||||
|
||||
numBodies = p.getNumBodies()
|
||||
print("numBodies=",numBodies)
|
||||
for i in range (numBodies):
|
||||
print("bodyInfo[",i,"]=",p.getBodyInfo(i))
|
||||
|
||||
p.setGravity(0,0,-10)
|
||||
timeStep = 1./240.
|
||||
p.setPhysicsEngineParameter(fixedTimeStep=timeStep)
|
||||
|
||||
#while (p.isConnected()):
|
||||
for i in range (1000):
|
||||
p.stepSimulation()
|
||||
|
||||
for b in bodies:
|
||||
pos,orn=p.getBasePositionAndOrientation(b)
|
||||
print("pos[",b,"]=",pos)
|
||||
print("orn[",b,"]=",orn)
|
||||
linvel,angvel=p.getBaseVelocity(b)
|
||||
print("linvel[",b,"]=",linvel)
|
||||
print("angvel[",b,"]=",angvel)
|
||||
time.sleep(timeStep)
|
||||
Reference in New Issue
Block a user