pybullet vr_kuka_setup.py: add a gear joint, to keep the gripper centered,
vr_kuka_control.py: control all joints, use analogue button to close gripper remove some debug warnings/prints pybullet, avoid crash in changeUserConstraint if not passing a [list] allow some gym environments (pybullet_pendulum and locomotors) to re-use an existing physics client connection.
This commit is contained in:
@@ -18,6 +18,7 @@ class MJCFBaseBulletEnv(gym.Env):
|
||||
def __init__(self, robot, render=False):
|
||||
self.scene = None
|
||||
self.physicsClientId=-1
|
||||
self.ownsPhysicsClient = 0
|
||||
self.camera = Camera()
|
||||
self.isRender = render
|
||||
self.robot = robot
|
||||
@@ -39,17 +40,24 @@ class MJCFBaseBulletEnv(gym.Env):
|
||||
|
||||
def _reset(self):
|
||||
if (self.physicsClientId<0):
|
||||
self.physicsClientId = p.connect(p.SHARED_MEMORY)
|
||||
if (self.physicsClientId<0):
|
||||
if (self.isRender):
|
||||
self.physicsClientId = p.connect(p.GUI)
|
||||
else:
|
||||
self.physicsClientId = p.connect(p.DIRECT)
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
|
||||
conInfo = p.getConnectionInfo()
|
||||
if (conInfo['isConnected']):
|
||||
self.ownsPhysicsClient = False
|
||||
|
||||
self.physicsClientId = 0
|
||||
else:
|
||||
self.ownsPhysicsClient = True
|
||||
self.physicsClientId = p.connect(p.SHARED_MEMORY)
|
||||
if (self.physicsClientId<0):
|
||||
if (self.isRender):
|
||||
self.physicsClientId = p.connect(p.GUI)
|
||||
else:
|
||||
self.physicsClientId = p.connect(p.DIRECT)
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
|
||||
|
||||
if self.scene is None:
|
||||
self.scene = self.create_single_player_scene()
|
||||
if not self.scene.multiplayer:
|
||||
if not self.scene.multiplayer and self.ownsPhysicsClient:
|
||||
self.scene.episode_restart()
|
||||
|
||||
self.robot.scene = self.scene
|
||||
@@ -93,9 +101,10 @@ class MJCFBaseBulletEnv(gym.Env):
|
||||
return rgb_array
|
||||
|
||||
def _close(self):
|
||||
if (self.physicsClientId>=0):
|
||||
p.disconnect(self.physicsClientId)
|
||||
self.physicsClientId = -1
|
||||
if (self.ownsPhysicsClient):
|
||||
if (self.physicsClientId>=0):
|
||||
p.disconnect(self.physicsClientId)
|
||||
self.physicsClientId = -1
|
||||
|
||||
def HUD(self, state, a, done):
|
||||
pass
|
||||
|
||||
@@ -17,6 +17,7 @@ class MJCFBasedRobot:
|
||||
|
||||
def __init__(self, model_xml, robot_name, action_dim, obs_dim):
|
||||
self.parts = None
|
||||
self.objects = []
|
||||
self.jdict = None
|
||||
self.ordered_joints = None
|
||||
self.robot_body = None
|
||||
@@ -85,13 +86,15 @@ class MJCFBasedRobot:
|
||||
|
||||
def reset(self):
|
||||
self.ordered_joints = []
|
||||
|
||||
for ob in self.objects:
|
||||
p.removeBody(ob)
|
||||
|
||||
if self.self_collision:
|
||||
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(
|
||||
p.loadMJCF(os.path.join(pybullet_data.getDataPath(),"mjcf", self.model_xml), flags=p.URDF_USE_SELF_COLLISION+p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS))
|
||||
self.objects = p.loadMJCF(os.path.join(pybullet_data.getDataPath(),"mjcf", self.model_xml), flags=p.URDF_USE_SELF_COLLISION+p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
|
||||
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(self.objects )
|
||||
else:
|
||||
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(
|
||||
p.loadMJCF(os.path.join(pybullet_data.getDataPath(),"mjcf", self.model_xml)))
|
||||
self.objects = p.loadMJCF(os.path.join(pybullet_data.getDataPath(),"mjcf", self.model_xml))
|
||||
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(self.objects)
|
||||
|
||||
self.robot_specific_reset()
|
||||
|
||||
|
||||
@@ -62,7 +62,7 @@ class World:
|
||||
self.clean_everything()
|
||||
|
||||
def clean_everything(self):
|
||||
p.resetSimulation()
|
||||
#p.resetSimulation()
|
||||
p.setGravity(0, 0, -self.gravity)
|
||||
p.setDefaultContactERP(0.9)
|
||||
p.setPhysicsEngineParameter(fixedTimeStep=self.timestep*self.frame_skip, numSolverIterations=5, numSubSteps=self.frame_skip)
|
||||
|
||||
Reference in New Issue
Block a user