Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
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