correspondence.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  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  */
00038 #ifndef PCL_COMMON_CORRESPONDENCE_H_
00039 #define PCL_COMMON_CORRESPONDENCE_H_
00040 
00041 #ifdef __GNUC__
00042 #pragma GCC system_header 
00043 #endif
00044 
00045 #include <boost/shared_ptr.hpp>
00046 #include <Eigen/StdVector>
00047 #include <Eigen/Geometry>
00048 #include <pcl/pcl_exports.h>
00049 
00050 namespace pcl
00051 {
00058   struct Correspondence
00059   {
00061     int index_query;
00063     int index_match;
00065     union
00066     {
00067       float distance;
00068       float weight;
00069     };
00070     
00074     inline Correspondence () : index_query (0), index_match (-1), 
00075                                distance (std::numeric_limits<float>::max ())
00076     {}
00077 
00079     inline Correspondence (int _index_query, int _index_match, float _distance) : 
00080       index_query (_index_query), index_match (_index_match), distance (_distance)
00081     {}
00082 
00084     virtual ~Correspondence () {}
00085     
00086     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00087   };
00088   
00090   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Correspondence& c);
00091 
00092   typedef std::vector< pcl::Correspondence, Eigen::aligned_allocator<pcl::Correspondence> > Correspondences;
00093   typedef boost::shared_ptr<Correspondences> CorrespondencesPtr;
00094   typedef boost::shared_ptr<const Correspondences > CorrespondencesConstPtr;
00095 
00109   void
00110   getRejectedQueryIndices (const pcl::Correspondences &correspondences_before,
00111                            const pcl::Correspondences &correspondences_after,
00112                            std::vector<int>& indices,
00113                            bool presorting_required = true);
00114 
00120   struct PointCorrespondence3D : public Correspondence
00121   {
00122     Eigen::Vector3f point1;  
00123     Eigen::Vector3f point2;  
00124 
00126     PointCorrespondence3D () : point1 (), point2 () {}
00127 
00129     virtual ~PointCorrespondence3D () {}
00130     
00131     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00132   };
00133   typedef std::vector<PointCorrespondence3D, Eigen::aligned_allocator<PointCorrespondence3D> > PointCorrespondences3DVector;
00134 
00140   struct PointCorrespondence6D : public PointCorrespondence3D
00141   {
00142     Eigen::Affine3f transformation;  
00143 
00144 
00145     virtual ~PointCorrespondence6D () {}
00146 
00147     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00148   };
00149   typedef std::vector<PointCorrespondence6D, Eigen::aligned_allocator<PointCorrespondence6D> > PointCorrespondences6DVector;
00150 
00156   inline bool
00157   isBetterCorrespondence (const Correspondence &pc1, const Correspondence &pc2)
00158   {
00159     return (pc1.distance > pc2.distance);
00160   }
00161 }
00162 
00163 #endif /* PCL_COMMON_CORRESPONDENCE_H_ */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:56