default to be sensor

This commit is contained in:
fxia22 2017-11-02 15:25:17 -07:00
parent 621f9d1b76
commit 04eac7a7f7
2 changed files with 7 additions and 31 deletions

View File

@ -22,7 +22,8 @@ class WalkerBase(BaseRobot):
):
assert (type(obs_dim) == int or len(obs_dim) == 3), "Observation space needs to be either integer (sensor) or length 3 list (image). Passed in length is {}".format(len(obs_dim))
if mode == "sensor":
obs_dim=[obs_dim, 1]
#obs_dim=[obs_dim, 1]
pass
elif mode == "grey":
obs_dim=[256, 256, 1]
elif mode == "rgb":
@ -283,7 +284,7 @@ class Humanoid(WalkerBase):
class Husky(WalkerBase):
foot_list = ['front_left_wheel_link', 'front_right_wheel_link', 'rear_left_wheel_link', 'rear_right_wheel_link']
def __init__(self, is_discrete, mode='rgbd'):
def __init__(self, is_discrete, mode='sensor'):
self.model_type = "URDF"
self.is_discrete = is_discrete
WalkerBase.__init__(self, "husky.urdf", "base_link", action_dim=4, obs_dim=20, mode=mode, power=2.5, scale = 0.6)

View File

@ -157,22 +157,9 @@ class HuskySensorEnv(HuskyEnv, SensorRobotEnv):
x, y, z, w = self.robot.eyes.current_orientation()
eye_quat = quaternions.qmult([w, x, y, z], self.robot.eye_offset_orn)
print(sum(self.rewards))
return state, sum(self.rewards), bool(done), {"eye_pos": eye_pos, "eye_quat": eye_quat}
#self.tracking_camera['pitch'] = -45 ## stairs
yaw = 90 ## demo: living room
#yaw = 30 ## demo: kitchen
offset = 0.5
distance = 0.7 ## living room
#self.tracking_camera['yaw'] = 90 ## demo: stairs
self.tracking_camera['yaw'] = yaw ## living roon
self.tracking_camera['pitch'] = -10
self.tracking_camera['distance'] = distance
self.tracking_camera['z_offset'] = offset
class HuskyFlagRunEnv(HuskyEnv, SensorRobotEnv):
def __init__(self, human=True, timestep=HUMANOID_TIMESTEP,
@ -240,7 +227,7 @@ class HuskyFlagRunEnv(HuskyEnv, SensorRobotEnv):
alive = float(self.robot.alive_bonus(state[0] + self.robot.initial_z, self.robot.body_rpy[
1])) # state[0] is body height above ground, body_rpy[1] is pitch
done = False
done = self.nframe > 2000
print(self.nframe)
# done = alive < 0
if not np.isfinite(state).all():
@ -317,18 +304,6 @@ class HuskyFlagRunEnv(HuskyEnv, SensorRobotEnv):
x, y, z, w = self.robot.eyes.current_orientation()
eye_quat = quaternions.qmult([w, x, y, z], self.robot.eye_offset_orn)
print(sum(self.rewards))
print(state.shape)
return state, sum(self.rewards), bool(done), {"eye_pos": eye_pos, "eye_quat": eye_quat}
# self.tracking_camera['pitch'] = -45 ## stairs
yaw = 90 ## demo: living room
# yaw = 30 ## demo: kitchen
offset = 0.5
distance = 0.7 ## living room
# self.tracking_camera['yaw'] = 90 ## demo: stairs
self.tracking_camera['yaw'] = yaw ## living roon
self.tracking_camera['pitch'] = -10
self.tracking_camera['distance'] = distance
self.tracking_camera['z_offset'] = offset