enable planar reflection in minitaur_gym_env.py and locomotion scenes

This commit is contained in:
erwincoumans
2018-04-11 08:50:29 -07:00
parent 1f756cfb8d
commit c2869e0a3c
5 changed files with 40 additions and 1053 deletions

View File

@@ -177,7 +177,9 @@ class MinitaurBulletEnv(gym.Env):
self._pybullet_client.setPhysicsEngineParameter(
numSolverIterations=int(self._num_bullet_solver_iterations))
self._pybullet_client.setTimeStep(self._time_step)
self._pybullet_client.loadURDF("%s/plane.urdf" % self._urdf_root)
plane = self._pybullet_client.loadURDF("%s/plane.urdf" % self._urdf_root)
self._pybullet_client.changeVisualShape(plane,-1,rgbaColor=[1,1,1,0.9])
self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION,0)
self._pybullet_client.setGravity(0, 0, -10)
acc_motor = self._accurate_motor_model_enabled
motor_protect = self._motor_overheat_protection
@@ -252,8 +254,16 @@ class MinitaurBulletEnv(gym.Env):
if time_to_sleep > 0:
time.sleep(time_to_sleep)
base_pos = self.minitaur.GetBasePosition()
camInfo = self._pybullet_client.getDebugVisualizerCamera()
curTargetPos = camInfo[11]
distance=camInfo[10]
yaw = camInfo[8]
pitch=camInfo[9]
targetPos = [0.95*curTargetPos[0]+0.05*base_pos[0],0.95*curTargetPos[1]+0.05*base_pos[1],curTargetPos[2]]
self._pybullet_client.resetDebugVisualizerCamera(
self._cam_dist, self._cam_yaw, self._cam_pitch, base_pos)
distance, yaw, pitch, base_pos)
action = self._transform_action_to_motor_command(action)
for _ in range(self._action_repeat):
self.minitaur.ApplyAction(action)