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 PCL_REGISTRATION_IMPL_CORRESPONDENCE_ESTIMATION_H_
00037 #define PCL_REGISTRATION_IMPL_CORRESPONDENCE_ESTIMATION_H_
00038
00040 template <typename PointSource, typename PointTarget> inline void
00041 pcl::registration::CorrespondenceEstimation<PointSource, PointTarget>::setInputTarget (const PointCloudTargetConstPtr &cloud)
00042 {
00043 if (cloud->points.empty ())
00044 {
00045 ROS_ERROR ("[pcl::%s::setInputTarget] Invalid or empty point cloud dataset given!", getClassName ().c_str ());
00046 return;
00047 }
00048 PointCloudTarget target = *cloud;
00049
00050 for (size_t i = 0; i < target.points.size (); ++i)
00051 target.points[i].data[3] = 1.0;
00052
00053
00054 target_ = target.makeShared ();
00055 tree_->setInputCloud (target_);
00056 }
00057
00059 template <typename PointSource, typename PointTarget>
00060 template <typename FeatureType> inline void
00061 pcl::registration::CorrespondenceEstimation<PointSource, PointTarget>::setSourceFeature (
00062 const typename pcl::PointCloud<FeatureType>::ConstPtr &source_feature, std::string key)
00063 {
00064 if (features_map_.count (key) == 0)
00065 {
00066 features_map_[key] = boost::make_shared<FeatureContainer<FeatureType> > ();
00067 }
00068 boost::static_pointer_cast<FeatureContainer<FeatureType> > (features_map_[key])->setSourceFeature (source_feature);
00069 }
00070
00072 template <typename PointSource, typename PointTarget>
00073 template <typename FeatureType> inline typename pcl::PointCloud<FeatureType>::ConstPtr
00074 pcl::registration::CorrespondenceEstimation<PointSource, PointTarget>::getSourceFeature (std::string key)
00075 {
00076 if (features_map_.count (key) == 0)
00077 {
00078 return (boost::shared_ptr<pcl::PointCloud<const FeatureType> > ());
00079 }
00080 else
00081 {
00082 return (boost::static_pointer_cast<FeatureContainer<FeatureType> > (features_map_[key])->getSourceFeature ());
00083 }
00084 }
00085
00087 template <typename PointSource, typename PointTarget>
00088 template <typename FeatureType> inline void
00089 pcl::registration::CorrespondenceEstimation<PointSource, PointTarget>::setTargetFeature (
00090 const typename pcl::PointCloud<FeatureType>::ConstPtr &target_feature, std::string key)
00091 {
00092 if (features_map_.count (key) == 0)
00093 {
00094 features_map_[key] = boost::make_shared<FeatureContainer<FeatureType> > ();
00095 }
00096 boost::static_pointer_cast<FeatureContainer<FeatureType> > (features_map_[key])->setTargetFeature (target_feature);
00097 }
00098
00100 template <typename PointSource, typename PointTarget>
00101 template <typename FeatureType> inline typename pcl::PointCloud<FeatureType>::ConstPtr
00102 pcl::registration::CorrespondenceEstimation<PointSource, PointTarget>::getTargetFeature (std::string key)
00103 {
00104 typedef pcl::PointCloud<FeatureType> FeatureCloud;
00105 typedef typename FeatureCloud::ConstPtr FeatureCloudConstPtr;
00106
00107 if (features_map_.count (key) == 0)
00108 {
00109 return (boost::shared_ptr<const pcl::PointCloud<FeatureType> > ());
00110 }
00111 else
00112 {
00113 return (boost::static_pointer_cast<FeatureContainer<FeatureType> > (features_map_[key])->getTargetFeature ());
00114 }
00115 }
00116
00118 template <typename PointSource, typename PointTarget>
00119 template <typename FeatureType> inline void
00120 pcl::registration::CorrespondenceEstimation<PointSource, PointTarget>::setRadiusSearch (const typename pcl::KdTree<FeatureType>::Ptr &tree,
00121 float r, std::string key)
00122 {
00123 if (features_map_.count (key) == 0)
00124 {
00125 features_map_[key] = boost::make_shared<FeatureContainer<FeatureType> > ();
00126 }
00127 boost::static_pointer_cast<FeatureContainer<FeatureType> > (features_map_[key])->setRadiusSearch (tree, r);
00128 }
00129
00131 template <typename PointSource, typename PointTarget>
00132 template <typename FeatureType> inline void
00133 pcl::registration::CorrespondenceEstimation<PointSource, PointTarget>::setKSearch (const typename pcl::KdTree<FeatureType>::Ptr &tree,
00134 int k, std::string key)
00135 {
00136 if (features_map_.count (key) == 0)
00137 {
00138 features_map_[key] = boost::make_shared<FeatureContainer<FeatureType> > ();
00139 }
00140 boost::static_pointer_cast<FeatureContainer<FeatureType> > (features_map_[key])->setKSearch (tree, k);
00141 }
00142
00144 template <typename PointSource, typename PointTarget> inline bool
00145 pcl::registration::CorrespondenceEstimation<PointSource, PointTarget>::hasValidFeatures ()
00146 {
00147 if (features_map_.empty ())
00148 {
00149 return (false);
00150 }
00151 typename FeaturesMap::const_iterator feature_itr;
00152 for (feature_itr = features_map_.begin (); feature_itr != features_map_.end (); ++feature_itr)
00153 {
00154 if (!feature_itr->second->isValid ())
00155 {
00156 return (false);
00157 }
00158 }
00159 return (true);
00160 }
00161
00163 template <typename PointSource, typename PointTarget> void
00164 pcl::registration::CorrespondenceEstimation<PointSource, PointTarget>::findFeatureCorrespondences (int index,
00165 std::vector<int> &correspondence_indices)
00166 {
00167 if (features_map_.empty ())
00168 {
00169 ROS_ERROR ("[pcl::%s::findFeatureCorrespondences] One or more features must be set before finding correspondences!",
00170 getClassName ().c_str ());
00171 return;
00172 }
00173
00174 std::vector<int> nn_indices;
00175 std::vector<float> nn_dists;
00176
00177
00178 typename FeaturesMap::const_iterator feature_itr = features_map_.begin ();
00179 feature_itr->second->findFeatureCorrespondences (index, correspondence_indices, nn_dists);
00180 std::vector<int>::iterator correspondence_indices_end = correspondence_indices.end ();
00181 std::sort (correspondence_indices.begin (), correspondence_indices_end);
00182
00183
00184 for (++feature_itr; feature_itr != features_map_.end (); ++feature_itr)
00185 {
00186 feature_itr->second->findFeatureCorrespondences (index, nn_indices, nn_dists);
00187
00188 sort (nn_indices.begin (), nn_indices.end ());
00189 correspondence_indices_end = set_intersection (nn_indices.begin (), nn_indices.end (),
00190 correspondence_indices.begin (), correspondence_indices_end,
00191 correspondence_indices.begin ());
00192 }
00193
00194
00195
00196 correspondence_indices.resize (correspondence_indices_end - correspondence_indices.begin());
00197 }
00198
00199
00201 template <typename PointSource, typename PointTarget> void
00202 pcl::registration::CorrespondenceEstimation<PointSource, PointTarget>::determineCorrespondences(std::vector<pcl::registration::Correspondence> &correspondences, float max_distance)
00203 {
00204 if (!initCompute())
00205 return;
00206
00207 if (!target_)
00208 {
00209 ROS_WARN ("[pcl::%s::compute] No input target dataset was given!", getClassName ().c_str ());
00210 return;
00211 }
00212
00213 float max_dist_sqr = max_distance * max_distance;
00214
00215 correspondences.resize(indices_->size());
00216 std::vector<int> index(1);
00217 std::vector<float> distance(1);
00218 pcl::registration::Correspondence corr;
00219 for (unsigned int i = 0; i < indices_->size(); ++i)
00220 {
00221 if ( tree_->nearestKSearch(input_->points[(*indices_)[i]], 1, index, distance) )
00222 {
00223 if ( distance[0] <= max_dist_sqr )
00224 {
00225 corr.indexQuery = i;
00226 corr.indexMatch = index[0];
00227 corr.distance = distance[0];
00228 correspondences[i] = corr;
00229 continue;
00230 }
00231 }
00232
00233 }
00234 deinitCompute();
00235 }
00236
00238 template <typename PointSource, typename PointTarget> void
00239 pcl::registration::CorrespondenceEstimation<PointSource, PointTarget>::determineReciprocalCorrespondences(std::vector<pcl::registration::Correspondence> &correspondences)
00240 {
00241 if (!initCompute())
00242 return;
00243
00244 if (!target_)
00245 {
00246 ROS_WARN ("[pcl::%s::compute] No input target dataset was given!", getClassName ().c_str ());
00247 return;
00248 }
00249
00250
00251 pcl::KdTreeFLANN<PointTarget> tree_reciprocal;
00252 tree_reciprocal.setInputCloud(input_, indices_);
00253
00254 correspondences.resize(indices_->size());
00255 std::vector<int> index(1);
00256 std::vector<float> distance(1);
00257 std::vector<int> index_reciprocal(1);
00258 std::vector<float> distance_reciprocal(1);
00259 pcl::registration::Correspondence corr;
00260 unsigned int nr_valid_correspondences = 0;
00261
00262
00263 for (unsigned int i = 0; i < indices_->size(); ++i)
00264 {
00265 tree_->nearestKSearch(input_->points[(*indices_)[i]], 1, index, distance);
00266 tree_reciprocal.nearestKSearch(target_->points[index[0]], 1, index_reciprocal, distance_reciprocal);
00267
00268
00269 if ( (*indices_)[i] == index_reciprocal[0] )
00270 {
00271 corr.indexQuery = (*indices_)[i];
00272 corr.indexMatch = index[0];
00273 corr.distance = distance[0];
00274 correspondences[nr_valid_correspondences] = corr;
00275 ++nr_valid_correspondences;
00276 }
00277 }
00278 correspondences.resize(nr_valid_correspondences);
00279
00280 deinitCompute();
00281 }
00282
00283
00284
00285 #endif