add Franka Panda URDF and example (python3 -m pybullet_envs.examples.loadpanda)
add XArm6 URDF with optimized collision meshes and example (XArm gripper needs more work) python3 -m pybullet_envs.examples.xarm
This commit is contained in:
189
examples/pybullet/gym/pybullet_envs/examples/batchsim3.py
Normal file
189
examples/pybullet/gym/pybullet_envs/examples/batchsim3.py
Normal file
@@ -0,0 +1,189 @@
|
||||
import os
|
||||
import inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
from pybullet_utils import bullet_client
|
||||
import panda_sim
|
||||
|
||||
|
||||
import time
|
||||
|
||||
useGUI = False
|
||||
timeStep = 1./60.
|
||||
|
||||
# Importing the libraries
|
||||
import os
|
||||
import time
|
||||
import multiprocessing as mp
|
||||
from multiprocessing import Process, Pipe
|
||||
|
||||
pandaEndEffectorIndex = 11 #8
|
||||
pandaNumDofs = 7
|
||||
|
||||
|
||||
_RESET = 1
|
||||
_CLOSE = 2
|
||||
_EXPLORE = 3
|
||||
|
||||
|
||||
def ExploreWorker(rank, num_processes, childPipe, args):
|
||||
print("hi:",rank, " out of ", num_processes)
|
||||
import pybullet as op1
|
||||
import pybullet_data as pd
|
||||
logName=""
|
||||
p1=0
|
||||
n = 0
|
||||
space = 2
|
||||
simulations=[]
|
||||
sims_per_worker = 10
|
||||
|
||||
offsetY = rank*space
|
||||
while True:
|
||||
n += 1
|
||||
try:
|
||||
# Only block for short times to have keyboard exceptions be raised.
|
||||
if not childPipe.poll(0.0001):
|
||||
continue
|
||||
message, payload = childPipe.recv()
|
||||
except (EOFError, KeyboardInterrupt):
|
||||
break
|
||||
if message == _RESET:
|
||||
if (useGUI):
|
||||
p1 = bullet_client.BulletClient(op1.GUI)
|
||||
else:
|
||||
p1 = bullet_client.BulletClient(op1.DIRECT)
|
||||
p1.setTimeStep(timeStep)
|
||||
|
||||
p1.setPhysicsEngineParameter(numSolverIterations=8)
|
||||
p1.setPhysicsEngineParameter(minimumSolverIslandSize=100)
|
||||
p1.configureDebugVisualizer(p1.COV_ENABLE_Y_AXIS_UP,1)
|
||||
p1.configureDebugVisualizer(p1.COV_ENABLE_RENDERING,0)
|
||||
p1.setAdditionalSearchPath(pd.getDataPath())
|
||||
p1.setGravity(0,-9.8,0)
|
||||
logName = str("batchsim")+str(rank)
|
||||
for j in range (3):
|
||||
offsetX = 0#-sims_per_worker/2.0*space
|
||||
for i in range (sims_per_worker):
|
||||
offset=[offsetX,0, offsetY]
|
||||
sim = panda_sim.PandaSim(p1, offset)
|
||||
simulations.append(sim)
|
||||
offsetX += space
|
||||
offsetY += space
|
||||
childPipe.send(["reset ok"])
|
||||
p1.configureDebugVisualizer(p1.COV_ENABLE_RENDERING,1)
|
||||
for i in range (100):
|
||||
p1.stepSimulation()
|
||||
|
||||
logId = p1.startStateLogging(op1.STATE_LOGGING_PROFILE_TIMINGS,logName)
|
||||
continue
|
||||
if message == _EXPLORE:
|
||||
sum_rewards=rank
|
||||
|
||||
if useGUI:
|
||||
numSteps = int(20000)
|
||||
else:
|
||||
numSteps = int(5)
|
||||
for i in range (numSteps):
|
||||
for s in simulations:
|
||||
s.step()
|
||||
p1.stepSimulation()
|
||||
#print("logId=",logId)
|
||||
#print("numSteps=",numSteps)
|
||||
|
||||
childPipe.send([sum_rewards])
|
||||
continue
|
||||
if message == _CLOSE:
|
||||
p1.stopStateLogging(logId)
|
||||
childPipe.send(["close ok"])
|
||||
break
|
||||
childPipe.close()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
mp.freeze_support()
|
||||
if useGUI:
|
||||
num_processes = 1
|
||||
else:
|
||||
num_processes = 12
|
||||
processes = []
|
||||
args=[0]*num_processes
|
||||
|
||||
childPipes = []
|
||||
parentPipes = []
|
||||
|
||||
for pr in range(num_processes):
|
||||
parentPipe, childPipe = Pipe()
|
||||
parentPipes.append(parentPipe)
|
||||
childPipes.append(childPipe)
|
||||
|
||||
for rank in range(num_processes):
|
||||
p = mp.Process(target=ExploreWorker, args=(rank, num_processes, childPipes[rank], args))
|
||||
p.start()
|
||||
processes.append(p)
|
||||
|
||||
|
||||
for parentPipe in parentPipes:
|
||||
parentPipe.send([_RESET, "blaat"])
|
||||
|
||||
positive_rewards = [0]*num_processes
|
||||
for k in range(num_processes):
|
||||
#print("reset msg=",parentPipes[k].recv()[0])
|
||||
msg = parentPipes[k].recv()[0]
|
||||
|
||||
for parentPipe in parentPipes:
|
||||
parentPipe.send([_EXPLORE, "blaat"])
|
||||
|
||||
positive_rewards = [0]*num_processes
|
||||
for k in range(num_processes):
|
||||
positive_rewards[k] = parentPipes[k].recv()[0]
|
||||
#print("positive_rewards=",positive_rewards[k])
|
||||
|
||||
|
||||
for parentPipe in parentPipes:
|
||||
parentPipe.send([_EXPLORE, "blaat"])
|
||||
|
||||
positive_rewards = [0]*num_processes
|
||||
for k in range(num_processes):
|
||||
positive_rewards[k] = parentPipes[k].recv()[0]
|
||||
#print("positive_rewards=",positive_rewards[k])
|
||||
msg = positive_rewards[k]
|
||||
|
||||
for parentPipe in parentPipes:
|
||||
parentPipe.send([_EXPLORE, "blaat"])
|
||||
|
||||
positive_rewards = [0]*num_processes
|
||||
for k in range(num_processes):
|
||||
positive_rewards[k] = parentPipes[k].recv()[0]
|
||||
#print("positive_rewards=",positive_rewards[k])
|
||||
|
||||
|
||||
for parentPipe in parentPipes:
|
||||
parentPipe.send([_CLOSE, "pay2"])
|
||||
|
||||
for p in processes:
|
||||
p.join()
|
||||
|
||||
#now we merge the separate json files into a single one
|
||||
fnameout = 'batchsim.json'
|
||||
count = 0
|
||||
outfile = open(fnameout, "w+")
|
||||
outfile.writelines(["{\"traceEvents\":[\n"])
|
||||
numFiles = num_processes
|
||||
for num in range(numFiles):
|
||||
print("num=",num)
|
||||
fname = 'batchsim%d_0.json' % (num)
|
||||
with open(fname) as infile:
|
||||
for line in infile:
|
||||
if "pid" in line:
|
||||
line = line.replace('\"pid\":1', '\"pid\":'+str(num))
|
||||
if num < (numFiles-1) and not "{}}," in line:
|
||||
line = line.replace('{}}', '{}},')
|
||||
print("line[",count,"]=",line)
|
||||
outfile.write(line)
|
||||
count += 1
|
||||
print ("count=",count)
|
||||
outfile.writelines(["],\n"])
|
||||
outfile.writelines(["\"displayTimeUnit\": \"ns\"}\n"])
|
||||
outfile.close()
|
||||
21
examples/pybullet/gym/pybullet_envs/examples/loadpanda.py
Normal file
21
examples/pybullet/gym/pybullet_envs/examples/loadpanda.py
Normal file
@@ -0,0 +1,21 @@
|
||||
import pybullet as p
|
||||
import pybullet_data as pd
|
||||
import math
|
||||
import time
|
||||
import numpy as np
|
||||
import panda_sim
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_Y_AXIS_UP,1)
|
||||
p.setAdditionalSearchPath(pd.getDataPath())
|
||||
|
||||
timeStep=1./60.
|
||||
p.setTimeStep(timeStep)
|
||||
p.setGravity(0,-9.8,0)
|
||||
|
||||
panda = panda_sim.PandaSim(p,[0,0,0])
|
||||
while (1):
|
||||
panda.step()
|
||||
p.stepSimulation()
|
||||
time.sleep(timeStep)
|
||||
|
||||
65
examples/pybullet/gym/pybullet_envs/examples/panda_sim.py
Normal file
65
examples/pybullet/gym/pybullet_envs/examples/panda_sim.py
Normal file
@@ -0,0 +1,65 @@
|
||||
import time
|
||||
import numpy as np
|
||||
import math
|
||||
|
||||
useNullSpace = 1
|
||||
ikSolver = 0
|
||||
pandaEndEffectorIndex = 11 #8
|
||||
pandaNumDofs = 7
|
||||
|
||||
ll = [-7]*pandaNumDofs
|
||||
#upper limits for null space (todo: set them to proper range)
|
||||
ul = [7]*pandaNumDofs
|
||||
#joint ranges for null space (todo: set them to proper range)
|
||||
jr = [7]*pandaNumDofs
|
||||
#restposes for null space
|
||||
jointPositions=[0.98, 0.458, 0.31, -2.24, -0.30, 2.66, 2.32, 0.02, 0.02]
|
||||
rp = jointPositions
|
||||
|
||||
class PandaSim(object):
|
||||
def __init__(self, bullet_client, offset):
|
||||
self.bullet_client = bullet_client
|
||||
self.offset = np.array(offset)
|
||||
|
||||
#print("offset=",offset)
|
||||
flags = self.bullet_client.URDF_ENABLE_CACHED_GRAPHICS_SHAPES
|
||||
legos=[]
|
||||
self.bullet_client.loadURDF("tray/traybox.urdf", [0+offset[0], 0+offset[1], -0.6+offset[2]], [-0.5, -0.5, -0.5, 0.5], flags=flags)
|
||||
legos.append(self.bullet_client.loadURDF("lego/lego.urdf",np.array([0.1, 0.3, -0.5])+self.offset, flags=flags))
|
||||
legos.append(self.bullet_client.loadURDF("lego/lego.urdf",np.array([-0.1, 0.3, -0.5])+self.offset, flags=flags))
|
||||
legos.append(self.bullet_client.loadURDF("lego/lego.urdf",np.array([0.1, 0.3, -0.7])+self.offset, flags=flags))
|
||||
sphereId = self.bullet_client.loadURDF("sphere_small.urdf",np.array( [0, 0.3, -0.6])+self.offset, flags=flags)
|
||||
self.bullet_client.loadURDF("sphere_small.urdf",np.array( [0, 0.3, -0.5])+self.offset, flags=flags)
|
||||
self.bullet_client.loadURDF("sphere_small.urdf",np.array( [0, 0.3, -0.7])+self.offset, flags=flags)
|
||||
orn=[-0.707107, 0.0, 0.0, 0.707107]#p.getQuaternionFromEuler([-math.pi/2,math.pi/2,0])
|
||||
eul = self.bullet_client.getEulerFromQuaternion([-0.5, -0.5, -0.5, 0.5])
|
||||
self.panda = self.bullet_client.loadURDF("franka_panda/panda.urdf", np.array([0,0,0])+self.offset, orn, useFixedBase=True, flags=flags)
|
||||
index = 0
|
||||
for j in range(self.bullet_client.getNumJoints(self.panda)):
|
||||
self.bullet_client.changeDynamics(self.panda, j, linearDamping=0, angularDamping=0)
|
||||
info = self.bullet_client.getJointInfo(self.panda, j)
|
||||
|
||||
jointName = info[1]
|
||||
jointType = info[2]
|
||||
if (jointType == self.bullet_client.JOINT_PRISMATIC):
|
||||
|
||||
self.bullet_client.resetJointState(self.panda, j, jointPositions[index])
|
||||
index=index+1
|
||||
if (jointType == self.bullet_client.JOINT_REVOLUTE):
|
||||
self.bullet_client.resetJointState(self.panda, j, jointPositions[index])
|
||||
index=index+1
|
||||
self.t = 0.
|
||||
def reset(self):
|
||||
pass
|
||||
|
||||
def step(self):
|
||||
t = self.t
|
||||
self.t += 1./60.
|
||||
pos = [self.offset[0]+0.2 * math.sin(1.5 * t), self.offset[1]+0.044, self.offset[2]+-0.6 + 0.1 * math.cos(1.5 * t)]
|
||||
orn = self.bullet_client.getQuaternionFromEuler([math.pi/2.,0.,0.])
|
||||
jointPoses = self.bullet_client.calculateInverseKinematics(self.panda,pandaEndEffectorIndex, pos, orn, ll, ul,
|
||||
jr, rp, maxNumIterations=5)
|
||||
for i in range(pandaNumDofs):
|
||||
self.bullet_client.setJointMotorControl2(self.panda, i, self.bullet_client.POSITION_CONTROL, jointPoses[i],force=5 * 240.)
|
||||
pass
|
||||
|
||||
15
examples/pybullet/gym/pybullet_envs/examples/xarm.py
Normal file
15
examples/pybullet/gym/pybullet_envs/examples/xarm.py
Normal file
@@ -0,0 +1,15 @@
|
||||
import pybullet as p
|
||||
import pybullet_data as pd
|
||||
import time
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pd.getDataPath())
|
||||
|
||||
|
||||
useFixedBase = True
|
||||
flags = p.URDF_INITIALIZE_SAT_FEATURES#0#p.URDF_USE_SELF_COLLISION
|
||||
xarm = p.loadURDF("xarm/xarm6_with_gripper.urdf", flags = flags, useFixedBase=useFixedBase)
|
||||
|
||||
while (1):
|
||||
p.stepSimulation()
|
||||
time.sleep(1./240.)
|
||||
|
||||
Reference in New Issue
Block a user