handle_search.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015, Andreas ten Pas
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *
00018  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00019  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00020  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00021  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00022  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00023  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00024  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00026  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00027  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00028  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  *  POSSIBILITY OF SUCH DAMAGE.
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 /* HANDLE_SEARCH_H_ */


agile_grasp
Author(s):
autogenerated on Thu Aug 27 2015 12:01:28