diff --git a/mani_skill2/agents/base_agent.py b/mani_skill2/agents/base_agent.py index 05d0dc1b0..f21fc9e1f 100644 --- a/mani_skill2/agents/base_agent.py +++ b/mani_skill2/agents/base_agent.py @@ -11,13 +11,8 @@ from mani_skill2 import format_path from mani_skill2.sensors.base_sensor import BaseSensor, BaseSensorConfig -from mani_skill2.utils.sapien_utils import ( - apply_urdf_config, - check_urdf_config, - parse_urdf_config, -) -from mani_skill2.utils.structs.actor import Actor -from mani_skill2.utils.structs.articulation import Articulation +from mani_skill2.utils import sapien_utils +from mani_skill2.utils.structs import Actor, Articulation from .controllers.base_controller import ( BaseController, @@ -98,11 +93,11 @@ def _load_articulation(self): urdf_path = format_path(str(self.urdf_path)) - urdf_config = parse_urdf_config(self.urdf_config, self.scene) - check_urdf_config(urdf_config) + urdf_config = sapien_utils.parse_urdf_config(self.urdf_config, self.scene) + sapien_utils.check_urdf_config(urdf_config) # TODO(jigu): support loading multiple convex collision shapes - apply_urdf_config(loader, urdf_config) + sapien_utils.apply_urdf_config(loader, urdf_config) self.robot: Articulation = loader.load(urdf_path) assert self.robot is not None, f"Fail to load URDF from {urdf_path}" diff --git a/mani_skill2/agents/controllers/base_controller.py b/mani_skill2/agents/controllers/base_controller.py index c6fcf333b..c88cf38f2 100644 --- a/mani_skill2/agents/controllers/base_controller.py +++ b/mani_skill2/agents/controllers/base_controller.py @@ -16,8 +16,8 @@ get_active_joint_indices, get_joints_by_names, ) +from mani_skill2.utils import sapien_utils from mani_skill2.utils.common import clip_and_scale_action, normalize_action_space -from mani_skill2.utils.sapien_utils import to_tensor from mani_skill2.utils.structs.articulation import Articulation from mani_skill2.utils.structs.joint import Joint from mani_skill2.utils.structs.types import Array @@ -37,8 +37,10 @@ class BaseController: """the action space. If the number of parallel environments is > 1, this action space is also batched""" single_action_space: spaces.Space """The unbatched version of the action space which is also typically already normalized by this class""" + """The batched version of the action space which is also typically already normalized by this class""" _original_single_action_space: spaces.Space """The unbatched, original action space without any additional processing like normalization""" + """The batched, original action space without any additional processing like normalization""" def __init__( self, @@ -162,8 +164,8 @@ def _clip_and_scale_action_space(self): self._original_single_action_space.low, self._original_single_action_space.high, ) - self.action_space_low = to_tensor(low) - self.action_space_high = to_tensor(high) + self.action_space_low = sapien_utils.to_tensor(low) + self.action_space_high = sapien_utils.to_tensor(high) def _clip_and_scale_action(self, action): return clip_and_scale_action( @@ -251,7 +253,7 @@ def reset(self): def set_action(self, action: Dict[str, np.ndarray]): for uid, controller in self.controllers.items(): - controller.set_action(to_tensor(action[uid])) + controller.set_action(sapien_utils.to_tensor(action[uid])) def before_simulation_step(self): if physx.is_gpu_enabled(): diff --git a/mani_skill2/agents/controllers/pd_ee_pose.py b/mani_skill2/agents/controllers/pd_ee_pose.py index d3f51ff2c..846f90704 100644 --- a/mani_skill2/agents/controllers/pd_ee_pose.py +++ b/mani_skill2/agents/controllers/pd_ee_pose.py @@ -12,12 +12,12 @@ import torch from gymnasium import spaces +from mani_skill2.utils import sapien_utils from mani_skill2.utils.common import clip_and_scale_action from mani_skill2.utils.geometry.rotation_conversions import ( euler_angles_to_matrix, matrix_to_quaternion, ) -from mani_skill2.utils.sapien_utils import get_obj_by_name, to_numpy, to_tensor from mani_skill2.utils.structs.pose import Pose, vectorize_pose from mani_skill2.utils.structs.types import Array @@ -60,7 +60,7 @@ def suppress_stdout_stderr(): self.qmask[self.joint_indices] = 1 if self.config.ee_link: - self.ee_link = get_obj_by_name( + self.ee_link = sapien_utils.get_obj_by_name( self.articulation.get_links(), self.config.ee_link ) else: @@ -112,12 +112,14 @@ def compute_ik(self, target_pose: Pose, action: Array, max_iterations=100): result, success, error = self.pmodel.compute_inverse_kinematics( self.ee_link_idx, target_pose.sp, - initial_qpos=to_numpy(self.articulation.get_qpos()).squeeze(0), + initial_qpos=sapien_utils.to_numpy( + self.articulation.get_qpos() + ).squeeze(0), active_qmask=self.qmask, max_iterations=max_iterations, ) if success: - return to_tensor([result[self.joint_indices]]) + return sapien_utils.to_tensor([result[self.joint_indices]]) else: return None diff --git a/mani_skill2/agents/controllers/pd_joint_pos.py b/mani_skill2/agents/controllers/pd_joint_pos.py index cd1a5b958..f3e071709 100644 --- a/mani_skill2/agents/controllers/pd_joint_pos.py +++ b/mani_skill2/agents/controllers/pd_joint_pos.py @@ -5,7 +5,7 @@ import torch from gymnasium import spaces -from mani_skill2.utils.sapien_utils import to_tensor +from mani_skill2.utils import sapien_utils from mani_skill2.utils.structs.types import Array from .base_controller import BaseController, ControllerConfig @@ -67,7 +67,7 @@ def set_drive_targets(self, targets): def set_action(self, action: Array): action = self._preprocess_action(action) - action = to_tensor(action) + action = sapien_utils.to_tensor(action) self._step = 0 self._start_qpos = self.qpos if self.config.use_delta: diff --git a/mani_skill2/agents/robots/_template/template_robot.py b/mani_skill2/agents/robots/_template/template_robot.py index 192aa8655..ef505de2f 100644 --- a/mani_skill2/agents/robots/_template/template_robot.py +++ b/mani_skill2/agents/robots/_template/template_robot.py @@ -2,12 +2,6 @@ from mani_skill2.agents.base_agent import BaseAgent from mani_skill2.agents.controllers import * from mani_skill2.sensors.camera import CameraConfig -from mani_skill2.utils.sapien_utils import ( - compute_total_impulse, - get_actor_contacts, - get_obj_by_name, - get_pairwise_contact_impulse, -) class TemplateRobot(BaseAgent): diff --git a/mani_skill2/agents/robots/allegro_hand/allegro.py b/mani_skill2/agents/robots/allegro_hand/allegro.py index db0efb879..b10b7ba78 100644 --- a/mani_skill2/agents/robots/allegro_hand/allegro.py +++ b/mani_skill2/agents/robots/allegro_hand/allegro.py @@ -8,7 +8,7 @@ from mani_skill2.agents.base_agent import BaseAgent from mani_skill2.agents.controllers import * from mani_skill2.agents.registration import register_agent -from mani_skill2.utils.sapien_utils import get_obj_by_name, get_objs_by_names +from mani_skill2.utils import sapien_utils from mani_skill2.utils.structs.pose import vectorize_pose @@ -73,10 +73,10 @@ def __init__(self, *args, **kwargs): super().__init__(*args, **kwargs) def _after_init(self): - self.tip_links: List[sapien.Entity] = get_objs_by_names( + self.tip_links: List[sapien.Entity] = sapien_utils.get_objs_by_names( self.robot.get_links(), self.tip_link_names ) - self.palm_link: sapien.Entity = get_obj_by_name( + self.palm_link: sapien.Entity = sapien_utils.get_obj_by_name( self.robot.get_links(), self.palm_link_name ) diff --git a/mani_skill2/agents/robots/allegro_hand/allegro_touch.py b/mani_skill2/agents/robots/allegro_hand/allegro_touch.py index d2c976ef5..910c3cb7b 100644 --- a/mani_skill2/agents/robots/allegro_hand/allegro_touch.py +++ b/mani_skill2/agents/robots/allegro_hand/allegro_touch.py @@ -9,12 +9,7 @@ from mani_skill2 import PACKAGE_ASSET_DIR from mani_skill2.agents.registration import register_agent from mani_skill2.agents.robots.allegro_hand.allegro import AllegroHandRight -from mani_skill2.utils.sapien_utils import ( - compute_total_impulse, - get_actors_contacts, - get_multiple_pairwise_contacts, - get_objs_by_names, -) +from mani_skill2.utils import sapien_utils from mani_skill2.utils.structs.actor import Actor @@ -59,7 +54,7 @@ def __init__(self, *args, **kwargs): def _after_init(self): super()._after_init() - self.fsr_links: List[Actor] = get_objs_by_names( + self.fsr_links: List[Actor] = sapien_utils.get_objs_by_names( self.robot.get_links(), self.palm_fsr_link_names + self.finger_fsr_link_names, ) @@ -100,7 +95,8 @@ def get_fsr_obj_impulse(self, obj: Actor = None): ) sorted_contacts = [obj_contacts[link] for link in internal_fsr_links] contact_forces = [ - compute_total_impulse(contact) for contact in sorted_contacts + sapien_utils.compute_total_impulse(contact) + for contact in sorted_contacts ] return np.stack(contact_forces) @@ -133,10 +129,11 @@ def get_fsr_impulse(self): else: internal_fsr_links = [link._bodies[0].entity for link in self.fsr_links] contacts = self.scene.get_contacts() - contact_map = get_actors_contacts(contacts, internal_fsr_links) + contact_map = sapien_utils.get_actors_contacts(contacts, internal_fsr_links) sorted_contacts = [contact_map[link] for link in internal_fsr_links] contact_forces = [ - compute_total_impulse(contact) for contact in sorted_contacts + sapien_utils.compute_total_impulse(contact) + for contact in sorted_contacts ] contact_impulse = torch.from_numpy( diff --git a/mani_skill2/agents/robots/anymal/__init__.py b/mani_skill2/agents/robots/anymal/__init__.py new file mode 100644 index 000000000..4d8ef6200 --- /dev/null +++ b/mani_skill2/agents/robots/anymal/__init__.py @@ -0,0 +1 @@ +from .anymal_c import ANYmalC diff --git a/mani_skill2/agents/robots/anymal/anymal_c.py b/mani_skill2/agents/robots/anymal/anymal_c.py index 122511ab7..100d76330 100644 --- a/mani_skill2/agents/robots/anymal/anymal_c.py +++ b/mani_skill2/agents/robots/anymal/anymal_c.py @@ -1,14 +1,11 @@ +# TODO (stao): Anymal may not be modelled correctly or efficiently at the moment import torch from mani_skill2 import PACKAGE_ASSET_DIR, format_path from mani_skill2.agents.base_agent import BaseAgent from mani_skill2.agents.controllers import * from mani_skill2.agents.registration import register_agent -from mani_skill2.utils.sapien_utils import ( - apply_urdf_config, - check_urdf_config, - parse_urdf_config, -) +from mani_skill2.utils import sapien_utils from mani_skill2.utils.structs.articulation import Articulation @@ -82,11 +79,11 @@ def _load_articulation(self): urdf_path = format_path(str(self.urdf_path)) - urdf_config = parse_urdf_config(self.urdf_config, self.scene) - check_urdf_config(urdf_config) + urdf_config = sapien_utils.parse_urdf_config(self.urdf_config, self.scene) + sapien_utils.check_urdf_config(urdf_config) # TODO(jigu): support loading multiple convex collision shapes - apply_urdf_config(loader, urdf_config) + sapien_utils.apply_urdf_config(loader, urdf_config) loader.disable_self_collisions = True self.robot: Articulation = loader.load(urdf_path) assert self.robot is not None, f"Fail to load URDF from {urdf_path}" diff --git a/mani_skill2/agents/robots/dclaw/dclaw.py b/mani_skill2/agents/robots/dclaw/dclaw.py index eb76819a7..abcd39599 100644 --- a/mani_skill2/agents/robots/dclaw/dclaw.py +++ b/mani_skill2/agents/robots/dclaw/dclaw.py @@ -8,7 +8,7 @@ from mani_skill2.agents.controllers import * from mani_skill2.agents.registration import register_agent from mani_skill2.agents.utils import get_active_joint_indices -from mani_skill2.utils.sapien_utils import get_objs_by_names +from mani_skill2.utils import sapien_utils from mani_skill2.utils.structs.joint import Joint from mani_skill2.utils.structs.link import Link from mani_skill2.utils.structs.pose import vectorize_pose @@ -52,7 +52,7 @@ def __init__(self, *args, **kwargs): super().__init__(*args, **kwargs) def _after_init(self): - self.tip_links: List[Link] = get_objs_by_names( + self.tip_links: List[Link] = sapien_utils.get_objs_by_names( self.robot.get_links(), self.tip_link_names ) self.root_joints: List[Joint] = [ diff --git a/mani_skill2/agents/robots/fetch/fetch.py b/mani_skill2/agents/robots/fetch/fetch.py index da65e544a..d034f18d5 100644 --- a/mani_skill2/agents/robots/fetch/fetch.py +++ b/mani_skill2/agents/robots/fetch/fetch.py @@ -11,14 +11,8 @@ from mani_skill2.agents.controllers import * from mani_skill2.agents.registration import register_agent from mani_skill2.sensors.camera import CameraConfig +from mani_skill2.utils import sapien_utils from mani_skill2.utils.common import compute_angle_between, np_compute_angle_between -from mani_skill2.utils.sapien_utils import ( - compute_total_impulse, - get_actor_contacts, - get_obj_by_name, - get_pairwise_contact_impulse, - to_tensor, -) from mani_skill2.utils.structs.actor import Actor from mani_skill2.utils.structs.base import BaseStruct from mani_skill2.utils.structs.joint import Joint @@ -332,19 +326,23 @@ def controller_configs(self): return deepcopy_dict(controller_configs) def _after_init(self): - self.finger1_link: Link = get_obj_by_name( + self.finger1_link: Link = sapien_utils.get_obj_by_name( self.robot.get_links(), "l_gripper_finger_link" ) - self.finger2_link: Link = get_obj_by_name( + self.finger2_link: Link = sapien_utils.get_obj_by_name( self.robot.get_links(), "r_gripper_finger_link" ) - self.tcp: Link = get_obj_by_name(self.robot.get_links(), self.ee_link_name) + self.tcp: Link = sapien_utils.get_obj_by_name( + self.robot.get_links(), self.ee_link_name + ) - self.base_link: Link = get_obj_by_name(self.robot.get_links(), "base_link") - self.l_wheel_link: Link = get_obj_by_name( + self.base_link: Link = sapien_utils.get_obj_by_name( + self.robot.get_links(), "base_link" + ) + self.l_wheel_link: Link = sapien_utils.get_obj_by_name( self.robot.get_links(), "l_wheel_link" ) - self.r_wheel_link: Link = get_obj_by_name( + self.r_wheel_link: Link = sapien_utils.get_obj_by_name( self.robot.get_links(), "r_wheel_link" ) for link in [self.l_wheel_link, self.r_wheel_link]: @@ -354,11 +352,11 @@ def _after_init(self): cg[2] |= FETCH_UNIQUE_COLLISION_BIT cs.set_collision_groups(cg) - self.torso_lift_link: Link = get_obj_by_name( + self.torso_lift_link: Link = sapien_utils.get_obj_by_name( self.robot.get_links(), "torso_lift_link" ) - self.head_camera_link: Link = get_obj_by_name( + self.head_camera_link: Link = sapien_utils.get_obj_by_name( self.robot.get_links(), "head_camera_link" ) @@ -405,25 +403,27 @@ def is_grasping(self, object: Actor = None, min_impulse=1e-6, max_angle=85): contacts = self.scene.get_contacts() if object is None: - finger1_contacts = get_actor_contacts( + finger1_contacts = sapien_utils.get_actor_contacts( contacts, self.finger1_link._bodies[0].entity ) - finger2_contacts = get_actor_contacts( + finger2_contacts = sapien_utils.get_actor_contacts( contacts, self.finger2_link._bodies[0].entity ) return ( - np.linalg.norm(compute_total_impulse(finger1_contacts)) + np.linalg.norm(sapien_utils.compute_total_impulse(finger1_contacts)) >= min_impulse - and np.linalg.norm(compute_total_impulse(finger2_contacts)) + and np.linalg.norm( + sapien_utils.compute_total_impulse(finger2_contacts) + ) >= min_impulse ) else: - limpulse = get_pairwise_contact_impulse( + limpulse = sapien_utils.get_pairwise_contact_impulse( contacts, self.finger1_link._bodies[0].entity, object._bodies[0].entity, ) - rimpulse = get_pairwise_contact_impulse( + rimpulse = sapien_utils.get_pairwise_contact_impulse( contacts, self.finger2_link._bodies[0].entity, object._bodies[0].entity, diff --git a/mani_skill2/agents/robots/panda/panda.py b/mani_skill2/agents/robots/panda/panda.py index 096f3e75f..909507f9a 100644 --- a/mani_skill2/agents/robots/panda/panda.py +++ b/mani_skill2/agents/robots/panda/panda.py @@ -10,14 +10,8 @@ from mani_skill2.agents.base_agent import BaseAgent from mani_skill2.agents.controllers import * from mani_skill2.agents.registration import register_agent -from mani_skill2.sensors.camera import CameraConfig +from mani_skill2.utils import sapien_utils from mani_skill2.utils.common import compute_angle_between, np_compute_angle_between -from mani_skill2.utils.sapien_utils import ( - compute_total_impulse, - get_actor_contacts, - get_obj_by_name, - get_pairwise_contact_impulse, -) from mani_skill2.utils.structs.actor import Actor @@ -204,15 +198,21 @@ def controller_configs(self): sensor_configs = [] def _after_init(self): - self.finger1_link = get_obj_by_name(self.robot.get_links(), "panda_leftfinger") - self.finger2_link = get_obj_by_name(self.robot.get_links(), "panda_rightfinger") - self.finger1pad_link = get_obj_by_name( + self.finger1_link = sapien_utils.get_obj_by_name( + self.robot.get_links(), "panda_leftfinger" + ) + self.finger2_link = sapien_utils.get_obj_by_name( + self.robot.get_links(), "panda_rightfinger" + ) + self.finger1pad_link = sapien_utils.get_obj_by_name( self.robot.get_links(), "panda_leftfinger_pad" ) - self.finger2pad_link = get_obj_by_name( + self.finger2pad_link = sapien_utils.get_obj_by_name( self.robot.get_links(), "panda_rightfinger_pad" ) - self.tcp = get_obj_by_name(self.robot.get_links(), self.ee_link_name) + self.tcp = sapien_utils.get_obj_by_name( + self.robot.get_links(), self.ee_link_name + ) self.queries: Dict[ str, Tuple[physx.PhysxGpuContactPairImpulseQuery, Tuple[int]] @@ -257,19 +257,25 @@ def is_grasping(self, object: Actor = None, min_impulse=1e-6, max_angle=85): contacts = self.scene.get_contacts() if object is None: - finger1_contacts = get_actor_contacts(contacts, self.finger1_link) - finger2_contacts = get_actor_contacts(contacts, self.finger2_link) + finger1_contacts = sapien_utils.get_actor_contacts( + contacts, self.finger1_link + ) + finger2_contacts = sapien_utils.get_actor_contacts( + contacts, self.finger2_link + ) return ( - np.linalg.norm(compute_total_impulse(finger1_contacts)) + np.linalg.norm(sapien_utils.compute_total_impulse(finger1_contacts)) >= min_impulse - and np.linalg.norm(compute_total_impulse(finger2_contacts)) + and np.linalg.norm( + sapien_utils.compute_total_impulse(finger2_contacts) + ) >= min_impulse ) else: - limpulse = get_pairwise_contact_impulse( + limpulse = sapien_utils.get_pairwise_contact_impulse( contacts, self.finger1_link, object ) - rimpulse = get_pairwise_contact_impulse( + rimpulse = sapien_utils.get_pairwise_contact_impulse( contacts, self.finger2_link, object ) diff --git a/mani_skill2/agents/robots/xarm/xarm7_ability.py b/mani_skill2/agents/robots/xarm/xarm7_ability.py index d115e4bbf..70755cfc0 100644 --- a/mani_skill2/agents/robots/xarm/xarm7_ability.py +++ b/mani_skill2/agents/robots/xarm/xarm7_ability.py @@ -7,7 +7,7 @@ from mani_skill2.agents.base_agent import BaseAgent from mani_skill2.agents.controllers import * from mani_skill2.agents.registration import register_agent -from mani_skill2.utils.sapien_utils import get_obj_by_name, get_objs_by_names +from mani_skill2.utils import sapien_utils @register_agent() @@ -155,7 +155,7 @@ def _after_init(self): "ring_L2", "pinky_L2", ] - self.hand_front_links = get_objs_by_names( + self.hand_front_links = sapien_utils.get_objs_by_names( self.robot.get_links(), hand_front_link_names ) @@ -166,10 +166,12 @@ def _after_init(self): "ring_tip", "pinky_tip", ] - self.finger_tip_links = get_objs_by_names( + self.finger_tip_links = sapien_utils.get_objs_by_names( self.robot.get_links(), finger_tip_link_names ) - self.tcp = get_obj_by_name(self.robot.get_links(), self.ee_link_name) + self.tcp = sapien_utils.get_obj_by_name( + self.robot.get_links(), self.ee_link_name + ) self.queries: Dict[str, Tuple[physx.PhysxGpuContactQuery, Tuple[int]]] = dict() diff --git a/mani_skill2/agents/robots/xmate3/xmate3.py b/mani_skill2/agents/robots/xmate3/xmate3.py index f8d3b2433..a5f2b54c2 100644 --- a/mani_skill2/agents/robots/xmate3/xmate3.py +++ b/mani_skill2/agents/robots/xmate3/xmate3.py @@ -10,13 +10,8 @@ from mani_skill2.agents.controllers import * from mani_skill2.agents.registration import register_agent from mani_skill2.sensors.camera import CameraConfig +from mani_skill2.utils import sapien_utils from mani_skill2.utils.common import compute_angle_between, np_compute_angle_between -from mani_skill2.utils.sapien_utils import ( - compute_total_impulse, - get_actor_contacts, - get_obj_by_name, - get_pairwise_contact_impulse, -) from mani_skill2.utils.structs.actor import Actor @@ -71,13 +66,15 @@ def __init__( super().__init__(scene, control_freq, control_mode, fix_root_link, agent_idx) def _after_init(self): - self.finger1_link = get_obj_by_name( + self.finger1_link = sapien_utils.get_obj_by_name( self.robot.get_links(), "left_inner_finger_pad" ) - self.finger2_link = get_obj_by_name( + self.finger2_link = sapien_utils.get_obj_by_name( self.robot.get_links(), "right_inner_finger_pad" ) - self.tcp = get_obj_by_name(self.robot.get_links(), self.ee_link_name) + self.tcp = sapien_utils.get_obj_by_name( + self.robot.get_links(), self.ee_link_name + ) self.queries: Dict[ str, Tuple[physx.PhysxGpuContactPairImpulseQuery, Tuple[int]] ] = dict() @@ -221,19 +218,25 @@ def is_grasping(self, object: Actor = None, min_impulse=1e-6, max_angle=85): contacts = self.scene.get_contacts() if object is None: - finger1_contacts = get_actor_contacts(contacts, self.finger1_link) - finger2_contacts = get_actor_contacts(contacts, self.finger2_link) + finger1_contacts = sapien_utils.get_actor_contacts( + contacts, self.finger1_link + ) + finger2_contacts = sapien_utils.get_actor_contacts( + contacts, self.finger2_link + ) return ( - np.linalg.norm(compute_total_impulse(finger1_contacts)) + np.linalg.norm(sapien_utils.compute_total_impulse(finger1_contacts)) >= min_impulse - and np.linalg.norm(compute_total_impulse(finger2_contacts)) + and np.linalg.norm( + sapien_utils.compute_total_impulse(finger2_contacts) + ) >= min_impulse ) else: - limpulse = get_pairwise_contact_impulse( + limpulse = sapien_utils.get_pairwise_contact_impulse( contacts, self.finger1_link, object ) - rimpulse = get_pairwise_contact_impulse( + rimpulse = sapien_utils.get_pairwise_contact_impulse( contacts, self.finger2_link, object ) diff --git a/mani_skill2/agents/utils.py b/mani_skill2/agents/utils.py index b7a0b1651..e972aeada 100644 --- a/mani_skill2/agents/utils.py +++ b/mani_skill2/agents/utils.py @@ -7,7 +7,7 @@ import sapien.physx as physx from gymnasium import spaces -from mani_skill2.utils.sapien_utils import to_tensor +from mani_skill2.utils import sapien_utils from mani_skill2.utils.structs.articulation import Articulation @@ -15,7 +15,7 @@ def get_active_joint_indices(articulation: Articulation, joint_names: Sequence[s """get the indices of the provided joint names from the Articulation's list of active joints""" all_joint_names = [x.name for x in articulation.get_active_joints()] joint_indices = [all_joint_names.index(x) for x in joint_names] - return to_tensor(joint_indices).int() + return sapien_utils.to_tensor(joint_indices).int() def get_joints_by_names(articulation: Articulation, joint_names: Sequence[str]): diff --git a/mani_skill2/envs/minimal_template.py b/mani_skill2/envs/minimal_template.py index 533f8dcac..449fdc8b3 100644 --- a/mani_skill2/envs/minimal_template.py +++ b/mani_skill2/envs/minimal_template.py @@ -8,8 +8,8 @@ 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.registration import register_env -from mani_skill2.utils.sapien_utils import look_at from mani_skill2.utils.structs.types import GPUMemoryConfig, SimConfig @@ -42,13 +42,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): diff --git a/mani_skill2/envs/sapien_env.py b/mani_skill2/envs/sapien_env.py index 59cb4dcd3..6d1faf4c5 100644 --- a/mani_skill2/envs/sapien_env.py +++ b/mani_skill2/envs/sapien_env.py @@ -21,7 +21,7 @@ from mani_skill2.agents.base_agent import BaseAgent from mani_skill2.agents.multi_agent import MultiAgent from mani_skill2.envs.scene import ManiSkillScene -from mani_skill2.envs.utils.observations.observations import ( +from mani_skill2.envs.utils.observations import ( sensor_data_to_pointcloud, sensor_data_to_rgbd, ) @@ -33,18 +33,12 @@ update_camera_cfgs_from_dict, ) from mani_skill2.sensors.depth_camera import StereoDepthCamera, StereoDepthCameraConfig +from mani_skill2.utils import sapien_utils from mani_skill2.utils.common import ( convert_observation_to_space, dict_merge, flatten_state_dict, ) -from mani_skill2.utils.sapien_utils import ( - batch, - get_obj_by_type, - to_numpy, - to_tensor, - unbatch, -) from mani_skill2.utils.structs.actor import Actor from mani_skill2.utils.structs.articulation import Articulation from mani_skill2.utils.structs.types import Array, SimConfig @@ -238,10 +232,10 @@ def __init__( ) obs, _ = self.reset(seed=2022, options=dict(reconfigure=True)) if physx.is_gpu_enabled(): - obs = to_numpy(obs) + obs = sapien_utils.to_numpy(obs) self._init_raw_obs = obs.copy() """the raw observation returned by the env.reset. Useful for future observation wrappers to use to auto generate observation spaces""" - self._init_raw_state = to_numpy(self.get_state_dict()) + self._init_raw_state = sapien_utils.to_numpy(self.get_state_dict()) """the initial raw state returned by env.get_state. Useful for reconstructing state dictionaries from flattened state vectors""" self.action_space = self.agent.action_space @@ -660,7 +654,7 @@ def reset(self, seed=None, options=None): self._scene._gpu_fetch_all() obs = self.get_obs() if not physx.is_gpu_enabled(): - obs = to_numpy(unbatch(obs)) + obs = sapien_utils.to_numpy(sapien_utils.unbatch(obs)) self._elapsed_steps = 0 return obs, {} @@ -759,12 +753,12 @@ def step(self, action: Union[None, np.ndarray, torch.Tensor, Dict]): ) else: # On CPU sim mode, we always return numpy / python primitives without any batching. - return unbatch( - to_numpy(obs), - to_numpy(reward), - to_numpy(terminated), + return sapien_utils.unbatch( + sapien_utils.to_numpy(obs), + sapien_utils.to_numpy(reward), + sapien_utils.to_numpy(terminated), False, - to_numpy(info), + sapien_utils.to_numpy(info), ) def step_action( @@ -775,7 +769,7 @@ def step_action( if action is None: # simulation without action pass elif isinstance(action, np.ndarray) or isinstance(action, torch.Tensor): - action = to_tensor(action) + action = sapien_utils.to_tensor(action) if action.shape == self._orig_single_action_space.shape: action_is_unbatched = True set_action = True @@ -784,13 +778,13 @@ def step_action( if action["control_mode"] != self.agent.control_mode: self.agent.set_control_mode(action["control_mode"]) self.agent.controller.reset() - action = to_tensor(action["action"]) + action = sapien_utils.to_tensor(action["action"]) else: assert isinstance( self.agent, MultiAgent ), "Received a dictionary for an action but there are not multiple robots in the environment" # assume this is a multi-agent action - action = to_tensor(action) + action = sapien_utils.to_tensor(action) for k, a in action.items(): if a.shape == self._orig_single_action_space[k].shape: action_is_unbatched = True @@ -801,7 +795,7 @@ def step_action( if set_action: if self.num_envs == 1 and action_is_unbatched: - action = batch(action) + action = sapien_utils.batch(action) self.agent.set_action(action) if physx.is_gpu_enabled(): self._scene.px.gpu_apply_articulation_target_position() @@ -990,7 +984,7 @@ def _setup_viewer(self): # CAUTION: `set_scene` should be called after assets are loaded. self._viewer.set_scene(self._scene.sub_scenes[0]) control_window: sapien.utils.viewer.control_window.ControlWindow = ( - get_obj_by_type( + sapien_utils.get_obj_by_type( self._viewer.plugins, sapien.utils.viewer.control_window.ControlWindow ) ) diff --git a/mani_skill2/envs/scenes/base_env.py b/mani_skill2/envs/scenes/base_env.py index d80f50fbd..63ea3b6ed 100644 --- a/mani_skill2/envs/scenes/base_env.py +++ b/mani_skill2/envs/scenes/base_env.py @@ -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 ( @@ -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, @@ -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, @@ -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) diff --git a/mani_skill2/envs/tasks/__init__.py b/mani_skill2/envs/tasks/__init__.py index 9606f63b9..42ad0c2ac 100644 --- a/mani_skill2/envs/tasks/__init__.py +++ b/mani_skill2/envs/tasks/__init__.py @@ -1,6 +1,6 @@ -from .dexterity import RotateValveEnv +from .dexterity import RotateSingleObjectInHand, RotateValveEnv from .empty_env import EmptyEnv -from .fmb.fmb import FMBAssembly1Env +from .fmb import FMBAssembly1Env from .open_cabinet_drawer import OpenCabinetDoorEnv, OpenCabinetDrawerEnv from .pick_cube import PickCubeEnv from .pick_single_ycb import PickSingleYCBEnv @@ -10,4 +10,3 @@ from .stack_cube import StackCubeEnv from .two_robot_pick_cube import TwoRobotPickCube from .two_robot_stack_cube import TwoRobotStackCube -from .dexterity import RotateValveEnv, RotateSingleObjectInHand diff --git a/mani_skill2/envs/tasks/dexterity/rotate_single_object_in_hand.py b/mani_skill2/envs/tasks/dexterity/rotate_single_object_in_hand.py index b7d1abad2..22531c8cb 100644 --- a/mani_skill2/envs/tasks/dexterity/rotate_single_object_in_hand.py +++ b/mani_skill2/envs/tasks/dexterity/rotate_single_object_in_hand.py @@ -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, @@ -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 @@ -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): diff --git a/mani_skill2/envs/tasks/dexterity/rotate_valve.py b/mani_skill2/envs/tasks/dexterity/rotate_valve.py index b06a4272f..566ec89ce 100644 --- a/mani_skill2/envs/tasks/dexterity/rotate_valve.py +++ b/mani_skill2/envs/tasks/dexterity/rotate_valve.py @@ -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 @@ -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): @@ -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): diff --git a/mani_skill2/envs/tasks/empty_env.py b/mani_skill2/envs/tasks/empty_env.py index eac22e2e9..606d3b994 100644 --- a/mani_skill2/envs/tasks/empty_env.py +++ b/mani_skill2/envs/tasks/empty_env.py @@ -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 @@ -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): diff --git a/mani_skill2/envs/tasks/fmb/__init__.py b/mani_skill2/envs/tasks/fmb/__init__.py new file mode 100644 index 000000000..0122f5d7b --- /dev/null +++ b/mani_skill2/envs/tasks/fmb/__init__.py @@ -0,0 +1 @@ +from .fmb import FMBAssembly1Env diff --git a/mani_skill2/envs/tasks/fmb/fmb.py b/mani_skill2/envs/tasks/fmb/fmb.py index 6345add67..69245e30c 100644 --- a/mani_skill2/envs/tasks/fmb/fmb.py +++ b/mani_skill2/envs/tasks/fmb/fmb.py @@ -10,15 +10,14 @@ 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 -@register_env("FMBAssembly1-v0", max_episode_steps=200) +# TODO (stao): Complete this task example +# @register_env("FMBAssembly1-v0", max_episode_steps=200) class FMBAssembly1Env(BaseEnv): """ Task Description @@ -45,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): diff --git a/mani_skill2/envs/tasks/open_cabinet_drawer.py b/mani_skill2/envs/tasks/open_cabinet_drawer.py index 4e8638944..7ea1d4c00 100644 --- a/mani_skill2/envs/tasks/open_cabinet_drawer.py +++ b/mani_skill2/envs/tasks/open_cabinet_drawer.py @@ -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, @@ -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 @@ -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) @@ -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 diff --git a/mani_skill2/envs/tasks/pick_cube.py b/mani_skill2/envs/tasks/pick_cube.py index c82fff98b..8e51a66c1 100644 --- a/mani_skill2/envs/tasks/pick_cube.py +++ b/mani_skill2/envs/tasks/pick_cube.py @@ -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 @@ -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): diff --git a/mani_skill2/envs/tasks/pick_single_ycb.py b/mani_skill2/envs/tasks/pick_single_ycb.py index 7390b5bf0..7e5351afc 100644 --- a/mani_skill2/envs/tasks/pick_single_ycb.py +++ b/mani_skill2/envs/tasks/pick_single_ycb.py @@ -11,6 +11,7 @@ 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, @@ -18,7 +19,6 @@ 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 @@ -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): diff --git a/mani_skill2/envs/tasks/push_cube.py b/mani_skill2/envs/tasks/push_cube.py index 5f9fe9b2b..e63cbca8b 100644 --- a/mani_skill2/envs/tasks/push_cube.py +++ b/mani_skill2/envs/tasks/push_cube.py @@ -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 @@ -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): diff --git a/mani_skill2/envs/tasks/quadruped_run.py b/mani_skill2/envs/tasks/quadruped_run.py index 8aeb4f323..c7cc1f7f2 100644 --- a/mani_skill2/envs/tasks/quadruped_run.py +++ b/mani_skill2/envs/tasks/quadruped_run.py @@ -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 @@ -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", @@ -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, diff --git a/mani_skill2/envs/tasks/quadruped_stand.py b/mani_skill2/envs/tasks/quadruped_stand.py index 5a16445a3..c3ddacb80 100644 --- a/mani_skill2/envs/tasks/quadruped_stand.py +++ b/mani_skill2/envs/tasks/quadruped_stand.py @@ -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 @@ -41,7 +41,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(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", @@ -57,7 +57,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, diff --git a/mani_skill2/envs/tasks/stack_cube.py b/mani_skill2/envs/tasks/stack_cube.py index 793f0ef23..dff917e46 100644 --- a/mani_skill2/envs/tasks/stack_cube.py +++ b/mani_skill2/envs/tasks/stack_cube.py @@ -11,9 +11,9 @@ from mani_skill2.envs.utils.randomization.pose import random_quaternions from mani_skill2.envs.utils.randomization.samplers import UniformPlacementSampler from mani_skill2.sensors.camera import CameraConfig +from mani_skill2.utils import sapien_utils from mani_skill2.utils.building.actors import build_cube from mani_skill2.utils.registration import register_env -from mani_skill2.utils.sapien_utils import look_at, to_tensor 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 @@ -53,17 +53,17 @@ 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): - self.cube_half_size = to_tensor([0.02] * 3) + self.cube_half_size = sapien_utils.to_tensor([0.02] * 3) self.table_scene = TableSceneBuilder( env=self, robot_init_qpos_noise=self.robot_init_qpos_noise ) diff --git a/mani_skill2/envs/tasks/two_robot_pick_cube.py b/mani_skill2/envs/tasks/two_robot_pick_cube.py index 46d0d4bcf..eb1cfb3fe 100644 --- a/mani_skill2/envs/tasks/two_robot_pick_cube.py +++ b/mani_skill2/envs/tasks/two_robot_pick_cube.py @@ -10,9 +10,9 @@ from mani_skill2.envs.sapien_env import BaseEnv from mani_skill2.envs.utils import randomization 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, to_tensor 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 @@ -59,13 +59,13 @@ def __init__( super().__init__(*args, robot_uids=robot_uids, **kwargs) def _register_sensors(self): - pose = look_at([1.0, 0, 0.75], [0.0, 0.0, 0.25]) + pose = sapien_utils.look_at([1.0, 0, 0.75], [0.0, 0.0, 0.25]) 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.4, 0.8, 0.75], [0.0, 0.1, 0.1]) + pose = sapien_utils.look_at([1.4, 0.8, 0.75], [0.0, 0.1, 0.1]) return CameraConfig("render_camera", pose.p, pose.q, 512, 512, 1, 0.01, 100) def _load_actors(self): diff --git a/mani_skill2/envs/tasks/two_robot_stack_cube.py b/mani_skill2/envs/tasks/two_robot_stack_cube.py index f173f8e92..57d363d91 100644 --- a/mani_skill2/envs/tasks/two_robot_stack_cube.py +++ b/mani_skill2/envs/tasks/two_robot_stack_cube.py @@ -10,9 +10,9 @@ 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 import actors from mani_skill2.utils.registration import register_env -from mani_skill2.utils.sapien_utils import look_at, to_tensor 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 @@ -61,18 +61,18 @@ def __init__( 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.4, 0.8, 0.75], [0.0, 0.1, 0.1]) # this perspective is good for demos - pose = look_at(eye=[0.6, 0.2, 0.4], target=[-0.1, 0, 0.1]) + # pose = sapien_utils.look_at([1.4, 0.8, 0.75], [0.0, 0.1, 0.1]) # this perspective is good for demos + pose = sapien_utils.look_at(eye=[0.6, 0.2, 0.4], target=[-0.1, 0, 0.1]) return CameraConfig("render_camera", pose.p, pose.q, 512, 512, 1, 0.01, 100) def _load_actors(self): - self.cube_half_size = to_tensor([0.02] * 3) + self.cube_half_size = sapien_utils.to_tensor([0.02] * 3) self.table_scene = TableSceneBuilder( env=self, robot_init_qpos_noise=self.robot_init_qpos_noise ) diff --git a/mani_skill2/envs/template.py b/mani_skill2/envs/template.py index 67d73b75c..0aa88294a 100644 --- a/mani_skill2/envs/template.py +++ b/mani_skill2/envs/template.py @@ -31,9 +31,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 import actors 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 @@ -95,9 +95,9 @@ def __init__(self, *args, robot_uids="panda", robot_init_qpos_noise=0.02, **kwar def _register_sensors(self): # To customize the sensors that capture images/pointclouds for the environment observations, # simply define a CameraConfig as done below for Camera sensors. You can add multiple sensors by returning a list - pose = look_at( + pose = sapien_utils.look_at( eye=[0.3, 0, 0.6], target=[-0.1, 0, 0.1] - ) # look_at is a utility to get the pose of a camera that looks at a target + ) # sapien_utils.look_at is a utility to get the pose of a camera that looks at a target # to see what all the sensors capture in the environment for observations, run env.render_sensors() which returns an rgb array you can visualize return [ @@ -106,7 +106,7 @@ def _register_sensors(self): def _register_human_render_cameras(self): # this is just like _register_sensors, but for adding cameras used for rendering when you call env.render() when render_mode="rgb_array" or 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 _setup_sensors(self): diff --git a/mani_skill2/envs/utils/__init__.py b/mani_skill2/envs/utils/__init__.py new file mode 100644 index 000000000..df4447b22 --- /dev/null +++ b/mani_skill2/envs/utils/__init__.py @@ -0,0 +1 @@ +from .observations import * diff --git a/mani_skill2/envs/utils/randomization/pose.py b/mani_skill2/envs/utils/randomization/pose.py index 851fcba00..506ddb91e 100644 --- a/mani_skill2/envs/utils/randomization/pose.py +++ b/mani_skill2/envs/utils/randomization/pose.py @@ -2,11 +2,11 @@ import torch import transforms3d +from mani_skill2.utils import sapien_utils from mani_skill2.utils.geometry.rotation_conversions import ( euler_angles_to_matrix, matrix_to_quaternion, ) -from mani_skill2.utils.sapien_utils import to_tensor from mani_skill2.utils.structs.types import Device diff --git a/mani_skill2/envs/utils/randomization/samplers.py b/mani_skill2/envs/utils/randomization/samplers.py index fb30a51cf..ebc9e04e2 100644 --- a/mani_skill2/envs/utils/randomization/samplers.py +++ b/mani_skill2/envs/utils/randomization/samplers.py @@ -6,7 +6,7 @@ import torch -from mani_skill2.utils.sapien_utils import to_tensor +from mani_skill2.utils import sapien_utils class UniformPlacementSampler: @@ -21,7 +21,7 @@ def __init__( self, bounds: Tuple[List[float], List[float]], batch_size: int ) -> None: assert len(bounds) == 2 and len(bounds[0]) == len(bounds[1]) - self._bounds = to_tensor(bounds) + self._bounds = sapien_utils.to_tensor(bounds) self._ranges = self._bounds[1] - self._bounds[0] self.fixtures_radii = None self.fixture_positions = None @@ -76,14 +76,14 @@ def sample(self, radius, max_trials, append=True, verbose=False): [self.fixture_positions, sampled_pos[None, ...]] ) if self.fixtures_radii is None: - self.fixtures_radii = to_tensor(radius).reshape( + self.fixtures_radii = sapien_utils.to_tensor(radius).reshape( 1, ) else: self.fixtures_radii = torch.concat( [ self.fixtures_radii, - to_tensor(radius).reshape( + sapien_utils.to_tensor(radius).reshape( 1, ), ] diff --git a/mani_skill2/examples/interactive_teleop.py b/mani_skill2/examples/interactive_teleop.py index ff850bdd5..3a4e547e9 100644 --- a/mani_skill2/examples/interactive_teleop.py +++ b/mani_skill2/examples/interactive_teleop.py @@ -11,7 +11,7 @@ import h5py import json from mani_skill2.trajectory.dataset import dict_to_list_of_dicts -from mani_skill2.utils.sapien_utils import get_obj_by_name +from mani_skill2.utils import sapien_utils from mani_skill2.utils.wrappers.record import RecordEpisode def main(args): output_dir = f"{args.record_dir}/teleop/{args.env_id}" @@ -110,7 +110,7 @@ def solve(env: BaseEnv, debug=False, vis=False): last_checkpoint_state = None gripper_open = True - viewer.select_entity(get_obj_by_name(env.agent.robot.links, "panda_hand")._objs[0].entity) + viewer.select_entity(sapien_utils.get_obj_by_name(env.agent.robot.links, "panda_hand")._objs[0].entity) while True: transform_window = viewer.plugins[0] diff --git a/mani_skill2/sensors/camera.py b/mani_skill2/sensors/camera.py index 3b87d8ce4..23c2ecc58 100644 --- a/mani_skill2/sensors/camera.py +++ b/mani_skill2/sensors/camera.py @@ -16,7 +16,7 @@ if TYPE_CHECKING: from mani_skill2.envs.scene import ManiSkillScene -from mani_skill2.utils.sapien_utils import get_obj_by_name, hide_entity +from mani_skill2.utils import sapien_utils from .base_sensor import BaseSensor, BaseSensorConfig @@ -133,7 +133,9 @@ def __init__( else: # if given an articulation and entity_uid (as a string), find the correct link to mount on # this is just for convenience so robot configurations can pick link to mount to by string/id - self.entity = get_obj_by_name(articulation.get_links(), entity_uid) + self.entity = sapien_utils.get_obj_by_name( + articulation.get_links(), entity_uid + ) if self.entity is None: raise RuntimeError(f"Mount entity ({entity_uid}) is not found") @@ -162,7 +164,7 @@ def __init__( if camera_cfg.hide_link: # TODO (stao): this will not work on gpu sim probably - hide_entity(self.entity) + sapien_utils.hide_entity(self.entity) # Filter texture names according to renderer type if necessary (legacy for Kuafu) self.texture_names = camera_cfg.texture_names diff --git a/mani_skill2/sensors/depth_camera.py b/mani_skill2/sensors/depth_camera.py index 14a86111a..1eeb331c5 100644 --- a/mani_skill2/sensors/depth_camera.py +++ b/mani_skill2/sensors/depth_camera.py @@ -7,7 +7,7 @@ from gymnasium import spaces from sapien.sensor import StereoDepthSensor, StereoDepthSensorConfig -from mani_skill2.utils.sapien_utils import get_obj_by_name +from mani_skill2.utils import sapien_utils from .camera import Camera, CameraConfig @@ -48,9 +48,13 @@ def __init__( self.actor = None else: if articulation is None: - self.actor = get_obj_by_name(scene.get_all_actors(), actor_uid) + self.actor = sapien_utils.get_obj_by_name( + scene.get_all_actors(), actor_uid + ) else: - self.actor = get_obj_by_name(articulation.get_links(), actor_uid) + self.actor = sapien_utils.get_obj_by_name( + articulation.get_links(), actor_uid + ) if self.actor is None: raise RuntimeError(f"Mount actor ({actor_uid}) is not found") diff --git a/mani_skill2/utils/building/actor_builder.py b/mani_skill2/utils/building/actor_builder.py index 6c5f4edee..5e50ed540 100644 --- a/mani_skill2/utils/building/actor_builder.py +++ b/mani_skill2/utils/building/actor_builder.py @@ -9,7 +9,7 @@ from sapien import ActorBuilder as SAPIENActorBuilder from sapien.wrapper.coacd import do_coacd -from mani_skill2.utils.sapien_utils import to_numpy, to_tensor +from mani_skill2.utils import sapien_utils from mani_skill2.utils.structs.actor import Actor from mani_skill2.utils.structs.pose import Pose, to_sapien_pose @@ -177,15 +177,17 @@ def build(self, name): len(self.scene_mask) == self.scene.num_envs ), "Scene mask size is not correct. Must be the same as the number of sub scenes" num_actors = np.sum(num_actors) - self.scene_mask = to_tensor(self.scene_mask) + self.scene_mask = sapien_utils.to_tensor(self.scene_mask) else: # if scene mask is none, set it here - self.scene_mask = to_tensor(torch.ones((self.scene.num_envs), dtype=bool)) + self.scene_mask = sapien_utils.to_tensor( + torch.ones((self.scene.num_envs), dtype=bool) + ) initial_pose = Pose.create(self.initial_pose) initial_pose_b = initial_pose.raw_pose.shape[0] assert initial_pose_b == 1 or initial_pose_b == num_actors - initial_pose_np = to_numpy(initial_pose.raw_pose) + initial_pose_np = sapien_utils.to_numpy(initial_pose.raw_pose) entities = [] i = 0 diff --git a/mani_skill2/utils/building/articulation_builder.py b/mani_skill2/utils/building/articulation_builder.py index 55c7987b8..be4930c64 100644 --- a/mani_skill2/utils/building/articulation_builder.py +++ b/mani_skill2/utils/building/articulation_builder.py @@ -11,7 +11,7 @@ ) from sapien.wrapper.articulation_builder import LinkBuilder -from mani_skill2.utils.sapien_utils import to_tensor +from mani_skill2.utils import sapien_utils from mani_skill2.utils.structs.articulation import Articulation if TYPE_CHECKING: @@ -111,10 +111,12 @@ def build(self, name=None, fix_root_link=None): len(self.scene_mask) == self.scene.num_envs ), "Scene mask size is not correct. Must be the same as the number of sub scenes" num_arts = np.sum(num_arts) - self.scene_mask = to_tensor(self.scene_mask) + self.scene_mask = sapien_utils.to_tensor(self.scene_mask) else: # if scene mask is none, set it here - self.scene_mask = to_tensor(torch.ones((self.scene.num_envs), dtype=bool)) + self.scene_mask = sapien_utils.to_tensor( + torch.ones((self.scene.num_envs), dtype=bool) + ) articulations = [] diff --git a/mani_skill2/utils/building/articulations.py b/mani_skill2/utils/building/articulations.py index 2088f2e0d..dcad2cc54 100644 --- a/mani_skill2/utils/building/articulations.py +++ b/mani_skill2/utils/building/articulations.py @@ -14,12 +14,12 @@ from mani_skill2 import ASSET_DIR, PACKAGE_ASSET_DIR from mani_skill2.envs.scene import ManiSkillScene +from mani_skill2.utils import sapien_utils from mani_skill2.utils.geometry.trimesh_utils import ( get_articulation_meshes, merge_meshes, ) from mani_skill2.utils.io_utils import load_json -from mani_skill2.utils.sapien_utils import apply_urdf_config, parse_urdf_config @dataclass @@ -105,8 +105,8 @@ def build_preprocessed_partnet_mobility_articulation( # loader.multiple_collisions_decomposition="coacd" loader.disable_self_collisions = True urdf_path = MODEL_DBS["PartnetMobility"]["model_urdf_paths"][model_id] - urdf_config = parse_urdf_config(urdf_config or {}, scene) - apply_urdf_config(loader, urdf_config) + urdf_config = sapien_utils.parse_urdf_config(urdf_config or {}, scene) + sapien_utils.apply_urdf_config(loader, urdf_config) articulation = loader.load(str(urdf_path), name=name, scene_mask=scene_mask) metadata = ArticulationMetadata( joints=dict(), links=dict(), movable_links=[], bbox=None, scale=loader.scale diff --git a/mani_skill2/utils/common.py b/mani_skill2/utils/common.py index 72c1157e6..2776a50b6 100644 --- a/mani_skill2/utils/common.py +++ b/mani_skill2/utils/common.py @@ -7,7 +7,7 @@ import torch from gymnasium import spaces -from mani_skill2.utils.sapien_utils import to_tensor +from mani_skill2.utils import sapien_utils from mani_skill2.utils.structs.types import Array, Device from .logging_utils import logger @@ -209,20 +209,20 @@ def flatten_state_dict( if state.size == 0: state = None if use_torch: - state = to_tensor(state) + state = sapien_utils.to_tensor(state) elif isinstance(value, (tuple, list)): state = None if len(value) == 0 else value if use_torch: - state = to_tensor(state) + state = sapien_utils.to_tensor(state) elif isinstance(value, (bool, np.bool_, int, np.int32, np.int64)): # x = np.array(1) > 0 is np.bool_ instead of ndarray state = int(value) if use_torch: - state = to_tensor(state) + state = sapien_utils.to_tensor(state) elif isinstance(value, (float, np.float32, np.float64)): state = np.float32(value) if use_torch: - state = to_tensor(state) + state = sapien_utils.to_tensor(state) elif isinstance(value, np.ndarray): if value.ndim > 2: raise AssertionError( @@ -230,7 +230,7 @@ def flatten_state_dict( ) state = value if value.size > 0 else None if use_torch: - state = to_tensor(state) + state = sapien_utils.to_tensor(state) else: is_torch_tensor = False diff --git a/mani_skill2/utils/scene_builder/replicacad/__init__.py b/mani_skill2/utils/scene_builder/replicacad/__init__.py new file mode 100644 index 000000000..61fcf83a0 --- /dev/null +++ b/mani_skill2/utils/scene_builder/replicacad/__init__.py @@ -0,0 +1 @@ +from .scene_builder import ReplicaCADSceneBuilder diff --git a/mani_skill2/utils/structs/__init__.py b/mani_skill2/utils/structs/__init__.py new file mode 100644 index 000000000..39ba971af --- /dev/null +++ b/mani_skill2/utils/structs/__init__.py @@ -0,0 +1,12 @@ +from .actor import Actor +from .articulation import Articulation +from .base import ( + BaseStruct, + PhysxRigidBodyComponentStruct, + PhysxRigidDynamicComponentStruct, +) +from .joint import Joint +from .link import Link +from .pose import Pose +from .render_camera import RenderCamera +from .types import * diff --git a/mani_skill2/utils/structs/actor.py b/mani_skill2/utils/structs/actor.py index 2e92a74d0..30f8cafef 100644 --- a/mani_skill2/utils/structs/actor.py +++ b/mani_skill2/utils/structs/actor.py @@ -10,7 +10,7 @@ import sapien.render import torch -from mani_skill2.utils.sapien_utils import to_numpy, to_tensor +from mani_skill2.utils import sapien_utils from mani_skill2.utils.structs.base import BaseStruct, PhysxRigidDynamicComponentStruct from mani_skill2.utils.structs.pose import Pose, to_sapien_pose, vectorize_pose from mani_skill2.utils.structs.types import Array @@ -130,12 +130,12 @@ def get_state(self): def set_state(self, state: Array): if physx.is_gpu_enabled(): - state = to_tensor(state) + state = sapien_utils.to_tensor(state) self.set_pose(Pose.create(state[:, :7])) self.set_linear_velocity(state[:, 7:10]) self.set_angular_velocity(state[:, 10:13]) else: - state = to_numpy(state[0]) + state = sapien_utils.to_numpy(state[0]) self.set_pose(sapien.Pose(state[0:3], state[3:7])) if self.px_body_type == "dynamic": self.set_linear_velocity(state[7:10]) diff --git a/mani_skill2/utils/structs/articulation.py b/mani_skill2/utils/structs/articulation.py index c7f210cc8..3b4de9c43 100644 --- a/mani_skill2/utils/structs/articulation.py +++ b/mani_skill2/utils/structs/articulation.py @@ -11,13 +11,8 @@ import torch import trimesh +from mani_skill2.utils import sapien_utils from mani_skill2.utils.geometry.trimesh_utils import get_component_meshes, merge_meshes -from mani_skill2.utils.sapien_utils import ( - compute_total_impulse, - get_articulation_contacts, - to_numpy, - to_tensor, -) from mani_skill2.utils.structs.base import BaseStruct from mani_skill2.utils.structs.joint import Joint from mani_skill2.utils.structs.link import Link @@ -201,7 +196,7 @@ def get_state(self): def set_state(self, state: Array): if physx.is_gpu_enabled(): - state = to_tensor(state) + state = sapien_utils.to_tensor(state) self.set_root_pose(Pose.create(state[:, :7])) self.set_root_linear_velocity(state[:, 7:10]) self.set_root_angular_velocity(state[:, 10:13]) @@ -209,7 +204,7 @@ def set_state(self, state: Array): self.set_qpos(state[:, 13 : 13 + self.max_dof]) self.set_qvel(state[:, 13 + self.max_dof :]) else: - state = to_numpy(state[0]) + state = sapien_utils.to_numpy(state[0]) self.set_root_pose(sapien.Pose(state[0:3], state[3:7])) self.set_root_linear_velocity(state[7:10]) self.set_root_angular_velocity(state[10:13]) @@ -283,13 +278,16 @@ def get_net_contact_forces(self, link_names: Union[List[str], Tuple[str]]): ) else: - body_contacts = get_articulation_contacts( + body_contacts = sapien_utils.get_articulation_contacts( self.px.get_contacts(), self._objs[0], included_links=[self.link_map[k]._objs[0] for k in link_names], ) net_force = ( - to_tensor(compute_total_impulse(body_contacts)) / self._scene.timestep + sapien_utils.to_tensor( + sapien_utils.compute_total_impulse(body_contacts) + ) + / self._scene.timestep ) return net_force[None, :] @@ -451,12 +449,12 @@ def qf(self): @qf.setter def qf(self, arg1: torch.Tensor): if physx.is_gpu_enabled(): - arg1 = to_tensor(arg1) + arg1 = sapien_utils.to_tensor(arg1) self.px.cuda_articulation_qf.torch()[ self._data_index[self._scene._reset_mask], : self.max_dof ] = arg1 else: - arg1 = to_numpy(arg1) + arg1 = sapien_utils.to_numpy(arg1) if len(arg1.shape) == 2: arg1 = arg1[0] self._objs[0].qf = arg1 @@ -489,12 +487,12 @@ def qpos(self): @qpos.setter def qpos(self, arg1: torch.Tensor): if physx.is_gpu_enabled(): - arg1 = to_tensor(arg1) + arg1 = sapien_utils.to_tensor(arg1) self.px.cuda_articulation_qpos.torch()[ self._data_index[self._scene._reset_mask], : self.max_dof ] = arg1 else: - arg1 = to_numpy(arg1) + arg1 = sapien_utils.to_numpy(arg1) if len(arg1.shape) == 2: arg1 = arg1[0] self._objs[0].qpos = arg1 @@ -511,12 +509,12 @@ def qvel(self): @qvel.setter def qvel(self, arg1: torch.Tensor): if physx.is_gpu_enabled(): - arg1 = to_tensor(arg1) + arg1 = sapien_utils.to_tensor(arg1) self.px.cuda_articulation_qvel.torch()[ self._data_index[self._scene._reset_mask], : self.max_dof ] = arg1 else: - arg1 = to_numpy(arg1) + arg1 = sapien_utils.to_numpy(arg1) if len(arg1.shape) == 2: arg1 = arg1[0] self._objs[0].qvel = arg1 @@ -528,12 +526,12 @@ def root_angular_velocity(self) -> torch.Tensor: @root_angular_velocity.setter def root_angular_velocity(self, arg1: Array) -> None: if physx.is_gpu_enabled(): - arg1 = to_tensor(arg1) + arg1 = sapien_utils.to_tensor(arg1) self.px.cuda_rigid_body_data.torch()[ self.root._body_data_index[self._scene._reset_mask], 10:13 ] = arg1 else: - arg1 = to_numpy(arg1) + arg1 = sapien_utils.to_numpy(arg1) if len(arg1.shape) == 2: arg1 = arg1[0] self._objs[0].set_root_angular_velocity(arg1) @@ -545,12 +543,12 @@ def root_linear_velocity(self) -> torch.Tensor: @root_linear_velocity.setter def root_linear_velocity(self, arg1: Array) -> None: if physx.is_gpu_enabled(): - arg1 = to_tensor(arg1) + arg1 = sapien_utils.to_tensor(arg1) self.px.cuda_rigid_body_data.torch()[ self.root._body_data_index[self._scene._reset_mask], 7:10 ] = arg1 else: - arg1 = to_numpy(arg1) + arg1 = sapien_utils.to_numpy(arg1) if len(arg1.shape) == 2: arg1 = arg1[0] self._objs[0].set_root_linear_velocity(arg1) @@ -590,7 +588,7 @@ def set_joint_drive_targets( TODO (stao): can we use joint indices for the CPU sim as well? Some global joint indices? """ if physx.is_gpu_enabled(): - targets = to_tensor(targets) + targets = sapien_utils.to_tensor(targets) if joint_indices not in self._cached_joint_target_indices: self._cached_joint_target_indices[joint_indices] = torch.meshgrid( self._data_index, joint_indices, indexing="ij" @@ -613,7 +611,7 @@ def set_joint_drive_velocity_targets( TODO (stao): can we use joint indices for the CPU sim as well? Some global joint indices? """ if physx.is_gpu_enabled(): - targets = to_tensor(targets) + targets = sapien_utils.to_tensor(targets) if joint_indices not in self._cached_joint_target_indices: self._cached_joint_target_indices[joint_indices] = torch.meshgrid( self._data_index, joint_indices, indexing="ij" diff --git a/mani_skill2/utils/structs/base.py b/mani_skill2/utils/structs/base.py index d9fba8745..cb146a474 100644 --- a/mani_skill2/utils/structs/base.py +++ b/mani_skill2/utils/structs/base.py @@ -7,12 +7,7 @@ import sapien.physx as physx import torch -from mani_skill2.utils.sapien_utils import ( - compute_total_impulse, - get_actor_contacts, - to_numpy, - to_tensor, -) +from mani_skill2.utils import sapien_utils from mani_skill2.utils.structs.decorators import before_gpu_init from mani_skill2.utils.structs.types import Array @@ -94,11 +89,14 @@ def get_net_contact_forces(self): / self._scene.timestep ) else: - body_contacts = get_actor_contacts( + body_contacts = sapien_utils.get_actor_contacts( self.px.get_contacts(), self._bodies[0].entity ) net_force = ( - to_tensor(compute_total_impulse(body_contacts)) / self._scene.timestep + sapien_utils.to_tensor( + sapien_utils.compute_total_impulse(body_contacts) + ) + / self._scene.timestep ) return net_force[None, :] @@ -299,12 +297,12 @@ def angular_velocity(self) -> torch.Tensor: @angular_velocity.setter def angular_velocity(self, arg1: Array): if physx.is_gpu_enabled(): - arg1 = to_tensor(arg1) + arg1 = sapien_utils.to_tensor(arg1) self._body_data[ self._body_data_index[self._scene._reset_mask], 10:13 ] = arg1 else: - arg1 = to_numpy(arg1) + arg1 = sapien_utils.to_numpy(arg1) if len(arg1.shape) == 2: arg1 = arg1[0] self._bodies[0].angular_velocity = arg1 @@ -368,10 +366,10 @@ def linear_velocity(self) -> torch.Tensor: @linear_velocity.setter def linear_velocity(self, arg1: Array): if physx.is_gpu_enabled(): - arg1 = to_tensor(arg1) + arg1 = sapien_utils.to_tensor(arg1) self._body_data[self._body_data_index[self._scene._reset_mask], 7:10] = arg1 else: - arg1 = to_numpy(arg1) + arg1 = sapien_utils.to_numpy(arg1) if len(arg1.shape) == 2: arg1 = arg1[0] self._bodies[0].linear_velocity = arg1 diff --git a/mani_skill2/utils/structs/joint.py b/mani_skill2/utils/structs/joint.py index 8f3cb6573..2c6b56c02 100644 --- a/mani_skill2/utils/structs/joint.py +++ b/mani_skill2/utils/structs/joint.py @@ -8,7 +8,7 @@ import sapien.physx as physx import torch -from mani_skill2.utils.sapien_utils import to_tensor +from mani_skill2.utils import sapien_utils from mani_skill2.utils.structs.base import BaseStruct from mani_skill2.utils.structs.decorators import before_gpu_init from mani_skill2.utils.structs.link import Link @@ -194,7 +194,7 @@ def drive_target(self) -> torch.Tensor: @drive_target.setter def drive_target(self, arg1: Array) -> None: if physx.is_gpu_enabled(): - arg1 = to_tensor(arg1) + arg1 = sapien_utils.to_tensor(arg1) raise NotImplementedError( "Setting drive targets of individual joints is not implemented yet." ) @@ -217,7 +217,7 @@ def drive_velocity_target(self) -> torch.Tensor: @drive_velocity_target.setter def drive_velocity_target(self, arg1: Array) -> None: if physx.is_gpu_enabled(): - arg1 = to_tensor(arg1) + arg1 = sapien_utils.to_tensor(arg1) raise NotImplementedError( "Cannot set drive velocity targets at the moment in GPU simulation" ) diff --git a/mani_skill2/utils/structs/pose.py b/mani_skill2/utils/structs/pose.py index f32fd9d64..aebbab658 100644 --- a/mani_skill2/utils/structs/pose.py +++ b/mani_skill2/utils/structs/pose.py @@ -6,12 +6,12 @@ import sapien.physx as physx import torch +from mani_skill2.utils import sapien_utils from mani_skill2.utils.geometry.rotation_conversions import ( quaternion_apply, quaternion_multiply, quaternion_to_matrix, ) -from mani_skill2.utils.sapien_utils import to_numpy, to_tensor from mani_skill2.utils.structs.types import Array, Device @@ -24,7 +24,7 @@ def add_batch_dim(x): def to_batched_tensor(x: Union[List, Array]): if x is None: return None - return add_batch_dim(to_tensor(x)) + return add_batch_dim(sapien_utils.to_tensor(x)) @dataclass @@ -95,13 +95,15 @@ def create_from_pq( @classmethod def create(cls, pose: Union[torch.Tensor, sapien.Pose, "Pose"]): if isinstance(pose, sapien.Pose): - raw_pose = torch.hstack([to_tensor(pose.p), to_tensor(pose.q)]) + raw_pose = torch.hstack( + [sapien_utils.to_tensor(pose.p), sapien_utils.to_tensor(pose.q)] + ) return cls(raw_pose=add_batch_dim(raw_pose)) elif isinstance(pose, cls): return pose else: assert len(pose.shape) <= 2 and len(pose.shape) > 0 - pose = to_tensor(pose) + pose = sapien_utils.to_tensor(pose) pose = add_batch_dim(pose) if pose.shape[-1] == 3: return cls.create_from_pq(p=pose, device=pose.device) @@ -167,7 +169,7 @@ def p(self): @p.setter def p(self, arg1: torch.Tensor): - self.raw_pose[..., :3] = to_tensor(arg1) + self.raw_pose[..., :3] = sapien_utils.to_tensor(arg1) @property def q(self): @@ -175,7 +177,7 @@ def q(self): @q.setter def q(self, arg1: torch.Tensor): - self.raw_pose[..., 3:] = to_tensor(arg1) + self.raw_pose[..., 3:] = sapien_utils.to_tensor(arg1) # @property # def rpy(self) -> numpy.ndarray[numpy.float32, _Shape, _Shape[3]]: @@ -193,7 +195,9 @@ def vectorize_pose(pose: Union[sapien.Pose, Pose]) -> torch.Tensor: """ if isinstance(pose, sapien.Pose): if physx.is_gpu_enabled(): - return torch.concatenate([to_tensor(pose.p), to_tensor(pose.q)]) + return torch.concatenate( + [sapien_utils.to_tensor(pose.p), sapien_utils.to_tensor(pose.q)] + ) else: return np.hstack([pose.p, pose.q]) elif isinstance(pose, Pose): @@ -213,7 +217,7 @@ def to_sapien_pose(pose: Union[torch.Tensor, sapien.Pose, Pose]) -> sapien.Pose: ), "pose is batched. Note that sapien Poses are not batched. If you want to use a batched Pose object use from mani_skill2.utils.structs.pose import Pose" if len(pose.shape) == 2: pose = pose[0] - pose = to_numpy(pose) + pose = sapien_utils.to_numpy(pose) return sapien.Pose(pose[:3], pose[3:]) else: assert len(pose.shape) == 1 or ( @@ -221,5 +225,5 @@ def to_sapien_pose(pose: Union[torch.Tensor, sapien.Pose, Pose]) -> sapien.Pose: ), "pose is batched. Note that sapien Poses are not batched. If you want to use a batched Pose object use from mani_skill2.utils.structs.pose import Pose" if len(pose.shape) == 2: pose = pose[0] - pose = to_numpy(pose) + pose = sapien_utils.to_numpy(pose) return sapien.Pose(pose[:3], pose[3:]) diff --git a/mani_skill2/utils/structs/render_camera.py b/mani_skill2/utils/structs/render_camera.py index 71ee0527b..bd89980b5 100644 --- a/mani_skill2/utils/structs/render_camera.py +++ b/mani_skill2/utils/structs/render_camera.py @@ -7,7 +7,7 @@ import sapien.render import torch -from mani_skill2.utils.sapien_utils import to_tensor +from mani_skill2.utils import sapien_utils # NOTE (stao): commented out functions are functions that are not confirmed to be working in the wrapped class but the original class has @@ -48,7 +48,9 @@ def __hash__(self): # TODO (stao): support extrinsic matrix changing @cache def get_extrinsic_matrix(self): - return to_tensor(self._render_cameras[0].get_extrinsic_matrix())[None, :] + return sapien_utils.to_tensor(self._render_cameras[0].get_extrinsic_matrix())[ + None, : + ] def get_far(self) -> float: return self._render_cameras[0].get_far() @@ -61,14 +63,18 @@ def get_height(self) -> int: @cache def get_intrinsic_matrix(self): - return to_tensor(self._render_cameras[0].get_intrinsic_matrix())[None, :] + return sapien_utils.to_tensor(self._render_cameras[0].get_intrinsic_matrix())[ + None, : + ] def get_local_pose(self) -> sapien.Pose: return self._render_cameras[0].get_local_pose() @cache def get_model_matrix(self): - return to_tensor(self._render_cameras[0].get_model_matrix())[None, :] + return sapien_utils.to_tensor(self._render_cameras[0].get_model_matrix())[ + None, : + ] def get_near(self) -> float: return self._render_cameras[0].get_near() @@ -77,7 +83,9 @@ def get_picture(self, name: str): if physx.is_gpu_enabled(): return self.camera_group.get_picture_cuda(name).torch() else: - return to_tensor(self._render_cameras[0].get_picture(name))[None, ...] + return sapien_utils.to_tensor(self._render_cameras[0].get_picture(name))[ + None, ... + ] def get_picture_cuda(self, name: str): return self._render_cameras[0].get_picture_cuda(name) diff --git a/mani_skill2/utils/wrappers/flatten.py b/mani_skill2/utils/wrappers/flatten.py index 757d657e5..3c22276df 100644 --- a/mani_skill2/utils/wrappers/flatten.py +++ b/mani_skill2/utils/wrappers/flatten.py @@ -5,8 +5,8 @@ from gymnasium.vector.utils import batch_space from mani_skill2.envs.sapien_env import BaseEnv +from mani_skill2.utils import sapien_utils from mani_skill2.utils.common import flatten_state_dict -from mani_skill2.utils.sapien_utils import batch class FlattenObservationWrapper(gym.ObservationWrapper): @@ -49,7 +49,7 @@ def action(self, action): self.base_env.num_envs == 1 and action.shape == self.single_action_space.shape ): - action = batch(action) + action = sapien_utils.batch(action) # TODO (stao): This code only supports flat dictionary at the moment unflattened_action = dict() diff --git a/mani_skill2/utils/wrappers/record.py b/mani_skill2/utils/wrappers/record.py index 077568693..2811e384e 100644 --- a/mani_skill2/utils/wrappers/record.py +++ b/mani_skill2/utils/wrappers/record.py @@ -11,12 +11,12 @@ from mani_skill2 import get_commit_info from mani_skill2.envs.sapien_env import BaseEnv +from mani_skill2.utils import sapien_utils from mani_skill2.utils.common import ( extract_scalars_from_info, find_max_episode_steps_value, ) from mani_skill2.utils.io_utils import dump_json -from mani_skill2.utils.sapien_utils import batch, to_numpy from mani_skill2.utils.structs.types import Array from mani_skill2.utils.visualization.misc import ( images_to_video, @@ -278,7 +278,7 @@ def _base_env(self) -> BaseEnv: def capture_image(self): img = self.env.render() - img = to_numpy(img) + img = sapien_utils.to_numpy(img) if len(img.shape) > 3: img = tile_images(img, nrows=self.video_nrows) return img @@ -297,16 +297,18 @@ def reset( if "env_idx" not in options: self.flush_trajectory(env_idxs_to_flush=np.arange(self.num_envs)) else: - self.flush_trajectory(env_idxs_to_flush=to_numpy(options["env_idx"])) + self.flush_trajectory( + env_idxs_to_flush=sapien_utils.to_numpy(options["env_idx"]) + ) obs, info = super().reset(*args, seed=seed, options=options, **kwargs) if self.save_trajectory: state_dict = self._base_env.get_state_dict() - action = batch(self.action_space.sample()) + action = sapien_utils.batch(self.action_space.sample()) first_step = Step( - state=to_numpy(batch(state_dict)), - observation=to_numpy(batch(obs)), + state=sapien_utils.to_numpy(sapien_utils.batch(state_dict)), + observation=sapien_utils.to_numpy(sapien_utils.batch(obs)), # note first reward/action etc. are ignored when saving trajectories to disk action=action, reward=np.zeros( @@ -326,11 +328,11 @@ def reset( env_episode_ptr=np.zeros((self.num_envs,), dtype=int), ) if self.num_envs == 1: - first_step.observation = batch(first_step.observation) - first_step.action = batch(first_step.action) + first_step.observation = sapien_utils.batch(first_step.observation) + first_step.action = sapien_utils.batch(first_step.action) env_idx = np.arange(self.num_envs) if "env_idx" in options: - env_idx = to_numpy(options["env_idx"]) + env_idx = sapien_utils.to_numpy(options["env_idx"]) if self._trajectory_buffer is None: # Initialize trajectory buffer on the first episode based on given observation (which should be generated after all wrappers) self._trajectory_buffer = first_step @@ -363,7 +365,7 @@ def recursive_replace(x, y): if self._trajectory_buffer.fail is not None: recursive_replace(self._trajectory_buffer.fail, first_step.fail) if "env_idx" in options: - options["env_idx"] = to_numpy(options["env_idx"]) + options["env_idx"] = sapien_utils.to_numpy(options["env_idx"]) self.last_reset_kwargs = copy.deepcopy( dict(seed=seed, options=options, **kwargs) ) @@ -386,41 +388,50 @@ def step(self, action): truncated = self._base_env.elapsed_steps >= self.max_episode_steps state_dict = self._base_env.get_state_dict() self._trajectory_buffer.state = append_dict_array( - self._trajectory_buffer.state, to_numpy(batch(state_dict)) + self._trajectory_buffer.state, + sapien_utils.to_numpy(sapien_utils.batch(state_dict)), ) self._trajectory_buffer.observation = append_dict_array( - self._trajectory_buffer.observation, to_numpy(batch(obs)) + self._trajectory_buffer.observation, + sapien_utils.to_numpy(sapien_utils.batch(obs)), ) self._trajectory_buffer.action = append_dict_array( - self._trajectory_buffer.action, to_numpy(batch(action)) + self._trajectory_buffer.action, + sapien_utils.to_numpy(sapien_utils.batch(action)), ) self._trajectory_buffer.reward = append_dict_array( - self._trajectory_buffer.reward, to_numpy(batch(rew)) + self._trajectory_buffer.reward, + sapien_utils.to_numpy(sapien_utils.batch(rew)), ) self._trajectory_buffer.terminated = append_dict_array( - self._trajectory_buffer.terminated, to_numpy(batch(terminated)) + self._trajectory_buffer.terminated, + sapien_utils.to_numpy(sapien_utils.batch(terminated)), ) self._trajectory_buffer.truncated = append_dict_array( - self._trajectory_buffer.truncated, to_numpy(batch(truncated)) + self._trajectory_buffer.truncated, + sapien_utils.to_numpy(sapien_utils.batch(truncated)), ) done = terminated | truncated self._trajectory_buffer.done = append_dict_array( - self._trajectory_buffer.done, to_numpy(batch(done)) + self._trajectory_buffer.done, + sapien_utils.to_numpy(sapien_utils.batch(done)), ) if "success" in info: self._trajectory_buffer.success = append_dict_array( - self._trajectory_buffer.success, to_numpy(batch(info["success"])) + self._trajectory_buffer.success, + sapien_utils.to_numpy(sapien_utils.batch(info["success"])), ) else: self._trajectory_buffer.success = None if "fail" in info: self._trajectory_buffer.fail = append_dict_array( - self._trajectory_buffer.fail, to_numpy(batch(info["fail"])) + self._trajectory_buffer.fail, + sapien_utils.to_numpy(sapien_utils.batch(info["fail"])), ) else: self._trajectory_buffer.fail = None - self._last_info = to_numpy(info) + self._last_info = sapien_utils.to_numpy(info) if self.save_video: self._video_steps += 1 diff --git a/mani_skill2/utils/wrappers/visual_encoders.py b/mani_skill2/utils/wrappers/visual_encoders.py index 647be708f..db7e18d1a 100644 --- a/mani_skill2/utils/wrappers/visual_encoders.py +++ b/mani_skill2/utils/wrappers/visual_encoders.py @@ -4,7 +4,7 @@ import torch from mani_skill2.envs.sapien_env import BaseEnv -from mani_skill2.utils.sapien_utils import to_numpy, to_tensor +from mani_skill2.utils import sapien_utils class VisualEncoderWrapper(gym.ObservationWrapper): @@ -30,7 +30,9 @@ def __init__(self, env, encoder: Literal["r3m"], encoder_cfg=dict()): self.single_image_embedding_size = 512 # for resnet18 self.base_env._update_obs_space( - to_numpy(self.observation(to_tensor(self.base_env._init_raw_obs))) + sapien_utils.to_numpy( + self.observation(sapien_utils.to_tensor(self.base_env._init_raw_obs)) + ) ) super().__init__(env) diff --git a/mani_skill2/vector/__init__.py b/mani_skill2/vector/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/mani_skill2/vector/wrappers/__init__.py b/mani_skill2/vector/wrappers/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/manualtest/basic_replay.py b/manualtest/basic_replay.py index 5acc0356a..d0436251c 100644 --- a/manualtest/basic_replay.py +++ b/manualtest/basic_replay.py @@ -4,7 +4,7 @@ import torch import mani_skill2.envs -from mani_skill2.utils.sapien_utils import to_numpy +from mani_skill2.utils import sapien_utils from mani_skill2.utils.wrappers import RecordEpisode from mani_skill2.vector.wrappers.gymnasium import ManiSkillVectorEnv @@ -60,7 +60,9 @@ # TODO (stao): on cpu sim, -1 here goes up, gpu sim -1 goes down? action[:, 1] = -1 obs, rew, terminated, truncated, info = env.step(action) - done = np.logical_or(to_numpy(terminated), to_numpy(truncated)) + done = np.logical_or( + sapien_utils.to_numpy(terminated), sapien_utils.to_numpy(truncated) + ) if num_envs == 1: env.render_human() done = done.any() diff --git a/manualtest/enc.py b/manualtest/enc.py index 67ec7cdb3..6d99c8405 100644 --- a/manualtest/enc.py +++ b/manualtest/enc.py @@ -3,7 +3,7 @@ import sapien import mani_skill2.envs -from mani_skill2.utils.sapien_utils import to_numpy +from mani_skill2.utils import sapien_utils from mani_skill2.utils.wrappers import RecordEpisode from mani_skill2.utils.wrappers.visual_encoders import VisualEncoderWrapper @@ -66,7 +66,9 @@ # TODO (stao): on cpu sim, -1 here goes up, gpu sim -1 goes down? # action[:, 2] = -1 obs, rew, terminated, truncated, info = env.step(action) - done = np.logical_or(to_numpy(terminated), to_numpy(truncated)) + done = np.logical_or( + sapien_utils.to_numpy(terminated), sapien_utils.to_numpy(truncated) + ) if num_envs == 1: env.render_human() done = done.any() diff --git a/manualtest/memory.py b/manualtest/memory.py index 3f772c87f..05ddbc13f 100644 --- a/manualtest/memory.py +++ b/manualtest/memory.py @@ -3,7 +3,7 @@ import sapien import mani_skill2.envs -from mani_skill2.utils.sapien_utils import to_numpy +from mani_skill2.utils import sapien_utils from mani_skill2.utils.wrappers import RecordEpisode # sapien.set_log_level("info") @@ -30,7 +30,9 @@ if len(action.shape) == 1: action = action.reshape(1, -1) obs, rew, terminated, truncated, info = env.step(action) - done = np.logical_or(to_numpy(terminated), to_numpy(truncated)) + done = np.logical_or( + sapien_utils.to_numpy(terminated), sapien_utils.to_numpy(truncated) + ) if num_envs == 1: env.render_human() done = done.any() diff --git a/manualtest/multirobot.py b/manualtest/multirobot.py index 82d1a1f7a..aaf1bca31 100644 --- a/manualtest/multirobot.py +++ b/manualtest/multirobot.py @@ -3,7 +3,7 @@ import sapien import mani_skill2.envs -from mani_skill2.utils.sapien_utils import to_numpy +from mani_skill2.utils import sapien_utils from mani_skill2.utils.wrappers import RecordEpisode from mani_skill2.utils.wrappers.flatten import FlattenActionSpaceWrapper @@ -65,7 +65,9 @@ # TODO (stao): on cpu sim, -1 here goes up, gpu sim -1 goes down? # action[:, 2] = -1 obs, rew, terminated, truncated, info = env.step(action) - done = np.logical_or(to_numpy(terminated), to_numpy(truncated)) + done = np.logical_or( + sapien_utils.to_numpy(terminated), sapien_utils.to_numpy(truncated) + ) if num_envs == 1 and VIS: env.render_human() done = done.any() diff --git a/manualtest/record_test.py b/manualtest/record_test.py index 06ee54f78..ab82c46ed 100644 --- a/manualtest/record_test.py +++ b/manualtest/record_test.py @@ -3,7 +3,7 @@ import sapien import mani_skill2.envs -from mani_skill2.utils.sapien_utils import to_numpy +from mani_skill2.utils import sapien_utils from mani_skill2.utils.wrappers import RecordEpisode from mani_skill2.vector.wrappers.gymnasium import ManiSkillVectorEnv diff --git a/manualtest/visual_all_envs_cpu.py b/manualtest/visual_all_envs_cpu.py index 3055a0c97..860103bbe 100644 --- a/manualtest/visual_all_envs_cpu.py +++ b/manualtest/visual_all_envs_cpu.py @@ -2,8 +2,9 @@ import numpy as np import sapien +# cd ManiSkill2 && pip uninstall -y mani_skill2 && pip install . && cd .. import mani_skill2.envs -from mani_skill2.utils.sapien_utils import to_numpy +from mani_skill2.utils import sapien_utils from mani_skill2.utils.wrappers import RecordEpisode if __name__ == "__main__": @@ -59,7 +60,9 @@ # TODO (stao): on cpu sim, -1 here goes up, gpu sim -1 goes down? # action[:, 2] = -1 obs, rew, terminated, truncated, info = env.step(action) - done = np.logical_or(to_numpy(terminated), to_numpy(truncated)) + done = np.logical_or( + sapien_utils.to_numpy(terminated), sapien_utils.to_numpy(truncated) + ) if num_envs == 1: env.render_human() done = done.any() diff --git a/manualtest/visual_fetch.py b/manualtest/visual_fetch.py index 8a0ad3d7d..ce50c49d8 100644 --- a/manualtest/visual_fetch.py +++ b/manualtest/visual_fetch.py @@ -2,7 +2,7 @@ import numpy as np import mani_skill2.envs -from mani_skill2.utils.sapien_utils import to_numpy +from mani_skill2.utils import sapien_utils from mani_skill2.utils.wrappers import RecordEpisode if __name__ == "__main__": @@ -43,7 +43,9 @@ # action[-4] = 1 # action[1] = -1 obs, rew, terminated, truncated, info = env.step(action) - done = np.logical_or(to_numpy(terminated), to_numpy(truncated)) + done = np.logical_or( + sapien_utils.to_numpy(terminated), sapien_utils.to_numpy(truncated) + ) if num_envs == 1: env.render_human() done = done.any() diff --git a/setup.py b/setup.py index 47dc7e728..f1aecfe44 100644 --- a/setup.py +++ b/setup.py @@ -41,6 +41,8 @@ package_data={ "mani_skill2": [ "assets/**", + "envs/**/*/assets/**", + "utils/**/*/assets/**", "envs/mpm/shader/**", "envs/mpm/RopeInit.pkl", ], diff --git a/tests/utils.py b/tests/utils.py index 0fadce7ce..01ce23ce6 100644 --- a/tests/utils.py +++ b/tests/utils.py @@ -3,9 +3,9 @@ import numpy as np import torch +from mani_skill2.utils import sapien_utils from mani_skill2.utils.common import flatten_dict_keys from mani_skill2.utils.registration import REGISTERED_ENVS -from mani_skill2.utils.sapien_utils import to_numpy # TODO (stao): reactivate old tasks once fixed ENV_IDS = list(REGISTERED_ENVS.keys()) @@ -76,7 +76,7 @@ def assert_obs_equal(obs1, obs2, ignore_col_vector_shape_mismatch=False): ignore_col_vector_shape_mismatch - If true, will ignore shape mismatch if one shape is (n, 1) but another is (n, ). this is added since SB3 outputs scalars as (n, ) whereas Gymnasium and ManiSkill2 use (n, 1) """ - obs1, obs2 = to_numpy(obs1), to_numpy(obs2) + obs1, obs2 = sapien_utils.to_numpy(obs1), sapien_utils.to_numpy(obs2) if isinstance(obs1, dict): assert isinstance(obs2, dict) obs1 = flatten_dict_keys(obs1)