Public Member Functions | Private Member Functions | Private Attributes
HandSearch Class Reference

Search for grasp hypotheses. More...

#include <hand_search.h>

List of all members.

Public Member Functions

std::vector< GraspHypothesisfindHands (const PointCloud::Ptr cloud, const Eigen::VectorXi &pts_cam_source, const std::vector< int > &indices, const PointCloud::Ptr cloud_plot, bool calculates_antipodal, bool uses_clustering)
 Find grasp hypotheses in a point cloud.
 HandSearch (double finger_width, double hand_outer_diameter, double hand_depth, double hand_height, double init_bite, int num_threads, int num_samples, bool plots_hands)
 Constructor.

Private Member Functions

std::vector< GraspHypothesisfindHands (const PointCloud::Ptr cloud, const Eigen::VectorXi &pts_cam_source, const std::vector< Quadric > &quadric_list, const Eigen::VectorXi &hands_cam_source, const pcl::KdTreeFLANN< pcl::PointXYZ > &kdtree)
 Find grasp hypotheses in a point cloud given a list of quadratic surfaces.
std::vector< QuadricfindQuadrics (const PointCloud::Ptr cloud, const Eigen::VectorXi &pts_cam_source, const pcl::KdTreeFLANN< pcl::PointXYZ > &kdtree, const std::vector< int > &indices)
 Find quadratic surfaces in a point cloud.

Private Attributes

Eigen::Matrix4d cam_tf_left_
Eigen::Matrix4d cam_tf_right_
 camera poses
Eigen::Matrix3Xd cloud_normals_
 a 3xn matrix containing the normals for points in the point cloud
double finger_width_
double hand_depth_
 the finger length
double hand_height_
 the hand extends plus/minus this value along the hand axis
double hand_outer_diameter_
 the maximum robot hand aperture
double init_bite_
 the minimum object height
double nn_radius_hands_
 the radius for the neighborhood search for the hand search
double nn_radius_taubin_
 the radius for the neighborhood search for the quadratic surface fit
int num_samples_
 the number of samples used in the search
int num_threads_
 the number of threads used in the search
Plot plot_
 plot object for visualization of search results
bool plots_camera_sources_
 whether the camera source for each point in the point cloud is plotted
bool plots_hands_
 whether the grasp hypotheses are plotted
bool plots_local_axes_
 whether the local axes estimated for each point neighborhood are plotted
bool plots_samples_
 whether the samples drawn from the point cloud are plotted
bool tolerant_antipodal_
 whether the antipodal testing uses "tolerant" thresholds
bool uses_determinstic_normal_estimation_
 whether the normal estimation for the quadratic surface is deterministic (used for debugging)

Detailed Description

Search for grasp hypotheses.

HandSearch class

This class searches for grasp hypotheses in a point cloud by first fitting a quadratic surface to a small, local point neighborhood, and then finding geometrically feasible grasp hypotheses for a larger point neighborhood. It can also estimate whether the grasp is antipodal from the normals of the point neighborhood.

Definition at line 61 of file hand_search.h.


Constructor & Destructor Documentation

HandSearch::HandSearch ( double  finger_width,
double  hand_outer_diameter,
double  hand_depth,
double  hand_height,
double  init_bite,
int  num_threads,
int  num_samples,
bool  plots_hands 
) [inline]

Constructor.

Parameters:
finger_widththe width of the robot hand fingers
hand_outer_diameterthe maximum robot hand aperture
hand_depththe hand depth (length of fingers)
hand_heightthe hand extends plus/minus this value along the hand axis
init_bitethe minimum object height
num_threadsthe number of CPU threads to be used for the search
num_samplesthe number of samples drawn from the point cloud
plots_handswhether grasp hypotheses are plotted

Definition at line 76 of file hand_search.h.


Member Function Documentation

std::vector< GraspHypothesis > HandSearch::findHands ( const PointCloud::Ptr  cloud,
const Eigen::VectorXi &  pts_cam_source,
const std::vector< int > &  indices,
const PointCloud::Ptr  cloud_plot,
bool  calculates_antipodal,
bool  uses_clustering 
)

Find grasp hypotheses in a point cloud.

If the parameter indices is of size 0, then indices are randomly drawn from the point cloud according to a uniform distribution.

Parameters:
cloudthe point cloud that is searched for grasp hypotheses
pts_cam_sourcethe camera source for each point in the point cloud
indicesthe list of point cloud indices that are used in the search
cloud_plotthe point cloud that is used for plotting
calculates_antipodalwhether grasp hypotheses are estimated to be antipodal
uses_clusteringwhether clustering is used to divide the point cloud (useful for creating training data)
Returns:
a list of grasp hypotheses

Definition at line 4 of file hand_search.cpp.

std::vector< GraspHypothesis > HandSearch::findHands ( const PointCloud::Ptr  cloud,
const Eigen::VectorXi &  pts_cam_source,
const std::vector< Quadric > &  quadric_list,
const Eigen::VectorXi &  hands_cam_source,
const pcl::KdTreeFLANN< pcl::PointXYZ > &  kdtree 
) [private]

Find grasp hypotheses in a point cloud given a list of quadratic surfaces.

Parameters:
cloudthe point cloud that is searched for quadrics
pts_cam_sourcethe camera source for each point in the point cloud
quadric_listthe list of quadratic surfaces
hands_cam_sourcethe camera source for each sample
kdtreethe KD tree that is used for finding point neighborhoods
Returns:
a list of grasp hypotheses

Definition at line 116 of file hand_search.cpp.

std::vector< Quadric > HandSearch::findQuadrics ( const PointCloud::Ptr  cloud,
const Eigen::VectorXi &  pts_cam_source,
const pcl::KdTreeFLANN< pcl::PointXYZ > &  kdtree,
const std::vector< int > &  indices 
) [private]

Find quadratic surfaces in a point cloud.

Parameters:
cloudthe point cloud that is searched for quadrics
pts_cam_sourcethe camera source for each point in the point cloud
kdtreethe KD tree that is used for finding point neighborhoods
indicesthe list of point cloud indices that are used in the search
Returns:
a list of quadratic surfaces

Definition at line 65 of file hand_search.cpp.


Member Data Documentation

Eigen::Matrix4d HandSearch::cam_tf_left_ [private]

Definition at line 132 of file hand_search.h.

Eigen::Matrix4d HandSearch::cam_tf_right_ [private]

camera poses

Definition at line 132 of file hand_search.h.

Eigen::Matrix3Xd HandSearch::cloud_normals_ [private]

a 3xn matrix containing the normals for points in the point cloud

Definition at line 143 of file hand_search.h.

double HandSearch::finger_width_ [private]

hand search parameters

Definition at line 135 of file hand_search.h.

double HandSearch::hand_depth_ [private]

the finger length

Definition at line 137 of file hand_search.h.

double HandSearch::hand_height_ [private]

the hand extends plus/minus this value along the hand axis

Definition at line 138 of file hand_search.h.

the maximum robot hand aperture

Definition at line 136 of file hand_search.h.

double HandSearch::init_bite_ [private]

the minimum object height

Definition at line 139 of file hand_search.h.

double HandSearch::nn_radius_hands_ [private]

the radius for the neighborhood search for the hand search

Definition at line 155 of file hand_search.h.

the radius for the neighborhood search for the quadratic surface fit

Definition at line 154 of file hand_search.h.

int HandSearch::num_samples_ [private]

the number of samples used in the search

Definition at line 141 of file hand_search.h.

int HandSearch::num_threads_ [private]

the number of threads used in the search

Definition at line 140 of file hand_search.h.

plot object for visualization of search results

Definition at line 144 of file hand_search.h.

whether the camera source for each point in the point cloud is plotted

Definition at line 150 of file hand_search.h.

bool HandSearch::plots_hands_ [private]

whether the grasp hypotheses are plotted

Definition at line 152 of file hand_search.h.

whether the local axes estimated for each point neighborhood are plotted

Definition at line 151 of file hand_search.h.

whether the samples drawn from the point cloud are plotted

Definition at line 149 of file hand_search.h.

whether the antipodal testing uses "tolerant" thresholds

Definition at line 147 of file hand_search.h.

whether the normal estimation for the quadratic surface is deterministic (used for debugging)

Definition at line 146 of file hand_search.h.


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


agile_grasp
Author(s):
autogenerated on Thu Aug 27 2015 12:01:28