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
00040 template <typename PointSource, typename PointTarget> void
00041 pcl::estimateRigidTransformationSVD (const pcl::PointCloud<PointSource> &cloud_src,
00042 const pcl::PointCloud<PointTarget> &cloud_tgt,
00043 Eigen::Matrix4f &transformation_matrix)
00044 {
00045 if (cloud_src.points.size () != cloud_tgt.points.size ())
00046 {
00047 ROS_ERROR ("[pcl::estimateRigidTransformationSVD] Number or points in source (%zu) differs than target (%zu)!", cloud_src.points.size (), cloud_tgt.points.size ());
00048 return;
00049 }
00050
00051
00052 transformation_matrix.setIdentity ();
00053
00054 Eigen::Vector4f centroid_src, centroid_tgt;
00055
00056 compute3DCentroid (cloud_src, centroid_src);
00057 compute3DCentroid (cloud_tgt, centroid_tgt);
00058
00059
00060 Eigen::MatrixXf cloud_src_demean;
00061 demeanPointCloud (cloud_src, centroid_src, cloud_src_demean);
00062
00063 Eigen::MatrixXf cloud_tgt_demean;
00064 demeanPointCloud (cloud_tgt, centroid_tgt, cloud_tgt_demean);
00065
00066
00067 Eigen::Matrix3f H = (cloud_src_demean * cloud_tgt_demean.transpose ()).topLeftCorner<3, 3>();
00068
00069
00070 Eigen::JacobiSVD<Eigen::Matrix3f> svd (H, Eigen::ComputeFullU | Eigen::ComputeFullV);
00071 Eigen::Matrix3f u = svd.matrixU ();
00072 Eigen::Matrix3f v = svd.matrixV ();
00073
00074
00075 if (u.determinant () * v.determinant () < 0)
00076 {
00077 for (int x = 0; x < 3; ++x)
00078 v (x, 2) *= -1;
00079 }
00080
00081 Eigen::Matrix3f R = v * u.transpose ();
00082
00083
00084 transformation_matrix.topLeftCorner<3, 3> () = R;
00085 Eigen::Vector3f Rc = R * centroid_src.head<3> ();
00086 transformation_matrix.block <3, 1> (0, 3) = centroid_tgt.head<3> () - Rc;
00087 }
00088
00090 template <typename PointSource, typename PointTarget> void
00091 pcl::estimateRigidTransformationSVD (const pcl::PointCloud<PointSource> &cloud_src,
00092 const std::vector<int> &indices_src,
00093 const pcl::PointCloud<PointTarget> &cloud_tgt,
00094 const std::vector<int> &indices_tgt,
00095 Eigen::Matrix4f &transformation_matrix)
00096 {
00097 if (indices_src.size () != indices_tgt.size ())
00098 {
00099 ROS_ERROR ("[pcl::estimateRigidTransformationSVD] Number or points in source (%zu) differs than target (%zu)!", indices_src.size (), indices_tgt.size ());
00100 return;
00101 }
00102
00103
00104 transformation_matrix.setIdentity ();
00105
00106 Eigen::Vector4f centroid_src, centroid_tgt;
00107
00108 compute3DCentroid (cloud_src, indices_src, centroid_src);
00109 compute3DCentroid (cloud_tgt, indices_tgt, centroid_tgt);
00110
00111
00112 Eigen::MatrixXf cloud_src_demean;
00113 demeanPointCloud (cloud_src, indices_src, centroid_src, cloud_src_demean);
00114
00115 Eigen::MatrixXf cloud_tgt_demean;
00116 demeanPointCloud (cloud_tgt, indices_tgt, centroid_tgt, cloud_tgt_demean);
00117
00118
00119 Eigen::Matrix3f H = (cloud_src_demean * cloud_tgt_demean.transpose ()).topLeftCorner<3, 3>();
00120
00121
00122 Eigen::JacobiSVD<Eigen::Matrix3f> svd (H, Eigen::ComputeFullU | Eigen::ComputeFullV);
00123 Eigen::Matrix3f u = svd.matrixU ();
00124 Eigen::Matrix3f v = svd.matrixV ();
00125
00126
00127 if (u.determinant () * v.determinant () < 0)
00128 {
00129 for (int x = 0; x < 3; ++x)
00130 v (x, 2) *= -1;
00131 }
00132
00133 Eigen::Matrix3f R = v * u.transpose ();
00134
00135
00136 transformation_matrix.topLeftCorner<3, 3> () = R;
00137 Eigen::Vector3f Rc = R * centroid_src.head<3> ();
00138 transformation_matrix.block <3, 1> (0, 3) = centroid_tgt.head<3> () - Rc;
00139 }
00140
00141
00143 template <typename PointSource, typename PointTarget> void
00144 pcl::estimateRigidTransformationSVD (const pcl::PointCloud<PointSource> &cloud_src,
00145 const std::vector<int> &indices_src,
00146 const pcl::PointCloud<PointTarget> &cloud_tgt,
00147 Eigen::Matrix4f &transformation_matrix)
00148 {
00149 if (indices_src.size () != cloud_tgt.points.size ())
00150 {
00151 ROS_ERROR ("[pcl::estimateRigidTransformationSVD] Number or points in source (%zu) differs than target (%zu)!", indices_src.size (), cloud_tgt.points.size ());
00152 return;
00153 }
00154
00155
00156 transformation_matrix.setIdentity ();
00157
00158 Eigen::Vector4f centroid_src, centroid_tgt;
00159
00160 compute3DCentroid (cloud_src, indices_src, centroid_src);
00161 compute3DCentroid (cloud_tgt, centroid_tgt);
00162
00163
00164 Eigen::MatrixXf cloud_src_demean;
00165 demeanPointCloud (cloud_src, indices_src, centroid_src, cloud_src_demean);
00166
00167 Eigen::MatrixXf cloud_tgt_demean;
00168 demeanPointCloud (cloud_tgt, centroid_tgt, cloud_tgt_demean);
00169
00170
00171 Eigen::Matrix3f H = (cloud_src_demean * cloud_tgt_demean.transpose ()).topLeftCorner<3, 3>();
00172
00173
00174 Eigen::JacobiSVD<Eigen::Matrix3f> svd (H, Eigen::ComputeFullU | Eigen::ComputeFullV);
00175 const Eigen::Matrix3f &u = svd.matrixU ();
00176 const Eigen::Matrix3f &v = svd.matrixV ();
00177
00178
00179 if (u.determinant () * v.determinant () < 0)
00180 {
00181 for (int x = 0; x < 3; ++x)
00182 v (x, 2) *= -1;
00183 }
00184
00185 Eigen::Matrix3f R = v * u.transpose ();
00186
00187
00188 transformation_matrix.topLeftCorner<3, 3> () = R;
00189 Eigen::Vector3f Rc = R * centroid_src.head<3> ();
00190 transformation_matrix.block <3, 1> (0, 3) = centroid_tgt.head<3> () - Rc;
00191 }
00192
00194 template <typename PointSource, typename PointTarget> inline void
00195 pcl::Registration<PointSource, PointTarget>::setInputTarget (const PointCloudTargetConstPtr &cloud)
00196 {
00197 if (cloud->points.empty ())
00198 {
00199 ROS_ERROR ("[pcl::%s::setInputTarget] Invalid or empty point cloud dataset given!", getClassName ().c_str ());
00200 return;
00201 }
00202 PointCloudTarget target = *cloud;
00203
00204 for (size_t i = 0; i < target.points.size (); ++i)
00205 target.points[i].data[3] = 1.0;
00206
00207
00208 target_ = target.makeShared ();
00209 tree_->setInputCloud (target_);
00210 }
00211
00213 template <typename PointSource, typename PointTarget>
00214 template <typename FeatureType> inline void
00215 pcl::Registration<PointSource, PointTarget>::setSourceFeature (
00216 const typename pcl::PointCloud<FeatureType>::ConstPtr &source_feature, std::string key)
00217 {
00218 if (features_map_.count (key) == 0)
00219 {
00220 features_map_[key] = boost::make_shared<FeatureContainer<FeatureType> > ();
00221 }
00222 boost::static_pointer_cast<FeatureContainer<FeatureType> > (features_map_[key])->setSourceFeature (source_feature);
00223 }
00224
00226 template <typename PointSource, typename PointTarget>
00227 template <typename FeatureType> inline typename pcl::PointCloud<FeatureType>::ConstPtr
00228 pcl::Registration<PointSource, PointTarget>::getSourceFeature (std::string key)
00229 {
00230 if (features_map_.count (key) == 0)
00231 {
00232 return (boost::shared_ptr<pcl::PointCloud<const FeatureType> > ());
00233 }
00234 else
00235 {
00236 return (boost::static_pointer_cast<FeatureContainer<FeatureType> > (features_map_[key])->getSourceFeature ());
00237 }
00238 }
00239
00241 template <typename PointSource, typename PointTarget>
00242 template <typename FeatureType> inline void
00243 pcl::Registration<PointSource, PointTarget>::setTargetFeature (
00244 const typename pcl::PointCloud<FeatureType>::ConstPtr &target_feature, std::string key)
00245 {
00246 if (features_map_.count (key) == 0)
00247 {
00248 features_map_[key] = boost::make_shared<FeatureContainer<FeatureType> > ();
00249 }
00250 boost::static_pointer_cast<FeatureContainer<FeatureType> > (features_map_[key])->setTargetFeature (target_feature);
00251 }
00252
00254 template <typename PointSource, typename PointTarget>
00255 template <typename FeatureType> inline typename pcl::PointCloud<FeatureType>::ConstPtr
00256 pcl::Registration<PointSource, PointTarget>::getTargetFeature (std::string key)
00257 {
00258 typedef pcl::PointCloud<FeatureType> FeatureCloud;
00259 typedef typename FeatureCloud::ConstPtr FeatureCloudConstPtr;
00260
00261 if (features_map_.count (key) == 0)
00262 {
00263 return (boost::shared_ptr<const pcl::PointCloud<FeatureType> > ());
00264 }
00265 else
00266 {
00267 return (boost::static_pointer_cast<FeatureContainer<FeatureType> > (features_map_[key])->getTargetFeature ());
00268 }
00269 }
00270
00272 template <typename PointSource, typename PointTarget>
00273 template <typename FeatureType> inline void
00274 pcl::Registration<PointSource, PointTarget>::setRadiusSearch (const typename pcl::KdTree<FeatureType>::Ptr &tree,
00275 float r, std::string key)
00276 {
00277 if (features_map_.count (key) == 0)
00278 {
00279 features_map_[key] = boost::make_shared<FeatureContainer<FeatureType> > ();
00280 }
00281 boost::static_pointer_cast<FeatureContainer<FeatureType> > (features_map_[key])->setRadiusSearch (tree, r);
00282 }
00283
00285 template <typename PointSource, typename PointTarget>
00286 template <typename FeatureType> inline void
00287 pcl::Registration<PointSource, PointTarget>::setKSearch (const typename pcl::KdTree<FeatureType>::Ptr &tree,
00288 int k, std::string key)
00289 {
00290 if (features_map_.count (key) == 0)
00291 {
00292 features_map_[key] = boost::make_shared<FeatureContainer<FeatureType> > ();
00293 }
00294 boost::static_pointer_cast<FeatureContainer<FeatureType> > (features_map_[key])->setKSearch (tree, k);
00295 }
00296
00298 template <typename PointSource, typename PointTarget> inline bool
00299 pcl::Registration<PointSource, PointTarget>::hasValidFeatures ()
00300 {
00301 if (features_map_.empty ())
00302 {
00303 return (false);
00304 }
00305 typename FeaturesMap::const_iterator feature_itr;
00306 for (feature_itr = features_map_.begin (); feature_itr != features_map_.end (); ++feature_itr)
00307 {
00308 if (!feature_itr->second->isValid ())
00309 {
00310 return (false);
00311 }
00312 }
00313 return (true);
00314 }
00315
00317 template <typename PointSource, typename PointTarget> void
00318 pcl::Registration<PointSource, PointTarget>::findFeatureCorrespondences (int index,
00319 std::vector<int> &correspondence_indices)
00320 {
00321 if (features_map_.empty ())
00322 {
00323 ROS_ERROR ("[pcl::%s::findFeatureCorrespondences] One or more features must be set before finding correspondences!",
00324 getClassName ().c_str ());
00325 return;
00326 }
00327
00328 std::vector<int> nn_indices;
00329 std::vector<float> nn_dists;
00330
00331
00332 typename FeaturesMap::const_iterator feature_itr = features_map_.begin ();
00333 feature_itr->second->findFeatureCorrespondences (index, correspondence_indices, nn_dists);
00334 std::vector<int>::iterator correspondence_indices_end = correspondence_indices.end ();
00335 std::sort (correspondence_indices.begin (), correspondence_indices_end);
00336
00337
00338 for (++feature_itr; feature_itr != features_map_.end (); ++feature_itr)
00339 {
00340 feature_itr->second->findFeatureCorrespondences (index, nn_indices, nn_dists);
00341
00342 std::sort (nn_indices.begin (), nn_indices.end ());
00343 correspondence_indices_end = set_intersection (nn_indices.begin (), nn_indices.end (),
00344 correspondence_indices.begin (), correspondence_indices_end,
00345 correspondence_indices.begin ());
00346 }
00347
00348
00349
00350 correspondence_indices.resize (correspondence_indices_end - correspondence_indices.begin());
00351 }
00352
00353
00355 template <typename PointSource, typename PointTarget> inline double
00356 pcl::Registration<PointSource, PointTarget>::getFitnessScore (double max_range)
00357 {
00358 double fitness_score = 0.0;
00359
00360
00361 PointCloudSource input_transformed;
00362 transformPointCloud (*input_, input_transformed, final_transformation_);
00363
00364 std::vector<int> nn_indices (1);
00365 std::vector<float> nn_dists (1);
00366
00367
00368 int nr = 0;
00369 for (size_t i = 0; i < input_transformed.points.size (); ++i)
00370 {
00371 Eigen::Vector4f p1 = Eigen::Vector4f (input_transformed.points[i].x,
00372 input_transformed.points[i].y,
00373 input_transformed.points[i].z, 0);
00374
00375 tree_->nearestKSearch (input_transformed.points[i], 1, nn_indices, nn_dists);
00376
00377
00378 if (nn_dists[0] > max_range)
00379 continue;
00380
00381 Eigen::Vector4f p2 = Eigen::Vector4f (target_->points[nn_indices[0]].x,
00382 target_->points[nn_indices[0]].y,
00383 target_->points[nn_indices[0]].z, 0);
00384
00385 fitness_score += fabs ((p1-p2).squaredNorm ());
00386 nr++;
00387 }
00388
00389 if (nr > 0)
00390 return (fitness_score / nr);
00391 else
00392 return (std::numeric_limits<double>::max ());
00393 }
00394
00396 template <typename PointSource, typename PointTarget> inline void
00397 pcl::Registration<PointSource, PointTarget>::align (PointCloudSource &output)
00398 {
00399 if (!initCompute ()) return;
00400
00401 if (!target_)
00402 {
00403 ROS_WARN ("[pcl::%s::compute] No input target dataset was given!", getClassName ().c_str ());
00404 return;
00405 }
00406
00407
00408 if (output.points.size () != indices_->size ())
00409 output.points.resize (indices_->size ());
00410
00411 output.header = input_->header;
00412
00413 if (indices_->size () != input_->points.size ())
00414 {
00415 output.width = indices_->size ();
00416 output.height = 1;
00417 }
00418 else
00419 {
00420 output.width = input_->width;
00421 output.height = input_->height;
00422 }
00423 output.is_dense = input_->is_dense;
00424
00425
00426 for (size_t i = 0; i < indices_->size (); ++i)
00427 output.points[i] = input_->points[(*indices_)[i]];
00428
00429
00430 if (point_representation_)
00431 tree_->setPointRepresentation (point_representation_);
00432
00433
00434 converged_ = false;
00435 final_transformation_ = transformation_ = previous_transformation_ = Eigen::Matrix4f::Identity ();
00436
00437
00438
00439 for (size_t i = 0; i < indices_->size (); ++i)
00440 output.points[i].data[3] = 1.0;
00441
00442 computeTransformation (output);
00443
00444 deinitCompute ();
00445 }
00446