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_NDT_2D_H_
00042 #define PCL_NDT_2D_H_
00043
00044 #include <pcl/registration/registration.h>
00045
00046 namespace pcl
00047 {
00059 template <typename PointSource, typename PointTarget>
00060 class NormalDistributionsTransform2D : public Registration<PointSource, PointTarget>
00061 {
00062 typedef typename Registration<PointSource, PointTarget>::PointCloudSource PointCloudSource;
00063 typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00064 typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00065
00066 typedef typename Registration<PointSource, PointTarget>::PointCloudTarget PointCloudTarget;
00067
00068 typedef PointIndices::Ptr PointIndicesPtr;
00069 typedef PointIndices::ConstPtr PointIndicesConstPtr;
00070
00071 public:
00072
00073 typedef boost::shared_ptr< NormalDistributionsTransform2D<PointSource, PointTarget> > Ptr;
00074 typedef boost::shared_ptr< const NormalDistributionsTransform2D<PointSource, PointTarget> > ConstPtr;
00075
00077 NormalDistributionsTransform2D ()
00078 : Registration<PointSource,PointTarget> (),
00079 grid_centre_ (0,0), grid_step_ (1,1), grid_extent_ (20,20), newton_lambda_ (1,1,1)
00080 {
00081 reg_name_ = "NormalDistributionsTransform2D";
00082 }
00083
00085 virtual ~NormalDistributionsTransform2D () {}
00086
00090 virtual void
00091 setGridCentre (const Eigen::Vector2f& centre) { grid_centre_ = centre; }
00092
00096 virtual void
00097 setGridStep (const Eigen::Vector2f& step) { grid_step_ = step; }
00098
00102 virtual void
00103 setGridExtent (const Eigen::Vector2f& extent) { grid_extent_ = extent; }
00104
00108 virtual void
00109 setOptimizationStepSize (const double& lambda) { newton_lambda_ = Eigen::Vector3d (lambda, lambda, lambda); }
00110
00121 virtual void
00122 setOptimizationStepSize (const Eigen::Vector3d& lambda) { newton_lambda_ = lambda; }
00123
00124 protected:
00129 virtual void
00130 computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess);
00131
00132 using Registration<PointSource, PointTarget>::reg_name_;
00133 using Registration<PointSource, PointTarget>::target_;
00134 using Registration<PointSource, PointTarget>::converged_;
00135 using Registration<PointSource, PointTarget>::nr_iterations_;
00136 using Registration<PointSource, PointTarget>::max_iterations_;
00137 using Registration<PointSource, PointTarget>::transformation_epsilon_;
00138 using Registration<PointSource, PointTarget>::transformation_;
00139 using Registration<PointSource, PointTarget>::previous_transformation_;
00140 using Registration<PointSource, PointTarget>::final_transformation_;
00141 using Registration<PointSource, PointTarget>::update_visualizer_;
00142 using Registration<PointSource, PointTarget>::indices_;
00143
00144 Eigen::Vector2f grid_centre_;
00145 Eigen::Vector2f grid_step_;
00146 Eigen::Vector2f grid_extent_;
00147 Eigen::Vector3d newton_lambda_;
00148 public:
00149 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00150 };
00151
00152 }
00153
00154 #include <pcl/registration/impl/ndt_2d.hpp>
00155
00156 #endif // ndef PCL_NDT_2D_H_
00157