add yapf style and apply yapf to format all Python files
This recreates pull request #2192
This commit is contained in:
@@ -1,3 +1,2 @@
|
||||
from . import boxstack_pybullet_sim
|
||||
from . import pybullet_sim_gym_env
|
||||
|
||||
|
||||
@@ -14,10 +14,7 @@ class BoxStackPyBulletSim(object):
|
||||
|
||||
"""
|
||||
|
||||
def __init__(self,
|
||||
pybullet_client,
|
||||
urdf_root= pybullet_data.getDataPath(),
|
||||
time_step=0.01):
|
||||
def __init__(self, pybullet_client, urdf_root=pybullet_data.getDataPath(), time_step=0.01):
|
||||
"""Constructs an example simulation and reset it to the initial states.
|
||||
|
||||
Args:
|
||||
@@ -28,11 +25,10 @@ class BoxStackPyBulletSim(object):
|
||||
"""
|
||||
self._pybullet_client = pybullet_client
|
||||
self._urdf_root = urdf_root
|
||||
self.m_actions_taken_since_reset=0
|
||||
self.m_actions_taken_since_reset = 0
|
||||
self.time_step = time_step
|
||||
self.stateId = -1
|
||||
self.Reset(reload_urdf=True)
|
||||
|
||||
|
||||
def Reset(self, reload_urdf=False):
|
||||
"""Reset the minitaur to its initial states.
|
||||
@@ -41,58 +37,59 @@ class BoxStackPyBulletSim(object):
|
||||
reload_urdf: Whether to reload the urdf file. If not, Reset() just place
|
||||
the minitaur back to its starting position.
|
||||
"""
|
||||
self.m_actions_taken_since_reset=0
|
||||
xPosRange=0.025
|
||||
yPosRange=0.025
|
||||
self.m_actions_taken_since_reset = 0
|
||||
xPosRange = 0.025
|
||||
yPosRange = 0.025
|
||||
boxHalfExtents = 0.025
|
||||
|
||||
|
||||
if reload_urdf:
|
||||
camInfo = self._pybullet_client.getDebugVisualizerCamera()
|
||||
cameraDistance=camInfo[10]
|
||||
print("cameraYaw=",camInfo[8])
|
||||
print("cameraPitch=",camInfo[9])
|
||||
print("camtarget=",camInfo[11])
|
||||
print("projectionMatrix=",camInfo[3])
|
||||
self._pybullet_client.resetDebugVisualizerCamera(cameraDistance=0.3, cameraYaw=camInfo[8], cameraPitch=camInfo[9],cameraTargetPosition=camInfo[11])
|
||||
cameraDistance = camInfo[10]
|
||||
print("cameraYaw=", camInfo[8])
|
||||
print("cameraPitch=", camInfo[9])
|
||||
print("camtarget=", camInfo[11])
|
||||
print("projectionMatrix=", camInfo[3])
|
||||
self._pybullet_client.resetDebugVisualizerCamera(cameraDistance=0.3,
|
||||
cameraYaw=camInfo[8],
|
||||
cameraPitch=camInfo[9],
|
||||
cameraTargetPosition=camInfo[11])
|
||||
|
||||
plane = self._pybullet_client.loadURDF("plane.urdf")
|
||||
texUid = self._pybullet_client.loadTexture("checker_blue.png")
|
||||
self._pybullet_client.changeVisualShape(plane,-1, textureUniqueId = texUid)
|
||||
|
||||
|
||||
self._numObjects=4 #random number?
|
||||
|
||||
|
||||
self._cubes=[]
|
||||
|
||||
red=[0.97,0.25,0.25,1]
|
||||
green=[0.41,0.68,0.31,1]
|
||||
yellow=[0.92,0.73,0,1]
|
||||
blue=[0,0.55,0.81,1]
|
||||
colors=[red,green,yellow,blue]
|
||||
|
||||
for i in range (self._numObjects):
|
||||
pos=[0,0,boxHalfExtents + i*2*boxHalfExtents]
|
||||
orn = self._pybullet_client.getQuaternionFromEuler([0,0,0])
|
||||
orn=[0,0,0,1]
|
||||
cube = self._pybullet_client.loadURDF("cube_small.urdf",pos,orn)
|
||||
self._pybullet_client.changeVisualShape(cube,-1,rgbaColor=colors[i])
|
||||
self._cubes.append(cube)
|
||||
|
||||
self._pybullet_client.changeVisualShape(plane, -1, textureUniqueId=texUid)
|
||||
|
||||
self._numObjects = 4 #random number?
|
||||
|
||||
self._cubes = []
|
||||
|
||||
red = [0.97, 0.25, 0.25, 1]
|
||||
green = [0.41, 0.68, 0.31, 1]
|
||||
yellow = [0.92, 0.73, 0, 1]
|
||||
blue = [0, 0.55, 0.81, 1]
|
||||
colors = [red, green, yellow, blue]
|
||||
|
||||
for i in range(self._numObjects):
|
||||
pos = [0, 0, boxHalfExtents + i * 2 * boxHalfExtents]
|
||||
orn = self._pybullet_client.getQuaternionFromEuler([0, 0, 0])
|
||||
orn = [0, 0, 0, 1]
|
||||
cube = self._pybullet_client.loadURDF("cube_small.urdf", pos, orn)
|
||||
self._pybullet_client.changeVisualShape(cube, -1, rgbaColor=colors[i])
|
||||
self._cubes.append(cube)
|
||||
|
||||
self._pybullet_client.setGravity(0, 0, -10)
|
||||
self.stateId = self._pybullet_client.saveState()
|
||||
else:
|
||||
if (self.stateId>=0):
|
||||
if (self.stateId >= 0):
|
||||
self._pybullet_client.restoreState(self.stateId)
|
||||
index=0
|
||||
index = 0
|
||||
for i in self._cubes:
|
||||
posX = random.uniform(-xPosRange,xPosRange)
|
||||
posY = random.uniform(-yPosRange,yPosRange)
|
||||
yaw = random.uniform(-math.pi,math.pi)
|
||||
pos=[posX,posY,boxHalfExtents + index*2*boxHalfExtents]
|
||||
index+=1
|
||||
orn = self._pybullet_client.getQuaternionFromEuler([0,0,yaw])
|
||||
self._pybullet_client.resetBasePositionAndOrientation(i,pos,orn)
|
||||
posX = random.uniform(-xPosRange, xPosRange)
|
||||
posY = random.uniform(-yPosRange, yPosRange)
|
||||
yaw = random.uniform(-math.pi, math.pi)
|
||||
pos = [posX, posY, boxHalfExtents + index * 2 * boxHalfExtents]
|
||||
index += 1
|
||||
orn = self._pybullet_client.getQuaternionFromEuler([0, 0, yaw])
|
||||
self._pybullet_client.resetBasePositionAndOrientation(i, pos, orn)
|
||||
|
||||
def GetActionDimension(self):
|
||||
"""Get the length of the action list.
|
||||
@@ -100,7 +97,7 @@ class BoxStackPyBulletSim(object):
|
||||
Returns:
|
||||
The length of the action list.
|
||||
"""
|
||||
return 4#self.num_motors
|
||||
return 4 #self.num_motors
|
||||
|
||||
def GetObservationUpperBound(self):
|
||||
"""Get the upper bound of the observation.
|
||||
@@ -124,7 +121,7 @@ class BoxStackPyBulletSim(object):
|
||||
The length of the observation list.
|
||||
"""
|
||||
sz = len(self.GetObservation())
|
||||
print("sz=",sz)
|
||||
print("sz=", sz)
|
||||
return sz
|
||||
|
||||
def GetObservation(self):
|
||||
@@ -135,7 +132,7 @@ class BoxStackPyBulletSim(object):
|
||||
"""
|
||||
observation = []
|
||||
for i in self._cubes:
|
||||
pos,orn=self._pybullet_client.getBasePositionAndOrientation(i)
|
||||
pos, orn = self._pybullet_client.getBasePositionAndOrientation(i)
|
||||
observation.extend(list(pos))
|
||||
observation.extend(list(orn))
|
||||
return observation
|
||||
@@ -143,14 +140,14 @@ class BoxStackPyBulletSim(object):
|
||||
def ApplyAction(self, action):
|
||||
"""Set the desired action.
|
||||
"""
|
||||
self.m_actions_taken_since_reset+=1
|
||||
|
||||
self.m_actions_taken_since_reset += 1
|
||||
|
||||
def Termination(self):
|
||||
return self.m_actions_taken_since_reset>=200
|
||||
|
||||
def CreateSim(pybullet_client,urdf_root,time_step):
|
||||
return self.m_actions_taken_since_reset >= 200
|
||||
|
||||
|
||||
def CreateSim(pybullet_client, urdf_root, time_step):
|
||||
sim = BoxStackPyBulletSim(pybullet_client=pybullet_client,
|
||||
urdf_root=urdf_root,
|
||||
time_step=time_step)
|
||||
urdf_root=urdf_root,
|
||||
time_step=time_step)
|
||||
return sim
|
||||
|
||||
@@ -5,8 +5,7 @@
|
||||
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)
|
||||
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import math
|
||||
import time
|
||||
@@ -30,20 +29,18 @@ class PyBulletSimGymEnv(gym.Env):
|
||||
|
||||
|
||||
"""
|
||||
metadata = {
|
||||
"render.modes": ["human", "rgb_array"],
|
||||
"video.frames_per_second": 50
|
||||
}
|
||||
metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 50}
|
||||
|
||||
def __init__(self,pybullet_sim_factory = boxstack_pybullet_sim,
|
||||
def __init__(self,
|
||||
pybullet_sim_factory=boxstack_pybullet_sim,
|
||||
render=True,
|
||||
render_sleep=False,
|
||||
debug_visualization=True,
|
||||
hard_reset = False,
|
||||
hard_reset=False,
|
||||
render_width=240,
|
||||
render_height=240,
|
||||
action_repeat=1,
|
||||
time_step = 1./240.,
|
||||
time_step=1. / 240.,
|
||||
num_bullet_solver_iterations=50,
|
||||
urdf_root=pybullet_data.getDataPath()):
|
||||
"""Initialize the gym environment.
|
||||
@@ -55,45 +52,46 @@ class PyBulletSimGymEnv(gym.Env):
|
||||
self._time_step = time_step
|
||||
self._urdf_root = urdf_root
|
||||
self._observation = []
|
||||
self._action_repeat=action_repeat
|
||||
self._action_repeat = action_repeat
|
||||
self._num_bullet_solver_iterations = num_bullet_solver_iterations
|
||||
self._env_step_counter = 0
|
||||
self._is_render = render
|
||||
self._debug_visualization = debug_visualization
|
||||
self._render_sleep = render_sleep
|
||||
self._render_width=render_width
|
||||
self._render_height=render_height
|
||||
self._render_width = render_width
|
||||
self._render_height = render_height
|
||||
self._cam_dist = .3
|
||||
self._cam_yaw = 50
|
||||
self._cam_pitch = -35
|
||||
self._hard_reset = True
|
||||
self._last_frame_time = 0.0
|
||||
|
||||
optionstring='--width={} --height={}'.format(render_width,render_height)
|
||||
optionstring = '--width={} --height={}'.format(render_width, render_height)
|
||||
|
||||
print("urdf_root=" + self._urdf_root)
|
||||
|
||||
if self._is_render:
|
||||
self._pybullet_client = bullet_client.BulletClient(
|
||||
connection_mode=pybullet.GUI, options=optionstring)
|
||||
self._pybullet_client = bullet_client.BulletClient(connection_mode=pybullet.GUI,
|
||||
options=optionstring)
|
||||
else:
|
||||
self._pybullet_client = bullet_client.BulletClient()
|
||||
|
||||
if (debug_visualization==False):
|
||||
self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_GUI,enable=0)
|
||||
self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_RGB_BUFFER_PREVIEW,enable=0)
|
||||
self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_DEPTH_BUFFER_PREVIEW,enable=0)
|
||||
self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_SEGMENTATION_MARK_PREVIEW,enable=0)
|
||||
|
||||
if (debug_visualization == False):
|
||||
self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_GUI,
|
||||
enable=0)
|
||||
self._pybullet_client.configureDebugVisualizer(
|
||||
flag=self._pybullet_client.COV_ENABLE_RGB_BUFFER_PREVIEW, enable=0)
|
||||
self._pybullet_client.configureDebugVisualizer(
|
||||
flag=self._pybullet_client.COV_ENABLE_DEPTH_BUFFER_PREVIEW, enable=0)
|
||||
self._pybullet_client.configureDebugVisualizer(
|
||||
flag=self._pybullet_client.COV_ENABLE_SEGMENTATION_MARK_PREVIEW, enable=0)
|
||||
|
||||
self._pybullet_client.setAdditionalSearchPath(urdf_root)
|
||||
self.seed()
|
||||
self.reset()
|
||||
|
||||
observation_high = (
|
||||
self._example_sim.GetObservationUpperBound())
|
||||
observation_low = (
|
||||
self._example_sim.GetObservationLowerBound())
|
||||
observation_high = (self._example_sim.GetObservationUpperBound())
|
||||
observation_low = (self._example_sim.GetObservationLowerBound())
|
||||
|
||||
action_dim = self._example_sim.GetActionDimension()
|
||||
self._action_bound = 1
|
||||
@@ -104,7 +102,6 @@ class PyBulletSimGymEnv(gym.Env):
|
||||
self.viewer = None
|
||||
self._hard_reset = hard_reset # This assignment need to be after reset()
|
||||
|
||||
|
||||
def configure(self, args):
|
||||
self._args = args
|
||||
|
||||
@@ -163,7 +160,6 @@ class PyBulletSimGymEnv(gym.Env):
|
||||
#self._pybullet_client.resetDebugVisualizerCamera(
|
||||
# self._cam_dist, self._cam_yaw, self._cam_pitch, base_pos)
|
||||
|
||||
|
||||
for _ in range(self._action_repeat):
|
||||
self._example_sim.ApplyAction(action)
|
||||
self._pybullet_client.stepSimulation()
|
||||
@@ -176,7 +172,7 @@ class PyBulletSimGymEnv(gym.Env):
|
||||
def render(self, mode="rgb_array", close=False):
|
||||
if mode != "rgb_array":
|
||||
return np.array([])
|
||||
base_pos = [0,0,0]
|
||||
base_pos = [0, 0, 0]
|
||||
view_matrix = self._pybullet_client.computeViewMatrixFromYawPitchRoll(
|
||||
cameraTargetPosition=base_pos,
|
||||
distance=self._cam_dist,
|
||||
@@ -185,19 +181,24 @@ class PyBulletSimGymEnv(gym.Env):
|
||||
roll=0,
|
||||
upAxisIndex=2)
|
||||
proj_matrix = self._pybullet_client.computeProjectionMatrixFOV(
|
||||
fov=60, aspect=float(self._render_width)/self._render_width,
|
||||
nearVal=0.01, farVal=100.0)
|
||||
proj_matrix=[1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0, -0.02000020071864128, 0.0]
|
||||
fov=60, aspect=float(self._render_width) / self._render_width, nearVal=0.01, farVal=100.0)
|
||||
proj_matrix = [
|
||||
1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0,
|
||||
-0.02000020071864128, 0.0
|
||||
]
|
||||
(_, _, px, _, _) = self._pybullet_client.getCameraImage(
|
||||
width=self._render_width, height=self._render_height, viewMatrix=view_matrix,
|
||||
projectionMatrix=proj_matrix, renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)#ER_TINY_RENDERER)
|
||||
width=self._render_width,
|
||||
height=self._render_height,
|
||||
viewMatrix=view_matrix,
|
||||
projectionMatrix=proj_matrix,
|
||||
renderer=pybullet.ER_BULLET_HARDWARE_OPENGL) #ER_TINY_RENDERER)
|
||||
rgb_array = np.array(px, dtype=np.uint8)
|
||||
rgb_array = np.reshape(rgb_array, (self._render_height, self._render_width, 4))
|
||||
rgb_array = rgb_array[:, :, :3]
|
||||
return rgb_array
|
||||
|
||||
def _termination(self):
|
||||
terminate=self._example_sim.Termination()
|
||||
terminate = self._example_sim.Termination()
|
||||
return terminate
|
||||
|
||||
def _reward(self):
|
||||
|
||||
@@ -5,7 +5,7 @@ import os
|
||||
import 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)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import math
|
||||
import numpy as np
|
||||
@@ -16,18 +16,18 @@ import time
|
||||
from pybullet_envs.prediction import boxstack_pybullet_sim
|
||||
from gym.wrappers.monitoring import video_recorder
|
||||
|
||||
|
||||
def ResetPoseExample(steps):
|
||||
"""An example that the minitaur stands still using the reset pose."""
|
||||
|
||||
|
||||
environment = pybullet_sim_gym_env.PyBulletSimGymEnv(
|
||||
pybullet_sim_factory=boxstack_pybullet_sim,
|
||||
debug_visualization=False,
|
||||
render=True, action_repeat=30)
|
||||
|
||||
environment = pybullet_sim_gym_env.PyBulletSimGymEnv(pybullet_sim_factory=boxstack_pybullet_sim,
|
||||
debug_visualization=False,
|
||||
render=True,
|
||||
action_repeat=30)
|
||||
action = [math.pi / 2] * 8
|
||||
|
||||
vid = video_recorder.VideoRecorder(env=environment,path="vid.mp4")
|
||||
|
||||
|
||||
vid = video_recorder.VideoRecorder(env=environment, path="vid.mp4")
|
||||
|
||||
for _ in range(steps):
|
||||
print(_)
|
||||
startsim = time.time()
|
||||
@@ -37,24 +37,21 @@ def ResetPoseExample(steps):
|
||||
#environment.render(mode='rgb_array')
|
||||
vid.capture_frame()
|
||||
stoprender = time.time()
|
||||
print ("env.step " , (stopsim - startsim))
|
||||
print ("env.render " , (stoprender - startrender))
|
||||
print("env.step ", (stopsim - startsim))
|
||||
print("env.render ", (stoprender - startrender))
|
||||
if done:
|
||||
environment.reset()
|
||||
|
||||
|
||||
environment.reset()
|
||||
|
||||
|
||||
def main():
|
||||
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
|
||||
parser.add_argument('--env', help='environment ID (0==reset)',type=int, default=0)
|
||||
args = parser.parse_args()
|
||||
print("--env=" + str(args.env))
|
||||
|
||||
if (args.env == 0):
|
||||
ResetPoseExample(steps = 1000)
|
||||
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
|
||||
parser.add_argument('--env', help='environment ID (0==reset)', type=int, default=0)
|
||||
args = parser.parse_args()
|
||||
print("--env=" + str(args.env))
|
||||
|
||||
if (args.env == 0):
|
||||
ResetPoseExample(steps=1000)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
||||
|
||||
|
||||
main()
|
||||
|
||||
Reference in New Issue
Block a user