Skip to content

Commit

Permalink
work
Browse files Browse the repository at this point in the history
  • Loading branch information
StoneT2000 committed Mar 6, 2024
1 parent 38d1571 commit 67b4b01
Show file tree
Hide file tree
Showing 10 changed files with 38 additions and 38 deletions.
12 changes: 6 additions & 6 deletions mani_skill2/envs/scenes/base_env.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,8 @@
from mani_skill2.agents.robots import Fetch, Panda
from mani_skill2.envs.sapien_env import BaseEnv
from mani_skill2.sensors.camera import CameraConfig
from mani_skill2.utils import sapien_utils
from mani_skill2.utils.registration import register_env
from mani_skill2.utils.sapien_utils import look_at
from mani_skill2.utils.scene_builder import SceneBuilder
from mani_skill2.utils.scene_builder.registration import REGISTERED_SCENE_BUILDERS
from mani_skill2.utils.scene_builder.replicacad.scene_builder import (
Expand Down Expand Up @@ -120,14 +120,14 @@ def _register_sensors(self):
if self.robot_uids == "fetch":
return ()

pose = look_at([0.3, 0, 0.6], [-0.1, 0, 0.1])
pose = sapien_utils.look_at([0.3, 0, 0.6], [-0.1, 0, 0.1])
return CameraConfig(
"base_camera", pose.p, pose.q, 128, 128, np.pi / 2, 0.01, 10
)

def _register_human_render_cameras(self):
if self.robot_uids == "fetch":
room_camera_pose = look_at([2.5, -2.5, 3], [0.0, 0.0, 0])
room_camera_pose = sapien_utils.look_at([2.5, -2.5, 3], [0.0, 0.0, 0])
room_camera_config = CameraConfig(
"render_camera",
room_camera_pose.p,
Expand All @@ -138,7 +138,7 @@ def _register_human_render_cameras(self):
0.01,
10,
)
robot_camera_pose = look_at([2, 0, 1], [0, 0, -1])
robot_camera_pose = sapien_utils.look_at([2, 0, 1], [0, 0, -1])
robot_camera_config = CameraConfig(
"robot_render_camera",
robot_camera_pose.p,
Expand All @@ -153,7 +153,7 @@ def _register_human_render_cameras(self):
return [room_camera_config, robot_camera_config]

if self.robot_uids == "panda":
pose = look_at([0.4, 0.4, 0.8], [0.0, 0.0, 0.4])
pose = sapien_utils.look_at([0.4, 0.4, 0.8], [0.0, 0.0, 0.4])
else:
pose = look_at([0, 10, -3], [0, 0, 0])
pose = sapien_utils.look_at([0, 10, -3], [0, 0, 0])
return CameraConfig("render_camera", pose.p, pose.q, 512, 512, 1, 0.01, 10)
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
from mani_skill2.agents.robots import AllegroHandRightTouch
from mani_skill2.envs.sapien_env import BaseEnv
from mani_skill2.sensors.camera import CameraConfig
from mani_skill2.utils import sapien_utils
from mani_skill2.utils.building.actors import (
MODEL_DBS,
_load_ycb_dataset,
Expand All @@ -17,7 +18,6 @@
)
from mani_skill2.utils.geometry.rotation_conversions import quaternion_apply
from mani_skill2.utils.registration import register_env
from mani_skill2.utils.sapien_utils import look_at
from mani_skill2.utils.scene_builder.table.table_scene_builder import TableSceneBuilder
from mani_skill2.utils.structs.actor import Actor
from mani_skill2.utils.structs.pose import Pose, vectorize_pose
Expand Down Expand Up @@ -69,13 +69,15 @@ def sim_cfg(self):
)

def _register_sensors(self):
pose = look_at(eye=[0.15, 0, 0.45], target=[-0.1, 0, self.hand_init_height])
pose = sapien_utils.look_at(
eye=[0.15, 0, 0.45], target=[-0.1, 0, self.hand_init_height]
)
return [
CameraConfig("base_camera", pose.p, pose.q, 128, 128, np.pi / 2, 0.01, 10)
]

def _register_human_render_cameras(self):
pose = look_at([0.2, 0.4, 0.4], [0.0, 0.0, 0.1])
pose = sapien_utils.look_at([0.2, 0.4, 0.4], [0.0, 0.0, 0.1])
return CameraConfig("render_camera", pose.p, pose.q, 512, 512, 1, 0.01, 10)

def _load_actors(self):
Expand Down
8 changes: 4 additions & 4 deletions mani_skill2/envs/tasks/dexterity/rotate_valve.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,10 @@
from mani_skill2.agents.robots import DClaw
from mani_skill2.envs.sapien_env import BaseEnv
from mani_skill2.sensors.camera import CameraConfig
from mani_skill2.utils import sapien_utils
from mani_skill2.utils.building.articulations import build_robel_valve
from mani_skill2.utils.geometry.rotation_conversions import axis_angle_to_quaternion
from mani_skill2.utils.registration import register_env
from mani_skill2.utils.sapien_utils import get_obj_by_name, look_at
from mani_skill2.utils.scene_builder.table.table_scene_builder import TableSceneBuilder
from mani_skill2.utils.structs.articulation import Articulation
from mani_skill2.utils.structs.pose import Pose, vectorize_pose
Expand Down Expand Up @@ -59,13 +59,13 @@ def __init__(
super().__init__(*args, robot_uids="dclaw", **kwargs)

def _register_sensors(self):
pose = look_at(eye=[0.3, 0, 0.3], target=[-0.1, 0, 0.05])
pose = sapien_utils.look_at(eye=[0.3, 0, 0.3], target=[-0.1, 0, 0.05])
return [
CameraConfig("base_camera", pose.p, pose.q, 128, 128, np.pi / 2, 0.01, 10)
]

def _register_human_render_cameras(self):
pose = look_at([0.2, 0.4, 0.4], [0.0, 0.0, 0.1])
pose = sapien_utils.look_at([0.2, 0.4, 0.4], [0.0, 0.0, 0.1])
return CameraConfig("render_camera", pose.p, pose.q, 512, 512, 1, 0.01, 10)

def _load_actors(self):
Expand Down Expand Up @@ -132,7 +132,7 @@ def _load_articulations(self):
capsule_lens.append(capsule_len)
self.valve = Articulation.merge(valves, "valve_station")
self.capsule_lens = torch.from_numpy(np.array(capsule_lens)).to(self.device)
self.valve_link = get_obj_by_name(self.valve.get_links(), "valve")
self.valve_link = sapien_utils.get_obj_by_name(self.valve.get_links(), "valve")

def _initialize_actors(self, env_idx: torch.Tensor):
with torch.device(self.device):
Expand Down
6 changes: 3 additions & 3 deletions mani_skill2/envs/tasks/empty_env.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,9 @@
from mani_skill2.agents.robots.panda.panda import Panda
from mani_skill2.envs.sapien_env import BaseEnv
from mani_skill2.sensors.camera import CameraConfig
from mani_skill2.utils import sapien_utils
from mani_skill2.utils.building.ground import build_ground
from mani_skill2.utils.registration import register_env
from mani_skill2.utils.sapien_utils import look_at
from mani_skill2.utils.structs.types import GPUMemoryConfig, SimConfig


Expand Down Expand Up @@ -40,13 +40,13 @@ def __init__(self, *args, robot_uids="panda", **kwargs):
super().__init__(*args, robot_uids=robot_uids, **kwargs)

def _register_sensors(self):
pose = look_at(eye=[0.3, 0, 0.6], target=[-0.1, 0, 0.1])
pose = sapien_utils.look_at(eye=[0.3, 0, 0.6], target=[-0.1, 0, 0.1])
return [
CameraConfig("base_camera", pose.p, pose.q, 128, 128, np.pi / 2, 0.01, 10)
]

def _register_human_render_cameras(self):
pose = look_at([0.75, -0.75, 0.5], [0.0, 0.0, 0.2])
pose = sapien_utils.look_at([0.75, -0.75, 0.5], [0.0, 0.0, 0.2])
return CameraConfig("render_camera", pose.p, pose.q, 2048, 2048, 1, 0.01, 10)

def _load_actors(self):
Expand Down
8 changes: 3 additions & 5 deletions mani_skill2/envs/tasks/fmb/fmb.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,9 @@
from mani_skill2.agents.robots.panda.panda import Panda
from mani_skill2.envs.sapien_env import BaseEnv
from mani_skill2.sensors.camera import CameraConfig
from mani_skill2.utils import sapien_utils
from mani_skill2.utils.building.actor_builder import ActorBuilder
from mani_skill2.utils.registration import register_env
from mani_skill2.utils.sapien_utils import ( # import various useful utilities for working with sapien
look_at,
)
from mani_skill2.utils.scene_builder.table.table_scene_builder import TableSceneBuilder


Expand Down Expand Up @@ -46,13 +44,13 @@ def __init__(self, *args, robot_uids="panda", robot_init_qpos_noise=0.02, **kwar
super().__init__(*args, robot_uids=robot_uids, **kwargs)

def _register_sensors(self):
pose = look_at(eye=[0.3, 0, 0.6], target=[-0.1, 0, 0.1])
pose = sapien_utils.look_at(eye=[0.3, 0, 0.6], target=[-0.1, 0, 0.1])
return [
CameraConfig("base_camera", pose.p, pose.q, 128, 128, np.pi / 2, 0.01, 10)
]

def _register_human_render_cameras(self):
pose = look_at([1.0, 0.8, 0.8], [0.0, 0.0, 0.35])
pose = sapien_utils.look_at([1.0, 0.8, 0.8], [0.0, 0.0, 0.35])
return CameraConfig("render_camera", pose.p, pose.q, 1024, 1024, 1, 0.01, 10)

def _load_actors(self):
Expand Down
10 changes: 5 additions & 5 deletions mani_skill2/envs/tasks/open_cabinet_drawer.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@

from mani_skill2.envs.sapien_env import BaseEnv
from mani_skill2.sensors.camera import CameraConfig
from mani_skill2.utils import sapien_utils
from mani_skill2.utils.building.actors import build_sphere
from mani_skill2.utils.building.articulations import (
MODEL_DBS,
Expand All @@ -16,10 +17,9 @@
from mani_skill2.utils.building.ground import build_ground
from mani_skill2.utils.geometry.geometry import transform_points
from mani_skill2.utils.registration import register_env
from mani_skill2.utils.sapien_utils import look_at, to_tensor
from mani_skill2.utils.structs import Pose
from mani_skill2.utils.structs.articulation import Articulation
from mani_skill2.utils.structs.link import Link
from mani_skill2.utils.structs.pose import Pose


# TODO (stao): we need to cut the meshes of all the cabinets in this dataset for gpu sim, not registering task for now
Expand Down Expand Up @@ -56,13 +56,13 @@ def __init__(
super().__init__(*args, robot_uids=robot_uids, **kwargs)

def _register_sensors(self):
pose = look_at(eye=[-2.5, -1.5, 1.8], target=[-0.3, 0.5, 0.1])
pose = sapien_utils.look_at(eye=[-2.5, -1.5, 1.8], target=[-0.3, 0.5, 0.1])
return [
CameraConfig("base_camera", pose.p, pose.q, 128, 128, np.pi / 2, 0.01, 100)
]

def _register_human_render_cameras(self):
pose = look_at(eye=[-2.3, -1.5, 1.8], target=[-0.3, 0.5, 0])
pose = sapien_utils.look_at(eye=[-2.3, -1.5, 1.8], target=[-0.3, 0.5, 0])
# TODO (stao): how much does far affect rendering speed?
return CameraConfig("render_camera", pose.p, pose.q, 512, 512, 1, 0.01, 100)

Expand Down Expand Up @@ -158,7 +158,7 @@ def _initialize_actors(self, env_idx: torch.Tensor):
index_q = torch.tensor(index_q, dtype=int)
self.target_qpos_idx = (torch.arange(0, b), index_q)
# TODO (stao): For performance improvement, one can save relative position of link handles ahead of time.
handle_link_positions = to_tensor(
handle_link_positions = sapien_utils.to_tensor(
np.array(
[
x[self.link_indices[i]].bounding_box.center_mass
Expand Down
6 changes: 3 additions & 3 deletions mani_skill2/envs/tasks/pick_cube.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,9 @@
from mani_skill2.agents.robots.xmate3.xmate3 import Xmate3Robotiq
from mani_skill2.envs.sapien_env import BaseEnv
from mani_skill2.sensors.camera import CameraConfig
from mani_skill2.utils import sapien_utils
from mani_skill2.utils.building.actors import build_cube, build_sphere
from mani_skill2.utils.registration import register_env
from mani_skill2.utils.sapien_utils import look_at
from mani_skill2.utils.scene_builder.table.table_scene_builder import TableSceneBuilder
from mani_skill2.utils.structs.pose import Pose
from mani_skill2.utils.structs.types import GPUMemoryConfig, SimConfig
Expand Down Expand Up @@ -56,13 +56,13 @@ def __init__(self, *args, robot_uids="panda", robot_init_qpos_noise=0.02, **kwar
super().__init__(*args, robot_uids=robot_uids, **kwargs)

def _register_sensors(self):
pose = look_at(eye=[0.3, 0, 0.6], target=[-0.1, 0, 0.1])
pose = sapien_utils.look_at(eye=[0.3, 0, 0.6], target=[-0.1, 0, 0.1])
return [
CameraConfig("base_camera", pose.p, pose.q, 128, 128, np.pi / 2, 0.01, 10)
]

def _register_human_render_cameras(self):
pose = look_at([0.6, 0.7, 0.6], [0.0, 0.0, 0.35])
pose = sapien_utils.look_at([0.6, 0.7, 0.6], [0.0, 0.0, 0.35])
return CameraConfig("render_camera", pose.p, pose.q, 512, 512, 1, 0.01, 10)

def _load_actors(self):
Expand Down
6 changes: 3 additions & 3 deletions mani_skill2/envs/tasks/pick_single_ycb.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,14 +11,14 @@
from mani_skill2.envs.sapien_env import BaseEnv
from mani_skill2.envs.utils.randomization.pose import random_quaternions
from mani_skill2.sensors.camera import CameraConfig
from mani_skill2.utils import sapien_utils
from mani_skill2.utils.building.actors import (
MODEL_DBS,
_load_ycb_dataset,
build_actor_ycb,
build_sphere,
)
from mani_skill2.utils.registration import register_env
from mani_skill2.utils.sapien_utils import look_at
from mani_skill2.utils.scene_builder.table.table_scene_builder import TableSceneBuilder
from mani_skill2.utils.structs.actor import Actor
from mani_skill2.utils.structs.pose import Pose
Expand Down Expand Up @@ -82,13 +82,13 @@ def __init__(
)

def _register_sensors(self):
pose = look_at(eye=[0.3, 0, 0.6], target=[-0.1, 0, 0.1])
pose = sapien_utils.look_at(eye=[0.3, 0, 0.6], target=[-0.1, 0, 0.1])
return [
CameraConfig("base_camera", pose.p, pose.q, 128, 128, np.pi / 2, 0.01, 10)
]

def _register_human_render_cameras(self):
pose = look_at([0.6, 0.7, 0.6], [0.0, 0.0, 0.35])
pose = sapien_utils.look_at([0.6, 0.7, 0.6], [0.0, 0.0, 0.35])
return CameraConfig("render_camera", pose.p, pose.q, 512, 512, 1, 0.01, 10)

def _load_actors(self):
Expand Down
6 changes: 3 additions & 3 deletions mani_skill2/envs/tasks/push_cube.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,9 @@
from mani_skill2.agents.robots.xmate3.xmate3 import Xmate3Robotiq
from mani_skill2.envs.sapien_env import BaseEnv
from mani_skill2.sensors.camera import CameraConfig
from mani_skill2.utils import sapien_utils
from mani_skill2.utils.building import actors
from mani_skill2.utils.registration import register_env
from mani_skill2.utils.sapien_utils import look_at
from mani_skill2.utils.scene_builder.table.table_scene_builder import TableSceneBuilder
from mani_skill2.utils.structs.pose import Pose
from mani_skill2.utils.structs.types import Array, GPUMemoryConfig, SimConfig
Expand Down Expand Up @@ -78,14 +78,14 @@ def __init__(self, *args, robot_uids="panda", robot_init_qpos_noise=0.02, **kwar
def _register_sensors(self):
# registers one 128x128 camera looking at the robot, cube, and target
# a smaller sized camera will be lower quality, but render faster
pose = look_at(eye=[0.3, 0, 0.6], target=[-0.1, 0, 0.1])
pose = sapien_utils.look_at(eye=[0.3, 0, 0.6], target=[-0.1, 0, 0.1])
return [
CameraConfig("base_camera", pose.p, pose.q, 128, 128, np.pi / 2, 0.01, 10)
]

def _register_human_render_cameras(self):
# registers a more high-definition (512x512) camera used just for rendering when render_mode="rgb_array" or calling env.render_rgb_array()
pose = look_at([0.6, 0.7, 0.6], [0.0, 0.0, 0.35])
pose = sapien_utils.look_at([0.6, 0.7, 0.6], [0.0, 0.0, 0.35])
return CameraConfig("render_camera", pose.p, pose.q, 512, 512, 1, 0.01, 10)

def _load_actors(self):
Expand Down
6 changes: 3 additions & 3 deletions mani_skill2/envs/tasks/quadruped_run.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,10 @@
from mani_skill2.agents.robots.panda.panda import Panda
from mani_skill2.envs.sapien_env import BaseEnv
from mani_skill2.sensors.camera import CameraConfig
from mani_skill2.utils import sapien_utils
from mani_skill2.utils.building import actors
from mani_skill2.utils.building.ground import build_ground, build_meter_ground
from mani_skill2.utils.registration import register_env
from mani_skill2.utils.sapien_utils import look_at
from mani_skill2.utils.structs.pose import Pose
from mani_skill2.utils.structs.types import GPUMemoryConfig, SceneConfig, SimConfig

Expand Down Expand Up @@ -69,7 +69,7 @@ def __init__(self, *args, robot_uids="anymal-c", **kwargs):
super().__init__(*args, robot_uids=robot_uids, **kwargs)

def _register_sensors(self):
pose = look_at([1.5, 1.5, 1], [0.0, 0.0, 0])
pose = sapien_utils.look_at([1.5, 1.5, 1], [0.0, 0.0, 0])
return [
CameraConfig(
"base_camera",
Expand All @@ -85,7 +85,7 @@ def _register_sensors(self):
]

def _register_human_render_cameras(self):
pose = look_at([2.5, 2.5, 1], [0.0, 0.0, 0])
pose = sapien_utils.look_at([2.5, 2.5, 1], [0.0, 0.0, 0])
return CameraConfig(
"render_camera",
pose.p,
Expand Down

0 comments on commit 67b4b01

Please sign in to comment.