pycram.datastructures.grasp#

Classes#

GraspDescription

Describes a grasp configuration for a manipulator the description consists of the approach direction (the side from

PreferredGraspAlignment

Description of the preferred grasp alignment for an object.

GraspPose

A pose from which a grasp can be performed along with the respective arm and grasp description.

Module Contents#

class pycram.datastructures.grasp.GraspDescription#

Describes a grasp configuration for a manipulator the description consists of the approach direction (the side from which to grasp e.g. FRONT, LEFT, etc and the vertical alignment (TOP, BOTTOM).

approach_direction: pycram.datastructures.enums.ApproachDirection#

The direction from which the body should be grasped. These are the four directions in the x-y plane (FRONT, BACK, LEFT, RIGHT).

vertical_alignment: pycram.datastructures.enums.VerticalAlignment#

The alignment of the gripper with the body in the z-axis (TOP, BOTTOM).

manipulator: semantic_digital_twin.robots.abstract_robot.Manipulator#

The manipulator that is used to grasp the body.

rotate_gripper: bool = False#

Rotate the gripper by 90 degrees.

manipulation_offset: float = 0.05#

The offset between the center of the pose in the grasp sequence

_pose_sequence(target_T_grasp_pose: semantic_digital_twin.spatial_types.spatial_types.Pose, body: semantic_digital_twin.world_description.world_entity.Body = None, reverse: bool = False) List[semantic_digital_twin.spatial_types.spatial_types.Pose]#

Calculates the pose sequence to grasp something at the pose if the body is given its geometry is also taken into account. The pose sequence consists of 3 poses: one in front of the body (taking body geometry into account), one at the center of the body, and the last one above the body to lift it.

Parameters:
  • target_T_grasp_pose – The pose of the grasp in the target frame.

  • body – The body of the grasp.

  • reverse – If the sequence should be reversed.

Returns:

The pose sequence.

grasp_pose_sequence(body: semantic_digital_twin.world_description.world_entity.Body)#

Calculates the pose sequence to grasp the body. The sequence is 3 poses, one in front of the body (taking body geometry into account), one at the center of the body, and the last one above the body to lift it.

Parameters:

body – The body of the grasp.

Returns:

The pose sequence.

place_pose_sequence(pose: semantic_digital_twin.spatial_types.spatial_types.Pose) List[semantic_digital_twin.spatial_types.spatial_types.Pose]#

Calculates the pose sequence to place a body at the given pose. Assumes that the manipulator is holding a body which is being placed.

Parameters:

pose – The pose at which the body in the manipulator should be placed

Returns:

The pose sequence.

manipulation_axis() List[float]#

Axis of the manipulator that is manipulating the body. Translates the x-axis of the global frame to how the manipulator is rotated.

Returns:

The axis of the manipulator that is manipulating the body.

lift_axis() List[float]#

Axis of the manipulator that is lifting the body. Translates the z-axis of the global frame to how the manipulator is rotated.

Returns:

The axis of the manipulator that is lifting the body.

calculate_manipulator_axis(axis: pycram.datastructures.enums.AxisIdentifier) List[float]#

Calculates the corresponding axis of the manipulator for a given axis of the body.

Parameters:

axis – The axis of the body as a list of [x, y, z] indices.

Returns:

The corresponding axis of the manipulator as a list of [x, y, z] values.

grasp_orientation() semantic_digital_twin.spatial_types.spatial_types.Quaternion#

The orientation of the grasp. Takes into account the approach direction and vertical alignment.

edge_offset(body: semantic_digital_twin.world_description.world_entity.Body) float#

The offset between the center of the body and its edge in the direction of the approach axis.

Parameters:

body – The body to calculate the edge offset for.

Returns:

The edge offset.

grasp_pose(body: semantic_digital_twin.world_description.world_entity.Body, grasp_edge: bool = False) semantic_digital_twin.spatial_types.spatial_types.Pose#

The pose for the given manipulator to grasp the body in the frame of the body.

Parameters:
  • body – The body to grasp.

  • grasp_edge – Indicates if the pose should be for the edge of the body or the center.

Returns:

The pose of the body in the body frame.

classmethod calculate_grasp_descriptions(manipulator: semantic_digital_twin.robots.abstract_robot.Manipulator, pose: semantic_digital_twin.spatial_types.spatial_types.Pose, grasp_alignment: PreferredGraspAlignment | None = None) List[GraspDescription]#

This method determines the possible grasp configurations (approach axis and vertical alignment) of the body, taking into account the bodies orientation, position, and whether the gripper should be rotated by 90°.

Parameters:
  • manipulator – The manipulator to use.

  • grasp_alignment – An optional PreferredGraspAlignment object that specifies preferred grasp axis,

  • pose – The pose of the object to be grasped.

Returns:

A sorted list of GraspDescription instances representing all grasp permutations.

static calculate_closest_faces(pose_to_robot_vector: semantic_digital_twin.spatial_types.spatial_types.Vector3, specified_grasp_axis: pycram.datastructures.enums.AxisIdentifier = AxisIdentifier.Undefined) Tuple[pycram.datastructures.enums.ApproachDirection, pycram.datastructures.enums.ApproachDirection] | Tuple[pycram.datastructures.enums.VerticalAlignment, pycram.datastructures.enums.VerticalAlignment]#

Determines the faces of the object based on the input vector.

If specified_grasp_axis is None, it calculates the primary and secondary faces based on the vector’s magnitude determining which sides of the object are most aligned with the robot. This will either be the x, y plane for side faces or the z axis for top/bottom faces. If specified_grasp_axis is provided, it only considers the specified axis and calculates the faces aligned with that axis.

Parameters:
  • pose_to_robot_vector – A 3D vector representing one of the robot’s axes in the pose’s frame, with irrelevant components set to np.nan.

  • specified_grasp_axis – Specifies a specific axis (e.g., X, Y, Z) to focus on.

Returns:

A tuple of two Grasp enums representing the primary and secondary faces.

class pycram.datastructures.grasp.PreferredGraspAlignment#

Description of the preferred grasp alignment for an object.

preferred_axis: pycram.datastructures.enums.AxisIdentifier | None#

The preferred axis, X, Y, or Z, for grasping the object, or None if not specified.

with_vertical_alignment: bool#

Indicates if the object should be grasped with a vertical alignment.

with_rotated_gripper: bool#

Indicates if the gripper should be rotated by 90° around X.

class pycram.datastructures.grasp.GraspPose(position: semantic_digital_twin.spatial_types.spatial_types.Point3 | None = None, orientation: semantic_digital_twin.spatial_types.spatial_types.Quaternion | None = None, reference_frame: semantic_digital_twin.world_description.world_entity.KinematicStructureEntity | None = None, arm: pycram.datastructures.enums.Arms = None, grasp_description: GraspDescription = None)#

Bases: semantic_digital_twin.spatial_types.spatial_types.Pose

A pose from which a grasp can be performed along with the respective arm and grasp description.

arm: pycram.datastructures.enums.Arms = None#

Arm corresponding to the grasp pose.

grasp_description: GraspDescription = None#

Grasp description corresponding to the grasp pose.

classmethod from_pose(pose: semantic_digital_twin.spatial_types.spatial_types.Pose, arm: pycram.datastructures.enums.Arms, grasp_description: GraspDescription)#