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 #ifndef IA_RANSAC_H_
00037 #define IA_RANSAC_H_
00038
00039
00040 #include "pcl/registration/registration.h"
00041
00042 namespace pcl
00043 {
00047
00051 template <typename PointSource, typename PointTarget, typename FeatureT>
00052 class SampleConsensusInitialAlignment : public Registration<PointSource, PointTarget>
00053 {
00054 using Registration<PointSource, PointTarget>::reg_name_;
00055 using Registration<PointSource, PointTarget>::getClassName;
00056 using Registration<PointSource, PointTarget>::input_;
00057 using Registration<PointSource, PointTarget>::indices_;
00058 using Registration<PointSource, PointTarget>::target_;
00059 using Registration<PointSource, PointTarget>::final_transformation_;
00060 using Registration<PointSource, PointTarget>::transformation_;
00061 using Registration<PointSource, PointTarget>::corr_dist_threshold_;
00062 using Registration<PointSource, PointTarget>::min_number_correspondences_;
00063 using Registration<PointSource, PointTarget>::max_iterations_;
00064 using Registration<PointSource, PointTarget>::tree_;
00065
00066 typedef typename Registration<PointSource, PointTarget>::PointCloudSource PointCloudSource;
00067 typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00068 typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00069
00070 typedef typename Registration<PointSource, PointTarget>::PointCloudTarget PointCloudTarget;
00071
00072 typedef PointIndices::Ptr PointIndicesPtr;
00073 typedef PointIndices::ConstPtr PointIndicesConstPtr;
00074
00075 typedef pcl::PointCloud<FeatureT> FeatureCloud;
00076 typedef typename FeatureCloud::Ptr FeatureCloudPtr;
00077 typedef typename FeatureCloud::ConstPtr FeatureCloudConstPtr;
00078
00079 typedef typename KdTreeFLANN<FeatureT>::Ptr FeatureKdTreePtr;
00080
00081 public:
00083
00084 SampleConsensusInitialAlignment () : nr_samples_(3)
00085 {
00086 reg_name_ = "SampleConsensusInitialAlignment";
00087 feature_tree_ = boost::make_shared<pcl::KdTreeFLANN<FeatureT> > ();
00088 };
00089
00091
00094 void setSourceFeatures (const FeatureCloudConstPtr &features);
00095
00097
00098 inline FeatureCloudConstPtr const getSourceFeatures () { return (input_features_); }
00099
00101
00104 void setTargetFeatures (const FeatureCloudConstPtr &features);
00105
00107
00108 inline FeatureCloudConstPtr const getTargetFeatures () { return (target_features_); }
00109
00111
00114 void setMinSampleDistance (float min_sample_distance) { min_sample_distance_ = min_sample_distance; }
00115
00117
00118 float getMinSampleDistance () { return (min_sample_distance_); }
00119
00121
00124 void setNumberOfSamples (int nr_samples) { nr_samples_ = nr_samples; }
00125
00127
00128 int getNumberOfSamples () { return (nr_samples_); }
00129
00130 private:
00132
00135 inline int getRandomIndex (int n) { return (n * (rand () / (RAND_MAX + 1.0))); };
00136
00138
00145 void selectSamples (const PointCloudSource &cloud, int nr_samples, float min_sample_distance,
00146 std::vector<int> &sample_indices);
00147
00149
00156 void findSimilarFeatures(const FeatureCloud &input_features, const std::vector<int> &sample_indices,
00157 std::vector<int> &corresponding_indices);
00158
00160
00164 float computeErrorMetric (const PointCloudSource &cloud, float threshold);
00165
00166 protected:
00168
00171 virtual void computeTransformation (PointCloudSource &output);
00172
00173
00175 FeatureCloudConstPtr input_features_;
00176
00178 FeatureCloudConstPtr target_features_;
00179
00181 int nr_samples_;
00182
00184 float min_sample_distance_;
00185
00187 FeatureKdTreePtr feature_tree_;
00188
00189 };
00190 }
00191
00192 #include "pcl/registration/ia_ransac.hpp"
00193
00194 #endif //#ifndef IA_RANSAC_H_