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 #ifndef PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_BACK_PROJECTION_H_
00041 #define PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_BACK_PROJECTION_H_
00042
00043 #include <pcl/registration/correspondence_types.h>
00044 #include <pcl/registration/correspondence_estimation.h>
00045
00046 namespace pcl
00047 {
00048 namespace registration
00049 {
00055 template <typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
00056 class CorrespondenceEstimationBackProjection : public CorrespondenceEstimationBase <PointSource, PointTarget, Scalar>
00057 {
00058 public:
00059 typedef boost::shared_ptr<CorrespondenceEstimationBackProjection<PointSource, PointTarget, NormalT, Scalar> > Ptr;
00060 typedef boost::shared_ptr<const CorrespondenceEstimationBackProjection<PointSource, PointTarget, NormalT, Scalar> > ConstPtr;
00061
00062 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::initCompute;
00063 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::initComputeReciprocal;
00064 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::input_transformed_;
00065 using PCLBase<PointSource>::deinitCompute;
00066 using PCLBase<PointSource>::input_;
00067 using PCLBase<PointSource>::indices_;
00068 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::getClassName;
00069 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::point_representation_;
00070 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::target_indices_;
00071
00072 typedef typename pcl::search::KdTree<PointTarget> KdTree;
00073 typedef typename pcl::search::KdTree<PointTarget>::Ptr KdTreePtr;
00074
00075 typedef pcl::PointCloud<PointSource> PointCloudSource;
00076 typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00077 typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00078
00079 typedef pcl::PointCloud<PointTarget> PointCloudTarget;
00080 typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
00081 typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
00082
00083 typedef pcl::PointCloud<NormalT> PointCloudNormals;
00084 typedef typename PointCloudNormals::Ptr NormalsPtr;
00085 typedef typename PointCloudNormals::ConstPtr NormalsConstPtr;
00086
00092 CorrespondenceEstimationBackProjection ()
00093 : source_normals_ ()
00094 , source_normals_transformed_ ()
00095 , target_normals_ ()
00096 , k_ (10)
00097 {
00098 corr_name_ = "CorrespondenceEstimationBackProjection";
00099 }
00100
00102 virtual ~CorrespondenceEstimationBackProjection () {}
00103
00107 inline void
00108 setSourceNormals (const NormalsConstPtr &normals) { source_normals_ = normals; }
00109
00112 inline NormalsConstPtr
00113 getSourceNormals () const { return (source_normals_); }
00114
00118 inline void
00119 setTargetNormals (const NormalsConstPtr &normals) { target_normals_ = normals; }
00120
00123 inline NormalsConstPtr
00124 getTargetNormals () const { return (target_normals_); }
00125
00131 void
00132 determineCorrespondences (pcl::Correspondences &correspondences,
00133 double max_distance = std::numeric_limits<double>::max ());
00134
00142 virtual void
00143 determineReciprocalCorrespondences (pcl::Correspondences &correspondences,
00144 double max_distance = std::numeric_limits<double>::max ());
00145
00151 inline void
00152 setKSearch (unsigned int k) { k_ = k; }
00153
00158 inline void
00159 getKSearch () const { return (k_); }
00160
00161 protected:
00162
00163 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::corr_name_;
00164 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::tree_;
00165 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::tree_reciprocal_;
00166 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::target_;
00167
00169 bool
00170 initCompute ();
00171
00172 private:
00173
00175 NormalsConstPtr source_normals_;
00176
00178 NormalsPtr source_normals_transformed_;
00179
00181 NormalsConstPtr target_normals_;
00182
00184 unsigned int k_;
00185 };
00186 }
00187 }
00188
00189 #include <pcl/registration/impl/correspondence_estimation_backprojection.hpp>
00190
00191 #endif