Random humanoid agent using new realenv interface

This commit is contained in:
hzyjerry 2017-10-22 16:21:34 -07:00
parent bb6545ac83
commit a45a7527ba
13 changed files with 397 additions and 70 deletions

View File

@ -93,12 +93,11 @@ build_local() {
mv glfw-3.1.2 ./realenv/core/channels/external/glfw-3.1.2
mkdir -p ./realenv/core/channels/build
cd ./realenv/core/channels/build
cmake .. && make -j 10
cmake .. && make clean && make -j 10
cd -
cd ./realenv/core/render/
wget --quiet https://www.dropbox.com/s/msd32wg144eew5r/coord.npy
pip install cython
bash build.sh
bash build_cuda.sh
@ -124,6 +123,11 @@ download_data () {
wget --quiet https://www.dropbox.com/s/vb3pv4igllr39pi/models.zip
unzip -q models.zip && rm models.zip
cd -
cd ./realenv/core/render/
wget --quiet https://www.dropbox.com/s/msd32wg144eew5r/coord.npy
cd -
}
ec2_install_conda() {

View File

@ -1,45 +0,0 @@
import go_vncdriver
import time
import numpy as np
import realenv
from realenv import actions
from realenv import VNCClient
## For visualization
from PIL import Image
from gym.envs.classic_control import rendering
class RandomAgent(object):
"""The world's simplest agent"""
def __init__(self, action_space):
self.action_space = action_space
def act(self, observation, reward=None):
return self.action_space[np.random.randint(0, len(self.action_space))]
client = VNCClient()
client.connect()
viewer = rendering.SimpleImageViewer()
if __name__ == '__main__':
agent = RandomAgent(actions)
ob = None
for i in range(10000):
## Hardcoded connection time
if (i == 15):
## Relocate the view to a new position
observation, infos, err = client.reset()
else:
action = agent.act(ob)
observation, infos, err = client.step(action)
## display
if any(infos[i]['stats.vnc.updates.n'] for i in infos.keys()):
# TODO: is network causing bottleneck here?
for ob in observation.keys():
viewer.imshow(observation[ob])
time.sleep(0.2)

View File

@ -0,0 +1,73 @@
from __future__ import print_function
import time
import numpy as np
import sys
import gym
from PIL import Image
from realenv.core.render.profiler import Profiler
import pybullet as p
class RandomAgent(object):
"""The world's simplest agent"""
def __init__(self, action_space):
self.action_space = action_space
self.time = 0
self.repeat = 1
self.action_last = np.zeros(self.action_space.shape[0])
def act(self, observation, reward=None):
if self.time < self.repeat:
self.time = self.time + 1
return self.action_last
else:
self.time = 0
action = np.zeros(self.action_space.shape[0])
#action[np.random.randint(0, len(action))] = 1
action = [0] * self.action_space.shape[0]
self.action_last = action
return action
if __name__ == '__main__':
env = gym.make('HumanoidWalking-v0')
agent = RandomAgent(env.action_space)
ob = None
torsoId = -1
for i in range (p.getNumBodies()):
print(p.getBodyInfo(i))
if (p.getBodyInfo(i)[0].decode() == "torso"):
torsoId=i
print("found humanoid torso")
i = 0
try:
while 1:
frame = 0
score = 0
restart_delay = 0
obs = env.reset()
while True:
time.sleep(0.01)
a = agent.act(obs)
with Profiler("Agent step function"):
obs, r, done, meta = env.step(a)
score += r
frame += 1
distance=5
yaw = 0
humanPos, humanOrn = p.getBasePositionAndOrientation(torsoId)
p.resetDebugVisualizerCamera(distance,yaw,-20,humanPos);
if not done: continue
if restart_delay==0:
print("score=%0.2f in %i frames" % (score, frame))
restart_delay = 60*2 # 2 sec at 60 fps
else:
restart_delay -= 1
if restart_delay==0: break
except KeyboardInterrupt:
env._end()
print("Program finished")

View File

@ -67,7 +67,7 @@ void main(){
//float B = gl_ProjectionMatrix[3].z;
float zNear = 0.1f; //- B / (1.0 - A);
float zFar = 5000f;// B / (1.0 + A);
float depthN = (EyeDirection_cameraspace.z - zNear)/128; // scale to a value in [0, 1]
float depthN = abs(EyeDirection_cameraspace.z - zNear)/128; // scale to a value in [0, 1]
vec3 depthNPack3 = fract(depthN*bitShift3);
depthNPack3 -= depthNPack3.xxy*bitMask3;
@ -75,11 +75,25 @@ void main(){
//depth = vec3(EyeDirection_cameraspace.z/128, EyeDirection_cameraspace.z/128, EyeDirection_cameraspace.z/128);
float m = sqrt(EyeDirection_cameraspace.x * EyeDirection_cameraspace.x + EyeDirection_cameraspace.y * EyeDirection_cameraspace.y + EyeDirection_cameraspace.z * EyeDirection_cameraspace.z);
//float m = sqrt(EyeDirection_cameraspace.x * EyeDirection_cameraspace.x + EyeDirection_cameraspace.y * EyeDirection_cameraspace.y + EyeDirection_cameraspace.z * EyeDirection_cameraspace.z);
float m = length(EyeDirection_cameraspace);
// float cosine = sqrt(EyeDirection_cameraspace.x * EyeDirection_cameraspace.x + EyeDirection_cameraspace.y * EyeDirection_cameraspace.y) / sqrt(EyeDirection_cameraspace.x * EyeDirection_cameraspace.x + EyeDirection_cameraspace.y * EyeDirection_cameraspace.y + EyeDirection_cameraspace.z * EyeDirection_cameraspace.z);
//float cosine = 1;
//if (dot(E, n) >= -0.05f ) {
// m = 0.0f;
//} else {
// m = 128.0f;
//}
mist = vec3(m, m, m);
float cull_delta = 0.7f;
//if (dot(EyeDirection_cameraspace, Normal_cameraspace) >= 0) {
// mist = mist - cull_delta;
//}
//mist = vec3(cosine, cosine, cosine);
//depth = vec3(depthN * 65536, depthN * 65536, depthN * 65536);

View File

@ -1,7 +1,7 @@
from realenv.data.datasets import ViewDataSet3D
from realenv.core.render.show_3d2 import PCRenderer, sync_coords
from realenv.core.channels.depth_render import run_depth_render
from realenv.core.physics.render_physics import PhysRenderer
from realenv.core.physics.physics_env import PhysicsEnv
from realenv import error
import progressbar
@ -11,6 +11,7 @@ import sys
import zmq
import socket
import shlex
import gym
from realenv.data.datasets import get_model_path
@ -42,12 +43,11 @@ class Engine(object):
self._checkPortClear()
self._setupChannel()
self._setupPhysics(self.human)
self._setupVisuals()
## Sync initial poses
pose_init = self.r_visuals.renderOffScreenInitialPose()
self.r_physics.initialize(pose_init)
self._setupPhysics(self.human, pose_init)
if self.debug:
self.r_visuals.renderToScreenSetup()
@ -122,10 +122,16 @@ class Engine(object):
renderer = PCRenderer(5556, sources, source_depths, target, rts, self.scale_up)
self.r_visuals = renderer
def _setupPhysics(self, human):
def _setupPhysics(self, human, pose_init):
"""
framePerSec = 13
renderer = PhysRenderer(self.dataset.get_model_obj(), framePerSec, debug = self.debug, human = human)
renderer = PhysicsEnv(self.dataset.get_model_obj(), render_mode="human_play",fps=framePerSec, pose=pose_init)
self.r_physics = renderer
"""
env = gym.make("HumanoidWalkingEnv-v0")
env.render(mode="human")
env.reset()
self.r_physics = env
def cleanUp(self):
self.p_channel.terminate()

View File

@ -0,0 +1,28 @@
from gym.envs.registration import registry, register, make, spec
register(
id='SimpleHumanoidEnv-v0',
entry_point='realenv.core.physics.simple_humanoid_env:SimpleHumanoidEnv'
)
register(
id='PhysicsEnv-v0',
entry_point='realenv.core.physics.physics_env:PhysicsEnv'
)
register(
id='HumanoidWalkingEnv-v0',
entry_point='realenv.core.physics.physics_env:HumanoidWalkingEnv'
)
register(
id='AntWalkingEnv-v0',
entry_point='realenv.core.physics.physics_env:AntWalkingEnv'
)
register(
id='HuskyWalkingEnv-v0',
entry_point='realenv.core.physics.physics_env:HuskyWalkingEnv'
)

View File

@ -50,7 +50,8 @@ def main():
while 1:
time.sleep(0.01)
a = pi.act(obs)
obs, r, done, _ = env.step(a)
obs, r, done, meta = env.step(a)
print(meta)
score += r
frame += 1
distance=5
@ -62,9 +63,10 @@ def main():
if still_open==False:
return
if not done: continue
if restart_delay==0:
print("score=%0.2f in %i frames" % (score, frame))
restart_delay = 60*2 # 2 sec at 60 fps
restart_delay = 12*2 # 2 sec at 60 fps
else:
restart_delay -= 1
if restart_delay==0: break

View File

@ -253,7 +253,11 @@ class PhysicsExtendedEnv(MJCFBaseBulletEnv):
self.HUD(state, a, done)
self.reward += sum(self.rewards)
return state, sum(self.rewards), bool(done), {}
eye_pos = self.robot.eyes.current_position()
x, y, z ,w = self.robot.eyes.current_orientation()
eye_quat = [w, x, y, z]
return state, sum(self.rewards), bool(done), {"eye_pos":eye_pos, "eye_quat":eye_quat}
def camera_adjust(self):
x, y, z = self.body_xyz

View File

@ -0,0 +1,224 @@
## Author: pybullet, Zhiyang He
import pybullet as p
import gym, gym.spaces, gym.utils
import numpy as np
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(currentdir)
os.sys.path.insert(0,parentdir)
import pybullet_data
class MJCFBasedRobot:
"""
Base class for mujoco .xml based agents.
"""
self_collision = True
def __init__(self, model_path, robot_name, action_dim, obs_dim):
self.parts = None
self.jdict = None
self.ordered_joints = None
self.robot_body = None
high = np.ones([action_dim])
self.action_space = gym.spaces.Box(-high, high)
high = np.inf * np.ones([obs_dim])
self.observation_space = gym.spaces.Box(-high, high)
self.model_path = model_path
self.robot_name = robot_name
def addToScene(self, bodies):
if self.parts is not None:
parts = self.parts
else:
parts = {}
if self.jdict is not None:
joints = self.jdict
else:
joints = {}
if self.ordered_joints is not None:
ordered_joints = self.ordered_joints
else:
ordered_joints = []
dump = 0
print("adding to scene", bodies)
for i in range(len(bodies)):
if p.getNumJoints(bodies[i]) == 0:
part_name, robot_name = p.getBodyInfo(bodies[i], 0)
robot_name = robot_name.decode("utf8")
part_name = part_name.decode("utf8")
parts[part_name] = BodyPart(part_name, bodies, i, -1)
for j in range(p.getNumJoints(bodies[i])):
p.setJointMotorControl2(bodies[i],j,p.POSITION_CONTROL,positionGain=0.1,velocityGain=0.1,force=0)
_,joint_name,_,_,_,_,_,_,_,_,_,_,part_name = p.getJointInfo(bodies[i], j)
joint_name = joint_name.decode("utf8")
part_name = part_name.decode("utf8")
if dump: print("ROBOT PART '%s'" % part_name)
if dump: print("ROBOT JOINT '%s'" % joint_name) # limits = %+0.2f..%+0.2f effort=%0.3f speed=%0.3f" % ((joint_name,) + j.limits()) )
parts[part_name] = BodyPart(part_name, bodies, i, j)
if part_name == self.robot_name:
self.robot_body = parts[part_name]
if i == 0 and j == 0 and self.robot_body is None: # if nothing else works, we take this as robot_body
parts[self.robot_name] = BodyPart(self.robot_name, bodies, 0, -1)
self.robot_body = parts[self.robot_name]
if joint_name[:6] == "ignore":
Joint(joint_name, bodies, i, j).disable_motor()
continue
if joint_name[:8] != "jointfix":
joints[joint_name] = Joint(joint_name, bodies, i, j)
ordered_joints.append(joints[joint_name])
joints[joint_name].power_coef = 100.0
return parts, joints, ordered_joints, self.robot_body
def reset(self):
self.ordered_joints = []
if ".urdf" in self.model_path:
if self.self_collision:
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(
(p.loadURDF(os.path.join(pybullet_data.getDataPath(),"husky", self.model_path), 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.loadURDF(os.path.join(pybullet_data.getDataPath(),"husky", self.model_path)))
if ".mjcf" in self.model_path:
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_path), 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_path)))
self.robot_specific_reset()
s = self.calc_state() # optimization: calc_state() can calculate something in self.* for calc_potential() to use
self.eyes = self.parts["eyes"]
print(self.eyes)
return s
def calc_potential(self):
return 0
class Pose_Helper: # dummy class to comply to original interface
def __init__(self, body_part):
self.body_part = body_part
def xyz(self):
return self.body_part.current_position()
def rpy(self):
return p.getEulerFromQuaternion(self.body_part.current_orientation())
def orientation(self):
return self.body_part.current_orientation()
class BodyPart:
def __init__(self, body_name, bodies, bodyIndex, bodyPartIndex):
self.bodies = bodies
self.bodyIndex = bodyIndex
self.bodyPartIndex = bodyPartIndex
self.initialPosition = self.current_position()
self.initialOrientation = self.current_orientation()
self.bp_pose = Pose_Helper(self)
def state_fields_of_pose_of(self, body_id, link_id=-1): # a method you will most probably need a lot to get pose and orientation
if link_id == -1:
(x, y, z), (a, b, c, d) = p.getBasePositionAndOrientation(body_id)
else:
(x, y, z), (a, b, c, d), _, _, _, _ = p.getLinkState(body_id, link_id)
return np.array([x, y, z, a, b, c, d])
def get_pose(self):
return self.state_fields_of_pose_of(self.bodies[self.bodyIndex], self.bodyPartIndex)
def speed(self):
if self.bodyPartIndex == -1:
(vx, vy, vz), _ = p.getBaseVelocity(self.bodies[self.bodyIndex])
else:
(x,y,z), (a,b,c,d), _,_,_,_, (vx, vy, vz), (vr,vp,vy) = p.getLinkState(self.bodies[self.bodyIndex], self.bodyPartIndex, computeLinkVelocity=1)
return np.array([vx, vy, vz])
def current_position(self):
return self.get_pose()[:3]
def current_orientation(self):
return self.get_pose()[3:]
def reset_position(self, position):
p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], position, self.current_orientation())
def reset_orientation(self, orientation):
p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], self.current_position(), orientation)
def reset_pose(self, position, orientation):
p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], position, orientation)
def pose(self):
return self.bp_pose
def contact_list(self):
return p.getContactPoints(self.bodies[self.bodyIndex], -1, self.bodyPartIndex, -1)
class Joint:
def __init__(self, joint_name, bodies, bodyIndex, jointIndex):
self.bodies = bodies
self.bodyIndex = bodyIndex
self.jointIndex = jointIndex
self.joint_name = joint_name
_,_,_,_,_,_,_,_,self.lowerLimit, self.upperLimit,_,_,_ = p.getJointInfo(self.bodies[self.bodyIndex], self.jointIndex)
self.power_coeff = 0
def set_state(self, x, vx):
p.resetJointState(self.bodies[self.bodyIndex], self.jointIndex, x, vx)
def current_position(self): # just some synonyme method
return self.get_state()
def current_relative_position(self):
pos, vel = self.get_state()
pos_mid = 0.5 * (self.lowerLimit + self.upperLimit);
return (
2 * (pos - pos_mid) / (self.upperLimit - self.lowerLimit),
0.1 * vel
)
def get_state(self):
x, vx,_,_ = p.getJointState(self.bodies[self.bodyIndex],self.jointIndex)
return x, vx
def set_position(self, position):
p.setJointMotorControl2(self.bodies[self.bodyIndex],self.jointIndex,p.POSITION_CONTROL, targetPosition=position)
def set_velocity(self, velocity):
p.setJointMotorControl2(self.bodies[self.bodyIndex],self.jointIndex,p.VELOCITY_CONTROL, targetVelocity=velocity)
def set_motor_torque(self, torque): # just some synonyme method
self.set_torque(torque)
def set_torque(self, torque):
p.setJointMotorControl2(bodyIndex=self.bodies[self.bodyIndex], jointIndex=self.jointIndex, controlMode=p.TORQUE_CONTROL, force=torque) #, positionGain=0.1, velocityGain=0.1)
def reset_current_position(self, position, velocity): # just some synonyme method
self.reset_position(position, velocity)
def reset_position(self, position, velocity):
p.resetJointState(self.bodies[self.bodyIndex],self.jointIndex,targetValue=position, targetVelocity=velocity)
self.disable_motor()
def disable_motor(self):
p.setJointMotorControl2(self.bodies[self.bodyIndex],self.jointIndex,controlMode=p.POSITION_CONTROL, targetPosition=0, targetVelocity=0, positionGain=0.1, velocityGain=0.1, force=0)

View File

@ -1,6 +1,7 @@
from robot_bases import MJCFBasedRobot
import numpy as np
import pybullet as p
import os
from transforms3d.euler import euler2quat
@ -147,9 +148,25 @@ class Humanoid(WalkerBase):
foot_list = ["right_foot", "left_foot"] # "left_hand", "right_hand"
def __init__(self):
WalkerBase.__init__(self, 'humanoid_symmetric.xml', 'torso', action_dim=17, obs_dim=44, power=0.41)
WalkerBase.__init__(self, 'humanoid.xml', 'torso', action_dim=17, obs_dim=44, power=0.41)
# 17 joints, 4 of them important for walking (hip, knee), others may as well be turned off, 17/4 = 4.25
def reset(self):
self.ordered_joints = []
print(os.path.join(os.path.dirname(os.path.abspath(__file__)),"models", self.model_path))
if self.self_collision:
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(
p.loadMJCF(os.path.join(os.path.dirname(os.path.abspath(__file__)), "models", self.model_path), 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(os.path.dirname(os.path.abspath(__file__)), "models", self.model_path)))
self.robot_specific_reset()
s = self.calc_state() # optimization: calc_state() can calculate something in self.* for calc_potential() to use
self.eyes = self.parts["eyes"]
return s
def robot_specific_reset(self):
WalkerBase.robot_specific_reset(self)
self.motor_names = ["abdomen_z", "abdomen_y", "abdomen_x"]

View File

@ -452,18 +452,21 @@ void render(int n, int h,int w, int s, unsigned char * img, float * depth,float
merge <<< dimGrid2, dimBlock >>> (d_render_all, d_render, d_selection, n, nx * ny * s * s);
/*int fill_size[8] = {3, 5, 10, 20, 50, 100, 200};
int fill_size[8] = {3, 5, 10, 20, 50, 100};
//int fill_size[8] = {3, 5, 10, 20, 50, 100, 200};
for (int j = 0; j < 8; j++) {
cudaMemset(nz, 0, render_mem_size * sizeof(int));
cudaMemset(average, 0, render_mem_size * sizeof(int) * 3);
get_average <<< dimGrid2, dimBlock >>> (d_render, nz, average, fill_size[j]);
fill_with_average <<< dimGrid2, dimBlock >>> (d_render, nz, average, fill_size[j]);
}*/
}
/*
cudaMemset(nz, 0, render_mem_size * sizeof(int));
cudaMemset(average, 0, render_mem_size * sizeof(int) * 3);
get_average <<< dimGrid2, dimBlock >>> (d_render, nz, average, 3);
fill_with_average <<< dimGrid2, dimBlock >>> (d_render, nz, average, 3);
*/
cudaMemcpy(render, d_render, render_mem_size * sizeof(unsigned char) * 3 , cudaMemcpyDeviceToHost);
cudaFree(d_img);

View File

@ -41,9 +41,9 @@ def get_model_path(idx=0):
class ViewDataSet3D(data.Dataset):
def __init__(self, root, train=True, transform=None, mist_transform=None, loader=default_loader, seqlen=5, debug=False, dist_filter = None, off_3d = True, off_pc_render = True):
def __init__(self, train=True, transform=None, mist_transform=None, loader=default_loader, seqlen=5, debug=False, dist_filter = None, off_3d = True, off_pc_render = True):
print ('Processing the data:')
self.root = root
self.root = os.path.join(os.path.dirname(os.path.abspath(__file__)), "dataset")
self.fofn = self.root + '_fofn'+str(int(train))+'.pkl'
self.train = train
self.loader = loader

View File

@ -1,10 +1,7 @@
from gym.envs.registration import registry, register, make, spec
"""
register(
id='Copy-v0',
entry_point='gym.envs.algorithmic:CopyEnv',
max_episode_steps=200,
reward_threshold=25.0,
)
"""
id='HumanoidWalking-v0',
entry_point='realenv.envs.simple_env:SimpleEnv'
)