enable planar reflection in MinitaurGymEnv
enable follow cam in other Gym locomotion environments add testing assets for multi-material obj files -> sdf conversion. Also use ER_NO_SEGMENTATION_MASK flag for TinyRenderer/EGL plugin renderer
This commit is contained in:
@@ -111,6 +111,16 @@ class MJCFBaseBulletEnv(gym.Env):
|
||||
# backwards compatibility for gym >= v0.9.x
|
||||
# for extension of this class.
|
||||
def step(self, *args, **kwargs):
|
||||
if self.isRender:
|
||||
base_pos=[0,0,0]
|
||||
if (hasattr(self,'robot')):
|
||||
if (hasattr(self.robot,'body_xyz')):
|
||||
base_pos = self.robot.body_xyz
|
||||
# Keep the previous orientation of the camera set by the user.
|
||||
#[yaw, pitch, dist] = self._p.getDebugVisualizerCamera()[8:11]
|
||||
self._p.resetDebugVisualizerCamera(3,0,0, base_pos)
|
||||
|
||||
|
||||
return self._step(*args, **kwargs)
|
||||
|
||||
if parse_version(gym.__version__)>=parse_version('0.9.6'):
|
||||
|
||||
@@ -271,7 +271,7 @@ class MinitaurGymEnv(gym.Env):
|
||||
"%s/plane.urdf" % self._urdf_root)
|
||||
if (self._reflection):
|
||||
self._pybullet_client.changeVisualShape(self._ground_id,-1,rgbaColor=[1,1,1,0.8])
|
||||
#self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION,1)
|
||||
self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION,self._ground_id)
|
||||
self._pybullet_client.setGravity(0, 0, -10)
|
||||
acc_motor = self._accurate_motor_model_enabled
|
||||
motor_protect = self._motor_overheat_protection
|
||||
|
||||
Reference in New Issue
Block a user