Clarify in naming that the environment uses MJCF xml files with Bullet, it doesn't use MuJoCo.

This commit is contained in:
Erwin Coumans
2017-08-23 15:03:57 -07:00
parent a9fb0033a4
commit 8866840712
6 changed files with 20 additions and 20 deletions

View File

@@ -3,7 +3,7 @@ import numpy as np
import pybullet as p import pybullet as p
class MujocoXmlBaseBulletEnv(gym.Env): class MJCFBaseBulletEnv(gym.Env):
""" """
Base class for MuJoCo .xml environments in a Scene. Base class for MuJoCo .xml environments in a Scene.
These environments create single-player scenes and behave like normal Gym environments, if These environments create single-player scenes and behave like normal Gym environments, if

View File

@@ -1,12 +1,12 @@
from .scene_stadium import SinglePlayerStadiumScene from .scene_stadium import SinglePlayerStadiumScene
from .env_bases import MujocoXmlBaseBulletEnv from .env_bases import MJCFBaseBulletEnv
import numpy as np import numpy as np
from robot_locomotors import Hopper, Walker2D, HalfCheetah, Ant, Humanoid from robot_locomotors import Hopper, Walker2D, HalfCheetah, Ant, Humanoid
class WalkerBaseBulletEnv(MujocoXmlBaseBulletEnv): class WalkerBaseBulletEnv(MJCFBaseBulletEnv):
def __init__(self, robot): def __init__(self, robot):
MujocoXmlBaseBulletEnv.__init__(self, robot) MJCFBaseBulletEnv.__init__(self, robot)
self.camera_x = 0 self.camera_x = 0
self.walk_target_x = 1e3 # kilometer away self.walk_target_x = 1e3 # kilometer away
self.walk_target_y = 0 self.walk_target_y = 0
@@ -16,7 +16,7 @@ class WalkerBaseBulletEnv(MujocoXmlBaseBulletEnv):
return self.stadium_scene return self.stadium_scene
def _reset(self): def _reset(self):
r = MujocoXmlBaseBulletEnv._reset(self) r = MJCFBaseBulletEnv._reset(self)
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.robot.addToScene( self.parts, self.jdict, self.ordered_joints, self.robot_body = self.robot.addToScene(
self.stadium_scene.ground_plane_mjcf) 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.ground_ids = set([(self.parts[f].bodies[self.parts[f].bodyIndex], self.parts[f].bodyPartIndex) for f in

View File

@@ -1,14 +1,14 @@
from .scene_abstract import SingleRobotEmptyScene from .scene_abstract import SingleRobotEmptyScene
from .env_bases import MujocoXmlBaseBulletEnv from .env_bases import MJCFBaseBulletEnv
from robot_pendula import InvertedPendulum, InvertedPendulumSwingup, InvertedDoublePendulum from robot_pendula import InvertedPendulum, InvertedPendulumSwingup, InvertedDoublePendulum
import gym, gym.spaces, gym.utils, gym.utils.seeding import gym, gym.spaces, gym.utils, gym.utils.seeding
import numpy as np import numpy as np
import os, sys import os, sys
class InvertedPendulumBulletEnv(MujocoXmlBaseBulletEnv): class InvertedPendulumBulletEnv(MJCFBaseBulletEnv):
def __init__(self): def __init__(self):
self.robot = InvertedPendulum() self.robot = InvertedPendulum()
MujocoXmlBaseBulletEnv.__init__(self, self.robot) MJCFBaseBulletEnv.__init__(self, self.robot)
def create_single_player_scene(self): def create_single_player_scene(self):
return SingleRobotEmptyScene(gravity=9.8, timestep=0.0165, frame_skip=1) return SingleRobotEmptyScene(gravity=9.8, timestep=0.0165, frame_skip=1)
@@ -34,12 +34,12 @@ class InvertedPendulumBulletEnv(MujocoXmlBaseBulletEnv):
class InvertedPendulumSwingupBulletEnv(InvertedPendulumBulletEnv): class InvertedPendulumSwingupBulletEnv(InvertedPendulumBulletEnv):
def __init__(self): def __init__(self):
self.robot = InvertedPendulumSwingup() self.robot = InvertedPendulumSwingup()
MujocoXmlBaseBulletEnv.__init__(self, self.robot) MJCFBaseBulletEnv.__init__(self, self.robot)
class InvertedDoublePendulumBulletEnv(MujocoXmlBaseBulletEnv): class InvertedDoublePendulumBulletEnv(MJCFBaseBulletEnv):
def __init__(self): def __init__(self):
self.robot = InvertedDoublePendulum() self.robot = InvertedDoublePendulum()
MujocoXmlBaseBulletEnv.__init__(self, self.robot) MJCFBaseBulletEnv.__init__(self, self.robot)
def create_single_player_scene(self): def create_single_player_scene(self):
return SingleRobotEmptyScene(gravity=9.8, timestep=0.0165, frame_skip=1) return SingleRobotEmptyScene(gravity=9.8, timestep=0.0165, frame_skip=1)

View File

@@ -4,7 +4,7 @@ import numpy as np
import os import os
class MujocoXmlBasedRobot: class MJCFBasedRobot:
""" """
Base class for mujoco .xml based agents. Base class for mujoco .xml based agents.
""" """

View File

@@ -1,10 +1,10 @@
from robot_bases import MujocoXmlBasedRobot from robot_bases import MJCFBasedRobot
import numpy as np import numpy as np
class WalkerBase(MujocoXmlBasedRobot): class WalkerBase(MJCFBasedRobot):
def __init__(self, fn, robot_name, action_dim, obs_dim, power): def __init__(self, fn, robot_name, action_dim, obs_dim, power):
MujocoXmlBasedRobot.__init__(self, fn, robot_name, action_dim, obs_dim) MJCFBasedRobot.__init__(self, fn, robot_name, action_dim, obs_dim)
self.power = power self.power = power
self.camera_x = 0 self.camera_x = 0
self.walk_target_x = 1e3 # kilometer away self.walk_target_x = 1e3 # kilometer away

View File

@@ -1,11 +1,11 @@
from robot_bases import MujocoXmlBasedRobot from robot_bases import MJCFBasedRobot
import numpy as np import numpy as np
class InvertedPendulum(MujocoXmlBasedRobot): class InvertedPendulum(MJCFBasedRobot):
swingup = False swingup = False
force_gain = 12 # TODO: Try to find out why we need to scale the force force_gain = 12 # TODO: Try to find out why we need to scale the force
def __init__(self): def __init__(self):
MujocoXmlBasedRobot.__init__(self, 'inverted_pendulum.xml', 'cart', action_dim=1, obs_dim=5) MJCFBasedRobot.__init__(self, 'inverted_pendulum.xml', 'cart', action_dim=1, obs_dim=5)
def robot_specific_reset(self): def robot_specific_reset(self):
self.pole = self.parts["pole"] self.pole = self.parts["pole"]
@@ -53,9 +53,9 @@ class InvertedPendulumSwingup(InvertedPendulum):
force_gain = 2.2 # TODO: Try to find out why we need to scale the force force_gain = 2.2 # TODO: Try to find out why we need to scale the force
class InvertedDoublePendulum(MujocoXmlBasedRobot): class InvertedDoublePendulum(MJCFBasedRobot):
def __init__(self): def __init__(self):
MujocoXmlBasedRobot.__init__(self, 'inverted_double_pendulum.xml', 'cart', action_dim=1, obs_dim=9) MJCFBasedRobot.__init__(self, 'inverted_double_pendulum.xml', 'cart', action_dim=1, obs_dim=9)
def robot_specific_reset(self): def robot_specific_reset(self):
self.pole2 = self.parts["pole2"] self.pole2 = self.parts["pole2"]