habitat.tasks.rearrange.rearrange_grasp_manager.RearrangeGraspManager class

Manages the agent grasping onto rigid objects and the links of articulated objects.

Methods

def create_hold_constraint(self, constraint_type, pivot_in_link: _magnum.Vector3, pivot_in_obj: _magnum.Vector3, obj_id_b: int, link_id_b: typing.Optional[int] = None, rotation_lock_b: typing.Optional[_magnum.Matrix3] = None) -> int
Create a new rigid point-to-point (ball joint) constraint between the robot and an object.
def desnap(self, force = False) -> None
Removes any hold constraints currently active. Removes hold constraints for regular and articulated objects.
def is_violating_hold_constraint(self) -> bool
Returns true if the object is too far away from the gripper, meaning the agent violated the hold constraint.
def reconfigure(self) -> None
Removes any existing constraints managed by this structure.
def reset(self) -> None
Reset the grasp manager by re-defining the collision group and dropping any grasped object.
def snap_to_marker(self, marker_name: str) -> None
Create a constraint between the end-effector and the marker on the articulated object to be grasped.
def snap_to_obj(self, snap_obj_id: int, force: bool = True, should_open_gripper = True, rel_pos: typing.Optional[_magnum.Vector3] = None, keep_T: typing.Optional[_magnum.Matrix4] = None) -> None
Attempt to grasp an object, snapping/constraining it to the robot’s end effector with 3 ball-joint constraints forming a fixed frame.
def update(self) -> None
Reset the collision group of the grasped object if its distance to the end effector exceeds a threshold.
def update_debug(self) -> None
Creates visualizations for grasp points.
def update_object_to_grasp(self) -> None
Kinematically update held object to be within robot’s grasp. If nothing is grasped then nothing will happen.

Special methods

def __init__(self, sim: RearrangeSim, config: DictConfig, articulated_agent: Manipulator, ee_index = 0)
Initialize a grasp manager for the simulator instance provided.

Properties

is_grasped: bool get
Returns whether or not an object or marker is currently grasped.
snap_idx: typing.Optional[int] get
The index of the grasped RigidObject. None if nothing is being grasped.
snap_rigid_obj: habitat_sim._ext.habitat_sim_bindings.ManagedRigidObject get
The grasped object instance.
snapped_marker_id: typing.Optional[str] get
The name of the marker for the grasp. None if nothing is being grasped.

Method documentation

def habitat.tasks.rearrange.rearrange_grasp_manager.RearrangeGraspManager.create_hold_constraint(self, constraint_type, pivot_in_link: _magnum.Vector3, pivot_in_obj: _magnum.Vector3, obj_id_b: int, link_id_b: typing.Optional[int] = None, rotation_lock_b: typing.Optional[_magnum.Matrix3] = None) -> int

Create a new rigid point-to-point (ball joint) constraint between the robot and an object.

Parameters
constraint_type
pivot_in_link The origin of the constraint in end effector local space.
pivot_in_obj The origin of the constraint in object local space.
obj_id_b The id of the object to be constrained to the end effector.
link_id_b If the object is articulated, provide the link index for the constraint.
rotation_lock_b

def habitat.tasks.rearrange.rearrange_grasp_manager.RearrangeGraspManager.desnap(self, force = False) -> None

Removes any hold constraints currently active. Removes hold constraints for regular and articulated objects.

Parameters
force If True, reset the collision group of the now released object immediately instead of waiting for its distance from the end effector to reach a threshold.

def habitat.tasks.rearrange.rearrange_grasp_manager.RearrangeGraspManager.snap_to_marker(self, marker_name: str) -> None

Create a constraint between the end-effector and the marker on the articulated object to be grasped.

Parameters
marker_name The name/id of the marker.

def habitat.tasks.rearrange.rearrange_grasp_manager.RearrangeGraspManager.snap_to_obj(self, snap_obj_id: int, force: bool = True, should_open_gripper = True, rel_pos: typing.Optional[_magnum.Vector3] = None, keep_T: typing.Optional[_magnum.Matrix4] = None) -> None

Attempt to grasp an object, snapping/constraining it to the robot’s end effector with 3 ball-joint constraints forming a fixed frame.

Parameters
snap_obj_id The id of the object to be constrained to the end effector.
force Will kinematically snap the object to the robot’s end-effector, even if the object is already in the grasped state.
should_open_gripper
rel_pos
keep_T

def habitat.tasks.rearrange.rearrange_grasp_manager.RearrangeGraspManager.update(self) -> None

Reset the collision group of the grasped object if its distance to the end effector exceeds a threshold.

Used to wait for a dropped object to clear the end effector’s proximity before re-activating collisions between them.

def habitat.tasks.rearrange.rearrange_grasp_manager.RearrangeGraspManager.__init__(self, sim: RearrangeSim, config: DictConfig, articulated_agent: Manipulator, ee_index = 0)

Initialize a grasp manager for the simulator instance provided.

Parameters
sim Pointer to the simulator where the agent is instantiated
config The task’s “simulator” subconfig node. Defines grasping parameters.
articulated_agent The agent for which we want to manage grasping
ee_index The index of the end effector of the articulated_agent belonging to this grasp_manager