41 #ifndef PCL_FEATURES_IMPL_OURCVFH_H_
42 #define PCL_FEATURES_IMPL_OURCVFH_H_
44 #include <pcl/features/our_cvfh.h>
45 #include <pcl/features/vfh.h>
46 #include <pcl/features/normal_3d.h>
47 #include <pcl/common/io.h>
49 #include <pcl/common/transforms.h>
50 #include <pcl/search/kdtree.h>
53 template<
typename Po
intInT,
typename Po
intNT,
typename Po
intOutT>
void
70 computeFeature (output);
76 template<
typename Po
intInT,
typename Po
intNT,
typename Po
intOutT>
void
81 std::vector<pcl::PointIndices> &clusters,
double eps_angle,
82 unsigned int min_pts_per_cluster,
83 unsigned int max_pts_per_cluster)
87 PCL_ERROR(
"[pcl::extractEuclideanClusters] Tree built for a different point cloud "
88 "dataset (%zu) than the input cloud (%zu)!\n",
90 static_cast<std::size_t
>(cloud.
size()));
93 if (cloud.
size () != normals.
size ())
95 PCL_ERROR(
"[pcl::extractEuclideanClusters] Number of points in the input point "
96 "cloud (%zu) different than normals (%zu)!\n",
97 static_cast<std::size_t
>(cloud.
size()),
98 static_cast<std::size_t
>(normals.
size()));
105 std::vector<bool> processed (cloud.
size (),
false);
108 std::vector<float> nn_distances;
110 for (std::size_t i = 0; i < cloud.
size (); ++i)
115 std::vector<std::size_t> seed_queue;
116 std::size_t sq_idx = 0;
117 seed_queue.push_back (i);
121 while (sq_idx < seed_queue.size ())
124 if (!tree->
radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances))
130 for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j)
132 if (processed[nn_indices[j]])
138 double dot_p = normals[seed_queue[sq_idx]].normal[0] * normals[nn_indices[j]].normal[0]
139 + normals[seed_queue[sq_idx]].normal[1] * normals[nn_indices[j]].normal[1] + normals[seed_queue[sq_idx]].normal[2]
140 * normals[nn_indices[j]].normal[2];
142 if (std::abs (std::acos (dot_p)) < eps_angle)
144 processed[nn_indices[j]] =
true;
153 if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
156 r.
indices.resize (seed_queue.size ());
157 for (std::size_t j = 0; j < seed_queue.size (); ++j)
164 clusters.push_back (r);
170 template<
typename Po
intInT,
typename Po
intNT,
typename Po
intOutT>
void
176 indices_out.resize (cloud.
size ());
177 indices_in.resize (cloud.
size ());
182 for (
const auto &index : indices_to_use)
184 if (cloud[index].curvature > threshold)
186 indices_out[out] = index;
191 indices_in[in] = index;
196 indices_out.resize (out);
197 indices_in.resize (in);
200 template<
typename Po
intInT,
typename Po
intNT,
typename Po
intOutT>
bool
202 PointInTPtr & processed, std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > & transformations,
206 Eigen::Vector3f plane_normal;
207 plane_normal[0] = -centroid[0];
208 plane_normal[1] = -centroid[1];
209 plane_normal[2] = -centroid[2];
210 Eigen::Vector3f z_vector = Eigen::Vector3f::UnitZ ();
211 plane_normal.normalize ();
212 Eigen::Vector3f axis = plane_normal.cross (z_vector);
213 double rotation = -asin (axis.norm ());
216 Eigen::Affine3f transformPC (Eigen::AngleAxisf (
static_cast<float> (rotation), axis));
218 grid->resize (processed->size ());
219 for (std::size_t k = 0; k < processed->size (); k++)
220 (*grid)[k].getVector4fMap () = (*processed)[k].getVector4fMap ();
224 Eigen::Vector4f centroid4f (centroid[0], centroid[1], centroid[2], 0);
225 Eigen::Vector4f normal_centroid4f (normal_centroid[0], normal_centroid[1], normal_centroid[2], 0);
227 centroid4f = transformPC * centroid4f;
228 normal_centroid4f = transformPC * normal_centroid4f;
230 Eigen::Vector3f centroid3f (centroid4f[0], centroid4f[1], centroid4f[2]);
232 Eigen::Vector4f farthest_away;
234 farthest_away[3] = 0;
236 float max_dist = (farthest_away - centroid4f).norm ();
240 Eigen::Matrix4f center_mat;
241 center_mat.setIdentity (4, 4);
242 center_mat (0, 3) = -centroid4f[0];
243 center_mat (1, 3) = -centroid4f[1];
244 center_mat (2, 3) = -centroid4f[2];
246 Eigen::Matrix3f scatter;
250 for (
const auto &index : indices.
indices)
252 Eigen::Vector3f pvector = (*grid)[index].getVector3fMap ();
253 float d_k = (pvector).norm ();
254 float w = (max_dist - d_k);
255 Eigen::Vector3f diff = (pvector);
256 Eigen::Matrix3f mat = diff * diff.transpose ();
263 Eigen::JacobiSVD <Eigen::MatrixXf> svd (scatter, Eigen::ComputeFullV);
264 Eigen::Vector3f evx = svd.matrixV ().col (0);
265 Eigen::Vector3f evy = svd.matrixV ().col (1);
266 Eigen::Vector3f evz = svd.matrixV ().col (2);
267 Eigen::Vector3f evxminus = evx * -1;
268 Eigen::Vector3f evyminus = evy * -1;
269 Eigen::Vector3f evzminus = evz * -1;
271 float s_xplus, s_xminus, s_yplus, s_yminus;
272 s_xplus = s_xminus = s_yplus = s_yminus = 0.f;
275 for (
const auto& point: grid->points)
277 Eigen::Vector3f pvector = point.getVector3fMap ();
278 float dist_x, dist_y;
279 dist_x = std::abs (evx.dot (pvector));
280 dist_y = std::abs (evy.dot (pvector));
282 if ((pvector).dot (evx) >= 0)
287 if ((pvector).dot (evy) >= 0)
294 if (s_xplus < s_xminus)
297 if (s_yplus < s_yminus)
302 float max_x =
static_cast<float> (std::max (s_xplus, s_xminus));
303 float min_x =
static_cast<float> (std::min (s_xplus, s_xminus));
304 float max_y =
static_cast<float> (std::max (s_yplus, s_yminus));
305 float min_y =
static_cast<float> (std::min (s_yplus, s_yminus));
307 fx = (min_x / max_x);
308 fy = (min_y / max_y);
310 Eigen::Vector3f normal3f = Eigen::Vector3f (normal_centroid4f[0], normal_centroid4f[1], normal_centroid4f[2]);
311 if (normal3f.dot (evz) < 0)
317 float max_axis = std::max (fx, fy);
318 float min_axis = std::min (fx, fy);
320 if ((min_axis / max_axis) > axis_ratio_)
322 PCL_WARN (
"Both axes are equally easy/difficult to disambiguate\n");
324 Eigen::Vector3f evy_copy = evy;
325 Eigen::Vector3f evxminus = evx * -1;
326 Eigen::Vector3f evyminus = evy * -1;
328 if (min_axis > min_axis_value_)
331 evy = evx.cross (evz);
332 Eigen::Matrix4f trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat);
333 transformations.push_back (trans);
336 evy = evx.cross (evz);
337 trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat);
338 transformations.push_back (trans);
341 evy = evx.cross (evz);
342 trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat);
343 transformations.push_back (trans);
346 evy = evx.cross (evz);
347 trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat);
348 transformations.push_back (trans);
354 evy = evx.cross (evz);
355 Eigen::Matrix4f trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat);
356 transformations.push_back (trans);
360 evy = evx.cross (evz);
361 trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat);
362 transformations.push_back (trans);
373 evy = evx.cross (evz);
374 Eigen::Matrix4f trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat);
375 transformations.push_back (trans);
383 template<
typename Po
intInT,
typename Po
intNT,
typename Po
intOutT>
void
385 std::vector<pcl::PointIndices> & cluster_indices)
389 cluster_axes_.
clear ();
390 cluster_axes_.resize (centroids_dominant_orientations_.size ());
392 for (std::size_t i = 0; i < centroids_dominant_orientations_.size (); i++)
395 std::vector < Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > transformations;
397 sgurf (centroids_dominant_orientations_[i], dominant_normals_[i], processed, transformations, grid, cluster_indices[i]);
400 cluster_axes_[i] = transformations.size ();
402 for (
const auto &transformation : transformations)
406 transforms_.push_back (transformation);
407 valid_transforms_.push_back (
true);
409 std::vector < Eigen::VectorXf > quadrants (8);
412 for (
int k = 0; k < num_hists; k++)
413 quadrants[k].setZero (size_hists);
415 Eigen::Vector4f centroid_p;
416 centroid_p.setZero ();
417 Eigen::Vector4f max_pt;
420 double distance_normalization_factor = (centroid_p - max_pt).norm ();
424 hist_incr = 100.0f /
static_cast<float> (grid->size () - 1);
428 float * weights =
new float[num_hists];
430 float sigma_sq = sigma * sigma;
432 for (
const auto& point: grid->points)
434 Eigen::Vector4f p = point.getVector4fMap ();
439 float wx = 1.f - std::exp (-((p[0] * p[0]) / (2.f * sigma_sq)));
440 float wy = 1.f - std::exp (-((p[1] * p[1]) / (2.f * sigma_sq)));
441 float wz = 1.f - std::exp (-((p[2] * p[2]) / (2.f * sigma_sq)));
446 for (std::size_t ii = 0; ii <= 3; ii++)
447 weights[ii] = 0.5f - wx * 0.5f;
449 for (std::size_t ii = 4; ii <= 7; ii++)
450 weights[ii] = 0.5f + wx * 0.5f;
454 for (std::size_t ii = 0; ii <= 3; ii++)
455 weights[ii] = 0.5f + wx * 0.5f;
457 for (std::size_t ii = 4; ii <= 7; ii++)
458 weights[ii] = 0.5f - wx * 0.5f;
464 for (std::size_t ii = 0; ii <= 1; ii++)
465 weights[ii] *= 0.5f - wy * 0.5f;
466 for (std::size_t ii = 4; ii <= 5; ii++)
467 weights[ii] *= 0.5f - wy * 0.5f;
469 for (std::size_t ii = 2; ii <= 3; ii++)
470 weights[ii] *= 0.5f + wy * 0.5f;
472 for (std::size_t ii = 6; ii <= 7; ii++)
473 weights[ii] *= 0.5f + wy * 0.5f;
477 for (std::size_t ii = 0; ii <= 1; ii++)
478 weights[ii] *= 0.5f + wy * 0.5f;
479 for (std::size_t ii = 4; ii <= 5; ii++)
480 weights[ii] *= 0.5f + wy * 0.5f;
482 for (std::size_t ii = 2; ii <= 3; ii++)
483 weights[ii] *= 0.5f - wy * 0.5f;
485 for (std::size_t ii = 6; ii <= 7; ii++)
486 weights[ii] *= 0.5f - wy * 0.5f;
492 for (std::size_t ii = 0; ii <= 7; ii += 2)
493 weights[ii] *= 0.5f - wz * 0.5f;
495 for (std::size_t ii = 1; ii <= 7; ii += 2)
496 weights[ii] *= 0.5f + wz * 0.5f;
501 for (std::size_t ii = 0; ii <= 7; ii += 2)
502 weights[ii] *= 0.5f + wz * 0.5f;
504 for (std::size_t ii = 1; ii <= 7; ii += 2)
505 weights[ii] *= 0.5f - wz * 0.5f;
508 int h_index = (d <= 0) ? 0 : std::ceil (size_hists * (d / distance_normalization_factor)) - 1;
516 for (
int j = 0; j < num_hists; j++)
517 quadrants[j][h_index] += hist_incr * weights[j];
525 for (
int d = 0; d < 308; ++d)
526 vfh_signature[0].histogram[d] = output[i].histogram[d];
529 for (
int k = 0; k < num_hists; k++)
531 for (
int ii = 0; ii < size_hists; ii++, pos++)
533 vfh_signature[0].histogram[pos] = quadrants[k][ii];
537 ourcvfh_output.
push_back (vfh_signature[0]);
538 ourcvfh_output.
width = ourcvfh_output.
size ();
543 if (!ourcvfh_output.
empty ())
545 ourcvfh_output.
height = 1;
547 output = ourcvfh_output;
551 template<
typename Po
intInT,
typename Po
intNT,
typename Po
intOutT>
void
554 if (refine_clusters_ <= 0.f)
555 refine_clusters_ = 1.f;
560 PCL_ERROR (
"[pcl::%s::computeFeature] No input dataset containing normals was given!\n", getClassName ().c_str ());
561 output.width = output.height = 0;
565 if (normals_->size () != surface_->size ())
567 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 ());
568 output.width = output.height = 0;
573 centroids_dominant_orientations_.clear ();
575 transforms_.clear ();
576 dominant_normals_.clear ();
581 filterNormalsWithHighCurvature (*normals_, *indices_, indices_out, indices_in, curv_threshold_);
584 normals_filtered_cloud->width = indices_in.size ();
585 normals_filtered_cloud->height = 1;
586 normals_filtered_cloud->points.resize (normals_filtered_cloud->width);
589 indices_from_nfc_to_indices.resize (indices_in.size ());
591 for (std::size_t i = 0; i < indices_in.size (); ++i)
593 (*normals_filtered_cloud)[i].x = (*surface_)[indices_in[i]].x;
594 (*normals_filtered_cloud)[i].y = (*surface_)[indices_in[i]].y;
595 (*normals_filtered_cloud)[i].z = (*surface_)[indices_in[i]].z;
597 indices_from_nfc_to_indices[i] = indices_in[i];
600 std::vector<pcl::PointIndices> clusters;
602 if (normals_filtered_cloud->size () >= min_points_)
607 normals_tree_filtered->setInputCloud (normals_filtered_cloud);
612 n3d.
compute (*normals_filtered_cloud);
616 normals_tree->setInputCloud (normals_filtered_cloud);
618 extractEuclideanClustersSmooth (*normals_filtered_cloud, *normals_filtered_cloud, cluster_tolerance_, normals_tree, clusters,
619 eps_angle_threshold_,
static_cast<unsigned int> (min_points_));
621 std::vector<pcl::PointIndices> clusters_filtered;
622 int cluster_filtered_idx = 0;
623 for (
const auto &cluster : clusters)
629 clusters_.push_back (pi);
630 clusters_filtered.push_back (pi_filtered);
632 Eigen::Vector4f avg_normal = Eigen::Vector4f::Zero ();
633 Eigen::Vector4f avg_centroid = Eigen::Vector4f::Zero ();
635 for (
const auto &index : cluster.indices)
637 avg_normal += (*normals_filtered_cloud)[index].getNormalVector4fMap ();
638 avg_centroid += (*normals_filtered_cloud)[index].getVector4fMap ();
641 avg_normal /=
static_cast<float> (cluster.indices.size ());
642 avg_centroid /=
static_cast<float> (cluster.indices.size ());
643 avg_normal.normalize ();
645 Eigen::Vector3f avg_norm (avg_normal[0], avg_normal[1], avg_normal[2]);
646 Eigen::Vector3f avg_dominant_centroid (avg_centroid[0], avg_centroid[1], avg_centroid[2]);
648 for (
const auto &index : cluster.indices)
651 double dot_p = avg_normal.dot ((*normals_filtered_cloud)[index].getNormalVector4fMap ());
652 if (std::abs (std::acos (dot_p)) < (eps_angle_threshold_ * refine_clusters_))
654 clusters_[cluster_filtered_idx].indices.push_back (indices_from_nfc_to_indices[index]);
655 clusters_filtered[cluster_filtered_idx].indices.push_back (index);
660 if (clusters_[cluster_filtered_idx].indices.empty ())
662 clusters_.pop_back ();
663 clusters_filtered.pop_back ();
666 cluster_filtered_idx++;
669 clusters = clusters_filtered;
684 if (!clusters.empty ())
686 for (
const auto &cluster : clusters)
688 Eigen::Vector4f avg_normal = Eigen::Vector4f::Zero ();
689 Eigen::Vector4f avg_centroid = Eigen::Vector4f::Zero ();
691 for (
const auto &index : cluster.indices)
693 avg_normal += (*normals_filtered_cloud)[index].getNormalVector4fMap ();
694 avg_centroid += (*normals_filtered_cloud)[index].getVector4fMap ();
697 avg_normal /=
static_cast<float> (cluster.indices.size ());
698 avg_centroid /=
static_cast<float> (cluster.indices.size ());
699 avg_normal.normalize ();
702 dominant_normals_.emplace_back (avg_normal[0], avg_normal[1], avg_normal[2]);
703 centroids_dominant_orientations_.emplace_back (avg_centroid[0], avg_centroid[1], avg_centroid[2]);
707 output.resize (dominant_normals_.size ());
708 output.width = dominant_normals_.size ();
710 for (std::size_t i = 0; i < dominant_normals_.size (); ++i)
717 output[i] = vfh_signature[0];
723 computeRFAndShapeDistribution (cloud_input, output, clusters_);
728 PCL_WARN(
"No clusters were found in the surface... using VFH...\n");
729 Eigen::Vector4f avg_centroid;
731 Eigen::Vector3f cloud_centroid (avg_centroid[0], avg_centroid[1], avg_centroid[2]);
732 centroids_dominant_orientations_.push_back (cloud_centroid);
744 output[0] = vfh_signature[0];
745 Eigen::Matrix4f
id = Eigen::Matrix4f::Identity ();
746 transforms_.push_back (
id);
747 valid_transforms_.push_back (
false);
751 #define PCL_INSTANTIATE_OURCVFHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::OURCVFHEstimation<T,NT,OutT>;
void setInputNormals(const PointCloudNConstPtr &normals)
Provide a pointer to the input dataset that contains the point normals of the XYZ dataset.
Feature represents the base feature class.
void setRadiusSearch(double radius)
Set the sphere radius that is to be used for determining the nearest neighbors used for the feature e...
void setSearchMethod(const KdTreePtr &tree)
Provide a pointer to the search object.
void compute(PointCloudOut &output)
Base method for feature estimation for all points given in <setInputCloud (), setIndices ()> using th...
NormalEstimation estimates local surface properties (surface normals and curvatures)at each 3D point.
void setInputCloud(const PointCloudConstPtr &cloud) override
Provide a pointer to the input dataset.
OURCVFHEstimation estimates the Oriented, Unique and Repetable Clustered Viewpoint Feature Histogram ...
bool sgurf(Eigen::Vector3f ¢roid, Eigen::Vector3f &normal_centroid, PointInTPtr &processed, std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &transformations, PointInTPtr &grid, pcl::PointIndices &indices)
Computes SGURF.
void filterNormalsWithHighCurvature(const pcl::PointCloud< PointNT > &cloud, pcl::Indices &indices_to_use, pcl::Indices &indices_out, pcl::Indices &indices_in, float threshold)
Removes normals with high curvature caused by real edges or noisy data.
void compute(PointCloudOut &output)
Overloaded computed method from pcl::Feature.
typename pcl::PointCloud< PointInT >::Ptr PointInTPtr
void computeRFAndShapeDistribution(PointInTPtr &processed, PointCloudOut &output, std::vector< pcl::PointIndices > &cluster_indices)
Computes SGURF and the shape distribution based on the selected SGURF.
virtual void setInputCloud(const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset.
virtual void setIndices(const IndicesPtr &indices)
Provide a pointer to the vector of indices that represents the input data.
void push_back(const PointT &pt)
Insert a new point in the cloud, at the end of the container.
void resize(std::size_t count)
Resizes the container to contain count elements.
std::uint32_t width
The point cloud width (if organized as an image-structure).
pcl::PCLHeader header
The point cloud header.
std::uint32_t height
The point cloud height (if organized as an image-structure).
void clear()
Removes all points in a cloud and sets the width and height to 0.
shared_ptr< PointCloud< PointT > > Ptr
VFHEstimation estimates the Viewpoint Feature Histogram (VFH) descriptor for a given point cloud data...
void setUseGivenNormal(bool use)
Set use_given_normal_.
void setCentroidToUse(const Eigen::Vector3f ¢roid)
Set centroid_to_use_.
void compute(PointCloudOut &output)
Overloaded computed method from pcl::Feature.
void setNormalToUse(const Eigen::Vector3f &normal)
Set the normal to use.
void setNormalizeBins(bool normalize)
set normalize_bins_
void setUseGivenCentroid(bool use)
Set use_given_centroid_.
search::KdTree is a wrapper class which inherits the pcl::KdTree class for performing search function...
virtual bool getSortedResults()
Gets whether the results should be sorted (ascending in the distance) or not Otherwise the results ma...
shared_ptr< pcl::search::Search< PointT > > Ptr
virtual PointCloudConstPtr getInputCloud() const
Get a pointer to the input point cloud dataset.
virtual int radiusSearch(const PointT &point, double radius, Indices &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const =0
Search for all the nearest neighbors of the query point in a given radius.
Define standard C methods and C++ classes that are common to all methods.
void getMaxDistance(const pcl::PointCloud< PointT > &cloud, const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt)
Get the point at maximum distance from a given point and a given pointcloud.
void demeanPointCloud(ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, pcl::PointCloud< PointT > &cloud_out, int npts=0)
Subtract a centroid from a point cloud and return the de-meaned representation.
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform, bool copy_all_fields)
Apply a rigid transform defined by a 4x4 matrix.
unsigned int compute3DCentroid(ConstCloudIterator< PointT > &cloud_iterator, Eigen::Matrix< Scalar, 4, 1 > ¢roid)
Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector.
void copyPointCloud(const pcl::PointCloud< PointInT > &cloud_in, pcl::PointCloud< PointOutT > &cloud_out)
Copy all the fields from a given point cloud into a new point cloud.
IndicesAllocator<> Indices
Type used for indices in PCL.