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
00039 #ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_H_
00040 #define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_H_
00041
00042 #include <pcl/registration/correspondence_types.h>
00043 #include <pcl/registration/correspondence_sorting.h>
00044 #include <pcl/console/print.h>
00045 #include <pcl/point_cloud.h>
00046 #include <pcl/kdtree/kdtree_flann.h>
00047
00048 namespace pcl
00049 {
00050 namespace registration
00051 {
00056 class CorrespondenceRejector
00057 {
00058 public:
00060 CorrespondenceRejector () : rejection_name_ (), input_correspondences_ () {};
00061
00063 virtual ~CorrespondenceRejector () {}
00064
00068 virtual inline void
00069 setInputCorrespondences (const CorrespondencesConstPtr &correspondences)
00070 {
00071 input_correspondences_ = correspondences;
00072 };
00073
00077 inline CorrespondencesConstPtr
00078 getInputCorrespondences () { return input_correspondences_; };
00079
00083 inline void
00084 getCorrespondences (pcl::Correspondences &correspondences)
00085 {
00086 if (!input_correspondences_ || (input_correspondences_->empty ()))
00087 return;
00088
00089 applyRejection (correspondences);
00090 }
00091
00099 virtual inline void
00100 getRemainingCorrespondences (const pcl::Correspondences& original_correspondences,
00101 pcl::Correspondences& remaining_correspondences) = 0;
00102
00111 inline void
00112 getRejectedQueryIndices (const pcl::Correspondences &correspondences,
00113 std::vector<int>& indices)
00114 {
00115 if (!input_correspondences_ || input_correspondences_->empty ())
00116 {
00117 PCL_WARN ("[pcl::%s::getRejectedQueryIndices] Input correspondences not set (lookup of rejected correspondences _not_ possible).\n", getClassName ().c_str ());
00118 return;
00119 }
00120
00121 pcl::getRejectedQueryIndices(*input_correspondences_, correspondences, indices);
00122 }
00123
00124 protected:
00125
00127 std::string rejection_name_;
00128
00130 CorrespondencesConstPtr input_correspondences_;
00131
00133 inline const std::string&
00134 getClassName () const { return (rejection_name_); }
00135
00137 virtual void
00138 applyRejection (Correspondences &correspondences) = 0;
00139 };
00140
00145 class DataContainerInterface
00146 {
00147 public:
00148 virtual ~DataContainerInterface () {}
00149 virtual double getCorrespondenceScore (int index) = 0;
00150 virtual double getCorrespondenceScore (const pcl::Correspondence &) = 0;
00151 };
00152
00157 template <typename PointT, typename NormalT=pcl::PointNormal>
00158 class DataContainer : public DataContainerInterface
00159 {
00160 typedef typename pcl::PointCloud<PointT>::ConstPtr PointCloudConstPtr;
00161 typedef typename pcl::KdTree<PointT>::Ptr KdTreePtr;
00162 typedef typename pcl::PointCloud<NormalT>::ConstPtr NormalsPtr;
00163
00164 public:
00165
00167 DataContainer () : input_ (), target_ ()
00168 {
00169 tree_.reset (new pcl::KdTreeFLANN<PointT>);
00170 }
00171
00176 inline void
00177 setInputCloud (const PointCloudConstPtr &cloud)
00178 {
00179 input_ = cloud;
00180 }
00181
00186 inline void
00187 setInputTarget (const PointCloudConstPtr &target)
00188 {
00189 target_ = target;
00190 tree_->setInputCloud (target_);
00191 }
00192
00196 inline void
00197 setInputNormals (const NormalsPtr &normals) { input_normals_ = normals; }
00198
00202 inline void
00203 setTargetNormals (const NormalsPtr &normals) { target_normals_ = normals; }
00204
00206 inline NormalsPtr
00207 getInputNormals () { return input_normals_; }
00208
00210 inline NormalsPtr
00211 getTargetNormals () { return target_normals_; }
00212
00216 inline double
00217 getCorrespondenceScore (int index)
00218 {
00219 std::vector<int> indices (1);
00220 std::vector<float> distances (1);
00221 if (tree_->nearestKSearch (input_->points[index], 1, indices, distances))
00222 {
00223 return (distances[0]);
00224 }
00225 else
00226 return (std::numeric_limits<double>::max ());
00227 }
00228
00232 inline double
00233 getCorrespondenceScore (const pcl::Correspondence &corr)
00234 {
00235
00236 const PointT &src = input_->points[corr.index_query];
00237 const PointT &tgt = target_->points[corr.index_match];
00238
00239 return ((src.getVector4fMap () - tgt.getVector4fMap ()).squaredNorm ());
00240 }
00241
00247 double
00248 getCorrespondenceScoreFromNormals (const pcl::Correspondence &corr)
00249 {
00250
00251 assert ( input_normals_ && target_normals_ && "Normals are not set for the input and target point clouds");
00252 const NormalT &src = input_normals_->points[corr.index_query];
00253 const NormalT &tgt = target_normals_->points[corr.index_match];
00254 double score = (src.normal[0] * tgt.normal[0]) + (src.normal[1] * tgt.normal[1]) + (src.normal[2] * tgt.normal[2]);
00255 return score;
00256 }
00257 private:
00258
00260 PointCloudConstPtr input_;
00261
00263 PointCloudConstPtr target_;
00264
00266 NormalsPtr input_normals_;
00267
00269 NormalsPtr target_normals_;
00270
00272 KdTreePtr tree_;
00273 };
00274 }
00275 }
00276
00277 #endif
00278