move pybullet.connect into the Gym environment.
If you like to enable rendering, call the env.render(mode="human") before calling the first env.reset
This commit is contained in:
@@ -1,12 +1,15 @@
|
||||
from .scene_stadium import SinglePlayerStadiumScene
|
||||
from .env_bases import MJCFBaseBulletEnv
|
||||
import numpy as np
|
||||
import pybullet as p
|
||||
from robot_locomotors import Hopper, Walker2D, HalfCheetah, Ant, Humanoid
|
||||
|
||||
|
||||
class WalkerBaseBulletEnv(MJCFBaseBulletEnv):
|
||||
def __init__(self, robot):
|
||||
MJCFBaseBulletEnv.__init__(self, robot)
|
||||
def __init__(self, robot, render=False):
|
||||
print("WalkerBase::__init__")
|
||||
MJCFBaseBulletEnv.__init__(self, robot, render)
|
||||
|
||||
self.camera_x = 0
|
||||
self.walk_target_x = 1e3 # kilometer away
|
||||
self.walk_target_y = 0
|
||||
@@ -16,11 +19,15 @@ class WalkerBaseBulletEnv(MJCFBaseBulletEnv):
|
||||
return self.stadium_scene
|
||||
|
||||
def _reset(self):
|
||||
|
||||
r = MJCFBaseBulletEnv._reset(self)
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
|
||||
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.robot.addToScene(
|
||||
self.stadium_scene.ground_plane_mjcf)
|
||||
self.ground_ids = set([(self.parts[f].bodies[self.parts[f].bodyIndex], self.parts[f].bodyPartIndex) for f in
|
||||
self.foot_ground_object_names])
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||
return r
|
||||
|
||||
def move_robot(self, init_x, init_y, init_z):
|
||||
|
||||
Reference in New Issue
Block a user