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_PPF_REGISTRATION_H_
00040 #define PCL_PPF_REGISTRATION_H_
00041
00042 #include <pcl/registration/registration.h>
00043 #include <pcl/features/ppf.h>
00044 #include <boost/unordered_map.hpp>
00045
00046 namespace pcl
00047 {
00048 class PCL_EXPORTS PPFHashMapSearch
00049 {
00050 public:
00056 struct HashKeyStruct : public std::pair <int, std::pair <int, std::pair <int, int> > >
00057 {
00058 HashKeyStruct(int a, int b, int c, int d)
00059 {
00060 this->first = a;
00061 this->second.first = b;
00062 this->second.second.first = c;
00063 this->second.second.second = d;
00064 }
00065 };
00066 typedef boost::unordered_multimap<HashKeyStruct, std::pair<size_t, size_t> > FeatureHashMapType;
00067 typedef boost::shared_ptr<FeatureHashMapType> FeatureHashMapTypePtr;
00068 typedef boost::shared_ptr<PPFHashMapSearch> Ptr;
00069
00070
00075 PPFHashMapSearch (float angle_discretization_step = 12.0f / 180.0f * static_cast<float> (M_PI),
00076 float distance_discretization_step = 0.01f)
00077 : alpha_m_ ()
00078 , feature_hash_map_ (new FeatureHashMapType)
00079 , internals_initialized_ (false)
00080 , angle_discretization_step_ (angle_discretization_step)
00081 , distance_discretization_step_ (distance_discretization_step)
00082 , max_dist_ (-1.0f)
00083 {
00084 }
00085
00089 void
00090 setInputFeatureCloud (PointCloud<PPFSignature>::ConstPtr feature_cloud);
00091
00100 void
00101 nearestNeighborSearch (float &f1, float &f2, float &f3, float &f4,
00102 std::vector<std::pair<size_t, size_t> > &indices);
00103
00105 Ptr
00106 makeShared() { return Ptr (new PPFHashMapSearch (*this)); }
00107
00109 inline float
00110 getAngleDiscretizationStep () { return angle_discretization_step_; }
00111
00113 inline float
00114 getDistanceDiscretizationStep () { return distance_discretization_step_; }
00115
00117 inline float
00118 getModelDiameter () { return max_dist_; }
00119
00120 std::vector <std::vector <float> > alpha_m_;
00121 private:
00122 FeatureHashMapTypePtr feature_hash_map_;
00123 bool internals_initialized_;
00124
00125 float angle_discretization_step_, distance_discretization_step_;
00126 float max_dist_;
00127 };
00128
00140 template <typename PointSource, typename PointTarget>
00141 class PPFRegistration : public Registration<PointSource, PointTarget>
00142 {
00143 public:
00148 struct PoseWithVotes
00149 {
00150 PoseWithVotes(Eigen::Affine3f &a_pose, unsigned int &a_votes)
00151 : pose (a_pose),
00152 votes (a_votes)
00153 {}
00154
00155 Eigen::Affine3f pose;
00156 unsigned int votes;
00157 };
00158 typedef std::vector<PoseWithVotes, Eigen::aligned_allocator<PoseWithVotes> > PoseWithVotesList;
00159
00161 using Registration<PointSource, PointTarget>::input_;
00163 using Registration<PointSource, PointTarget>::target_;
00164 using Registration<PointSource, PointTarget>::converged_;
00165 using Registration<PointSource, PointTarget>::final_transformation_;
00166 using Registration<PointSource, PointTarget>::transformation_;
00167
00168 typedef pcl::PointCloud<PointSource> PointCloudSource;
00169 typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00170 typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00171
00172 typedef pcl::PointCloud<PointTarget> PointCloudTarget;
00173 typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
00174 typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
00175
00176
00178 PPFRegistration ()
00179 : Registration<PointSource, PointTarget> (),
00180 search_method_ (),
00181 scene_reference_point_sampling_rate_ (5),
00182 clustering_position_diff_threshold_ (0.01f),
00183 clustering_rotation_diff_threshold_ (20.0f / 180.0f * static_cast<float> (M_PI))
00184 {}
00185
00190 inline void
00191 setPositionClusteringThreshold (float clustering_position_diff_threshold) { clustering_position_diff_threshold_ = clustering_position_diff_threshold; }
00192
00197 inline float
00198 getPositionClusteringThreshold () { return clustering_position_diff_threshold_; }
00199
00204 inline void
00205 setRotationClusteringThreshold (float clustering_rotation_diff_threshold) { clustering_rotation_diff_threshold_ = clustering_rotation_diff_threshold; }
00206
00209 inline float
00210 getRotationClusteringThreshold () { return clustering_rotation_diff_threshold_; }
00211
00215 inline void
00216 setSceneReferencePointSamplingRate (unsigned int scene_reference_point_sampling_rate) { scene_reference_point_sampling_rate_ = scene_reference_point_sampling_rate; }
00217
00219 inline unsigned int
00220 getSceneReferencePointSamplingRate () { return scene_reference_point_sampling_rate_; }
00221
00227 inline void
00228 setSearchMethod (PPFHashMapSearch::Ptr search_method) { search_method_ = search_method; }
00229
00231 inline PPFHashMapSearch::Ptr
00232 getSearchMethod () { return search_method_; }
00233
00237 void
00238 setInputTarget (const PointCloudTargetConstPtr &cloud);
00239
00240
00241 private:
00243 void
00244 computeTransformation (PointCloudSource &output, const Eigen::Matrix4f& guess);
00245
00246
00248 PPFHashMapSearch::Ptr search_method_;
00249
00251 unsigned int scene_reference_point_sampling_rate_;
00252
00255 float clustering_position_diff_threshold_, clustering_rotation_diff_threshold_;
00256
00258 typename pcl::KdTreeFLANN<PointTarget>::Ptr scene_search_tree_;
00259
00262 static bool
00263 poseWithVotesCompareFunction (const PoseWithVotes &a,
00264 const PoseWithVotes &b);
00265
00268 static bool
00269 clusterVotesCompareFunction (const std::pair<size_t, unsigned int> &a,
00270 const std::pair<size_t, unsigned int> &b);
00271
00274 void
00275 clusterPoses (PoseWithVotesList &poses,
00276 PoseWithVotesList &result);
00277
00280 bool
00281 posesWithinErrorBounds (Eigen::Affine3f &pose1,
00282 Eigen::Affine3f &pose2);
00283 };
00284 }
00285
00286 #include <pcl/registration/impl/ppf_registration.hpp>
00287
00288 #endif // PCL_PPF_REGISTRATION_H_