Skip to content

Commit

Permalink
more
Browse files Browse the repository at this point in the history
  • Loading branch information
StoneT2000 committed Mar 6, 2024
1 parent dd74c0a commit 38d1571
Show file tree
Hide file tree
Showing 9 changed files with 94 additions and 93 deletions.
12 changes: 4 additions & 8 deletions mani_skill2/agents/robots/anymal/anymal_c.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,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 (
apply_urdf_config,
check_urdf_config,
parse_urdf_config,
)
from mani_skill2.utils import sapien_utils
from mani_skill2.utils.structs.articulation import Articulation


Expand Down Expand Up @@ -83,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}"
Expand Down
4 changes: 2 additions & 2 deletions mani_skill2/agents/robots/dclaw/dclaw.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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] = [
Expand Down
42 changes: 21 additions & 21 deletions mani_skill2/agents/robots/fetch/fetch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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]:
Expand All @@ -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"
)

Expand Down Expand Up @@ -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,
Expand Down
42 changes: 24 additions & 18 deletions mani_skill2/agents/robots/panda/panda.py
Original file line number Diff line number Diff line change
Expand Up @@ -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


Expand Down Expand Up @@ -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]]
Expand Down Expand Up @@ -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
)

Expand Down
10 changes: 6 additions & 4 deletions mani_skill2/agents/robots/xarm/xarm7_ability.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down Expand Up @@ -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
)

Expand All @@ -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()
33 changes: 18 additions & 15 deletions mani_skill2/agents/robots/xmate3/xmate3.py
Original file line number Diff line number Diff line change
Expand Up @@ -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


Expand Down Expand Up @@ -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()
Expand Down Expand Up @@ -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
)

Expand Down
4 changes: 2 additions & 2 deletions mani_skill2/agents/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,15 +7,15 @@
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


def get_active_joint_indices(articulation: Articulation, joint_names: Sequence[str]):
"""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]):
Expand Down
6 changes: 3 additions & 3 deletions mani_skill2/envs/minimal_template.py
Original file line number Diff line number Diff line change
Expand Up @@ -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


Expand Down Expand Up @@ -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):
Expand Down
Loading

0 comments on commit 38d1571

Please sign in to comment.