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_REGISTRATION_IMPL_PPF_REGISTRATION_H_
00040 #define PCL_REGISTRATION_IMPL_PPF_REGISTRATION_H_
00041
00042
00043 #include <pcl/features/ppf.h>
00044 #include <pcl/common/transforms.h>
00045
00046 #include <pcl/features/pfh.h>
00048 void
00049 pcl::PPFHashMapSearch::setInputFeatureCloud (PointCloud<PPFSignature>::ConstPtr feature_cloud)
00050 {
00051
00052 feature_hash_map_->clear ();
00053 unsigned int n = static_cast<unsigned int> (sqrt (static_cast<float> (feature_cloud->points.size ())));
00054 int d1, d2, d3, d4;
00055 max_dist_ = -1.0;
00056 alpha_m_.resize (n);
00057 for (size_t i = 0; i < n; ++i)
00058 {
00059 std::vector <float> alpha_m_row (n);
00060 for (size_t j = 0; j < n; ++j)
00061 {
00062 d1 = static_cast<int> (floor (feature_cloud->points[i*n+j].f1 / angle_discretization_step_));
00063 d2 = static_cast<int> (floor (feature_cloud->points[i*n+j].f2 / angle_discretization_step_));
00064 d3 = static_cast<int> (floor (feature_cloud->points[i*n+j].f3 / angle_discretization_step_));
00065 d4 = static_cast<int> (floor (feature_cloud->points[i*n+j].f4 / distance_discretization_step_));
00066 feature_hash_map_->insert (std::pair<HashKeyStruct, std::pair<size_t, size_t> > (HashKeyStruct (d1, d2, d3, d4), std::pair<size_t, size_t> (i, j)));
00067 alpha_m_row [j] = feature_cloud->points[i*n + j].alpha_m;
00068
00069 if (max_dist_ < feature_cloud->points[i*n + j].f4)
00070 max_dist_ = feature_cloud->points[i*n + j].f4;
00071 }
00072 alpha_m_[i] = alpha_m_row;
00073 }
00074
00075 internals_initialized_ = true;
00076 }
00077
00078
00080 void
00081 pcl::PPFHashMapSearch::nearestNeighborSearch (float &f1, float &f2, float &f3, float &f4,
00082 std::vector<std::pair<size_t, size_t> > &indices)
00083 {
00084 if (!internals_initialized_)
00085 {
00086 PCL_ERROR("[pcl::PPFRegistration::nearestNeighborSearch]: input feature cloud has not been set - skipping search!\n");
00087 return;
00088 }
00089
00090 int d1 = static_cast<int> (floor (f1 / angle_discretization_step_)),
00091 d2 = static_cast<int> (floor (f2 / angle_discretization_step_)),
00092 d3 = static_cast<int> (floor (f3 / angle_discretization_step_)),
00093 d4 = static_cast<int> (floor (f4 / distance_discretization_step_));
00094
00095 indices.clear ();
00096 HashKeyStruct key = HashKeyStruct (d1, d2, d3, d4);
00097 std::pair <FeatureHashMapType::iterator, FeatureHashMapType::iterator> map_iterator_pair = feature_hash_map_->equal_range (key);
00098 for (; map_iterator_pair.first != map_iterator_pair.second; ++ map_iterator_pair.first)
00099 indices.push_back (std::pair<size_t, size_t> (map_iterator_pair.first->second.first,
00100 map_iterator_pair.first->second.second));
00101 }
00102
00103
00105 template <typename PointSource, typename PointTarget> void
00106 pcl::PPFRegistration<PointSource, PointTarget>::setInputTarget (const PointCloudTargetConstPtr &cloud)
00107 {
00108 Registration<PointSource, PointTarget>::setInputTarget (cloud);
00109
00110 scene_search_tree_ = typename pcl::KdTreeFLANN<PointTarget>::Ptr (new pcl::KdTreeFLANN<PointTarget>);
00111 scene_search_tree_->setInputCloud (target_);
00112 }
00113
00114
00116 template <typename PointSource, typename PointTarget> void
00117 pcl::PPFRegistration<PointSource, PointTarget>::computeTransformation (PointCloudSource &output, const Eigen::Matrix4f& guess)
00118 {
00119 if (!search_method_)
00120 {
00121 PCL_ERROR("[pcl::PPFRegistration::computeTransformation] Search method not set - skipping computeTransformation!\n");
00122 return;
00123 }
00124
00125 if (guess != Eigen::Matrix4f::Identity ())
00126 {
00127 PCL_ERROR("[pcl::PPFRegistration::computeTransformation] setting initial transform (guess) not implemented!\n");
00128 }
00129
00130 PoseWithVotesList voted_poses;
00131 std::vector <std::vector <unsigned int> > accumulator_array;
00132 accumulator_array.resize (input_->points.size ());
00133 for (size_t i = 0; i < input_->points.size (); ++i)
00134 {
00135 std::vector <unsigned int> aux (static_cast<size_t> (floor(2*M_PI / search_method_->getAngleDiscretizationStep ()), 0));
00136 accumulator_array[i] = aux;
00137 }
00138 PCL_INFO ("Accumulator array size: %u x %u.\n", accumulator_array.size (), accumulator_array.back ().size ());
00139
00140
00141 float f1, f2, f3, f4;
00142 for (size_t scene_reference_index = 0; scene_reference_index < target_->points.size (); scene_reference_index += scene_reference_point_sampling_rate_)
00143 {
00144 Eigen::Vector3f scene_reference_point = target_->points[scene_reference_index].getVector3fMap (),
00145 scene_reference_normal = target_->points[scene_reference_index].getNormalVector3fMap ();
00146
00147 Eigen::AngleAxisf rotation_sg (acosf (scene_reference_normal.dot (Eigen::Vector3f::UnitX ())),
00148 scene_reference_normal.cross (Eigen::Vector3f::UnitX ()). normalized());
00149 Eigen::Affine3f transform_sg = Eigen::Translation3f ( rotation_sg* ((-1)*scene_reference_point)) * rotation_sg;
00150
00151
00152 std::vector<int> indices;
00153 std::vector<float> distances;
00154 scene_search_tree_->radiusSearch (target_->points[scene_reference_index],
00155 search_method_->getModelDiameter () /2,
00156 indices,
00157 distances);
00158 for(size_t i = 0; i < indices.size (); ++i)
00159
00160 {
00161
00162 size_t scene_point_index = indices[i];
00163 if (scene_reference_index != scene_point_index)
00164 {
00165 if (pcl::computePairFeatures (target_->points[scene_reference_index].getVector4fMap (),
00166 target_->points[scene_reference_index].getNormalVector4fMap (),
00167 target_->points[scene_point_index].getVector4fMap (),
00168 target_->points[scene_point_index].getNormalVector4fMap (),
00169 f1, f2, f3, f4))
00170 {
00171 std::vector<std::pair<size_t, size_t> > nearest_indices;
00172 search_method_->nearestNeighborSearch (f1, f2, f3, f4, nearest_indices);
00173
00174
00175 Eigen::Vector3f scene_point = target_->points[scene_point_index].getVector3fMap ();
00176 Eigen::AngleAxisf rotation_sg (acosf (scene_reference_normal.dot (Eigen::Vector3f::UnitX ())),
00177 scene_reference_normal.cross (Eigen::Vector3f::UnitX ()).normalized ());
00178 Eigen::Affine3f transform_sg = Eigen::Translation3f ( rotation_sg * ((-1) * scene_reference_point)) * rotation_sg;
00179
00180
00181 Eigen::Vector3f scene_point_transformed = transform_sg * scene_point;
00182 float alpha_s = atan2f ( -scene_point_transformed(2), scene_point_transformed(1));
00183 if ( alpha_s != alpha_s)
00184 {
00185 PCL_ERROR ("alpha_s is nan\n");
00186 continue;
00187 }
00188 if (sin (alpha_s) * scene_point_transformed(2) < 0.0f)
00189 alpha_s *= (-1);
00190 alpha_s *= (-1);
00191
00192
00193 for (std::vector<std::pair<size_t, size_t> >::iterator v_it = nearest_indices.begin (); v_it != nearest_indices.end (); ++ v_it)
00194 {
00195 size_t model_reference_index = v_it->first,
00196 model_point_index = v_it->second;
00197
00198 float alpha = search_method_->alpha_m_[model_reference_index][model_point_index] - alpha_s;
00199 unsigned int alpha_discretized = static_cast<unsigned int> (floor (alpha) + floor (M_PI / search_method_->getAngleDiscretizationStep ()));
00200 accumulator_array[model_reference_index][alpha_discretized] ++;
00201 }
00202 }
00203 else PCL_ERROR ("[pcl::PPFRegistration::computeTransformation] Computing pair feature vector between points %zu and %zu went wrong.\n", scene_reference_index, scene_point_index);
00204 }
00205 }
00206
00207 size_t max_votes_i = 0, max_votes_j = 0;
00208 unsigned int max_votes = 0;
00209
00210 for (size_t i = 0; i < accumulator_array.size (); ++i)
00211 for (size_t j = 0; j < accumulator_array.back ().size (); ++j)
00212 {
00213 if (accumulator_array[i][j] > max_votes)
00214 {
00215 max_votes = accumulator_array[i][j];
00216 max_votes_i = i;
00217 max_votes_j = j;
00218 }
00219
00220 accumulator_array[i][j] = 0;
00221 }
00222
00223 Eigen::Vector3f model_reference_point = input_->points[max_votes_i].getVector3fMap (),
00224 model_reference_normal = input_->points[max_votes_i].getNormalVector3fMap ();
00225 Eigen::AngleAxisf rotation_mg (acosf (model_reference_normal.dot (Eigen::Vector3f::UnitX ())), model_reference_normal.cross (Eigen::Vector3f::UnitX ()).normalized ());
00226 Eigen::Affine3f transform_mg = Eigen::Translation3f ( rotation_mg * ((-1) * model_reference_point)) * rotation_mg;
00227 Eigen::Affine3f max_transform =
00228 transform_sg.inverse () *
00229 Eigen::AngleAxisf ((static_cast<float> (max_votes_j) - floorf (static_cast<float> (M_PI) / search_method_->getAngleDiscretizationStep ())) * search_method_->getAngleDiscretizationStep (), Eigen::Vector3f::UnitX ()) *
00230 transform_mg;
00231
00232 voted_poses.push_back (PoseWithVotes (max_transform, max_votes));
00233 }
00234 PCL_DEBUG ("Done with the Hough Transform ...\n");
00235
00236
00237 PoseWithVotesList results;
00238 clusterPoses (voted_poses, results);
00239
00240 pcl::transformPointCloud (*input_, output, results.front ().pose);
00241
00242 transformation_ = final_transformation_ = results.front ().pose.matrix ();
00243 converged_ = true;
00244 }
00245
00246
00248 template <typename PointSource, typename PointTarget> void
00249 pcl::PPFRegistration<PointSource, PointTarget>::clusterPoses (typename pcl::PPFRegistration<PointSource, PointTarget>::PoseWithVotesList &poses,
00250 typename pcl::PPFRegistration<PointSource, PointTarget>::PoseWithVotesList &result)
00251 {
00252 PCL_INFO ("Clustering poses ...\n");
00253
00254 sort(poses.begin (), poses.end (), poseWithVotesCompareFunction);
00255
00256 std::vector<PoseWithVotesList> clusters;
00257 std::vector<std::pair<size_t, unsigned int> > cluster_votes;
00258 for (size_t poses_i = 0; poses_i < poses.size(); ++ poses_i)
00259 {
00260 bool found_cluster = false;
00261 for (size_t clusters_i = 0; clusters_i < clusters.size(); ++ clusters_i)
00262 {
00263 if (posesWithinErrorBounds (poses[poses_i].pose, clusters[clusters_i].front ().pose))
00264 {
00265 found_cluster = true;
00266 clusters[clusters_i].push_back (poses[poses_i]);
00267 cluster_votes[clusters_i].second += poses[poses_i].votes;
00268 break;
00269 }
00270 }
00271
00272 if (found_cluster == false)
00273 {
00274
00275 PoseWithVotesList new_cluster;
00276 new_cluster.push_back (poses[poses_i]);
00277 clusters.push_back (new_cluster);
00278 cluster_votes.push_back (std::pair<size_t, unsigned int> (clusters.size () - 1, poses[poses_i].votes));
00279 }
00280 }
00281
00282
00283 std::sort (cluster_votes.begin (), cluster_votes.end (), clusterVotesCompareFunction);
00284
00287 result.clear ();
00288 size_t max_clusters = (clusters.size () < 3) ? clusters.size () : 3;
00289 for (size_t cluster_i = 0; cluster_i < max_clusters; ++ cluster_i)
00290 {
00291 PCL_INFO ("Winning cluster has #votes: %d and #poses voted: %d.\n", cluster_votes[cluster_i].second, clusters[cluster_votes[cluster_i].first].size ());
00292 Eigen::Vector3f translation_average (0.0, 0.0, 0.0);
00293 Eigen::Vector4f rotation_average (0.0, 0.0, 0.0, 0.0);
00294 for (typename PoseWithVotesList::iterator v_it = clusters[cluster_votes[cluster_i].first].begin (); v_it != clusters[cluster_votes[cluster_i].first].end (); ++ v_it)
00295 {
00296 translation_average += v_it->pose.translation ();
00298 rotation_average += Eigen::Quaternionf (v_it->pose.rotation ()).coeffs ();
00299 }
00300
00301 translation_average /= static_cast<float> (clusters[cluster_votes[cluster_i].first].size ());
00302 rotation_average /= static_cast<float> (clusters[cluster_votes[cluster_i].first].size ());
00303
00304 Eigen::Affine3f transform_average;
00305 transform_average.translation () = translation_average;
00306 transform_average.linear () = Eigen::Quaternionf (rotation_average).normalized().toRotationMatrix ();
00307
00308 result.push_back (PoseWithVotes (transform_average, cluster_votes[cluster_i].second));
00309 }
00310 }
00311
00312
00314 template <typename PointSource, typename PointTarget> bool
00315 pcl::PPFRegistration<PointSource, PointTarget>::posesWithinErrorBounds (Eigen::Affine3f &pose1,
00316 Eigen::Affine3f &pose2)
00317 {
00318 float position_diff = (pose1.translation () - pose2.translation ()).norm ();
00319 Eigen::AngleAxisf rotation_diff_mat (pose1.rotation ().inverse () * pose2.rotation ());
00320
00321 float rotation_diff_angle = fabsf (rotation_diff_mat.angle ());
00322
00323 if (position_diff < clustering_position_diff_threshold_ && rotation_diff_angle < clustering_rotation_diff_threshold_)
00324 return true;
00325 else return false;
00326 }
00327
00328
00330 template <typename PointSource, typename PointTarget> bool
00331 pcl::PPFRegistration<PointSource, PointTarget>::poseWithVotesCompareFunction (const typename pcl::PPFRegistration<PointSource, PointTarget>::PoseWithVotes &a,
00332 const typename pcl::PPFRegistration<PointSource, PointTarget>::PoseWithVotes &b )
00333 {
00334 return (a.votes > b.votes);
00335 }
00336
00337
00339 template <typename PointSource, typename PointTarget> bool
00340 pcl::PPFRegistration<PointSource, PointTarget>::clusterVotesCompareFunction (const std::pair<size_t, unsigned int> &a,
00341 const std::pair<size_t, unsigned int> &b)
00342 {
00343 return (a.second > b.second);
00344 }
00345
00346
00347
00348 #endif // PCL_REGISTRATION_IMPL_PPF_REGISTRATION_H_