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 HANDLE_SEARCH_H_
00033 #define HANDLE_SEARCH_H_
00034
00035 #include <set>
00036 #include <vector>
00037
00038 #include <pcl/point_cloud.h>
00039 #include <pcl/visualization/pcl_visualizer.h>
00040
00041 #include <agile_grasp/handle.h>
00042 #include <agile_grasp/grasp_hypothesis.h>
00043
00044 typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
00045
00054 class HandleSearch
00055 {
00056 public:
00057
00065 std::vector<Handle> findHandles(const std::vector<GraspHypothesis>& hand_list, int min_inliers, double min_length);
00066
00073 void plotHandles(const std::vector<Handle>& handle_list, const PointCloud::Ptr& cloud, std::string str);
00074
00075 private:
00076
00086 bool shortenHandle(std::vector<Eigen::Vector2d> &inliers, double gap_threshold);
00087
00093 double safeAcos(double x);
00094
00098 struct VectorFirstTwoElementsComparator
00099 {
00107 bool operator ()(const Eigen::Vector3d& a, const Eigen::Vector3d& b)
00108 {
00109 for (int i = 0; i < 2; i++)
00110 {
00111 if (a(i) != b(i))
00112 {
00113 return a(i) < b(i);
00114 }
00115 }
00116
00117 return false;
00118 }
00119 };
00120
00124 struct LastElementComparator
00125 {
00132 bool operator ()(const Eigen::Vector2d& a, const Eigen::Vector2d& b)
00133 {
00134 if (a(1) != b(1))
00135 {
00136 return a(1) < b(1);
00137 }
00138
00139 return false;
00140 }
00141 };
00142 };
00143
00144 #endif