pybullet a bit more refactoring, moving around files.

pybullet: move data to pybullet_data package, with getDataPath() method
This commit is contained in:
Erwin Coumans
2017-08-27 18:08:46 -07:00
parent 97cb6df00c
commit 659e869b86
185 changed files with 149 additions and 68 deletions

View File

@@ -22,8 +22,5 @@ class BulletClient(object):
"""Inject the client id into Bullet functions."""
attribute = getattr(pybullet, name)
if inspect.isbuiltin(attribute):
if name not in ["invertTransform", "computeViewMatrix","multiplyTransforms",
"getMatrixFromQuaternion"]: # A temporary hack for now.
attribute = functools.partial(attribute, physicsClientId=self._client)
return attribute

View File

@@ -2,7 +2,11 @@
Classic cart-pole system implemented by Rich Sutton et al.
Copied from https://webdocs.cs.ualberta.ca/~sutton/book/code/pole.c
"""
import os
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
print ("current_dir=" + currentdir)
os.sys.path.insert(0,currentdir)
import logging
import math
import gym
@@ -12,6 +16,7 @@ import numpy as np
import time
import subprocess
import pybullet as p
import pybullet_data
logger = logging.getLogger(__name__)
@@ -76,7 +81,7 @@ class CartPoleBulletEnv(gym.Env):
def _reset(self):
# print("-----------reset simulation---------------")
p.resetSimulation()
self.cartpole = p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","cartpole.urdf"),[0,0,0])
self.cartpole = p.loadURDF(os.path.join(pybullet_data.getDataPath(),"cartpole.urdf"),[0,0,0])
self.timeStep = 0.01
p.setJointMotorControl2(self.cartpole, 1, p.VELOCITY_CONTROL, force=0)
p.setGravity(0,0, -10)

View File

@@ -1,12 +1,18 @@
import os
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
print ("current_dir=" + currentdir)
os.sys.path.insert(0,currentdir)
import pybullet as p
import numpy as np
import copy
import math
import pybullet_data
class Kuka:
def __init__(self, urdfRootPath='', timeStep=0.01):
def __init__(self, urdfRootPath=pybullet_data.getDataPath(), timeStep=0.01):
self.urdfRootPath = urdfRootPath
self.timeStep = timeStep
@@ -32,7 +38,7 @@ class Kuka:
self.reset()
def reset(self):
objects = p.loadSDF(os.path.join(os.path.dirname(__file__),"../data","kuka_iiwa/kuka_with_gripper2.sdf"))
objects = p.loadSDF(os.path.join(self.urdfRootPath,"kuka_iiwa/kuka_with_gripper2.sdf"))
self.kukaUid = objects[0]
#for i in range (p.getNumJoints(self.kukaUid)):
# print(p.getJointInfo(self.kukaUid,i))
@@ -43,7 +49,7 @@ class Kuka:
p.resetJointState(self.kukaUid,jointIndex,self.jointPositions[jointIndex])
p.setJointMotorControl2(self.kukaUid,jointIndex,p.POSITION_CONTROL,targetPosition=self.jointPositions[jointIndex],force=self.maxForce)
self.trayUid = p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","tray/tray.urdf"), 0.640000,0.075000,-0.190000,0.000000,0.000000,1.000000,0.000000)
self.trayUid = p.loadURDF(os.path.join(self.urdfRootPath,"tray/tray.urdf"), 0.640000,0.075000,-0.190000,0.000000,0.000000,1.000000,0.000000)
self.endEffectorPos = [0.537,0.0,0.5]
self.endEffectorAngle = 0

View File

@@ -1,4 +1,8 @@
import os
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
print ("current_dir=" + currentdir)
os.sys.path.insert(0,currentdir)
import math
import gym
from gym import spaces
@@ -8,6 +12,8 @@ import time
import pybullet as p
from . import kuka
import random
import pybullet_data
class KukaCamGymEnv(gym.Env):
metadata = {
@@ -16,7 +22,7 @@ class KukaCamGymEnv(gym.Env):
}
def __init__(self,
urdfRoot="",
urdfRoot=pybullet_data.getDataPath(),
actionRepeat=1,
isEnableSelfCollision=True,
renders=True):
@@ -55,15 +61,15 @@ class KukaCamGymEnv(gym.Env):
p.resetSimulation()
p.setPhysicsEngineParameter(numSolverIterations=150)
p.setTimeStep(self._timeStep)
p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","plane.urdf"),[0,0,-1])
p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"),[0,0,-1])
p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","table/table.urdf"), 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
p.loadURDF(os.path.join(self._urdfRoot,"table/table.urdf"), 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
xpos = 0.5 +0.05*random.random()
ypos = 0 +0.05*random.random()
ang = 3.1415925438*random.random()
orn = p.getQuaternionFromEuler([0,0,ang])
self.blockUid =p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","block.urdf"), xpos,ypos,-0.1,orn[0],orn[1],orn[2],orn[3])
self.blockUid =p.loadURDF(os.path.join(self._urdfRoot,"block.urdf"), xpos,ypos,-0.1,orn[0],orn[1],orn[2],orn[3])
p.setGravity(0,0,-10)
self._kuka = kuka.Kuka(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)

View File

@@ -1,4 +1,8 @@
import os
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
print ("current_dir=" + currentdir)
os.sys.path.insert(0,currentdir)
import math
import gym
from gym import spaces
@@ -8,6 +12,8 @@ import time
import pybullet as p
from . import kuka
import random
import pybullet_data
class KukaGymEnv(gym.Env):
metadata = {
@@ -16,7 +22,7 @@ class KukaGymEnv(gym.Env):
}
def __init__(self,
urdfRoot="",
urdfRoot=pybullet_data.getDataPath(),
actionRepeat=1,
isEnableSelfCollision=True,
renders=True):
@@ -53,15 +59,15 @@ class KukaGymEnv(gym.Env):
p.resetSimulation()
p.setPhysicsEngineParameter(numSolverIterations=150)
p.setTimeStep(self._timeStep)
p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","plane.urdf"),[0,0,-1])
p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"),[0,0,-1])
p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","table/table.urdf"), 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
p.loadURDF(os.path.join(self._urdfRoot,"table/table.urdf"), 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
xpos = 0.5 +0.05*random.random()
ypos = 0 +0.05*random.random()
ang = 3.1415925438*random.random()
orn = p.getQuaternionFromEuler([0,0,ang])
self.blockUid =p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","block.urdf"), xpos,ypos,-0.1,orn[0],orn[1],orn[2],orn[3])
self.blockUid =p.loadURDF(os.path.join(self._urdfRoot,"block.urdf"), xpos,ypos,-0.1,orn[0],orn[1],orn[2],orn[3])
p.setGravity(0,0,-10)
self._kuka = kuka.Kuka(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)

View File

@@ -70,7 +70,7 @@ class Minitaur(object):
kd_for_pd_controllers: kd value for the pd controllers of the motors.
"""
self.num_motors = 8
self.num_legs = self.num_motors / 2
self.num_legs = int(self.num_motors / 2)
self._pybullet_client = pybullet_client
self._urdf_root = urdf_root
self._self_collision_enabled = self_collision_enabled
@@ -114,7 +114,7 @@ class Minitaur(object):
def _BuildJointNameToIdDict(self):
num_joints = self._pybullet_client.getNumJoints(self.quadruped)
self._joint_name_to_id = {}
for i in xrange(num_joints):
for i in range(num_joints):
joint_info = self._pybullet_client.getJointInfo(self.quadruped, i)
self._joint_name_to_id[joint_info[1].decode("UTF-8")] = joint_info[0]
@@ -184,7 +184,7 @@ class Minitaur(object):
Args:
add_constraint: Whether to add a constraint at the joints of two feet.
"""
for i in xrange(self.num_legs):
for i in range(self.num_legs):
self._ResetPoseForLeg(i, add_constraint)
def _ResetPoseForLeg(self, leg_id, add_constraint):
@@ -368,7 +368,7 @@ class Minitaur(object):
actual_torque, observed_torque = self._motor_model.convert_to_torque(
motor_commands, q, qdot)
if self._motor_overheat_protection:
for i in xrange(self.num_motors):
for i in range(self.num_motors):
if abs(actual_torque[i]) > OVERHEAT_SHUTDOWN_TORQUE:
self._overheat_counter[i] += 1
else:
@@ -469,7 +469,7 @@ class Minitaur(object):
offset_for_singularity = 1.5
half_num_motors = self.num_motors / 2
quater_pi = math.pi / 4
for i in xrange(self.num_motors):
for i in range(self.num_motors):
action_idx = i // 2
forward_backward_component = (-scale_for_singularity * quater_pi * (
actions[action_idx + half_num_motors] + offset_for_singularity))

View File

@@ -1,6 +1,13 @@
"""This file implements the gym environment of minitaur.
"""
import os, 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)
import math
import time
import gym
@@ -11,6 +18,7 @@ import pybullet
from . import bullet_client
from . import minitaur
import os
import pybullet_data
NUM_SUBSTEPS = 5
NUM_MOTORS = 8
@@ -38,7 +46,7 @@ class MinitaurBulletEnv(gym.Env):
}
def __init__(self,
urdf_root=os.path.join(os.path.dirname(__file__),"../data"),
urdf_root=pybullet_data.getDataPath(),
action_repeat=1,
distance_weight=1.0,
energy_weight=0.005,
@@ -127,6 +135,7 @@ class MinitaurBulletEnv(gym.Env):
self._hard_reset = True
self._kd_for_pd_controllers = kd_for_pd_controllers
self._last_frame_time = 0.0
print("urdf_root=" + self._urdf_root)
self._env_randomizer = env_randomizer
# PD control needs smaller time step for stability.
if pd_control_enabled or accurate_motor_model_enabled:
@@ -160,7 +169,7 @@ class MinitaurBulletEnv(gym.Env):
if self._hard_reset:
self._pybullet_client.resetSimulation()
self._pybullet_client.setPhysicsEngineParameter(
numSolverIterations=self._num_bullet_solver_iterations)
numSolverIterations=int(self._num_bullet_solver_iterations))
self._pybullet_client.setTimeStep(self._time_step)
self._pybullet_client.loadURDF("%s/plane.urdf" % self._urdf_root)
self._pybullet_client.setGravity(0, 0, -10)
@@ -192,7 +201,7 @@ class MinitaurBulletEnv(gym.Env):
self._pybullet_client.resetDebugVisualizerCamera(
self._cam_dist, self._cam_yaw, self._cam_pitch, [0, 0, 0])
if not self._torque_control_enabled:
for _ in xrange(100):
for _ in range(100):
if self._pd_control_enabled or self._accurate_motor_model_enabled:
self.minitaur.ApplyAction([math.pi / 2] * 8)
self._pybullet_client.stepSimulation()
@@ -240,7 +249,7 @@ class MinitaurBulletEnv(gym.Env):
self._pybullet_client.resetDebugVisualizerCamera(
self._cam_dist, self._cam_yaw, self._cam_pitch, base_pos)
action = self._transform_action_to_motor_command(action)
for _ in xrange(self._action_repeat):
for _ in range(self._action_repeat):
self.minitaur.ApplyAction(action)
self._pybullet_client.stepSimulation()

View File

@@ -11,8 +11,8 @@ class Racecar:
self._p = bullet_client
self.reset()
def reset(self):
car = self._p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","racecar/racecar_differential.urdf"), [0,0,.2],useFixedBase=False)
def reset(self):
car = self._p.loadURDF(os.path.join(self.urdfRootPath,"racecar/racecar_differential.urdf"), [0,0,.2],useFixedBase=False)
self.racecarUniqueId = car
#for i in range (self._p.getNumJoints(car)):
# print (self._p.getJointInfo(car,i))

View File

@@ -1,4 +1,9 @@
import os
import os, 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)
import math
import gym
from gym import spaces
@@ -9,6 +14,7 @@ import pybullet
from . import racecar
import random
from . import bullet_client
import pybullet_data
class RacecarGymEnv(gym.Env):
metadata = {
@@ -17,7 +23,7 @@ class RacecarGymEnv(gym.Env):
}
def __init__(self,
urdfRoot="",
urdfRoot=pybullet_data.getDataPath(),
actionRepeat=50,
isEnableSelfCollision=True,
isDiscrete=False,
@@ -59,8 +65,8 @@ class RacecarGymEnv(gym.Env):
self._p.resetSimulation()
#p.setPhysicsEngineParameter(numSolverIterations=300)
self._p.setTimeStep(self._timeStep)
#self._p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","plane.urdf"))
stadiumobjects = self._p.loadSDF(os.path.join(os.path.dirname(__file__),"../data","stadium.sdf"))
#self._p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"))
stadiumobjects = self._p.loadSDF(os.path.join(self._urdfRoot,"stadium.sdf"))
#move the stadium objects slightly above 0
#for i in stadiumobjects:
# pos,orn = self._p.getBasePositionAndOrientation(i)
@@ -74,7 +80,7 @@ class RacecarGymEnv(gym.Env):
bally = dist * math.cos(ang)
ballz = 1
self._ballUniqueId = self._p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","sphere2.urdf"),[ballx,bally,ballz])
self._ballUniqueId = self._p.loadURDF(os.path.join(self._urdfRoot,"sphere2.urdf"),[ballx,bally,ballz])
self._p.setGravity(0,0,-10)
self._racecar = racecar.Racecar(self._p,urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
self._envStepCounter = 0

View File

@@ -1,4 +1,8 @@
import os
import os, 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)
import math
import gym
from gym import spaces
@@ -9,6 +13,7 @@ import pybullet
from . import bullet_client
from . import racecar
import random
import pybullet_data
class RacecarZEDGymEnv(gym.Env):
metadata = {
@@ -17,7 +22,7 @@ class RacecarZEDGymEnv(gym.Env):
}
def __init__(self,
urdfRoot="",
urdfRoot=pybullet_data.getDataPath(),
actionRepeat=10,
isEnableSelfCollision=True,
isDiscrete=True,
@@ -57,7 +62,7 @@ class RacecarZEDGymEnv(gym.Env):
#p.setPhysicsEngineParameter(numSolverIterations=300)
self._p.setTimeStep(self._timeStep)
#self._p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","plane.urdf"))
stadiumobjects = self._p.loadSDF(os.path.join(os.path.dirname(__file__),"../data","stadium.sdf"))
stadiumobjects = self._p.loadSDF(os.path.join(self._urdfRoot,"stadium.sdf"))
#move the stadium objects slightly above 0
for i in stadiumobjects:
pos,orn = self._p.getBasePositionAndOrientation(i)
@@ -71,7 +76,7 @@ class RacecarZEDGymEnv(gym.Env):
bally = dist * math.cos(ang)
ballz = 1
self._ballUniqueId = self._p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","sphere2red.urdf"),[ballx,bally,ballz])
self._ballUniqueId = self._p.loadURDF(os.path.join(self._urdfRoot,"sphere2red.urdf"),[ballx,bally,ballz])
self._p.setGravity(0,0,-10)
self._racecar = racecar.Racecar(self._p,urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
self._envStepCounter = 0

View File

@@ -5,21 +5,26 @@ import copy
import math
import time
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
print ("current_dir=" + currentdir)
os.sys.path.insert(0,currentdir)
import pybullet_data
class SimpleHumanoid:
def __init__(self, urdfRootPath='', timeStep=0.01):
def __init__(self, urdfRootPath=pybullet_data.getDataPath(), timeStep=0.01):
self.urdfRootPath = urdfRootPath
self.timeStep = timeStep
self.reset()
def reset(self):
self.initial_z = None
objs = p.loadMJCF(os.path.join(os.path.dirname(__file__),"../data","mjcf/humanoid_symmetric_no_ground.xml"),flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
objs = p.loadMJCF(os.path.join(self.urdfRootPath,"mjcf/humanoid_symmetric_no_ground.xml"),flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
self.human = objs[0]
self.jdict = {}
self.ordered_joints = []

View File

@@ -1,4 +1,9 @@
import os
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
print ("current_dir=" + currentdir)
os.sys.path.insert(0,currentdir)
import math
import gym
from gym import spaces
@@ -9,6 +14,10 @@ import pybullet as p
from . import simpleHumanoid
import random
import pybullet_data
class SimpleHumanoidGymEnv(gym.Env):
metadata = {
'render.modes': ['human', 'rgb_array'],
@@ -16,7 +25,7 @@ class SimpleHumanoidGymEnv(gym.Env):
}
def __init__(self,
urdfRoot="",
urdfRoot=pybullet_data.getDataPath(),
actionRepeat=50,
isEnableSelfCollision=True,
renders=True):
@@ -48,7 +57,7 @@ class SimpleHumanoidGymEnv(gym.Env):
p.resetSimulation()
#p.setPhysicsEngineParameter(numSolverIterations=300)
p.setTimeStep(self._timeStep)
p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","plane.urdf"))
p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"))
dist = 5 +2.*random.random()
ang = 2.*3.1415925438*random.random()