hand_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 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::PointXYZ> PointCloud;
00050 
00061 class HandSearch
00062 {
00063   public:
00064     
00076     HandSearch(double finger_width, double hand_outer_diameter, 
00077       double hand_depth, double hand_height, double init_bite, int num_threads, 
00078       int num_samples, bool plots_hands) : finger_width_(finger_width), 
00079       hand_outer_diameter_(hand_outer_diameter), hand_depth_(hand_depth), 
00080       hand_height_(hand_height), init_bite_(init_bite), 
00081       num_threads_(num_threads), num_samples_(num_samples), 
00082       plots_hands_(plots_hands), plots_samples_(false), 
00083       plots_local_axes_(false), uses_determinstic_normal_estimation_(false), 
00084       nn_radius_taubin_(0.03), nn_radius_hands_(0.08) { }
00085     
00100     std::vector<GraspHypothesis> findHands(const PointCloud::Ptr cloud, 
00101       const Eigen::VectorXi& pts_cam_source, const std::vector<int>& indices,
00102       const PointCloud::Ptr cloud_plot, bool calculates_antipodal, 
00103       bool uses_clustering);
00104       
00105   
00106   private:
00107     
00116     std::vector<Quadric> findQuadrics(const PointCloud::Ptr cloud, const Eigen::VectorXi& pts_cam_source,
00117                         const pcl::KdTreeFLANN<pcl::PointXYZ>& kdtree, const std::vector<int>& indices);
00118                 
00128     std::vector<GraspHypothesis> findHands(const PointCloud::Ptr cloud, const Eigen::VectorXi& pts_cam_source,
00129                         const std::vector<Quadric>& quadric_list, const Eigen::VectorXi& hands_cam_source, 
00130       const pcl::KdTreeFLANN<pcl::PointXYZ>& kdtree);
00131     
00132     Eigen::Matrix4d cam_tf_left_, cam_tf_right_; 
00133     
00135     double finger_width_;
00136     double hand_outer_diameter_; 
00137     double hand_depth_; 
00138     double hand_height_; 
00139     double init_bite_; 
00140     int num_threads_; 
00141     int num_samples_; 
00142     
00143     Eigen::Matrix3Xd cloud_normals_; 
00144     Plot plot_; 
00145     
00146     bool uses_determinstic_normal_estimation_; 
00147     bool tolerant_antipodal_; 
00148     
00149     bool plots_samples_; 
00150     bool plots_camera_sources_; 
00151     bool plots_local_axes_; 
00152     bool plots_hands_; 
00153     
00154     double nn_radius_taubin_; 
00155     double nn_radius_hands_; 
00156 };
00157 
00158 #endif /* HAND_SEARCH_H */ 


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