poses_from_matches.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-2012, 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 the copyright holder(s) 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 
00038 #ifndef PCL_POSES_FROM_MATCHES_H_
00039 #define PCL_POSES_FROM_MATCHES_H_
00040 
00041 #include <pcl/pcl_macros.h>
00042 #include <pcl/correspondence.h>
00043 
00044 namespace pcl
00045 {
00051   class PCL_EXPORTS PosesFromMatches
00052   {
00053     public:
00054       // =====CONSTRUCTOR & DESTRUCTOR=====
00056       PosesFromMatches();
00058       ~PosesFromMatches();
00059       
00060       // =====STRUCTS=====
00062       struct PCL_EXPORTS Parameters
00063       {
00064         Parameters() : max_correspondence_distance_error(0.2f) {}
00065         float max_correspondence_distance_error;  // As a fraction
00066       };
00067 
00069       struct PoseEstimate
00070       {
00071         PoseEstimate () : 
00072           transformation (Eigen::Affine3f::Identity ()),
00073           score (0),
00074           correspondence_indices (0) 
00075         {}
00076 
00077         Eigen::Affine3f transformation;   
00078         float score;                         
00079         std::vector<int> correspondence_indices;  
00080 
00081         struct IsBetter 
00082         {
00083           bool operator()(const PoseEstimate& pe1, const PoseEstimate& pe2) const { return pe1.score>pe2.score;}
00084         };
00085         public:
00086           EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00087       };
00088       
00089       // =====TYPEDEFS=====
00090       typedef std::vector<PoseEstimate, Eigen::aligned_allocator<PoseEstimate> > PoseEstimatesVector;
00091 
00092       
00093       // =====STATIC METHODS=====
00094       
00095       // =====PUBLIC METHODS=====
00099       void 
00100       estimatePosesUsing1Correspondence (
00101           const PointCorrespondences6DVector& correspondences,
00102           int max_no_of_results, PoseEstimatesVector& pose_estimates) const;
00103 
00106       void 
00107       estimatePosesUsing2Correspondences (
00108           const PointCorrespondences6DVector& correspondences,
00109           int max_no_of_tested_combinations, int max_no_of_results,
00110           PoseEstimatesVector& pose_estimates) const;
00111       
00114       void 
00115       estimatePosesUsing3Correspondences (
00116           const PointCorrespondences6DVector& correspondences,
00117           int max_no_of_tested_combinations, int max_no_of_results,
00118           PoseEstimatesVector& pose_estimates) const;
00119 
00121       Parameters& 
00122       getParameters () { return parameters_; }
00123 
00124     protected:
00125       // =====PROTECTED MEMBER VARIABLES=====
00126       Parameters parameters_;
00127 
00128   };
00129 
00130 }  // end namespace pcl
00131 
00132 #endif  //#ifndef PCL_POSES_FROM_MATCHES_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:31:11