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  *
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  *  $Id: correspondence.h 5295 2012-03-25 19:03:32Z rusu $
00037  */
00038 #ifndef PCL_COMMON_CORRESPONDENCE_H_
00039 #define PCL_COMMON_CORRESPONDENCE_H_
00040 
00041 #include <boost/shared_ptr.hpp>
00042 #include <pcl/common/eigen.h>
00043 #include <vector>
00044 
00045 namespace pcl
00046 {
00053   struct Correspondence
00054   {
00056     int index_query;
00058     int index_match;
00060     union
00061     {
00062       float distance;
00063       float weight;
00064     };
00065     
00069     inline Correspondence () : index_query (0), index_match (-1), 
00070                                distance (std::numeric_limits<float>::max ())
00071     {}
00072 
00074     inline Correspondence (int _index_query, int _index_match, float _distance) : 
00075       index_query (_index_query), index_match (_index_match), distance (_distance)
00076     {}
00077 
00079     virtual ~Correspondence () {}
00080     
00081     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00082   };
00083   
00085   inline std::ostream& 
00086   operator << (std::ostream& os, const Correspondence& c)
00087   {
00088     os << c.index_query << " " << c.index_match << " " << c.distance;
00089     return (os);
00090   }
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 Mon Oct 6 2014 03:14:43