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 <ros/ros.h>
00042
00043 #include <agile_grasp/grasp_hypothesis.h>
00044 #include <agile_grasp/handle.h>
00045
00046
00047 typedef pcl::PointCloud<pcl::PointXYZRGBA> PointCloud;
00048
00057 class HandleSearch
00058 {
00059 public:
00060
00068 std::vector<Handle> findHandles(const std::vector<GraspHypothesis>& hand_list, int min_inliers, double min_length);
00069
00070
00071 private:
00072
00082 bool shortenHandle(std::vector<Eigen::Vector2d> &inliers, double gap_threshold);
00083
00089 double safeAcos(double x);
00090
00094 struct VectorFirstTwoElementsComparator
00095 {
00103 bool operator ()(const Eigen::Vector3d& a, const Eigen::Vector3d& b)
00104 {
00105 for (int i = 0; i < 2; i++)
00106 {
00107 if (a(i) != b(i))
00108 {
00109 return a(i) < b(i);
00110 }
00111 }
00112
00113 return false;
00114 }
00115 };
00116
00120 struct LastElementComparator
00121 {
00128 bool operator ()(const Eigen::Vector2d& a, const Eigen::Vector2d& b)
00129 {
00130 if (a(1) != b(1))
00131 {
00132 return a(1) < b(1);
00133 }
00134
00135 return false;
00136 }
00137 };
00138 };
00139
00140 #endif