Merge remote-tracking branch 'upstream/master'

This commit is contained in:
yunfeibai
2017-06-02 18:26:04 -07:00
126 changed files with 111577 additions and 2758 deletions

Binary file not shown.

View File

@@ -13,7 +13,7 @@ p.setRealTimeSimulation(useRealTime)
p.setGravity(0,0,-10)
p.loadURDF("plane.urdf")
p.loadSDF("stadium.sdf")
obUids = p.loadMJCF("mjcf/humanoid_fixed.xml")
human = obUids[0]

View File

@@ -1,14 +1,6 @@
import pybullet as p
import time
import math
from datetime import datetime
from numpy import *
from pylab import *
import struct
import sys
import os, fnmatch
import argparse
from time import sleep
def readLogFile(filename, verbose = True):
f = open(filename, 'rb')

View File

@@ -0,0 +1,40 @@
#you can set the restitution (bouncyness) of an object in the URDF file
#or using changeDynamics
import pybullet as p
import time
cid = p.connect(p.SHARED_MEMORY)
if (cid<0):
cid = p.connect(p.GUI)
restitutionId = p.addUserDebugParameter("restitution",0,1,1)
restitutionVelocityThresholdId = p.addUserDebugParameter("res. vel. threshold",0,3,0.2)
lateralFrictionId = p.addUserDebugParameter("lateral friction",0,1,0.5)
spinningFrictionId = p.addUserDebugParameter("spinning friction",0,1,0.03)
rollingFrictionId = p.addUserDebugParameter("rolling friction",0,1,0.03)
plane = p.loadURDF("plane_with_restitution.urdf")
sphere = p.loadURDF("sphere_with_restitution.urdf",[0,0,2])
p.setRealTimeSimulation(1)
p.setGravity(0,0,-10)
while (1):
restitution = p.readUserDebugParameter(restitutionId)
restitutionVelocityThreshold = p.readUserDebugParameter(restitutionVelocityThresholdId)
p.setPhysicsEngineParameter(restitutionVelocityThreshold=restitutionVelocityThreshold)
lateralFriction = p.readUserDebugParameter(lateralFrictionId)
spinningFriction = p.readUserDebugParameter(spinningFrictionId)
rollingFriction = p.readUserDebugParameter(rollingFrictionId)
p.changeDynamics(plane,-1,lateralFriction=1)
p.changeDynamics(sphere,-1,lateralFriction=lateralFriction)
p.changeDynamics(sphere,-1,spinningFriction=spinningFriction)
p.changeDynamics(sphere,-1,rollingFriction=rollingFriction)
p.changeDynamics(plane,-1,restitution=restitution)
p.changeDynamics(sphere,-1,restitution=restitution)
pos,orn=p.getBasePositionAndOrientation(sphere)
#print("pos=")
#print(pos)
time.sleep(0.01)