pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::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 4-list (palm, left finger, right finger, space) of 2-lists (min, max) of 3-lists (x,y,z) of corner coords 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

 cbbf
 cluster_frame
 collision_point_id_start
 debug
 draw_functions
 gripper_box_id_start
 gripper_boxes
 min_good_grasp_points
 point_id_start
 pregrasp_dist
 tf_broadcaster
 tf_listener

Private Attributes

 _box_fits_in_hand
 _gripper_opening
 _height_good_for_side_grasps
 _outfile
 _output_features
 _palm_step
 _side_step
 _wrist_to_fingertip_center_dist

Detailed Description

Class for doing grasp planning on point clusters.

Definition at line 69 of file pr2_gripper_grasp_planner_cluster.py.


Member Function Documentation

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::__init__ (   self,
  tf_listener = None,
  tf_broadcaster = None 
)

Definition at line 71 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::check_box_plane_collisions (   self,
  pose,
  ranges 
)

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 219 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::check_grasp_neighbors (   self,
  points,
  grasp 
)

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

Definition at line 407 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::check_gripper_pose (   self,
  points,
  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

Definition at line 237 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::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 139 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::evaluate_arbitrary_grasp (   self,
  points,
  pose 
)

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 293 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::evaluate_point_cluster_grasps (   self,
  grasps,
  frame 
)

evaluate grasps on the point cluster

Definition at line 680 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::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 467 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::find_fingertip_object_center_dists (   self,
  pose 
)

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 372 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::find_grasps_along_direction (   self,
  points,
  start_pose,
  axis,
  spacing,
  palm_step,
  object_bounding_box,
  max_side_move = None 
)

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 511 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::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 557 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::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 183 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::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 439 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::gripper_model (   self  ) 

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 4-list (palm, left finger, right finger, space) of 2-lists (min, max) of 3-lists (x,y,z) of corner coords origin of gripper is at the ?_wrist_roll_link

Definition at line 168 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::init_cluster_grasper (   self,
  cluster 
)

initialization for planning grasps

Definition at line 656 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::keypause (   self  ) 

pause for enter

Definition at line 649 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::object_fits_in_hand (   self,
  points,
  pose 
)

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 389 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::orthogonal_measure (   self,
  pose 
)

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 344 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::overhead_angle (   self,
  pose 
)

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

Definition at line 399 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::plan_point_cluster_grasps (   self  ) 

plan grasps for a point cluster

Definition at line 697 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::pplist (   self,
  list 
)

pretty-print list to string

Definition at line 134 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::quality_to_probability (   self,
  quality 
)

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

Definition at line 330 of file pr2_gripper_grasp_planner_cluster.py.

def pr2_gripper_grasp_planner_cluster::pr2_gripper_grasp_planner_cluster::PointClusterGraspPlanner::transform_ranges (   self,
  transform,
  ranges 
)

transform ranges for a bounding box using transform

Definition at line 207 of file pr2_gripper_grasp_planner_cluster.py.


Member Data Documentation

Definition at line 667 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 113 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 110 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 127 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 125 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 119 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 116 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 122 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 86 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 658 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 105 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 130 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 92 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 106 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 89 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 101 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 104 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 98 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 81 of file pr2_gripper_grasp_planner_cluster.py.

Definition at line 75 of file pr2_gripper_grasp_planner_cluster.py.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables


pr2_gripper_grasp_planner_cluster
Author(s): Kaijen Hsiao
autogenerated on Fri Jan 11 09:42:43 2013