concepts.simulator.pybullet.components.ur5.ur5_gripper.Suction#

class Suction[source]#

Bases: BulletGripperBase

Simulate simple suction dynamics.

Methods

activate()

Simulate suction using a rigid fixed constraint to contacted object.

check_grasp()

Check a grasp (object in contact?) for picking success.

detect_contact()

Detects a contact with a rigid object.

release([verbose])

Release gripper object, only applied if gripper is 'activated'.

step()

This function can be used to create gripper-specific behaviors.

sync_gripper_qpos()

Sync gripper qpos with PyBullet simulation.

Attributes

__init__(client, robot, ee, obj_ids)[source]#

Creates suction and ‘attaches’ it to the robot.

Has special cases when dealing with rigid vs deformables. For rigid, only need to check contact_constraint for any constraint. For soft bodies (i.e., cloth or bags), use cloth_threshold to check distances from gripper body (self.head_id) to any vertex in the cloth mesh. We need correct code logic to handle gripping potentially a rigid or a deformable (and similarly for releasing).

To be clear on terminology: ‘deformable’ here should be interpreted as a PyBullet ‘softBody’, which includes cloths and bags. There’s also cables, but those are formed by connecting rigid body beads, so they can use standard ‘rigid body’ grasping code.

To get the suction gripper pose, use p.getLinkState(self.head_id, 0), and not p.getBasePositionAndOrientation(self.head_id) as the latter is about z=0.03m higher and empirically seems worse.

Parameters:
  • client – the BulletClient instance.

  • robot – int representing PyBullet ID of robot.

  • ee – int representing PyBullet ID of end effector link.

  • obj_ids – list of PyBullet IDs of all suctionable objects in the env.

__new__(**kwargs)#
activate()[source]#

Simulate suction using a rigid fixed constraint to contacted object.

check_grasp()[source]#

Check a grasp (object in contact?) for picking success.

detect_contact()[source]#

Detects a contact with a rigid object. When the suction is on, this function detects whether the object being gripped is in contact with other objects. When the suction is off, this function detects whether the suction is in contact with any objects.

release(verbose=False)[source]#

Release gripper object, only applied if gripper is ‘activated’.

If suction off, detect contact between gripper and objects. If suction on, detect contact between picked object and other objects.

To handle deformables, simply remove constraints (i.e., anchors). Also reset any relevant variables, e.g., if releasing a rigid, we should reset init_grip values back to None, which will be re-assigned in any subsequent grasps.

Parameters:

verbose (bool)

step()#

This function can be used to create gripper-specific behaviors.

sync_gripper_qpos()[source]#

Sync gripper qpos with PyBullet simulation.

property p#
property w#
property world#