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
00040
00041 #ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_H_
00042 #define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_H_
00043
00044 #include <pcl/registration/correspondence_types.h>
00045 #include <pcl/registration/correspondence_sorting.h>
00046 #include <pcl/console/print.h>
00047 #include <pcl/common/transforms.h>
00048 #include <pcl/point_cloud.h>
00049 #include <pcl/search/kdtree.h>
00050
00051 namespace pcl
00052 {
00053 namespace registration
00054 {
00059 class CorrespondenceRejector
00060 {
00061 public:
00062 typedef boost::shared_ptr<CorrespondenceRejector> Ptr;
00063 typedef boost::shared_ptr<const CorrespondenceRejector> ConstPtr;
00064
00066 CorrespondenceRejector ()
00067 : rejection_name_ ()
00068 , input_correspondences_ ()
00069 {}
00070
00072 virtual ~CorrespondenceRejector () {}
00073
00077 virtual inline void
00078 setInputCorrespondences (const CorrespondencesConstPtr &correspondences)
00079 {
00080 input_correspondences_ = correspondences;
00081 };
00082
00086 inline CorrespondencesConstPtr
00087 getInputCorrespondences () { return input_correspondences_; };
00088
00092 inline void
00093 getCorrespondences (pcl::Correspondences &correspondences)
00094 {
00095 if (!input_correspondences_ || (input_correspondences_->empty ()))
00096 return;
00097
00098 applyRejection (correspondences);
00099 }
00100
00108 virtual inline void
00109 getRemainingCorrespondences (const pcl::Correspondences& original_correspondences,
00110 pcl::Correspondences& remaining_correspondences) = 0;
00111
00120 inline void
00121 getRejectedQueryIndices (const pcl::Correspondences &correspondences,
00122 std::vector<int>& indices)
00123 {
00124 if (!input_correspondences_ || input_correspondences_->empty ())
00125 {
00126 PCL_WARN ("[pcl::registration::%s::getRejectedQueryIndices] Input correspondences not set (lookup of rejected correspondences _not_ possible).\n", getClassName ().c_str ());
00127 return;
00128 }
00129
00130 pcl::getRejectedQueryIndices(*input_correspondences_, correspondences, indices);
00131 }
00132
00134 inline const std::string&
00135 getClassName () const { return (rejection_name_); }
00136
00137 protected:
00138
00140 std::string rejection_name_;
00141
00143 CorrespondencesConstPtr input_correspondences_;
00144
00146 virtual void
00147 applyRejection (Correspondences &correspondences) = 0;
00148 };
00149
00154 class DataContainerInterface
00155 {
00156 public:
00157 virtual ~DataContainerInterface () {}
00158 virtual double getCorrespondenceScore (int index) = 0;
00159 virtual double getCorrespondenceScore (const pcl::Correspondence &) = 0;
00160 };
00161
00166 template <typename PointT, typename NormalT = pcl::PointNormal>
00167 class DataContainer : public DataContainerInterface
00168 {
00169 typedef pcl::PointCloud<PointT> PointCloud;
00170 typedef typename PointCloud::Ptr PointCloudPtr;
00171 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00172
00173 typedef typename pcl::search::KdTree<PointT>::Ptr KdTreePtr;
00174
00175 typedef pcl::PointCloud<NormalT> Normals;
00176 typedef typename Normals::Ptr NormalsPtr;
00177 typedef typename Normals::ConstPtr NormalsConstPtr;
00178
00179 public:
00180
00182 DataContainer (bool needs_normals = false)
00183 : input_ ()
00184 , input_transformed_ ()
00185 , target_ ()
00186 , input_normals_ ()
00187 , input_normals_transformed_ ()
00188 , target_normals_ ()
00189 , tree_ (new pcl::search::KdTree<PointT>)
00190 , class_name_ ("DataContainer")
00191 , needs_normals_ (needs_normals)
00192 , target_cloud_updated_ (true)
00193 , force_no_recompute_ (false)
00194 {
00195 }
00196
00198 virtual ~DataContainer () {}
00199
00204 PCL_DEPRECATED (void setInputCloud (const PointCloudConstPtr &cloud), "[pcl::registration::DataContainer::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.");
00205
00207 PCL_DEPRECATED (PointCloudConstPtr const getInputCloud (), "[pcl::registration::DataContainer::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.");
00208
00213 inline void
00214 setInputSource (const PointCloudConstPtr &cloud)
00215 {
00216 input_ = cloud;
00217 }
00218
00220 inline PointCloudConstPtr const
00221 getInputSource () { return (input_); }
00222
00227 inline void
00228 setInputTarget (const PointCloudConstPtr &target)
00229 {
00230 target_ = target;
00231 target_cloud_updated_ = true;
00232 }
00233
00235 inline PointCloudConstPtr const
00236 getInputTarget () { return (target_); }
00237
00245 inline void
00246 setSearchMethodTarget (const KdTreePtr &tree,
00247 bool force_no_recompute = false)
00248 {
00249 tree_ = tree;
00250 if (force_no_recompute)
00251 {
00252 force_no_recompute_ = true;
00253 }
00254 target_cloud_updated_ = true;
00255 }
00256
00260 inline void
00261 setInputNormals (const NormalsConstPtr &normals) { input_normals_ = normals; }
00262
00264 inline NormalsConstPtr
00265 getInputNormals () { return (input_normals_); }
00266
00270 inline void
00271 setTargetNormals (const NormalsConstPtr &normals) { target_normals_ = normals; }
00272
00274 inline NormalsConstPtr
00275 getTargetNormals () { return (target_normals_); }
00276
00280 inline double
00281 getCorrespondenceScore (int index)
00282 {
00283 if ( target_cloud_updated_ && !force_no_recompute_ )
00284 {
00285 tree_->setInputCloud (target_);
00286 }
00287 std::vector<int> indices (1);
00288 std::vector<float> distances (1);
00289 if (tree_->nearestKSearch (input_->points[index], 1, indices, distances))
00290 return (distances[0]);
00291 else
00292 return (std::numeric_limits<double>::max ());
00293 }
00294
00298 inline double
00299 getCorrespondenceScore (const pcl::Correspondence &corr)
00300 {
00301
00302 const PointT &src = input_->points[corr.index_query];
00303 const PointT &tgt = target_->points[corr.index_match];
00304
00305 return ((src.getVector4fMap () - tgt.getVector4fMap ()).squaredNorm ());
00306 }
00307
00313 inline double
00314 getCorrespondenceScoreFromNormals (const pcl::Correspondence &corr)
00315 {
00316
00317 assert (input_normals_ && target_normals_ && "Normals are not set for the input and target point clouds");
00318 const NormalT &src = input_normals_->points[corr.index_query];
00319 const NormalT &tgt = target_normals_->points[corr.index_match];
00320 return (double ((src.normal[0] * tgt.normal[0]) + (src.normal[1] * tgt.normal[1]) + (src.normal[2] * tgt.normal[2])));
00321 }
00322
00323 private:
00325 PointCloudConstPtr input_;
00326
00328 PointCloudPtr input_transformed_;
00329
00331 PointCloudConstPtr target_;
00332
00334 NormalsConstPtr input_normals_;
00335
00337 NormalsPtr input_normals_transformed_;
00338
00340 NormalsConstPtr target_normals_;
00341
00343 KdTreePtr tree_;
00344
00346 std::string class_name_;
00347
00349 bool needs_normals_;
00350
00353 bool target_cloud_updated_;
00354
00357 bool force_no_recompute_;
00358
00359
00360
00362 inline const std::string&
00363 getClassName () const { return (class_name_); }
00364 };
00365 }
00366 }
00367
00368 #include <pcl/registration/impl/correspondence_rejection.hpp>
00369
00370 #endif
00371