python3 compatibility
This commit is contained in:
parent
d1c1d19e18
commit
fc7866f54b
|
@ -4,7 +4,7 @@ from realenv.core.channels.depth_render import run_depth_render
|
|||
from realenv.core.physics.physics_env import PhysicsEnv
|
||||
from realenv import error
|
||||
|
||||
import progressbar
|
||||
from tqdm import *
|
||||
import subprocess, os, signal
|
||||
import numpy as np
|
||||
import sys
|
||||
|
@ -36,15 +36,15 @@ class Engine(object):
|
|||
filename = tb.tb_frame.f_code.co_filename
|
||||
name = tb.tb_frame.f_code.co_name
|
||||
lineno = tb.tb_lineno
|
||||
print ' File "%.500s", line %d, in %.500s' %(filename, lineno, name)
|
||||
print(' File "%.500s", line %d, in %.500s' %(filename, lineno, name) )
|
||||
tb = tb.tb_next
|
||||
print ' %s: %s' %(exctype.__name__, value)
|
||||
print (' %s: %s' %(exctype.__name__, value))
|
||||
sys.excepthook = channel_excepthook
|
||||
|
||||
|
||||
self._checkPortClear()
|
||||
self._setupChannel()
|
||||
self._setupVisuals()
|
||||
|
||||
|
||||
## Sync initial poses
|
||||
pose_init = self.r_visuals.renderOffScreenInitialPose()
|
||||
self._setupPhysics(self.human, pose_init)
|
||||
|
@ -79,7 +79,7 @@ class Engine(object):
|
|||
cmd = "./depth_render --modelpath {}".format(model_path)
|
||||
self.p_channel = subprocess.Popen(shlex.split(cmd), shell=False)
|
||||
os.chdir(cur_path)
|
||||
|
||||
|
||||
|
||||
def _setupVisuals(self):
|
||||
scene_dict = dict(zip(self.dataset.scenes, range(len(self.dataset.scenes))))
|
||||
|
@ -93,22 +93,17 @@ class Engine(object):
|
|||
sources = []
|
||||
source_depths = []
|
||||
poses = []
|
||||
pbar = progressbar.ProgressBar(widgets=[
|
||||
' [ Initializing Environment ] ',
|
||||
progressbar.Bar(),
|
||||
' (', progressbar.ETA(), ') ',
|
||||
])
|
||||
for k,v in pbar(uuids):
|
||||
for k,v in tqdm(uuids):
|
||||
data = self.dataset[v]
|
||||
target = data[1]
|
||||
target_depth = data[3]
|
||||
|
||||
|
||||
self.scale_up = 2
|
||||
|
||||
|
||||
if self.scale_up !=1:
|
||||
target = cv2.resize(target,None,fx=1.0/self.scale_up, fy=1.0/self.scale_up, interpolation = cv2.INTER_CUBIC)
|
||||
target_depth = cv2.resize(target_depth,None,fx=1.0/self.scale_up, fy=1.0/self.scale_up, interpolation = cv2.INTER_CUBIC)
|
||||
|
||||
|
||||
pose = data[-1][0].numpy()
|
||||
targets.append(target)
|
||||
poses.append(pose)
|
||||
|
@ -137,4 +132,4 @@ class Engine(object):
|
|||
|
||||
def cleanUp(self):
|
||||
self.p_channel.terminate()
|
||||
|
||||
|
||||
|
|
|
@ -10,7 +10,7 @@ import argparse
|
|||
import os
|
||||
import json
|
||||
import numpy as np
|
||||
import settings
|
||||
import realenv.core.physics.settings as settings
|
||||
from transforms3d import euler, quaternions
|
||||
from realenv.core.physics.physics_object import PhysicsObject
|
||||
from realenv.core.render.profiler import Profiler
|
||||
|
@ -25,7 +25,7 @@ class PhysicsExtendedEnv(MJCFBaseBulletEnv):
|
|||
def __init__(self, robot, render=False):
|
||||
print("PhysicsExtendedEnv::__init__")
|
||||
MJCFBaseBulletEnv.__init__(self, robot, render)
|
||||
|
||||
|
||||
self.camera_x = 0
|
||||
self.walk_target_x = 1e3 # kilometer away
|
||||
self.walk_target_y = 0
|
||||
|
@ -36,7 +36,7 @@ class PhysicsExtendedEnv(MJCFBaseBulletEnv):
|
|||
return self.building_scene
|
||||
|
||||
def _reset(self):
|
||||
|
||||
|
||||
r = MJCFBaseBulletEnv._reset(self)
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
|
||||
|
@ -158,7 +158,7 @@ class PhysicsExtendedEnv(MJCFBaseBulletEnv):
|
|||
if o not in top_k:
|
||||
top_k.append(o)
|
||||
if len(top_k) >= self.k:
|
||||
break
|
||||
break
|
||||
print("Found %d views" % len(top_k), top_k)
|
||||
return top_k
|
||||
|
||||
|
@ -204,7 +204,7 @@ class PhysicsEnv(MJCFBaseBulletEnv):
|
|||
## engine running at a minimum 100 frames per sec
|
||||
self.action_repeat = int(math.ceil(100.0 / update_freq))
|
||||
self.time_step = 1.0 / (update_freq * self.action_repeat)
|
||||
|
||||
|
||||
self._setup_context(obj_path)
|
||||
self._set_gravity()
|
||||
self._set_frame_skip()
|
||||
|
@ -264,13 +264,13 @@ class PhysicsEnv(MJCFBaseBulletEnv):
|
|||
elif self.r_mode == "human_play":
|
||||
self.robot.getUpdateFromKeyboard(restart=restart)
|
||||
else:
|
||||
raise Exception
|
||||
raise Exception
|
||||
|
||||
print("action repeat", self.action_repeat)
|
||||
with Profiler("Physics internal"):
|
||||
for s in range(self.action_repeat):
|
||||
p.stepSimulation()
|
||||
|
||||
|
||||
self._update_debug_panels()
|
||||
|
||||
pos_xyz, quat_wxyz = self.robot.getViewPosAndOrientation()
|
||||
|
@ -278,7 +278,7 @@ class PhysicsEnv(MJCFBaseBulletEnv):
|
|||
'distance_to_target': np.sum(np.square(pos_xyz - self.target_pos))
|
||||
}
|
||||
print(pos_xyz)
|
||||
return [pos_xyz, quat_wxyz], state
|
||||
return [pos_xyz, quat_wxyz], state
|
||||
|
||||
def _update_debug_panels(self):
|
||||
if not (self.r_mode == "human_eye" or self.r_mode == "human_play"):
|
||||
|
@ -301,7 +301,7 @@ class PhysicsEnv(MJCFBaseBulletEnv):
|
|||
cameraDist = p.readUserDebugParameter(self.debug_sliders['dist'])
|
||||
cameraYaw = p.readUserDebugParameter(self.debug_sliders['yaw'])
|
||||
cameraPitch = p.readUserDebugParameter(self.debug_sliders['pitch'])
|
||||
|
||||
|
||||
pos_xyz, quat_wxyz = self.robot.getViewPosAndOrientation()
|
||||
p.getCameraImage(256, 256, viewMatrix = self.viewMatrix, projectionMatrix = self.projMatrix)
|
||||
p.resetDebugVisualizerCamera(cameraDist, cameraYaw, cameraPitch, pos_xyz)
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
import numpy as np
|
||||
import settings
|
||||
import realenv.core.physics.settings as settings
|
||||
from transforms3d import euler, quaternions
|
||||
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
from robot_bases import MJCFBasedRobot
|
||||
from realenv.core.physics.robot_bases import MJCFBasedRobot
|
||||
import numpy as np
|
||||
import pybullet as p
|
||||
import os
|
||||
|
@ -18,14 +18,14 @@ class WalkerBase(MJCFBasedRobot):
|
|||
self.walk_target_y = 0
|
||||
self.body_xyz=[0,0,0]
|
||||
|
||||
|
||||
|
||||
def robot_specific_reset(self):
|
||||
for j in self.ordered_joints:
|
||||
j.reset_current_position(self.np_random.uniform(low=-0.1, high=0.1), 0)
|
||||
|
||||
self.feet = [self.parts[f] for f in self.foot_list]
|
||||
self.feet_contact = np.array([0.0 for f in self.foot_list], dtype=np.float32)
|
||||
|
||||
|
||||
self.scene.actor_introduce(self)
|
||||
self.initial_z = None
|
||||
|
||||
|
@ -153,7 +153,7 @@ class Humanoid(WalkerBase):
|
|||
|
||||
def robot_specific_reset(self):
|
||||
WalkerBase.robot_specific_reset(self)
|
||||
|
||||
|
||||
humanoidId = -1
|
||||
numBodies = p.getNumBodies()
|
||||
for i in range (numBodies):
|
||||
|
@ -164,7 +164,7 @@ class Humanoid(WalkerBase):
|
|||
glass_id = p.loadMJCF(os.path.join(self.physics_model_dir, "glass.xml"))
|
||||
print("setting up glass", glass_id, humanoidId)
|
||||
p.changeVisualShape(glass_id[0], -1, rgbaColor=[0, 0, 0, 0])
|
||||
cid = p.createConstraint(humanoidId, -1, glass_id[0],-1,p.JOINT_FIXED,[0,0,0],[0,0,1.4],[0,0,1])
|
||||
#cid = p.createConstraint(humanoidId, -1, glass_id[0],-1,p.JOINT_FIXED,[0,0,0],[0,0,1.4],[0,0,1])
|
||||
|
||||
self.motor_names = ["abdomen_z", "abdomen_y", "abdomen_x"]
|
||||
self.motor_power = [100, 100, 100]
|
||||
|
@ -197,7 +197,7 @@ class Humanoid(WalkerBase):
|
|||
self.robot_body.reset_position(position)
|
||||
self.robot_body.reset_orientation(quatWXYZ2quatXYZW(euler2quat(orientation)))
|
||||
self.initial_z = 0.8
|
||||
|
||||
|
||||
orientation, position = get_model_initial_pose("humanoid")
|
||||
roll = orientation[0]
|
||||
pitch = orientation[1]
|
||||
|
@ -207,7 +207,7 @@ class Humanoid(WalkerBase):
|
|||
|
||||
## BbxejD15Etk
|
||||
|
||||
|
||||
|
||||
random_yaw = False
|
||||
random_lean = False
|
||||
|
||||
|
@ -230,4 +230,4 @@ class Husky(WalkerBase):
|
|||
WalkerBase.__init__(self, "husky.urdf", "husky_robot", action_dim=10, obs_dim=32, 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
|
||||
return +1 if z > 0.26 else -1 # 0.25 is central sphere rad, die if it scrapes the ground
|
||||
|
|
|
@ -7,7 +7,7 @@ import sys
|
|||
import torch
|
||||
import argparse
|
||||
import time
|
||||
import utils
|
||||
import realenv.core.render.utils as utils
|
||||
import transforms3d
|
||||
import json
|
||||
import zmq
|
||||
|
@ -84,7 +84,7 @@ class PCRenderer:
|
|||
|
||||
#self.scale_up = scale_up
|
||||
|
||||
|
||||
|
||||
self.show = np.zeros((self.showsz, self.showsz, 3),dtype='uint8')
|
||||
self.show_rgb = np.zeros((self.showsz, self.showsz ,3),dtype='uint8')
|
||||
|
||||
|
@ -355,6 +355,7 @@ class PCRenderer:
|
|||
|
||||
def sync_coords():
|
||||
with Profiler("Transform coords"):
|
||||
|
||||
new_coords = np.getbuffer(coords.flatten().astype(np.uint32))
|
||||
socket_mist.send(new_coords)
|
||||
message = socket_mist.recv()
|
||||
|
|
|
@ -9,8 +9,8 @@ import json
|
|||
import codecs
|
||||
import numpy as np
|
||||
import ctypes as ct
|
||||
import progressbar
|
||||
import sys
|
||||
from tqdm import *
|
||||
import torchvision.transforms as transforms
|
||||
import argparse
|
||||
import json
|
||||
|
@ -88,12 +88,6 @@ class ViewDataSet3D(data.Dataset):
|
|||
if train:
|
||||
self.scenes = self.scenes[:num_train]
|
||||
|
||||
self.bar = progressbar.ProgressBar(widgets=[
|
||||
' [', progressbar.Timer(), '] ',
|
||||
progressbar.Bar(),
|
||||
' (', progressbar.ETA(), ') ',
|
||||
])
|
||||
|
||||
self.meta = {}
|
||||
if debug:
|
||||
last = 35
|
||||
|
@ -106,9 +100,9 @@ class ViewDataSet3D(data.Dataset):
|
|||
for line in f:
|
||||
l = line.strip().split(',')
|
||||
uuid = l[0]
|
||||
xyz = map(float, l[1:4])
|
||||
quat = map(float, l[4:8])
|
||||
if not self.meta.has_key(scene):
|
||||
xyz = list(map(float, l[1:4]))
|
||||
quat = list(map(float, l[4:8]))
|
||||
if not scene in self.meta:
|
||||
self.meta[scene] = {}
|
||||
metadata = (uuid, xyz, quat)
|
||||
#print(uuid, xyz)
|
||||
|
@ -117,11 +111,11 @@ class ViewDataSet3D(data.Dataset):
|
|||
self.meta[scene][uuid] = metadata
|
||||
print("Indexing")
|
||||
|
||||
for scene, meta in self.bar(self.meta.items()):
|
||||
for scene, meta in tqdm(list(self.meta.items())):
|
||||
if len(meta) < self.seqlen:
|
||||
continue
|
||||
for uuid,v in meta.items():
|
||||
dist_list = [(uuid2, np.linalg.norm(np.array(v2[1]) - np.array(v[1]))) for uuid2,v2 in meta.items()]
|
||||
for uuid,v in list(meta.items()):
|
||||
dist_list = [(uuid2, np.linalg.norm(np.array(v2[1]) - np.array(v[1]))) for uuid2,v2 in list(meta.items())]
|
||||
dist_list = sorted(dist_list, key = lambda x:x[-1])
|
||||
|
||||
if not dist_filter is None:
|
||||
|
|
|
@ -12,7 +12,7 @@ from realenv.data.datasets import ViewDataSet3D
|
|||
from multiprocessing import Process
|
||||
from realenv.core.channels.depth_render import run_depth_render
|
||||
from realenv.data.datasets import get_model_path
|
||||
import progressbar
|
||||
from tqdm import *
|
||||
import numpy as np
|
||||
import zmq
|
||||
import time
|
||||
|
@ -107,7 +107,7 @@ class SimpleDebugEnv(gym.Env):
|
|||
self.debug_mode = debug
|
||||
self.human_mode = human
|
||||
file_dir = os.path.dirname(__file__)
|
||||
|
||||
|
||||
self.model_id = get_model_path()[1]
|
||||
self.dataset = ViewDataSet3D(transform = np.array, mist_transform = np.array, seqlen = 2, off_3d = False, train = False)
|
||||
|
||||
|
@ -130,7 +130,7 @@ class SimpleDebugEnv(gym.Env):
|
|||
traceback.print_exc()
|
||||
self._end()
|
||||
raise(e)
|
||||
|
||||
|
||||
|
||||
def _setupRewardFunc(self):
|
||||
def _getReward(state_old, state_new):
|
||||
|
@ -139,7 +139,7 @@ class SimpleDebugEnv(gym.Env):
|
|||
else:
|
||||
return 5 * (state_old['distance_to_target'] - state_new['distance_to_target'])
|
||||
self.reward_func = _getReward
|
||||
|
||||
|
||||
def _setupVisuals(self):
|
||||
scene_dict = dict(zip(self.dataset.scenes, range(len(self.dataset.scenes))))
|
||||
if not self.model_id in scene_dict.keys():
|
||||
|
@ -153,12 +153,7 @@ class SimpleDebugEnv(gym.Env):
|
|||
sources = []
|
||||
source_depths = []
|
||||
poses = []
|
||||
pbar = progressbar.ProgressBar(widgets=[
|
||||
' [ Initializing Environment ] ',
|
||||
progressbar.Bar(),
|
||||
' (', progressbar.ETA(), ') ',
|
||||
])
|
||||
for k,v in pbar(uuids):
|
||||
for k,v in tqdm(uuids):
|
||||
data = self.dataset[v]
|
||||
source = data[0][0]
|
||||
target = data[1]
|
||||
|
@ -173,9 +168,9 @@ class SimpleDebugEnv(gym.Env):
|
|||
context_mist = zmq.Context()
|
||||
socket_mist = context_mist.socket(zmq.REQ)
|
||||
socket_mist.connect("tcp://localhost:5555")
|
||||
|
||||
|
||||
sync_coords()
|
||||
|
||||
|
||||
renderer = PCRenderer(5556, sources, source_depths, target, rts, scale_up=1)
|
||||
return renderer
|
||||
|
||||
|
@ -209,12 +204,12 @@ class SimpleDebugEnv(gym.Env):
|
|||
#self.r_displayer.add_reward(reward)
|
||||
self.state_old = state
|
||||
#with Profiler("Display reward"):
|
||||
|
||||
|
||||
#with Profiler("Render to screen"):
|
||||
visuals = self.r_visuals.renderToScreen(pose)
|
||||
|
||||
return visuals, reward
|
||||
except Exception as e:
|
||||
except Exception as e:
|
||||
self._end()
|
||||
raise(e)
|
||||
|
||||
|
@ -223,9 +218,9 @@ class SimpleDebugEnv(gym.Env):
|
|||
|
||||
def _render(self, mode='human', close=False):
|
||||
return
|
||||
|
||||
|
||||
def _end(self):
|
||||
## TODO (hzyjerry): this does not kill cleanly
|
||||
## to reproduce bug, set human = false, debug_mode = false
|
||||
self.p_channel.terminate()
|
||||
return
|
||||
return
|
||||
|
|
|
@ -23,17 +23,18 @@ class AdaptiveNorm2d(nn.Module):
|
|||
self.w1 = nn.Parameter(torch.ones(1))
|
||||
def forward(self, x):
|
||||
return self.w0.repeat(x.size()) * self.nm(x) + self.w1.repeat(x.size()) * x
|
||||
|
||||
|
||||
class CompletionNet2(nn.Module):
|
||||
def __init__(self, norm = AdaptiveNorm2d, nf = 64):
|
||||
super(CompletionNet2, self).__init__()
|
||||
|
||||
|
||||
self.nf = nf
|
||||
alpha = 0.05
|
||||
|
||||
self.convs = nn.Sequential(
|
||||
nn.Conv2d(5, nf/4, kernel_size = 5, stride = 1, padding = 2),
|
||||
nn.Conv2d(5, nf//4, kernel_size = 5, stride = 1, padding = 2),
|
||||
nn.LeakyReLU(0.1),
|
||||
nn.Conv2d(nf/4, nf, kernel_size = 5, stride = 2, padding = 2),
|
||||
nn.Conv2d(nf//4, nf, kernel_size = 5, stride = 2, padding = 2),
|
||||
norm(nf, momentum=alpha),
|
||||
nn.LeakyReLU(0.1),
|
||||
nn.Conv2d(nf, nf, kernel_size = 3, stride = 1, padding = 2),
|
||||
|
@ -78,19 +79,19 @@ class CompletionNet2(nn.Module):
|
|||
nn.Conv2d(nf, nf, kernel_size = 3, stride = 1, padding = 1),
|
||||
norm(nf, momentum=alpha),
|
||||
nn.LeakyReLU(0.1),
|
||||
nn.ConvTranspose2d(nf, nf/4, kernel_size = 4, stride = 2, padding = 1),
|
||||
norm(nf/4, momentum=alpha),
|
||||
nn.ConvTranspose2d(nf, nf//4, kernel_size = 4, stride = 2, padding = 1),
|
||||
norm(nf//4, momentum=alpha),
|
||||
nn.ReLU(),
|
||||
nn.Conv2d(nf/4, nf/4, kernel_size = 3, stride = 1, padding = 1),
|
||||
norm(nf/4, momentum=alpha),
|
||||
nn.Conv2d(nf//4, nf//4, kernel_size = 3, stride = 1, padding = 1),
|
||||
norm(nf//4, momentum=alpha),
|
||||
nn.LeakyReLU(0.1),
|
||||
nn.Conv2d(nf/4, 3, kernel_size = 3, stride = 1, padding = 1),
|
||||
nn.Conv2d(nf//4, 3, kernel_size = 3, stride = 1, padding = 1),
|
||||
)
|
||||
|
||||
def forward(self, x, mask):
|
||||
return self.convs(torch.cat([x, mask], 1))
|
||||
|
||||
|
||||
|
||||
def identity_init(m):
|
||||
classname = m.__class__.__name__
|
||||
if classname.find('Conv2d') != -1:
|
||||
|
@ -102,14 +103,14 @@ def identity_init(m):
|
|||
for i in range(nc):
|
||||
m.weight.data[i,i,cx,cy] = 1
|
||||
m.bias.data.fill_(0)
|
||||
|
||||
|
||||
if m.stride[0] == 2:
|
||||
for i in range(nc):
|
||||
m.weight.data[i+nc,i,cx+1,cy] = 1
|
||||
m.weight.data[i+nc*2,i,cx,cy+1] = 1
|
||||
m.weight.data[i+nc*3,i,cx+1,cy+1] = 1
|
||||
|
||||
|
||||
|
||||
|
||||
elif classname.find('ConvTranspose2d') != -1:
|
||||
o, i, k1, k2 = m.weight.data.size()
|
||||
nc = min(o,i)
|
||||
|
@ -120,22 +121,22 @@ def identity_init(m):
|
|||
m.weight.data[i+nc,i,cx+1,cy] = 1
|
||||
m.weight.data[i+nc*2,i,cx,cy+1] = 1
|
||||
m.weight.data[i+nc*3,i,cx+1,cy+1] = 1
|
||||
|
||||
|
||||
m.bias.data.fill_(0)
|
||||
|
||||
|
||||
|
||||
|
||||
elif classname.find('BatchNorm') != -1:
|
||||
m.weight.data.fill_(1)
|
||||
m.bias.data.fill_(0)
|
||||
|
||||
|
||||
|
||||
|
||||
class Perceptual(nn.Module):
|
||||
def __init__(self, features, early = False):
|
||||
super(Perceptual, self).__init__()
|
||||
self.features = features
|
||||
self.early = early
|
||||
|
||||
|
||||
def forward(self, x):
|
||||
bs = x.size(0)
|
||||
x = self.features[0](x)
|
||||
|
@ -170,12 +171,12 @@ class Perceptual(nn.Module):
|
|||
x = self.features[25](x)
|
||||
x = self.features[26](x)
|
||||
x4 = x.view(bs, -1, 1)
|
||||
|
||||
|
||||
if self.early:
|
||||
perfeat = torch.cat([x0, x1, x2], 1)
|
||||
else:
|
||||
else:
|
||||
perfeat = torch.cat([x0, x1, x2, x3, x4], 1)
|
||||
|
||||
|
||||
return perfeat
|
||||
|
||||
|
||||
|
|
5
setup.py
5
setup.py
|
@ -21,7 +21,7 @@ setup(name='realenv',
|
|||
author='Stanford University',
|
||||
zip_safe=False,
|
||||
install_requires=[
|
||||
'numpy>=1.10.4',
|
||||
'numpy>=1.10.4',
|
||||
#'go-vncdriver>=0.4.19',
|
||||
'pyglet>=1.2.0',
|
||||
'gym>=0.9.2',
|
||||
|
@ -30,7 +30,8 @@ setup(name='realenv',
|
|||
'numpy>=1.13',
|
||||
'pybullet>=1.5.6',
|
||||
'transforms3d>=0.3.1',
|
||||
'progressbar>=2.3',
|
||||
#'progressbar>=2.3',
|
||||
'tqdm >= 4',
|
||||
'pyzmq>=16.0.2',
|
||||
'Pillow>=4.2.1',
|
||||
'matplotlib>=2.1.0'
|
||||
|
|
Loading…
Reference in New Issue