diff --git a/examples/pybullet/gym/pybullet_envs/gym_locomotion_envs.py b/examples/pybullet/gym/pybullet_envs/gym_locomotion_envs.py index d13290449..bc75f7bfd 100644 --- a/examples/pybullet/gym/pybullet_envs/gym_locomotion_envs.py +++ b/examples/pybullet/gym/pybullet_envs/gym_locomotion_envs.py @@ -15,7 +15,7 @@ class WalkerBaseBulletEnv(MJCFBaseBulletEnv): self.walk_target_y = 0 def create_single_player_scene(self): - self.stadium_scene = SinglePlayerStadiumScene(gravity=9.8, timestep=0.0165/4, frame_skip=4) + self.stadium_scene = SinglePlayerStadiumScene(gravity=9.8, timestep=0.0165, frame_skip=4) return self.stadium_scene def _reset(self): diff --git a/examples/pybullet/gym/pybullet_envs/robot_bases.py b/examples/pybullet/gym/pybullet_envs/robot_bases.py index 573bfbd89..165ba8a09 100644 --- a/examples/pybullet/gym/pybullet_envs/robot_bases.py +++ b/examples/pybullet/gym/pybullet_envs/robot_bases.py @@ -13,7 +13,7 @@ class MJCFBasedRobot: Base class for mujoco .xml based agents. """ - self_collision = False + self_collision = True def __init__(self, model_xml, robot_name, action_dim, obs_dim): self.parts = None @@ -87,7 +87,7 @@ class MJCFBasedRobot: if self.self_collision: self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene( - p.loadMJCF(os.path.join(pybullet_data.getDataPath(),"mjcf", self.model_xml), flags=p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)) + p.loadMJCF(os.path.join(pybullet_data.getDataPath(),"mjcf", self.model_xml), flags=p.URDF_USE_SELF_COLLISION+p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)) else: self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene( p.loadMJCF(os.path.join(pybullet_data.getDataPath(),"mjcf", self.model_xml))) diff --git a/examples/pybullet/gym/pybullet_envs/robot_locomotors.py b/examples/pybullet/gym/pybullet_envs/robot_locomotors.py index 51149080b..772dee5c6 100644 --- a/examples/pybullet/gym/pybullet_envs/robot_locomotors.py +++ b/examples/pybullet/gym/pybullet_envs/robot_locomotors.py @@ -114,7 +114,7 @@ class Ant(WalkerBase): foot_list = ['front_left_foot', 'front_right_foot', 'left_back_foot', 'right_back_foot'] def __init__(self): - WalkerBase.__init__(self, "ant.xml", "torso", action_dim=8, obs_dim=28, power=10.5) + WalkerBase.__init__(self, "ant.xml", "torso", action_dim=8, obs_dim=28, power=2.5) def alive_bonus(self, z, pitch): return +1 if z > 0.26 else -1 # 0.25 is central sphere rad, die if it scrapes the ground diff --git a/examples/pybullet/gym/pybullet_envs/scene_abstract.py b/examples/pybullet/gym/pybullet_envs/scene_abstract.py index 663401458..152427a25 100644 --- a/examples/pybullet/gym/pybullet_envs/scene_abstract.py +++ b/examples/pybullet/gym/pybullet_envs/scene_abstract.py @@ -68,7 +68,8 @@ class World: def clean_everything(self): p.resetSimulation() p.setGravity(0, 0, -self.gravity) - p.setPhysicsEngineParameter(fixedTimeStep=self.timestep, numSolverIterations=5, numSubSteps=2) + p.setDefaultContactERP(0.9) + p.setPhysicsEngineParameter(fixedTimeStep=self.timestep, numSolverIterations=5, numSubSteps=4) def step(self, frame_skip): p.stepSimulation() diff --git a/examples/pybullet/gym/pybullet_envs/scene_stadium.py b/examples/pybullet/gym/pybullet_envs/scene_stadium.py index 64f64e30d..023e6b13f 100644 --- a/examples/pybullet/gym/pybullet_envs/scene_stadium.py +++ b/examples/pybullet/gym/pybullet_envs/scene_stadium.py @@ -19,8 +19,7 @@ class StadiumScene(Scene): # stadium_pose = cpp_household.Pose() # if self.zero_at_running_strip_start_line: # stadium_pose.set_xyz(27, 21, 0) # see RUN_STARTLINE, RUN_RAD constants - filename = os.path.join(pybullet_data.getDataPath(),"stadium.sdf") - print(filename) + filename = os.path.join(pybullet_data.getDataPath(),"stadium_no_collision.sdf") self.stadium = p.loadSDF(filename) planeName = os.path.join(pybullet_data.getDataPath(),"mjcf/ground_plane.xml")