High level interface for the localization of grasp hypotheses and handles. More...
#include <localization.h>
Classes | |
struct | UniqueVectorComparator |
Comparator for checking uniqueness of two 3D-vectors. More... | |
Public Member Functions | |
void | createVisualsPub (ros::NodeHandle &node, double marker_lifetime, const std::string &frame) |
Set the publisher for Rviz visualization, the lifetime of visual markers, and the frame associated with the grasps. | |
std::vector< Handle > | findHandles (const std::vector< GraspHypothesis > &hand_list, int min_inliers, double min_length) |
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, int plotting_mode) | |
Constructor. | |
std::vector< GraspHypothesis > | 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. | |
std::vector< GraspHypothesis > | 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. | |
std::vector< GraspHypothesis > | 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. | |
std::vector< GraspHypothesis > | predictAntipodalHands (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. | |
Static Public Attributes | |
static const int | NO_PLOTTING = 0 |
no plotting | |
static const int | PCL_PLOTTING = 1 |
plotting in PCL | |
static const int | PCL_PLOTTING_FINGERS = 2 |
plotting in PCL, plots hands with fingers | |
static const int | RVIZ_PLOTTING = 3 |
plotting in Rviz | |
Private Member Functions | |
std::vector< GraspHypothesis > | filterHands (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 | |
int | plotting_mode_ |
what plotting mode is used | |
std::string | visuals_frame_ |
visualization frame for Rviz | |
Eigen::VectorXd | workspace_ |
the robot's workspace dimensions |
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.
Localization::Localization | ( | ) | [inline] |
Default Constructor.
Definition at line 75 of file localization.h.
Localization::Localization | ( | int | num_threads, |
bool | filters_boundaries, | ||
int | plotting_mode | ||
) | [inline] |
Constructor.
num_threads | the number of threads to be used in the search |
filter_boundaries | whether grasp hypotheses that are close to the point cloud boundaries are filtered out |
plots_hands | whether grasp hypotheses are plotted |
Definition at line 84 of file localization.h.
void Localization::createVisualsPub | ( | ros::NodeHandle & | node, |
double | marker_lifetime, | ||
const std::string & | frame | ||
) | [inline] |
Set the publisher for Rviz visualization, the lifetime of visual markers, and the frame associated with the grasps.
node | the ROS node |
marker_lifetime | the lifetime of each visual marker |
frame | the frame to which the grasps belong |
Definition at line 255 of file localization.h.
std::vector< GraspHypothesis > Localization::filterHands | ( | const std::vector< GraspHypothesis > & | hand_list | ) | [private] |
Filter out grasp hypotheses that are close to the workspace boundaries.
hand_list | the list of grasp hypotheses to be filtered |
Definition at line 364 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.
[in] | cloud_in | the point cloud to be filtered |
[in] | pts_cam_source_in | the camera source for each point in the point cloud |
[out] | cloud_out | the filtered point cloud |
[out] | pts_cam_source_out | the camera source for each point in the filtered cloud |
Definition at line 216 of file localization.cpp.
std::vector< Handle > Localization::findHandles | ( | const std::vector< GraspHypothesis > & | hand_list, |
int | min_inliers, | ||
double | min_length | ||
) |
Find handles given a list of grasp hypotheses.
hand_list | the list of grasp hypotheses |
min_inliers | the minimum number of handle inliers |
min_length | the minimum length of the handle |
is_plotting | whether the handles are plotted |
Definition at line 390 of file localization.cpp.
Eigen::Vector3i Localization::floorVector | ( | const Eigen::Vector3d & | a | ) | [private] |
Round a 3D-vector down to the closest, smaller integers.
a | the 3D-vector to be rounded down |
Definition at line 357 of file localization.cpp.
const Eigen::Matrix4d& Localization::getCameraTransform | ( | bool | is_left | ) | [inline] |
Return the camera pose of one given camera.
is_left | true if the pose of the left camera is wanted, false if the pose of the right camera is wanted |
is_left
Definition at line 159 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.
cloud_in | the input point cloud |
indices | the set of point cloud indices for which point neighborhoods are found |
calculates_antipodal | whether the grasp hypotheses are checked for being antipodal |
uses_clustering | whether clustering is used for processing the point cloud |
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.
pcd_filename_left | the first point cloud file location and name |
pcd_filename_right | the second point cloud file location and name |
calculates_antipodal | whether the grasp hypotheses are checked for being antipodal |
uses_clustering | whether clustering is used for processing the point cloud |
Definition at line 169 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.
pcd_filename_left | the first point cloud file location and name |
pcd_filename_right | the second point cloud file location and name |
indices | the set of point cloud indices for which point neighborhoods are found |
calculates_antipodal | whether the grasp hypotheses are checked for being antipodal |
uses_clustering | whether clustering is used for processing the point cloud |
Definition at line 176 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.
hand_list | the list of grasp hypotheses |
svm_filename | the location and filename of the SVM |
Definition at line 142 of file localization.cpp.
void Localization::setCameraTransforms | ( | const Eigen::Matrix4d & | cam_tf_left, |
const Eigen::Matrix4d & | cam_tf_right | ||
) | [inline] |
Set the camera poses.
cam_tf_left | the pose of the left camera |
cam_tf_right | the pose of the right camera |
Definition at line 148 of file localization.h.
void Localization::setFingerWidth | ( | double | finger_width | ) | [inline] |
Set the finger width of the robot hand.
finger_width | the finger width |
Definition at line 207 of file localization.h.
void Localization::setHandDepth | ( | double | hand_depth | ) | [inline] |
Set the hand depth of the robot hand.
hand_depth | the hand depth of the robot hand (usually the finger length) |
Definition at line 216 of file localization.h.
void Localization::setHandHeight | ( | double | hand_height | ) | [inline] |
Set the height of the robot hand.
hand_height | the height of the robot hand, the hand extends plus/minus this value along the hand axis |
Definition at line 243 of file localization.h.
void Localization::setHandOuterDiameter | ( | double | hand_outer_diameter | ) | [inline] |
Set the maximum aperture of the robot hand.
hand_outer_diameter | the maximum aperture of the robot hand |
Definition at line 225 of file localization.h.
void Localization::setInitBite | ( | double | init_bite | ) | [inline] |
Set the initial "bite" of the robot hand (usually the minimum object "height").
init_bite | the initial "bite" of the robot hand ( |
Definition at line 234 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.
nn_radius_hands | the radius to be used for the point neighborhood search |
Definition at line 189 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.
nn_radius_hands | the radius to be used for the point neighborhood search |
Definition at line 198 of file localization.h.
void Localization::setNumSamples | ( | int | num_samples | ) | [inline] |
Set the number of samples to be used for the search.
num_samples | the number of samples to be used for the search |
Definition at line 180 of file localization.h.
void Localization::setWorkspace | ( | const Eigen::VectorXd & | workspace | ) | [inline] |
Set the dimensions of the robot's workspace.
workspace | 1x6 vector containing the robot's workspace dimensions |
Definition at line 171 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.
[in] | cloud_in | the point cloud to be voxelized |
[in] | pts_cam_source_in | the camera source for each point in the point cloud |
[out] | cloud_out | the voxelized point cloud |
[out] | pts_cam_source_out | the camera source for each point in the voxelized cloud |
[in] | cell_size | the size of each voxel |
Definition at line 247 of file localization.cpp.
Eigen::Matrix4d Localization::cam_tf_left_ [private] |
Definition at line 332 of file localization.h.
Eigen::Matrix4d Localization::cam_tf_right_ [private] |
the camera poses
Definition at line 332 of file localization.h.
PointCloud::Ptr Localization::cloud_ [private] |
the input point cloud
Definition at line 335 of file localization.h.
Eigen::Matrix3Xd Localization::cloud_normals_ [private] |
the normals for each point in the point cloud
Definition at line 334 of file localization.h.
bool Localization::filters_boundaries_ [private] |
whether grasp hypotheses close to the workspace boundaries are filtered out
Definition at line 346 of file localization.h.
double Localization::finger_width_ [private] |
width of the fingers
Definition at line 340 of file localization.h.
double Localization::hand_depth_ [private] |
hand depth (finger length)
Definition at line 342 of file localization.h.
double Localization::hand_height_ [private] |
hand height
Definition at line 343 of file localization.h.
double Localization::hand_outer_diameter_ [private] |
maximum hand aperture
Definition at line 341 of file localization.h.
double Localization::init_bite_ [private] |
initial bite
Definition at line 344 of file localization.h.
double Localization::nn_radius_hands_ [private] |
the radius of the neighborhood search used in the quadric fit
Definition at line 339 of file localization.h.
double Localization::nn_radius_taubin_ [private] |
the radius of the neighborhood search used in the grasp hypothesis search
Definition at line 338 of file localization.h.
const int Localization::NO_PLOTTING = 0 [static] |
int Localization::num_samples_ [private] |
the number of samples used in the search
Definition at line 337 of file localization.h.
int Localization::num_threads_ [private] |
the number of CPU threads used in the search
Definition at line 336 of file localization.h.
const int Localization::PCL_PLOTTING = 1 [static] |
plotting in PCL
Definition at line 263 of file localization.h.
const int Localization::PCL_PLOTTING_FINGERS = 2 [static] |
plotting in PCL, plots hands with fingers
Definition at line 264 of file localization.h.
Plot Localization::plot_ [private] |
the plot object
Definition at line 331 of file localization.h.
bool Localization::plots_camera_sources_ [private] |
whether the camera source is plotted for each point in the point cloud
Definition at line 345 of file localization.h.
int Localization::plotting_mode_ [private] |
what plotting mode is used
Definition at line 347 of file localization.h.
const int Localization::RVIZ_PLOTTING = 3 [static] |
plotting in Rviz
Definition at line 265 of file localization.h.
std::string Localization::visuals_frame_ [private] |
visualization frame for Rviz
Definition at line 348 of file localization.h.
Eigen::VectorXd Localization::workspace_ [private] |
the robot's workspace dimensions
Definition at line 333 of file localization.h.