Classes | Public Member Functions | Private Member Functions | Private Attributes
Localization Class Reference

High level interface for the localization of grasp hypotheses and handles. More...

#include <localization.h>

List of all members.

Classes

struct  UniqueVectorComparator
 Comparator for checking uniqueness of two 3D-vectors. More...

Public Member Functions

std::vector< HandlefindHandles (const std::vector< GraspHypothesis > &hand_list, int min_inliers, double min_length, bool is_plotting=false)
 Find handles given a list of grasp hypotheses.
const Eigen::Matrix4d & getCameraTransform (bool is_left)
 Return the camera pose of one given camera.
 Localization ()
 Default Constructor.
 Localization (int num_threads, bool filters_boundaries, bool plots_hands)
 Constructor.
std::vector< GraspHypothesislocalizeHands (const PointCloud::Ptr &cloud_in, int size_left, const std::vector< int > &indices, bool calculates_antipodal, bool uses_clustering)
 Localize hands in a given point cloud.
std::vector< GraspHypothesislocalizeHands (const std::string &pcd_filename_left, const std::string &pcd_filename_right, bool calculates_antipodal=false, bool uses_clustering=false)
 Localize hands given two point cloud files.
std::vector< GraspHypothesislocalizeHands (const std::string &pcd_filename_left, const std::string &pcd_filename_right, const std::vector< int > &indices, bool calculates_antipodal=false, bool uses_clustering=false)
 Localize hands given two point cloud files and a set of point cloud indices.
std::vector< GraspHypothesispredictAntipodalHands (const std::vector< GraspHypothesis > &hand_list, const std::string &svm_filename)
 Predict antipodal grasps given a list of grasp hypotheses.
void setCameraTransforms (const Eigen::Matrix4d &cam_tf_left, const Eigen::Matrix4d &cam_tf_right)
 Set the camera poses.
void setFingerWidth (double finger_width)
 Set the finger width of the robot hand.
void setHandDepth (double hand_depth)
 Set the hand depth of the robot hand.
void setHandHeight (double hand_height)
 Set the height of the robot hand.
void setHandOuterDiameter (double hand_outer_diameter)
 Set the maximum aperture of the robot hand.
void setInitBite (double init_bite)
 Set the initial "bite" of the robot hand (usually the minimum object "height").
void setNeighborhoodRadiusHands (double nn_radius_hands)
 Set the radius to be used for the point neighborhood search in the hand search.
void setNeighborhoodRadiusTaubin (double nn_radius_taubin)
 Set the radius to be used for the point neighborhood search in the quadric fit.
void setNumSamples (int num_samples)
 Set the number of samples to be used for the search.
void setWorkspace (const Eigen::VectorXd &workspace)
 Set the dimensions of the robot's workspace.

Private Member Functions

std::vector< GraspHypothesisfilterHands (const std::vector< GraspHypothesis > &hand_list)
 Filter out grasp hypotheses that are close to the workspace boundaries.
void filterWorkspace (const PointCloud::Ptr &cloud_in, const Eigen::VectorXi &pts_cam_source_in, PointCloud::Ptr &cloud_out, Eigen::VectorXi &pts_cam_source_out)
 Filter out points in the point cloud that lie outside the workspace dimensions and keep track of the camera source for each point that is not filtered out.
Eigen::Vector3i floorVector (const Eigen::Vector3d &a)
 Round a 3D-vector down to the closest, smaller integers.
void voxelizeCloud (const PointCloud::Ptr &cloud_in, const Eigen::VectorXi &pts_cam_source_in, PointCloud::Ptr &cloud_out, Eigen::VectorXi &pts_cam_source_out, double cell_size)
 Voxelize the point cloud and keep track of the camera source for each voxel.

Private Attributes

Eigen::Matrix4d cam_tf_left_
Eigen::Matrix4d cam_tf_right_
 the camera poses
PointCloud::Ptr cloud_
 the input point cloud
Eigen::Matrix3Xd cloud_normals_
 the normals for each point in the point cloud
bool filters_boundaries_
 whether grasp hypotheses close to the workspace boundaries are filtered out
double finger_width_
 width of the fingers
double hand_depth_
 hand depth (finger length)
double hand_height_
 hand height
double hand_outer_diameter_
 maximum hand aperture
double init_bite_
 initial bite
double nn_radius_hands_
 the radius of the neighborhood search used in the quadric fit
double nn_radius_taubin_
 the radius of the neighborhood search used in the grasp hypothesis search
int num_samples_
 the number of samples used in the search
int num_threads_
 the number of CPU threads used in the search
Plot plot_
 the plot object
bool plots_camera_sources_
 whether the camera source is plotted for each point in the point cloud
bool plots_hands_
 whether the results of the grasp hypothesis search are plotted
Eigen::VectorXd workspace_
 the robot's workspace dimensions

Detailed Description

High level interface for the localization of grasp hypotheses and handles.

Localization class

This class provides a high level interface to search for grasp hypotheses, antipodal grasps, and handles. It can also preprocess the point clouds.

Definition at line 68 of file localization.h.


Constructor & Destructor Documentation

Default Constructor.

Definition at line 75 of file localization.h.

Localization::Localization ( int  num_threads,
bool  filters_boundaries,
bool  plots_hands 
) [inline]

Constructor.

Parameters:
num_threadsthe number of threads to be used in the search
filter_boundarieswhether grasp hypotheses that are close to the point cloud boundaries are filtered out
plots_handswhether grasp hypotheses are plotted

Definition at line 85 of file localization.h.


Member Function Documentation

std::vector< GraspHypothesis > Localization::filterHands ( const std::vector< GraspHypothesis > &  hand_list) [private]

Filter out grasp hypotheses that are close to the workspace boundaries.

Parameters:
hand_listthe list of grasp hypotheses to be filtered
Returns:
the list of grasp hypotheses that are not filtered out

Definition at line 330 of file localization.cpp.

void Localization::filterWorkspace ( const PointCloud::Ptr &  cloud_in,
const Eigen::VectorXi &  pts_cam_source_in,
PointCloud::Ptr &  cloud_out,
Eigen::VectorXi &  pts_cam_source_out 
) [private]

Filter out points in the point cloud that lie outside the workspace dimensions and keep track of the camera source for each point that is not filtered out.

Parameters:
[in]cloud_inthe point cloud to be filtered
[in]pts_cam_source_inthe camera source for each point in the point cloud
[out]cloud_outthe filtered point cloud
[out]pts_cam_source_outthe camera source for each point in the filtered cloud

Definition at line 182 of file localization.cpp.

std::vector< Handle > Localization::findHandles ( const std::vector< GraspHypothesis > &  hand_list,
int  min_inliers,
double  min_length,
bool  is_plotting = false 
)

Find handles given a list of grasp hypotheses.

Parameters:
hand_listthe list of grasp hypotheses
min_inliersthe minimum number of handle inliers
min_lengththe minimum length of the handle
is_plottingwhether the handles are plotted

Definition at line 356 of file localization.cpp.

Eigen::Vector3i Localization::floorVector ( const Eigen::Vector3d &  a) [private]

Round a 3D-vector down to the closest, smaller integers.

Parameters:
athe 3D-vector to be rounded down
Returns:
the rounded down 3D-vector

Definition at line 323 of file localization.cpp.

const Eigen::Matrix4d& Localization::getCameraTransform ( bool  is_left) [inline]

Return the camera pose of one given camera.

Parameters:
is_lefttrue if the pose of the left camera is wanted, false if the pose of the right camera is wanted
Returns:
the pose of the camera specified by is_left

Definition at line 161 of file localization.h.

std::vector< GraspHypothesis > Localization::localizeHands ( const PointCloud::Ptr &  cloud_in,
int  size_left,
const std::vector< int > &  indices,
bool  calculates_antipodal,
bool  uses_clustering 
)

Localize hands in a given point cloud.

Parameters:
cloud_inthe input point cloud
indicesthe set of point cloud indices for which point neighborhoods are found
calculates_antipodalwhether the grasp hypotheses are checked for being antipodal
uses_clusteringwhether clustering is used for processing the point cloud
Returns:
the list of grasp hypotheses found

Definition at line 3 of file localization.cpp.

std::vector< GraspHypothesis > Localization::localizeHands ( const std::string &  pcd_filename_left,
const std::string &  pcd_filename_right,
bool  calculates_antipodal = false,
bool  uses_clustering = false 
)

Localize hands given two point cloud files.

Parameters:
pcd_filename_leftthe first point cloud file location and name
pcd_filename_rightthe second point cloud file location and name
calculates_antipodalwhether the grasp hypotheses are checked for being antipodal
uses_clusteringwhether clustering is used for processing the point cloud
Returns:
the list of grasp hypotheses found

Definition at line 135 of file localization.cpp.

std::vector< GraspHypothesis > Localization::localizeHands ( const std::string &  pcd_filename_left,
const std::string &  pcd_filename_right,
const std::vector< int > &  indices,
bool  calculates_antipodal = false,
bool  uses_clustering = false 
)

Localize hands given two point cloud files and a set of point cloud indices.

Parameters:
pcd_filename_leftthe first point cloud file location and name
pcd_filename_rightthe second point cloud file location and name
indicesthe set of point cloud indices for which point neighborhoods are found
calculates_antipodalwhether the grasp hypotheses are checked for being antipodal
uses_clusteringwhether clustering is used for processing the point cloud
Returns:
the list of grasp hypotheses found

Definition at line 142 of file localization.cpp.

std::vector< GraspHypothesis > Localization::predictAntipodalHands ( const std::vector< GraspHypothesis > &  hand_list,
const std::string &  svm_filename 
)

Predict antipodal grasps given a list of grasp hypotheses.

Parameters:
hand_listthe list of grasp hypotheses
svm_filenamethe location and filename of the SVM

Definition at line 118 of file localization.cpp.

void Localization::setCameraTransforms ( const Eigen::Matrix4d &  cam_tf_left,
const Eigen::Matrix4d &  cam_tf_right 
) [inline]

Set the camera poses.

Parameters:
cam_tf_leftthe pose of the left camera
cam_tf_rightthe pose of the right camera

Definition at line 150 of file localization.h.

void Localization::setFingerWidth ( double  finger_width) [inline]

Set the finger width of the robot hand.

Parameters:
finger_widththe finger width

Definition at line 209 of file localization.h.

void Localization::setHandDepth ( double  hand_depth) [inline]

Set the hand depth of the robot hand.

Parameters:
hand_depththe hand depth of the robot hand (usually the finger length)

Definition at line 218 of file localization.h.

void Localization::setHandHeight ( double  hand_height) [inline]

Set the height of the robot hand.

Parameters:
hand_heightthe height of the robot hand, the hand extends plus/minus this value along the hand axis

Definition at line 245 of file localization.h.

void Localization::setHandOuterDiameter ( double  hand_outer_diameter) [inline]

Set the maximum aperture of the robot hand.

Parameters:
hand_outer_diameterthe maximum aperture of the robot hand

Definition at line 227 of file localization.h.

void Localization::setInitBite ( double  init_bite) [inline]

Set the initial "bite" of the robot hand (usually the minimum object "height").

Parameters:
init_bitethe initial "bite" of the robot hand (
See also:
FingerHand)

Definition at line 236 of file localization.h.

void Localization::setNeighborhoodRadiusHands ( double  nn_radius_hands) [inline]

Set the radius to be used for the point neighborhood search in the hand search.

Parameters:
nn_radius_handsthe radius to be used for the point neighborhood search

Definition at line 191 of file localization.h.

void Localization::setNeighborhoodRadiusTaubin ( double  nn_radius_taubin) [inline]

Set the radius to be used for the point neighborhood search in the quadric fit.

Parameters:
nn_radius_handsthe radius to be used for the point neighborhood search

Definition at line 200 of file localization.h.

void Localization::setNumSamples ( int  num_samples) [inline]

Set the number of samples to be used for the search.

Parameters:
num_samplesthe number of samples to be used for the search

Definition at line 182 of file localization.h.

void Localization::setWorkspace ( const Eigen::VectorXd &  workspace) [inline]

Set the dimensions of the robot's workspace.

Parameters:
workspace1x6 vector containing the robot's workspace dimensions

Definition at line 173 of file localization.h.

void Localization::voxelizeCloud ( const PointCloud::Ptr &  cloud_in,
const Eigen::VectorXi &  pts_cam_source_in,
PointCloud::Ptr &  cloud_out,
Eigen::VectorXi &  pts_cam_source_out,
double  cell_size 
) [private]

Voxelize the point cloud and keep track of the camera source for each voxel.

Parameters:
[in]cloud_inthe point cloud to be voxelized
[in]pts_cam_source_inthe camera source for each point in the point cloud
[out]cloud_outthe voxelized point cloud
[out]pts_cam_source_outthe camera source for each point in the voxelized cloud
[in]cell_sizethe size of each voxel

Definition at line 213 of file localization.cpp.


Member Data Documentation

Eigen::Matrix4d Localization::cam_tf_left_ [private]

Definition at line 314 of file localization.h.

Eigen::Matrix4d Localization::cam_tf_right_ [private]

the camera poses

Definition at line 314 of file localization.h.

PointCloud::Ptr Localization::cloud_ [private]

the input point cloud

Definition at line 317 of file localization.h.

Eigen::Matrix3Xd Localization::cloud_normals_ [private]

the normals for each point in the point cloud

Definition at line 316 of file localization.h.

whether grasp hypotheses close to the workspace boundaries are filtered out

Definition at line 329 of file localization.h.

double Localization::finger_width_ [private]

width of the fingers

Definition at line 322 of file localization.h.

double Localization::hand_depth_ [private]

hand depth (finger length)

Definition at line 324 of file localization.h.

double Localization::hand_height_ [private]

hand height

Definition at line 325 of file localization.h.

maximum hand aperture

Definition at line 323 of file localization.h.

double Localization::init_bite_ [private]

initial bite

Definition at line 326 of file localization.h.

the radius of the neighborhood search used in the quadric fit

Definition at line 321 of file localization.h.

the radius of the neighborhood search used in the grasp hypothesis search

Definition at line 320 of file localization.h.

the number of samples used in the search

Definition at line 319 of file localization.h.

the number of CPU threads used in the search

Definition at line 318 of file localization.h.

the plot object

Definition at line 313 of file localization.h.

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

Definition at line 327 of file localization.h.

whether the results of the grasp hypothesis search are plotted

Definition at line 328 of file localization.h.

Eigen::VectorXd Localization::workspace_ [private]

the robot's workspace dimensions

Definition at line 315 of file localization.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