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
00040
00041 #ifndef PCL_FEATURES_IMPL_CVFH_H_
00042 #define PCL_FEATURES_IMPL_CVFH_H_
00043
00044 #include <pcl/features/cvfh.h>
00045 #include <pcl/features/normal_3d.h>
00046 #include <pcl/features/pfh_tools.h>
00047 #include <pcl/common/centroid.h>
00048
00050 template<typename PointInT, typename PointNT, typename PointOutT> void
00051 pcl::CVFHEstimation<PointInT, PointNT, PointOutT>::compute (PointCloudOut &output)
00052 {
00053 if (!Feature<PointInT, PointOutT>::initCompute ())
00054 {
00055 output.width = output.height = 0;
00056 output.points.clear ();
00057 return;
00058 }
00059
00060
00061
00062
00063 output.width = output.height = 1;
00064 output.points.resize (1);
00065
00066
00067 computeFeature (output);
00068
00069 Feature<PointInT, PointOutT>::deinitCompute ();
00070 }
00071
00073 template<typename PointInT, typename PointNT, typename PointOutT> void
00074 pcl::CVFHEstimation<PointInT, PointNT, PointOutT>::extractEuclideanClustersSmooth (
00075 const pcl::PointCloud<pcl::PointNormal> &cloud,
00076 const pcl::PointCloud<pcl::PointNormal> &normals,
00077 float tolerance,
00078 const pcl::search::Search<pcl::PointNormal>::Ptr &tree,
00079 std::vector<pcl::PointIndices> &clusters,
00080 double eps_angle,
00081 unsigned int min_pts_per_cluster,
00082 unsigned int max_pts_per_cluster)
00083 {
00084 if (tree->getInputCloud ()->points.size () != cloud.points.size ())
00085 {
00086 PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset (%zu) than the input cloud (%zu)!\n", tree->getInputCloud ()->points.size (), cloud.points.size ());
00087 return;
00088 }
00089 if (cloud.points.size () != normals.points.size ())
00090 {
00091 PCL_ERROR ("[pcl::extractEuclideanClusters] Number of points in the input point cloud (%zu) different than normals (%zu)!\n", cloud.points.size (), normals.points.size ());
00092 return;
00093 }
00094
00095
00096 std::vector<bool> processed (cloud.points.size (), false);
00097
00098 std::vector<int> nn_indices;
00099 std::vector<float> nn_distances;
00100
00101 for (int i = 0; i < static_cast<int> (cloud.points.size ()); ++i)
00102 {
00103 if (processed[i])
00104 continue;
00105
00106 std::vector<unsigned int> seed_queue;
00107 int sq_idx = 0;
00108 seed_queue.push_back (i);
00109
00110 processed[i] = true;
00111
00112 while (sq_idx < static_cast<int> (seed_queue.size ()))
00113 {
00114
00115 if (!tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances))
00116 {
00117 sq_idx++;
00118 continue;
00119 }
00120
00121 for (size_t j = 1; j < nn_indices.size (); ++j)
00122 {
00123 if (processed[nn_indices[j]])
00124 continue;
00125
00126
00127
00128
00129 double dot_p = normals.points[seed_queue[sq_idx]].normal[0] * normals.points[nn_indices[j]].normal[0]
00130 + normals.points[seed_queue[sq_idx]].normal[1] * normals.points[nn_indices[j]].normal[1]
00131 + normals.points[seed_queue[sq_idx]].normal[2] * normals.points[nn_indices[j]].normal[2];
00132
00133 if (fabs (acos (dot_p)) < eps_angle)
00134 {
00135 processed[nn_indices[j]] = true;
00136 seed_queue.push_back (nn_indices[j]);
00137 }
00138 }
00139
00140 sq_idx++;
00141 }
00142
00143
00144 if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
00145 {
00146 pcl::PointIndices r;
00147 r.indices.resize (seed_queue.size ());
00148 for (size_t j = 0; j < seed_queue.size (); ++j)
00149 r.indices[j] = seed_queue[j];
00150
00151 std::sort (r.indices.begin (), r.indices.end ());
00152 r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
00153
00154 r.header = cloud.header;
00155 clusters.push_back (r);
00156 }
00157 }
00158 }
00159
00161 template<typename PointInT, typename PointNT, typename PointOutT> void
00162 pcl::CVFHEstimation<PointInT, PointNT, PointOutT>::filterNormalsWithHighCurvature (
00163 const pcl::PointCloud<PointNT> & cloud,
00164 std::vector<int> &indices_to_use,
00165 std::vector<int> &indices_out,
00166 std::vector<int> &indices_in,
00167 float threshold)
00168 {
00169 indices_out.resize (cloud.points.size ());
00170 indices_in.resize (cloud.points.size ());
00171
00172 size_t in, out;
00173 in = out = 0;
00174
00175 for (int i = 0; i < static_cast<int> (indices_to_use.size ()); i++)
00176 {
00177 if (cloud.points[indices_to_use[i]].curvature > threshold)
00178 {
00179 indices_out[out] = indices_to_use[i];
00180 out++;
00181 }
00182 else
00183 {
00184 indices_in[in] = indices_to_use[i];
00185 in++;
00186 }
00187 }
00188
00189 indices_out.resize (out);
00190 indices_in.resize (in);
00191 }
00192
00194 template<typename PointInT, typename PointNT, typename PointOutT> void
00195 pcl::CVFHEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
00196 {
00197
00198 if (!normals_)
00199 {
00200 PCL_ERROR ("[pcl::%s::computeFeature] No input dataset containing normals was given!\n", getClassName ().c_str ());
00201 output.width = output.height = 0;
00202 output.points.clear ();
00203 return;
00204 }
00205 if (normals_->points.size () != surface_->points.size ())
00206 {
00207 PCL_ERROR ("[pcl::%s::computeFeature] The number of points in the input dataset differs from the number of points in the dataset containing the normals!\n", getClassName ().c_str ());
00208 output.width = output.height = 0;
00209 output.points.clear ();
00210 return;
00211 }
00212
00213 centroids_dominant_orientations_.clear ();
00214
00215
00216 std::vector<int> indices_out;
00217 std::vector<int> indices_in;
00218 filterNormalsWithHighCurvature (*normals_, *indices_, indices_out, indices_in, curv_threshold_);
00219
00220 pcl::PointCloud<pcl::PointNormal>::Ptr normals_filtered_cloud (new pcl::PointCloud<pcl::PointNormal> ());
00221 normals_filtered_cloud->width = static_cast<uint32_t> (indices_in.size ());
00222 normals_filtered_cloud->height = 1;
00223 normals_filtered_cloud->points.resize (normals_filtered_cloud->width);
00224
00225 for (size_t i = 0; i < indices_in.size (); ++i)
00226 {
00227 normals_filtered_cloud->points[i].x = surface_->points[indices_in[i]].x;
00228 normals_filtered_cloud->points[i].y = surface_->points[indices_in[i]].y;
00229 normals_filtered_cloud->points[i].z = surface_->points[indices_in[i]].z;
00230 }
00231
00232 std::vector<pcl::PointIndices> clusters;
00233
00234 if(normals_filtered_cloud->points.size() >= min_points_)
00235 {
00236
00237 KdTreePtr normals_tree_filtered (new pcl::search::KdTree<pcl::PointNormal> (false));
00238 normals_tree_filtered->setInputCloud (normals_filtered_cloud);
00239
00240
00241 pcl::NormalEstimation<PointNormal, PointNormal> n3d;
00242 n3d.setRadiusSearch (radius_normals_);
00243 n3d.setSearchMethod (normals_tree_filtered);
00244 n3d.setInputCloud (normals_filtered_cloud);
00245 n3d.compute (*normals_filtered_cloud);
00246
00247 KdTreePtr normals_tree (new pcl::search::KdTree<pcl::PointNormal> (false));
00248 normals_tree->setInputCloud (normals_filtered_cloud);
00249
00250 extractEuclideanClustersSmooth (*normals_filtered_cloud,
00251 *normals_filtered_cloud,
00252 cluster_tolerance_,
00253 normals_tree,
00254 clusters,
00255 eps_angle_threshold_,
00256 static_cast<unsigned int> (min_points_));
00257
00258 }
00259
00260 VFHEstimator vfh;
00261 vfh.setInputCloud (surface_);
00262 vfh.setInputNormals (normals_);
00263 vfh.setIndices(indices_);
00264 vfh.setSearchMethod (this->tree_);
00265 vfh.setUseGivenNormal (true);
00266 vfh.setUseGivenCentroid (true);
00267 vfh.setNormalizeBins (normalize_bins_);
00268 vfh.setNormalizeDistance (true);
00269 vfh.setFillSizeComponent (true);
00270 output.height = 1;
00271
00272
00273 if (clusters.size () > 0)
00274 {
00275
00276 for (size_t i = 0; i < clusters.size (); ++i)
00277 {
00278 Eigen::Vector4f avg_normal = Eigen::Vector4f::Zero ();
00279 Eigen::Vector4f avg_centroid = Eigen::Vector4f::Zero ();
00280
00281 for (size_t j = 0; j < clusters[i].indices.size (); j++)
00282 {
00283 avg_normal += normals_filtered_cloud->points[clusters[i].indices[j]].getNormalVector4fMap ();
00284 avg_centroid += normals_filtered_cloud->points[clusters[i].indices[j]].getVector4fMap ();
00285 }
00286
00287 avg_normal /= static_cast<float> (clusters[i].indices.size ());
00288 avg_centroid /= static_cast<float> (clusters[i].indices.size ());
00289
00290 Eigen::Vector4f centroid_test;
00291 pcl::compute3DCentroid (*normals_filtered_cloud, centroid_test);
00292 avg_normal.normalize ();
00293
00294 Eigen::Vector3f avg_norm (avg_normal[0], avg_normal[1], avg_normal[2]);
00295 Eigen::Vector3f avg_dominant_centroid (avg_centroid[0], avg_centroid[1], avg_centroid[2]);
00296
00297
00298 dominant_normals_.push_back (avg_norm);
00299 centroids_dominant_orientations_.push_back (avg_dominant_centroid);
00300 }
00301
00302
00303 output.points.resize (dominant_normals_.size ());
00304 output.width = static_cast<uint32_t> (dominant_normals_.size ());
00305
00306 for (size_t i = 0; i < dominant_normals_.size (); ++i)
00307 {
00308
00309 vfh.setNormalToUse (dominant_normals_[i]);
00310 vfh.setCentroidToUse (centroids_dominant_orientations_[i]);
00311 pcl::PointCloud<pcl::VFHSignature308> vfh_signature;
00312 vfh.compute (vfh_signature);
00313 output.points[i] = vfh_signature.points[0];
00314 }
00315 }
00316 else
00317 {
00318 Eigen::Vector4f avg_centroid;
00319 pcl::compute3DCentroid (*surface_, avg_centroid);
00320 Eigen::Vector3f cloud_centroid (avg_centroid[0], avg_centroid[1], avg_centroid[2]);
00321 centroids_dominant_orientations_.push_back (cloud_centroid);
00322
00323
00324 vfh.setCentroidToUse (cloud_centroid);
00325 vfh.setUseGivenNormal (false);
00326
00327 pcl::PointCloud<pcl::VFHSignature308> vfh_signature;
00328 vfh.compute (vfh_signature);
00329
00330 output.points.resize (1);
00331 output.width = 1;
00332
00333 output.points[0] = vfh_signature.points[0];
00334 }
00335 }
00336
00337 #define PCL_INSTANTIATE_CVFHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::CVFHEstimation<T,NT,OutT>;
00338
00339 #endif // PCL_FEATURES_IMPL_VFH_H_