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 #ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_POLY_H_
00039 #define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_POLY_H_
00040
00041 #include <pcl/registration/correspondence_rejection.h>
00042 #include <pcl/point_cloud.h>
00043
00044 namespace pcl
00045 {
00046 namespace registration
00047 {
00063 template <typename SourceT, typename TargetT>
00064 class PCL_EXPORTS CorrespondenceRejectorPoly: public CorrespondenceRejector
00065 {
00066 using CorrespondenceRejector::input_correspondences_;
00067 using CorrespondenceRejector::rejection_name_;
00068 using CorrespondenceRejector::getClassName;
00069
00070 public:
00071 typedef boost::shared_ptr<CorrespondenceRejectorPoly> Ptr;
00072 typedef boost::shared_ptr<const CorrespondenceRejectorPoly> ConstPtr;
00073
00074 typedef pcl::PointCloud<SourceT> PointCloudSource;
00075 typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00076 typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00077
00078 typedef pcl::PointCloud<TargetT> PointCloudTarget;
00079 typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
00080 typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
00081
00083 CorrespondenceRejectorPoly ()
00084 : iterations_ (10000)
00085 , cardinality_ (3)
00086 , similarity_threshold_ (0.75f)
00087 , similarity_threshold_squared_ (0.75f * 0.75f)
00088 {
00089 rejection_name_ = "CorrespondenceRejectorPoly";
00090 }
00091
00096 void
00097 getRemainingCorrespondences (const pcl::Correspondences& original_correspondences,
00098 pcl::Correspondences& remaining_correspondences);
00099
00103 inline void
00104 setInputSource (const PointCloudSourceConstPtr &cloud)
00105 {
00106 input_ = cloud;
00107 }
00108
00112 inline void
00113 setInputCloud (const PointCloudSourceConstPtr &cloud)
00114 {
00115 PCL_WARN ("[pcl::registration::%s::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.\n",
00116 getClassName ().c_str ());
00117 input_ = cloud;
00118 }
00119
00123 inline void
00124 setInputTarget (const PointCloudTargetConstPtr &target)
00125 {
00126 target_ = target;
00127 }
00128
00132 inline void
00133 setCardinality (int cardinality)
00134 {
00135 cardinality_ = cardinality;
00136 }
00137
00141 inline int
00142 getCardinality ()
00143 {
00144 return (cardinality_);
00145 }
00146
00151 inline void
00152 setSimilarityThreshold (float similarity_threshold)
00153 {
00154 similarity_threshold_ = similarity_threshold;
00155 similarity_threshold_squared_ = similarity_threshold * similarity_threshold;
00156 }
00157
00161 inline float
00162 getSimilarityThreshold ()
00163 {
00164 return (similarity_threshold_);
00165 }
00166
00170 inline void
00171 setIterations (int iterations)
00172 {
00173 iterations_ = iterations;
00174 }
00175
00179 inline int
00180 getIterations ()
00181 {
00182 return (iterations_);
00183 }
00184
00190 inline bool
00191 thresholdPolygon (const pcl::Correspondences& corr, const std::vector<int>& idx)
00192 {
00193 if (cardinality_ == 2)
00194 {
00195 return (thresholdEdgeLength (corr[ idx[0] ].index_query, corr[ idx[1] ].index_query,
00196 corr[ idx[0] ].index_match, corr[ idx[1] ].index_match,
00197 cardinality_));
00198 }
00199 else
00200 {
00201 for (int i = 0; i < cardinality_; ++i)
00202 if (!thresholdEdgeLength (corr[ idx[i] ].index_query, corr[ idx[(i+1)%cardinality_] ].index_query,
00203 corr[ idx[i] ].index_match, corr[ idx[(i+1)%cardinality_] ].index_match,
00204 similarity_threshold_squared_))
00205 return (false);
00206
00207 return (true);
00208 }
00209 }
00210
00216 inline bool
00217 thresholdPolygon (const std::vector<int>& source_indices, const std::vector<int>& target_indices)
00218 {
00219
00220 pcl::Correspondences corr (cardinality_);
00221 std::vector<int> idx (cardinality_);
00222 for (int i = 0; i < cardinality_; ++i)
00223 {
00224 corr[i].index_query = source_indices[i];
00225 corr[i].index_match = target_indices[i];
00226 idx[i] = i;
00227 }
00228
00229 return (thresholdPolygon (corr, idx));
00230 }
00231
00232 protected:
00236 inline void
00237 applyRejection (pcl::Correspondences &correspondences)
00238 {
00239 getRemainingCorrespondences (*input_correspondences_, correspondences);
00240 }
00241
00248 inline std::vector<int>
00249 getUniqueRandomIndices (int n, int k)
00250 {
00251
00252 std::vector<bool> sampled (n, false);
00253 int samples = 0;
00254
00255 std::vector<int> result;
00256 result.reserve (k);
00257 do
00258 {
00259
00260 const int idx = (std::rand () % n);
00261
00262 if (!sampled[idx])
00263 {
00264
00265 sampled[idx] = true;
00266 ++samples;
00267
00268 result.push_back (idx);
00269 }
00270 }
00271 while (samples < k);
00272
00273 return (result);
00274 }
00275
00281 inline float
00282 computeSquaredDistance (const SourceT& p1, const TargetT& p2)
00283 {
00284 const float dx = p2.x - p1.x;
00285 const float dy = p2.y - p1.y;
00286 const float dz = p2.z - p1.z;
00287
00288 return (dx*dx + dy*dy + dz*dz);
00289 }
00290
00299 inline bool
00300 thresholdEdgeLength (int index_query_1,
00301 int index_query_2,
00302 int index_match_1,
00303 int index_match_2,
00304 float simsq)
00305 {
00306
00307 const float dist_src = computeSquaredDistance ((*input_)[index_query_1], (*input_)[index_query_2]);
00308
00309 const float dist_tgt = computeSquaredDistance ((*target_)[index_match_1], (*target_)[index_match_2]);
00310
00311 const float edge_sim = (dist_src < dist_tgt ? dist_src / dist_tgt : dist_tgt / dist_src);
00312
00313 return (edge_sim >= simsq);
00314 }
00315
00324 std::vector<int>
00325 computeHistogram (const std::vector<float>& data, float lower, float upper, int bins);
00326
00331 int
00332 findThresholdOtsu (const std::vector<int>& histogram);
00333
00335 PointCloudSourceConstPtr input_;
00336
00338 PointCloudTargetConstPtr target_;
00339
00341 int iterations_;
00342
00344 int cardinality_;
00345
00347 float similarity_threshold_;
00348
00350 float similarity_threshold_squared_;
00351 };
00352 }
00353 }
00354
00355 #include <pcl/registration/impl/correspondence_rejection_poly.hpp>
00356
00357 #endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_POLY_H_