Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef HAND_SEARCH_H
00033 #define HAND_SEARCH_H
00034
00035
00036 #include <Eigen/Dense>
00037
00038 #include <pcl/filters/random_sample.h>
00039 #include <pcl/kdtree/kdtree_flann.h>
00040 #include <pcl/point_cloud.h>
00041
00042 #include <agile_grasp/finger_hand.h>
00043 #include <agile_grasp/grasp_hypothesis.h>
00044 #include <agile_grasp/plot.h>
00045 #include <agile_grasp/quadric.h>
00046 #include <agile_grasp/rotating_hand.h>
00047
00048
00049 typedef pcl::PointCloud<pcl::PointXYZRGBA> PointCloud;
00050
00051
00062 class HandSearch
00063 {
00064 public:
00065
00077 HandSearch(double finger_width, double hand_outer_diameter,
00078 double hand_depth, double hand_height, double init_bite, int num_threads,
00079 int num_samples, const Eigen::Matrix4d& cam_tf_left, bool plots_hands) : finger_width_(finger_width),
00080 hand_outer_diameter_(hand_outer_diameter), hand_depth_(hand_depth),
00081 hand_height_(hand_height), init_bite_(init_bite),
00082 num_threads_(num_threads), num_samples_(num_samples), cam_tf_left_(cam_tf_left),
00083 plots_hands_(plots_hands), plots_samples_(false),
00084 plots_local_axes_(false), uses_determinstic_normal_estimation_(false),
00085 nn_radius_taubin_(0.03), nn_radius_hands_(0.08) { }
00086
00101 std::vector<GraspHypothesis> findHands(const PointCloud::Ptr cloud,
00102 const Eigen::VectorXi& pts_cam_source, const std::vector<int>& indices,
00103 const PointCloud::Ptr cloud_plot, bool calculates_antipodal,
00104 bool uses_clustering);
00105
00106
00107 private:
00108
00117 std::vector<Quadric> findQuadrics(const PointCloud::Ptr cloud, const Eigen::VectorXi& pts_cam_source,
00118 const pcl::KdTreeFLANN<pcl::PointXYZRGBA>& kdtree, const std::vector<int>& indices);
00119
00129 std::vector<GraspHypothesis> findHands(const PointCloud::Ptr cloud, const Eigen::VectorXi& pts_cam_source,
00130 const std::vector<Quadric>& quadric_list, const Eigen::VectorXi& hands_cam_source,
00131 const pcl::KdTreeFLANN<pcl::PointXYZRGBA>& kdtree);
00132
00133 Eigen::Matrix4d cam_tf_left_, cam_tf_right_;
00134
00136 double finger_width_;
00137 double hand_outer_diameter_;
00138 double hand_depth_;
00139 double hand_height_;
00140 double init_bite_;
00141 int num_threads_;
00142 int num_samples_;
00143
00144 Eigen::Matrix3Xd cloud_normals_;
00145 Plot plot_;
00146
00147 bool uses_determinstic_normal_estimation_;
00148 bool tolerant_antipodal_;
00149
00150 bool plots_samples_;
00151 bool plots_camera_sources_;
00152 bool plots_local_axes_;
00153 bool plots_hands_;
00154
00155 double nn_radius_taubin_;
00156 double nn_radius_hands_;
00157 };
00158
00159 #endif