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

@@ -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()