in habitat/tasks/rearrange/grip_actions.py [0:0]
def step(self, _, should_step=True, *args, **kwargs):
if self._sim.grasp_mgr.is_grasped:
return
attempt_snap_idx = None
contacts = self._sim.get_physics_contact_points()
robot_id = self._sim.robot.sim_obj.object_id
robot_contacts = [
c for c in contacts if coll_name_matches(c, robot_id)
]
# Contacted any objects?
for scene_obj_id in self._sim.scene_obj_ids:
has_robot_match = any(
c for c in robot_contacts if coll_name_matches(c, scene_obj_id)
)
if has_robot_match:
attempt_snap_idx = scene_obj_id
if attempt_snap_idx is not None:
self._sim.grasp_mgr.snap_to_obj(attempt_snap_idx)
return
attempt_marker_snap_name = None
# Contacted any markers?
markers = self._sim.get_all_markers()
for marker_name, marker in markers.items():
has_match = any(
c
for c in robot_contacts
if coll_name_matches(c, marker.ao_parent.object_id)
and coll_link_name_matches(c, marker.link_id)
)
if has_match:
attempt_marker_snap_name = marker_name
if attempt_marker_snap_name is not None:
self._sim.grasp_mgr.snap_to_marker(attempt_marker_snap_name)