Public Member Functions | Public Attributes | Private Attributes
pr2_gripper_grasp_planner_cluster.point_cluster_grasp_planner.PointClusterGraspPlanner Class Reference

Class for doing grasp planning on point clusters. More...

List of all members.

Public Member Functions

def __init__
def check_box_plane_collisions
 check if a box goes through the x-y plane ranges is [[xmin, ymin, zmin], [xmax, ymax, zmax]] pose is a 4x4 scipy matrix
def check_grasp_neighbors
 check both sides of a grasp to see if they are also viable grasps
def check_gripper_pose
 check for collisions and points within the gripper when placed at a given pose (4x4 scipy mat) returns -1 for colliding with points, -2 for colliding with the table, and the number of points inside the gripper otherwise table is assumed to be the xy plane
def draw_gripper_model
 draw the box model of the gripper, placed at pose_mat (4x4 scipy matrix) in frame (defaults to the object frame)
def evaluate_arbitrary_grasp
 given a cluster and a grasp pose (4x4 scipy mat in object frame), guess at the probability of success for the grasp
def evaluate_point_cluster_grasps
 evaluate grasps on the point cluster
def find_best_palm_dir_grasp
 find the best grasp from a given start pose along the palm (gripper x) direction, in steps of size palm_step moving the gripper inward until/as long as there are object points within the gripper, until there are collisions checking for collisions with the table (assumed to be the xy plane) returns the grasp pose if a good grasp is found, None if not
def find_fingertip_object_center_dists
 find the distances from the object box center to the fingertip center when projected on the gripper x-, y-, and z-axes
def find_grasps_along_direction
 for a given gripper pose and axis (0=x, 1=y, 2=z), both expressed in the points frame, find grasps at a fixed spacing along that axis in both directions while varying the palm dist (inward by steps of palm_step) as long as there are object points within the gripper, until there are collisions start_pose is a 4x4 scipy mat, object_bounding_box is [[xmin, ymin, zmin], [xmax, ymax, zmax]] min_points is the minimum number of points that need to be inside the hand for the grasp to be okay
def find_high_point_grasps
 find grasps of high points on the object, pointing in towards the bottom center of the object
def find_points_in_bounding_box
 return a count of points (4xn scipy mat) contained in a bounding box (ranges is a 2-list (min, max) of 3-lists (x,y,z))
def grasp_quality
 assign a numerical quality value for this grasp
def gripper_model
 return the xyz bounding box ranges for the parts of the gripper model placed at 3-list pos and 3x3 scipy matrix rot uses a really simple model of the fully-open gripper as three boxes (2 fingers and a palm), with a box for the empty space in-between gripper_boxes is a list of boxes, each of which is a 2-list (min, max) of 3-lists (x,y,z) of corner coords space boxes is a list of lists of box ranges; there must be points contained in each box-list for the grasp to be valid (points are summed within lists) origin of gripper is at the ?_wrist_roll_link
def init_cluster_grasper
 initialization for planning grasps
def keypause
 pause for enter
def object_fits_in_hand
 figure out whether all the points fit within the gripper for an arbitrary pose (no more than gripper width/2 away from gripper x-z plane)
def orthogonal_measure
 how far is the pose from being orthogonal to the object frame? returns a measure of angle of the closest rotation that would make the pose orthogonal to the object frame
def overhead_angle
 angle of gripper pose x-axis away from directly overhead (global -z)
def plan_point_cluster_grasps
 plan grasps for a point cluster
def pplist
 pretty-print list to string
def quality_to_probability
 turn a quality value into a 'probability' value (fairly arbitrary, not based on real data)
def transform_ranges
 transform ranges for a bounding box using transform

Public Attributes

 actual_wrist_frame_in_model_frame
 backoff_depth_steps
 cbbf
 cluster_frame
 collision_point_id_start
 debug
 disable_grasp_neighbor_check
 draw_functions
 draw_gripper
 gripper_box_id_start
 gripper_boxes
 gripper_opening
 height_good_for_side_grasps
 include_high_point_grasps
 min_good_grasp_points
 model_frame_in_actual_wrist_frame
 overhead_grasps_only
 palm_step
 point_id_start
 pregrasp_dist
 pregrasp_just_outside_box
 side_grasp_start_height
 side_grasps_only
 side_step
 space_boxes
 tf_broadcaster
 tf_listener

Private Attributes

 _box_fits_in_hand
 _outfile
 _output_features
 _points_per_sq_cm
 _wrist_to_fingertip_center_dist
 _wrist_to_palm_dist

Detailed Description

Class for doing grasp planning on point clusters.

Definition at line 67 of file point_cluster_grasp_planner.py.


Constructor & Destructor Documentation

Definition at line 69 of file point_cluster_grasp_planner.py.


Member Function Documentation

check if a box goes through the x-y plane ranges is [[xmin, ymin, zmin], [xmax, ymax, zmax]] pose is a 4x4 scipy matrix

Definition at line 267 of file point_cluster_grasp_planner.py.

check both sides of a grasp to see if they are also viable grasps

Definition at line 475 of file point_cluster_grasp_planner.py.

check for collisions and points within the gripper when placed at a given pose (4x4 scipy mat) returns -1 for colliding with points, -2 for colliding with the table, and the number of points inside the gripper otherwise table is assumed to be the xy plane

Definition at line 285 of file point_cluster_grasp_planner.py.

def pr2_gripper_grasp_planner_cluster.point_cluster_grasp_planner.PointClusterGraspPlanner.draw_gripper_model (   self,
  pose_mat,
  frame = 'object_frame',
  pause_after_broadcast = 0 
)

draw the box model of the gripper, placed at pose_mat (4x4 scipy matrix) in frame (defaults to the object frame)

Definition at line 180 of file point_cluster_grasp_planner.py.

given a cluster and a grasp pose (4x4 scipy mat in object frame), guess at the probability of success for the grasp

Definition at line 356 of file point_cluster_grasp_planner.py.

evaluate grasps on the point cluster

Definition at line 761 of file point_cluster_grasp_planner.py.

def pr2_gripper_grasp_planner_cluster.point_cluster_grasp_planner.PointClusterGraspPlanner.find_best_palm_dir_grasp (   self,
  points,
  start_pose,
  palm_step,
  object_bounding_box 
)

find the best grasp from a given start pose along the palm (gripper x) direction, in steps of size palm_step moving the gripper inward until/as long as there are object points within the gripper, until there are collisions checking for collisions with the table (assumed to be the xy plane) returns the grasp pose if a good grasp is found, None if not

Definition at line 538 of file point_cluster_grasp_planner.py.

find the distances from the object box center to the fingertip center when projected on the gripper x-, y-, and z-axes

Definition at line 440 of file point_cluster_grasp_planner.py.

def pr2_gripper_grasp_planner_cluster.point_cluster_grasp_planner.PointClusterGraspPlanner.find_grasps_along_direction (   self,
  points,
  start_pose,
  axis,
  spacing,
  palm_step,
  object_bounding_box,
  max_side_move = None,
  omit_center = False 
)

for a given gripper pose and axis (0=x, 1=y, 2=z), both expressed in the points frame, find grasps at a fixed spacing along that axis in both directions while varying the palm dist (inward by steps of palm_step) as long as there are object points within the gripper, until there are collisions start_pose is a 4x4 scipy mat, object_bounding_box is [[xmin, ymin, zmin], [xmax, ymax, zmax]] min_points is the minimum number of points that need to be inside the hand for the grasp to be okay

Definition at line 582 of file point_cluster_grasp_planner.py.

def pr2_gripper_grasp_planner_cluster.point_cluster_grasp_planner.PointClusterGraspPlanner.find_high_point_grasps (   self,
  points,
  object_bounding_box,
  object_bounding_box_dims,
  palm_step,
  max_grasps_to_return = 40 
)

find grasps of high points on the object, pointing in towards the bottom center of the object

Definition at line 628 of file point_cluster_grasp_planner.py.

def pr2_gripper_grasp_planner_cluster.point_cluster_grasp_planner.PointClusterGraspPlanner.find_points_in_bounding_box (   self,
  wrist_frame_points,
  ranges,
  return_points = 0 
)

return a count of points (4xn scipy mat) contained in a bounding box (ranges is a 2-list (min, max) of 3-lists (x,y,z))

Definition at line 231 of file point_cluster_grasp_planner.py.

def pr2_gripper_grasp_planner_cluster.point_cluster_grasp_planner.PointClusterGraspPlanner.grasp_quality (   self,
  point_count,
  palm_dist,
  side_dist,
  overhead_grasp,
  fits_in_hand,
  not_edge,
  orthogonality = 1,
  centered_dist = 0,
  points = None,
  grasp = None,
  collision_point_count = 0 
)

assign a numerical quality value for this grasp

Definition at line 507 of file point_cluster_grasp_planner.py.

return the xyz bounding box ranges for the parts of the gripper model placed at 3-list pos and 3x3 scipy matrix rot uses a really simple model of the fully-open gripper as three boxes (2 fingers and a palm), with a box for the empty space in-between gripper_boxes is a list of boxes, each of which is a 2-list (min, max) of 3-lists (x,y,z) of corner coords space boxes is a list of lists of box ranges; there must be points contained in each box-list for the grasp to be valid (points are summed within lists) origin of gripper is at the ?_wrist_roll_link

Definition at line 215 of file point_cluster_grasp_planner.py.

initialization for planning grasps

Definition at line 729 of file point_cluster_grasp_planner.py.

pause for enter

Definition at line 722 of file point_cluster_grasp_planner.py.

figure out whether all the points fit within the gripper for an arbitrary pose (no more than gripper width/2 away from gripper x-z plane)

Definition at line 457 of file point_cluster_grasp_planner.py.

how far is the pose from being orthogonal to the object frame? returns a measure of angle of the closest rotation that would make the pose orthogonal to the object frame

Definition at line 407 of file point_cluster_grasp_planner.py.

angle of gripper pose x-axis away from directly overhead (global -z)

Definition at line 467 of file point_cluster_grasp_planner.py.

plan grasps for a point cluster

Definition at line 780 of file point_cluster_grasp_planner.py.

pretty-print list to string

Definition at line 175 of file point_cluster_grasp_planner.py.

turn a quality value into a 'probability' value (fairly arbitrary, not based on real data)

Definition at line 393 of file point_cluster_grasp_planner.py.

transform ranges for a bounding box using transform

Definition at line 255 of file point_cluster_grasp_planner.py.


Member Data Documentation

Definition at line 729 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 729 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.

Definition at line 69 of file point_cluster_grasp_planner.py.


The documentation for this class was generated from the following file:


pr2_gripper_grasp_planner_cluster
Author(s): Kaijen Hsiao
autogenerated on Mon Oct 6 2014 12:13:03