hv_papazov.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  */
00036 
00037 #ifndef PCL_RECOGNITION_HV_PAPAZOV_H_
00038 #define PCL_RECOGNITION_HV_PAPAZOV_H_
00039 
00040 #include <pcl/recognition/boost.h>
00041 #include <pcl/pcl_macros.h>
00042 #include <pcl/common/common.h>
00043 #include <pcl/recognition/hv/hypotheses_verification.h>
00044 #include <boost/graph/adjacency_list.hpp>
00045 
00046 namespace pcl
00047 {
00048 
00054   template<typename ModelT, typename SceneT>
00055   class PCL_EXPORTS PapazovHV : public HypothesisVerification<ModelT, SceneT>
00056   {
00057     using HypothesisVerification<ModelT, SceneT>::mask_;
00058     using HypothesisVerification<ModelT, SceneT>::scene_cloud_downsampled_;
00059     using HypothesisVerification<ModelT, SceneT>::scene_downsampled_tree_;
00060     using HypothesisVerification<ModelT, SceneT>::visible_models_;
00061     using HypothesisVerification<ModelT, SceneT>::complete_models_;
00062     using HypothesisVerification<ModelT, SceneT>::resolution_;
00063     using HypothesisVerification<ModelT, SceneT>::inliers_threshold_;
00064 
00065     float conflict_threshold_size_;
00066     float penalty_threshold_;
00067     float support_threshold_;
00068 
00069     class RecognitionModel 
00070     {
00071       public:
00072         std::vector<int> explained_; //indices vector referencing explained_by_RM_
00073         typename pcl::PointCloud<ModelT>::Ptr cloud_;
00074         typename pcl::PointCloud<ModelT>::Ptr complete_cloud_;
00075         int bad_information_;
00076         int id_;
00077     };
00078 
00079     std::vector<int> explained_by_RM_; //represents the points of scene_cloud_ that are explained by the recognition models
00080     std::vector< boost::shared_ptr<RecognitionModel> > recognition_models_;
00081     std::vector< std::vector <boost::shared_ptr<RecognitionModel> > > points_explained_by_rm_; //if inner size > 1, conflict
00082     std::map<int, boost::shared_ptr<RecognitionModel> > graph_id_model_map_;
00083 
00084     typedef boost::adjacency_list<boost::vecS, boost::vecS, boost::undirectedS, boost::shared_ptr<RecognitionModel> > Graph;
00085     Graph conflict_graph_;
00086 
00087     //builds the conflict_graph
00088     void buildConflictGraph();
00089     //non-maxima suppresion on the conflict graph
00090     void nonMaximaSuppresion();
00091     //create recognition models
00092     void initialize();
00093 
00094     public:
00095       PapazovHV() : HypothesisVerification<ModelT,SceneT>() {
00096         support_threshold_ = 0.1f;
00097         penalty_threshold_ = 0.1f;
00098         conflict_threshold_size_ = 0.02f;
00099       }
00100 
00101       void setConflictThreshold(float t) {
00102         conflict_threshold_size_ = t;
00103       }
00104 
00105       void setSupportThreshold(float t) {
00106         support_threshold_ = t;
00107       }
00108 
00109       void setPenaltyThreshold(float t) {
00110         penalty_threshold_ = t;
00111       }
00112 
00113       //build conflict graph
00114       //non-maxima supression
00115       void verify();
00116   };
00117 }
00118 
00119 #ifdef PCL_NO_PRECOMPILE
00120 #include <pcl/recognition/impl/hv/hv_papazov.hpp>
00121 #endif
00122 
00123 #endif /* PCL_RECOGNITION_HV_PAPAZOV_H_ */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:24:51