Humanoid Flagrun Harder, PyBullet version (request from Danijar)
Fix duplicate ground in all Roboschool converted scenes. Fix bug in all PyBullet-Roboschool converted Humanoid environments (action needs to be clipped to [-1,1] range)
This commit is contained in:
@@ -32,10 +32,10 @@
|
|||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
</model>
|
</model>
|
||||||
<model name='roboschool/models_outdoor/stadium/part1.obj'>
|
<model name='floor_obj'>
|
||||||
<static>1</static>
|
<static>1</static>
|
||||||
<pose frame=''>0 0 0 0 0 0</pose>
|
<pose frame=''>0 0 0 0 0 0</pose>
|
||||||
<link name='link_d1'>
|
<link name='floor'>
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass>0</mass>
|
<mass>0</mass>
|
||||||
<inertia>
|
<inertia>
|
||||||
|
|||||||
@@ -73,7 +73,7 @@ def demo_run():
|
|||||||
print("score=%0.2f in %i frames" % (score, frame))
|
print("score=%0.2f in %i frames" % (score, frame))
|
||||||
if still_open!=True: # not True in multiplayer or non-Roboschool environment
|
if still_open!=True: # not True in multiplayer or non-Roboschool environment
|
||||||
break
|
break
|
||||||
restart_delay = 123460*2 # 2 sec at 60 fps
|
restart_delay = 60*2 # 2 sec at 60 fps
|
||||||
restart_delay -= 1
|
restart_delay -= 1
|
||||||
if restart_delay==0: break
|
if restart_delay==0: break
|
||||||
|
|
||||||
|
|||||||
@@ -2,7 +2,7 @@ from .scene_stadium import SinglePlayerStadiumScene
|
|||||||
from .env_bases import MJCFBaseBulletEnv
|
from .env_bases import MJCFBaseBulletEnv
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import pybullet as p
|
import pybullet as p
|
||||||
from robot_locomotors import Hopper, Walker2D, HalfCheetah, Ant, Humanoid, HumanoidFlagrun
|
from robot_locomotors import Hopper, Walker2D, HalfCheetah, Ant, Humanoid, HumanoidFlagrun, HumanoidFlagrunHarder
|
||||||
|
|
||||||
|
|
||||||
class WalkerBaseBulletEnv(MJCFBaseBulletEnv):
|
class WalkerBaseBulletEnv(MJCFBaseBulletEnv):
|
||||||
@@ -160,10 +160,16 @@ class HumanoidFlagrunBulletEnv(HumanoidBulletEnv):
|
|||||||
s.zero_at_running_strip_start_line = False
|
s.zero_at_running_strip_start_line = False
|
||||||
return s
|
return s
|
||||||
|
|
||||||
class HumanoidFlagrunHarderBulletEnv(HumanoidFlagrunBulletEnv):
|
class HumanoidFlagrunHarderBulletEnv(HumanoidBulletEnv):
|
||||||
random_lean = True # can fall on start
|
random_lean = True # can fall on start
|
||||||
|
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
HumanoidFlagrunBulletEnv.__init__(self)
|
self.robot = HumanoidFlagrunHarder()
|
||||||
self.electricity_cost /= 4 # don't care that much about electricity, just stand up!
|
self.electricity_cost /= 4 # don't care that much about electricity, just stand up!
|
||||||
|
HumanoidBulletEnv.__init__(self, self.robot)
|
||||||
|
|
||||||
|
def create_single_player_scene(self):
|
||||||
|
s = HumanoidBulletEnv.create_single_player_scene(self)
|
||||||
|
s.zero_at_running_strip_start_line = False
|
||||||
|
return s
|
||||||
|
|
||||||
|
|||||||
@@ -245,6 +245,9 @@ class BodyPart:
|
|||||||
def current_orientation(self):
|
def current_orientation(self):
|
||||||
return self.get_pose()[3:]
|
return self.get_pose()[3:]
|
||||||
|
|
||||||
|
def get_orientation(self):
|
||||||
|
return self.current_orientation()
|
||||||
|
|
||||||
def reset_position(self, position):
|
def reset_position(self, position):
|
||||||
p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], position, self.get_orientation())
|
p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], position, self.get_orientation())
|
||||||
|
|
||||||
@@ -252,7 +255,7 @@ class BodyPart:
|
|||||||
p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], self.get_position(), orientation)
|
p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], self.get_position(), orientation)
|
||||||
|
|
||||||
def reset_velocity(self, linearVelocity=[0,0,0], angularVelocity =[0,0,0]):
|
def reset_velocity(self, linearVelocity=[0,0,0], angularVelocity =[0,0,0]):
|
||||||
p.resetBaseVelocity(linearVelocity, angularVelocity)
|
p.resetBaseVelocity(self.bodies[self.bodyIndex], linearVelocity, angularVelocity)
|
||||||
|
|
||||||
def reset_pose(self, position, orientation):
|
def reset_pose(self, position, orientation):
|
||||||
p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], position, orientation)
|
p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], position, orientation)
|
||||||
@@ -299,6 +302,10 @@ class Joint:
|
|||||||
x, _ = self.get_state()
|
x, _ = self.get_state()
|
||||||
return x
|
return x
|
||||||
|
|
||||||
|
def get_orientation(self):
|
||||||
|
_,r = self.get_state()
|
||||||
|
return r
|
||||||
|
|
||||||
def get_velocity(self):
|
def get_velocity(self):
|
||||||
_, vx = self.get_state()
|
_, vx = self.get_state()
|
||||||
return vx
|
return vx
|
||||||
|
|||||||
@@ -194,6 +194,7 @@ class Humanoid(WalkerBase):
|
|||||||
|
|
||||||
def get_cube(x, y, z):
|
def get_cube(x, y, z):
|
||||||
body = p.loadURDF(os.path.join(pybullet_data.getDataPath(),"cube_small.urdf"), x, y, z)
|
body = p.loadURDF(os.path.join(pybullet_data.getDataPath(),"cube_small.urdf"), x, y, z)
|
||||||
|
p.changeDynamics(body,-1, mass=1.2)#match Roboschool
|
||||||
part_name, _ = p.getBodyInfo(body, 0)
|
part_name, _ = p.getBodyInfo(body, 0)
|
||||||
part_name = part_name.decode("utf8")
|
part_name = part_name.decode("utf8")
|
||||||
bodies = [body]
|
bodies = [body]
|
||||||
@@ -244,10 +245,15 @@ class HumanoidFlagrun(Humanoid):
|
|||||||
|
|
||||||
class HumanoidFlagrunHarder(HumanoidFlagrun):
|
class HumanoidFlagrunHarder(HumanoidFlagrun):
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
HumanoidFlagrun.__init__()
|
HumanoidFlagrun.__init__(self)
|
||||||
|
self.flag = None
|
||||||
|
self.aggressive_cube = None
|
||||||
|
self.frame = 0
|
||||||
|
|
||||||
def robot_specific_reset(self):
|
def robot_specific_reset(self):
|
||||||
HumanoidFlagrun.robot_specific_reset(self)
|
HumanoidFlagrun.robot_specific_reset(self)
|
||||||
|
|
||||||
|
self.frame = 0
|
||||||
if (self.aggressive_cube):
|
if (self.aggressive_cube):
|
||||||
p.resetBasePositionAndOrientation(self.aggressive_cube.bodies[0],[-1.5,0,0.05],[0,0,0,1])
|
p.resetBasePositionAndOrientation(self.aggressive_cube.bodies[0],[-1.5,0,0.05],[0,0,0,1])
|
||||||
else:
|
else:
|
||||||
@@ -279,6 +285,7 @@ class HumanoidFlagrunHarder(HumanoidFlagrun):
|
|||||||
elif self.on_ground_frame_counter > 0:
|
elif self.on_ground_frame_counter > 0:
|
||||||
self.on_ground_frame_counter -= 1
|
self.on_ground_frame_counter -= 1
|
||||||
# End episode if the robot can't get up in 170 frames, to save computation and decorrelate observations.
|
# End episode if the robot can't get up in 170 frames, to save computation and decorrelate observations.
|
||||||
|
self.frame += 1
|
||||||
return self.potential_leak() if self.on_ground_frame_counter<170 else -1
|
return self.potential_leak() if self.on_ground_frame_counter<170 else -1
|
||||||
|
|
||||||
def potential_leak(self):
|
def potential_leak(self):
|
||||||
|
|||||||
@@ -25,12 +25,13 @@ class StadiumScene(Scene):
|
|||||||
# if self.zero_at_running_strip_start_line:
|
# if self.zero_at_running_strip_start_line:
|
||||||
# stadium_pose.set_xyz(27, 21, 0) # see RUN_STARTLINE, RUN_RAD constants
|
# stadium_pose.set_xyz(27, 21, 0) # see RUN_STARTLINE, RUN_RAD constants
|
||||||
filename = os.path.join(pybullet_data.getDataPath(),"stadium_no_collision.sdf")
|
filename = os.path.join(pybullet_data.getDataPath(),"stadium_no_collision.sdf")
|
||||||
self.stadium = p.loadSDF(filename)
|
self.ground_plane_mjcf = p.loadSDF(filename)
|
||||||
planeName = os.path.join(pybullet_data.getDataPath(),"mjcf/ground_plane.xml")
|
|
||||||
|
|
||||||
self.ground_plane_mjcf = p.loadMJCF(planeName, flags=p.URDF_USE_SELF_COLLISION|p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
|
|
||||||
for i in self.ground_plane_mjcf:
|
for i in self.ground_plane_mjcf:
|
||||||
p.changeVisualShape(i,-1,rgbaColor=[0,0,0,0])
|
p.changeDynamics(i,-1,lateralFriction=0.8, restitution=0.5)
|
||||||
|
for j in range(p.getNumJoints(i)):
|
||||||
|
p.changeDynamics(i,j,lateralFriction=0)
|
||||||
|
#despite the name (stadium_no_collision), it DID have collision, so don't add duplicate ground
|
||||||
|
|
||||||
class SinglePlayerStadiumScene(StadiumScene):
|
class SinglePlayerStadiumScene(StadiumScene):
|
||||||
"This scene created by environment, to work in a way as if there was no concept of scene visible to user."
|
"This scene created by environment, to work in a way as if there was no concept of scene visible to user."
|
||||||
|
|||||||
Reference in New Issue
Block a user