3 typedef pcl::PointCloud<pcl::PointXYZRGBA>
PointCloud;
33 std::string file_default =
"";
34 node.
param(
"file", this->
file, file_default);
57 printf(
"PARAMETERS\n");
58 printf(
" file: %s\n", this->
file.c_str());
60 printf(
" target radius error: %.3f\n", this->
radius_error);
61 printf(
" min. affordance gap: %.3f\n", this->
handle_gap);
62 printf(
" number of samples: %i\n", this->
num_samples);
63 printf(
" max. range: %.3f\n", this->
max_range);
85 for (std::size_t i = 0; i < cloud_in->points.size(); i++)
87 if (cloud_in->points[i].x * cloud_in->points[i].x + cloud_in->points[i].y * cloud_in->points[i].y
88 + cloud_in->points[i].z * cloud_in->points[i].z < this->max_range * this->max_range)
89 cloud_out->points.push_back(cloud_in->points[i]);
97 if (transform != NULL)
108 if (x >= limits.
min_x && x <= limits.max_x && y >= limits.
min_y && y <= limits.max_y && z >= limits.
min_z 109 && z <= limits.
max_z)
121 for (std::size_t i = 0; i < cloud_in->points.size(); i++)
123 if (this->
isPointInWorkspace(cloud_in->points[i].x, cloud_in->points[i].y, cloud_in->points[i].z, transform))
124 cloud_out->points.push_back(cloud_in->points[i]);
133 Eigen::Vector3f center = cloud->points[center_index].getVector3fMap();
134 double dist_center = center.norm();
135 double theta =
atan(radius / dist_center);
136 Eigen::Vector3f center_unit = center / dist_center;
137 int num_in_front = 0;
139 for (std::size_t i = 0; i < cloud->points.size(); i++)
141 if (isnan(cloud->points[i].x))
144 Eigen::Vector3f point = cloud->points[i].getVector3fMap();
145 float point_norm = point.norm();
146 Eigen::Vector3f point_unit = point / point_norm;
148 if (fabs(point_unit.dot(center_unit)) <
cos(theta))
151 if (point_norm < dist_center - radius)
159 Eigen::Vector3d &axis, Eigen::Vector3d &normal)
161 Eigen::Matrix3f covar_mat;
162 Eigen::Vector4f nn_centroid;
163 nn_centroid << cloud->points[nn_center_idx].x, cloud->points[nn_center_idx].y, cloud->points[nn_center_idx].z, 0;
165 pcl::computeCovarianceMatrix(*cloud, nn_indices, nn_centroid, covar_mat);
167 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigen_solver(covar_mat);
168 Eigen::Vector3f eig_vals = eigen_solver.eigenvalues();
170 eig_vals.maxCoeff(&max_index);
171 axis = eigen_solver.eigenvectors().col(max_index).cast<
double>();
172 Eigen::Vector3d perp_axis;
173 perp_axis << -axis(1), axis(0), 0;
174 normal = axis.cross(perp_axis);
175 normal /= normal.norm();
179 const std::vector<int> &nn_indices, Eigen::Vector3d &axis,
180 Eigen::Vector3d &normal)
185 for (std::size_t j = 0; j < nn_indices.size(); j++)
187 Eigen::Vector3d normal;
188 normal << cloud_normals->points[nn_indices[j]].normal[0], cloud_normals->points[nn_indices[j]].normal[1], cloud_normals->points[nn_indices[j]].normal[2];
189 Eigen::Matrix3d matNormal = normal * normal.transpose();
193 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> eigen_solver(mat);
194 Eigen::Vector3d eig_vals = eigen_solver.eigenvalues();
196 eig_vals.minCoeff(&min_index);
197 axis = eigen_solver.eigenvectors().col(min_index);
198 Eigen::Vector3d perp_axis;
199 perp_axis << -axis(1), axis(0), 0;
200 normal = axis.cross(perp_axis);
201 normal /= normal.norm();
206 pcl::NormalEstimationOMP<pcl::PointXYZRGBA, pcl::Normal> normal_estimator;
207 normal_estimator.setInputCloud(cloud);
208 pcl::search::KdTree<pcl::PointXYZRGBA>::Ptr tree(
new pcl::search::KdTree<pcl::PointXYZRGBA>());
209 normal_estimator.setSearchMethod(tree);
210 normal_estimator.setRadiusSearch(0.03);
211 normal_estimator.compute(*cloud_normals);
217 std::vector<CylindricalShell> shells;
233 pcl::PointCloud<pcl::Normal>::Ptr cloud_normals(
new pcl::PointCloud<pcl::Normal>);
238 double begin_time_normals_estimation = omp_get_wtime();
239 printf(
"Estimating surface normals ...\n");
241 printf(
" elapsed time: %.3f sec\n", omp_get_wtime() - begin_time_normals_estimation);
245 double begin_time_axis = omp_get_wtime();
246 printf(
"Estimating cylinder surface normal and curvature axis ...\n");
247 pcl::PointXYZRGBA searchPoint;
248 std::vector<int> nn_indices;
249 std::vector < std::vector<int> > neighborhoods(this->
num_samples);
250 std::vector<int> neighborhood_centroids(this->
num_samples);
251 std::vector<Eigen::Vector3d> normals(this->
num_samples);
252 std::vector<Eigen::Vector3d> curvature_axes(this->
num_samples);
255 if (cloud->isOrganized())
257 std::vector<float> nn_dists;
258 pcl::search::OrganizedNeighbor<pcl::PointXYZRGBA>::Ptr organized_neighbor(
259 new pcl::search::OrganizedNeighbor<pcl::PointXYZRGBA>());
260 organized_neighbor->setInputCloud(cloud);
261 std::srand(std::time(0));
266 int r = std::rand() % cloud->points.size();
268 while (!pcl::isFinite((*cloud)[r]) || !this->
isPointInWorkspace((*cloud)[r].
x, (*cloud)[r].
y, (*cloud)[r].
z))
269 r = std::rand() % cloud->points.size();
272 if (organized_neighbor->radiusSearch((*cloud)[r], this->NEIGHBOR_RADIUS, nn_indices, nn_dists) > 0)
279 neighborhoods[i] = nn_indices;
280 neighborhood_centroids[i] = r;
286 std::vector<float> nn_dists;
287 pcl::KdTreeFLANN<pcl::PointXYZRGBA> tree;
288 tree.setInputCloud(cloud);
289 std::srand(std::time(0));
294 int r = std::rand() % cloud->points.size();
296 while (!pcl::isFinite((*cloud)[r]) || !this->
isPointInWorkspace((*cloud)[r].
x, (*cloud)[r].
y, (*cloud)[r].
z))
297 r = std::rand() % cloud->points.size();
300 if (tree.radiusSearch((*cloud)[r], this->NEIGHBOR_RADIUS, nn_indices, nn_dists) > 0)
307 neighborhoods[i] = nn_indices;
308 neighborhood_centroids[i] = r;
313 printf(
" elapsed time: %.3f sec\n", omp_get_wtime() - begin_time_axis);
320 printf(
"Filtering on curvature, fitting cylinders, and filtering on low clearance ...\n");
322 printf(
"Filtering on curvature and fitting cylinders ...\n");
324 double begin_time = omp_get_wtime();
325 int cylinders_left_clearance = 0;
326 Eigen::Vector3d normal;
327 Eigen::Vector3d curvature_axis;
328 Eigen::Vector3d curvature_centroid;
329 std::vector<CylindricalShell> shells;
332 double outer_sample_radius = 1.5 * (maxHandAperture + this->
handle_gap);
335 pcl::search::OrganizedNeighbor<pcl::PointXYZRGBA>::Ptr organized_neighbor(
336 new pcl::search::OrganizedNeighbor<pcl::PointXYZRGBA>());
338 pcl::KdTreeFLANN<pcl::PointXYZRGBA> tree;
339 if (cloud->isOrganized())
340 organized_neighbor->setInputCloud(cloud);
342 tree.setInputCloud(cloud);
348 shell.
fitCylinder(cloud, neighborhoods[i], normals[i], curvature_axes[i]);
357 if (shell.
getRadius() > min_radius_cylinder && shell.
getRadius() < max_radius_cylinder)
362 pcl::PointXYZRGBA searchPoint;
363 std::vector<int> nn_indices;
364 std::vector<float> nn_dists;
366 searchPoint.x = centroid(0);
367 searchPoint.y = centroid(1);
368 searchPoint.z = centroid(2);
369 int num_in_radius = 0;
370 if (cloud->isOrganized())
371 num_in_radius = organized_neighbor->radiusSearch(searchPoint, outer_sample_radius, nn_indices, nn_dists);
373 num_in_radius = tree.radiusSearch(searchPoint, outer_sample_radius, nn_indices, nn_dists);
375 if ((num_in_radius > 0) && (shell.
hasClearance(cloud, nn_indices, maxHandAperture, this->handle_gap)))
376 shells.push_back(shell);
379 shells.push_back(shell);
383 printf(
" elapsed time: %.3f sec\n", omp_get_wtime() - begin_time);
385 printf(
" cylinders left after clearance filtering: %i\n", (
int)shells.size());
393 printf(
"Estimating curvature ...\n");
394 double beginTime = omp_get_wtime();
400 estimator.setInputCloud(cloud);
410 std::srand(std::time(0));
414 int r = std::rand() % cloud->points.size();
416 while (!pcl::isFinite((*cloud)[r])
417 || !this->
isPointInWorkspace(cloud->points[r].x, cloud->points[r].y, cloud->points[r].z, transform))
419 r = std::rand() % cloud->points.size();
421 if (k == cloud->points.size())
423 printf(
"No finite points in cloud!\n");
424 std::vector<CylindricalShell> shells;
432 estimator.setIndices(indices_ptr);
438 pcl::PointCloud<pcl::PointCurvatureTaubin>::Ptr cloud_curvature(
new pcl::PointCloud<pcl::PointCurvatureTaubin>);
441 estimator.compute(*cloud_curvature);
443 printf(
" elapsed time: %.3f sec\n", omp_get_wtime() - beginTime);
452 printf(
"Filtering on curvature, fitting cylinders, and filtering on low clearance ...\n");
454 printf(
"Filtering on curvature and fitting cylinders ...\n");
456 double begin_time = omp_get_wtime();
457 int cylinders_left_radius = 0;
458 int cylinders_left_clearance = 0;
459 Eigen::Vector3d normal;
460 Eigen::Vector3d curvature_axis;
461 std::vector<CylindricalShell> shells;
464 double outer_sample_radius = 1.5 * (maxHandAperture + this->
handle_gap);
467 pcl::search::OrganizedNeighbor<pcl::PointXYZRGBA>::Ptr organized_neighbor(
468 new pcl::search::OrganizedNeighbor<pcl::PointXYZRGBA>());
470 pcl::KdTreeFLANN<pcl::PointXYZRGBA> tree;
471 if (cloud->isOrganized())
472 organized_neighbor->setInputCloud(cloud);
474 tree.setInputCloud(cloud);
476 for (
int i = 0; i < cloud_curvature->size(); i++)
479 double radius = 1.0 / fabs(cloud_curvature->points[i].median_curvature);
482 if (radius > min_radius_osculating_sphere && radius < max_radius_osculating_sphere)
485 normal << cloud_curvature->points[i].normal_x, cloud_curvature->points[i].normal_y, cloud_curvature->points[i].normal_z;
486 curvature_axis << cloud_curvature->points[i].curvature_axis_x, cloud_curvature->points[i].curvature_axis_y, cloud_curvature->points[i].curvature_axis_z;
497 if (shell.
getRadius() > min_radius_cylinder && shell.
getRadius() < max_radius_cylinder)
499 cylinders_left_radius++;
504 pcl::PointXYZRGBA searchPoint;
505 std::vector<int> nn_indices;
506 std::vector<float> nn_dists;
508 searchPoint.x = centroid(0);
509 searchPoint.y = centroid(1);
510 searchPoint.z = centroid(2);
511 int num_in_radius = 0;
512 if (cloud->isOrganized())
513 num_in_radius = organized_neighbor->radiusSearch(searchPoint, outer_sample_radius, nn_indices, nn_dists);
515 num_in_radius = tree.radiusSearch(searchPoint, outer_sample_radius, nn_indices, nn_dists);
517 if ((num_in_radius > 0) && (shell.
hasClearance(cloud, nn_indices, maxHandAperture, this->handle_gap)))
518 shells.push_back(shell);
521 shells.push_back(shell);
526 printf(
" elapsed time: %.3f sec\n", omp_get_wtime() - begin_time);
527 printf(
" cylinders left after radius filtering: %i\n", cylinders_left_radius);
529 printf(
" cylinders left after clearance filtering: %i\n", (
int)shells.size());
535 std::vector<CylindricalShell> shells)
537 std::vector < std::vector<CylindricalShell> > handles;
542 std::cout <<
"alignment search for colinear sets of cylinders (handles) ... " << std::endl;
543 double beginTime = omp_get_wtime();
544 std::vector<int> inliersMaxSet, outliersMaxSet;
547 for (
int i = 0; i < this->
alignment_runs && shells.size() > 0; i++)
550 printf(
" number of inliers in run %i: %i", i, (
int)inliersMaxSet.size());
555 std::vector<CylindricalShell> handle;
556 for (std::size_t j = 0; j < inliersMaxSet.size(); j++)
558 int idx = inliersMaxSet[j];
559 handle.push_back(shells[idx]);
565 int MAX_NUM_OCCLUDED = (int)handle.size() * 0.5;
566 int num_occluded = 0;
567 bool is_occluded =
false;
569 for (std::size_t j = 0; j < handle.size(); j++)
571 if (this->
numInFront(cloud, handle[j].getNeighborhoodCentroidIndex(),
575 if (num_occluded > MAX_NUM_OCCLUDED)
583 printf(
" number of occluded affordances: %i; occluded: %s\n", num_occluded, is_occluded ?
"true" :
"false");
586 handles.push_back(handle);
590 handles.push_back(handle);
594 std::vector<CylindricalShell> remainder(outliersMaxSet.size());
595 for (std::size_t j = 0; j < outliersMaxSet.size(); j++)
596 remainder[j] = shells[outliersMaxSet[j]];
598 printf(
", remaining cylinders: %i\n", (
int)shells.size());
607 printf(
" elapsed time: %.3f\n", omp_get_wtime() - beginTime);
614 const std::vector<int> &indices)
616 Eigen::MatrixXd samples(3, indices.size());
617 for (std::size_t i = 0; i < indices.size(); i++)
618 samples.col(i) = cloud->points[indices[i]].getVector3fMap().cast<
double>();
624 const Eigen::MatrixXd &samples,
bool is_logging)
627 printf(
"Estimating curvature ...\n");
629 double beginTime = omp_get_wtime();
632 pcl::PointCloud<pcl::PointCurvatureTaubin>::Ptr cloud_curvature(
new pcl::PointCloud<pcl::PointCurvatureTaubin>);
634 estimator.setInputCloud(cloud);
643 printf(
" elapsed time: %.3f sec, cylinders left: %i\n", omp_get_wtime() - beginTime,
644 (
int)cloud_curvature->points.size());
653 printf(
"Filtering on curvature, fitting cylinders, and filtering on low clearance ...\n");
655 printf(
"Filtering on curvature and fitting cylinders ...\n");
657 double begin_time = omp_get_wtime();
658 int cylinders_left_radius = 0;
659 int cylinders_left_clearance = 0;
660 Eigen::Vector3d normal;
661 Eigen::Vector3d curvature_axis;
662 std::vector<CylindricalShell> shells;
663 double tcyltotal = 0.0;
664 double tcleartotal = 0.0;
667 double outer_sample_radius = 1.5 * (maxHandAperture + this->
handle_gap);
670 pcl::search::OrganizedNeighbor<pcl::PointXYZRGBA>::Ptr organized_neighbor(
671 new pcl::search::OrganizedNeighbor<pcl::PointXYZRGBA>());
673 pcl::KdTreeFLANN<pcl::PointXYZRGBA> tree;
674 if (cloud->isOrganized())
675 organized_neighbor->setInputCloud(cloud);
677 tree.setInputCloud(cloud);
682 for (
int i = 0; i < cloud_curvature->size(); i++)
684 if (isnan(cloud_curvature->points[i].normal[0]))
688 double radius = 1.0 / fabs(cloud_curvature->points[i].median_curvature);
692 if (radius > min_radius_osculating_sphere && radius < max_radius_osculating_sphere)
695 double tcyl0 = omp_get_wtime();
696 normal << cloud_curvature->points[i].normal_x, cloud_curvature->points[i].normal_y, cloud_curvature->points[i].normal_z;
697 curvature_axis << cloud_curvature->points[i].curvature_axis_x, cloud_curvature->points[i].curvature_axis_y, cloud_curvature->points[i].curvature_axis_z;
700 tcyltotal += omp_get_wtime() - tcyl0;
711 if (shell.
getRadius() > min_radius_cylinder && shell.
getRadius() < max_radius_cylinder)
713 cylinders_left_radius++;
718 double tclear0 = omp_get_wtime();
719 pcl::PointXYZRGBA searchPoint;
720 std::vector<int> nn_indices;
721 std::vector<float> nn_dists;
723 searchPoint.x = centroid(0);
724 searchPoint.y = centroid(1);
725 searchPoint.z = centroid(2);
726 int num_in_radius = 0;
727 if (cloud->isOrganized())
728 num_in_radius = organized_neighbor->radiusSearch(searchPoint, outer_sample_radius, nn_indices, nn_dists);
730 num_in_radius = tree.radiusSearch(searchPoint, outer_sample_radius, nn_indices, nn_dists);
732 if ((num_in_radius > 0) && (shell.
hasClearance(cloud, nn_indices, maxHandAperture, this->handle_gap)))
733 shells.push_back(shell);
735 tcleartotal += omp_get_wtime() - tclear0;
738 shells.push_back(shell);
745 printf(
" elapsed time: %.3f sec\n", omp_get_wtime() - begin_time);
746 printf(
" cylinders left after radius filtering: %i\n", cylinders_left_radius);
748 printf(
" cylinders left after clearance filtering: %i\n", (
int)shells.size());
749 printf(
" cylinder/circle fitting: %.3f sec\n", tcyltotal);
750 printf(
" shell search: %.3f sec\n", tcleartotal);
758 std::vector<int> indices(size);
760 for (
int i = 0; i < size; i++)
762 int r = std::rand() % cloud->points.size();
763 while (!pcl::isFinite((*cloud)[r])
764 || !this->
isPointInWorkspace(cloud->points[r].x, cloud->points[r].y, cloud->points[r].z))
765 r = std::rand() % cloud->points.size();
773 std::vector<int> &outliersMaxSet)
779 for (std::size_t i = 0; i < list.size(); i++)
781 Eigen::Vector3d axis = list[i].getCurvatureAxis();
782 Eigen::Vector3d centroid = list[i].getCentroid();
783 double radius = list[i].getRadius();
784 std::vector<int> inliers, outliers;
786 for (std::size_t j = 0; j < list.size(); j++)
788 Eigen::Vector3d distToOrientVec = (Eigen::MatrixXd::Identity(3, 3) - axis * axis.transpose())
789 * list[j].getCurvatureAxis();
790 double distToOrient = distToOrientVec.cwiseProduct(distToOrientVec).sum();
791 Eigen::Vector3d distToAxisVec = (Eigen::MatrixXd::Identity(3, 3) - axis * axis.transpose())
792 * (list[j].getCentroid() - centroid);
793 double distToAxis = distToAxisVec.cwiseProduct(distToAxisVec).sum();
794 double distToRadius = fabs(list[j].getRadius() - radius);
797 inliers.push_back(j);
799 outliers.push_back(j);
802 if (inliers.size() > maxInliers)
804 maxInliers = inliers.size();
805 inliersMaxSet = inliers;
806 outliersMaxSet = outliers;
static const double ALIGNMENT_RADIUS_RADIUS
const std::string CURVATURE_ESTIMATORS[]
static const double RADIUS_ERROR
void initParams(ros::NodeHandle node)
Read the parameters from a ROS launch file.
static const double WORKSPACE_MIN
CylindricalShell represents a cylindrical shell that consists of two colinear cylinders. A shell consists of an inner and an outer cylinder. The portion of the object to be grasped must fit inside the inner cylinder, and the radius of that cylinder must be no larger than the maximum hand aperture. The gap between the inner and outer cylinder must be free of obstacles and wide enough to be able to contain the robot fingers.
int alignment_min_inliers
PointCloud::Ptr maxRangeFilter(const PointCloud::Ptr &cloud_in)
Filter out all points from a given cloud that are outside of a sphere with a radius max_range and cen...
std::vector< std::vector< int > > const & getNeighborhoods() const
Get the indices of each point neighborhood.
WorkspaceLimits workspace_limits
void estimateNormals(const PointCloud::Ptr &cloud, const pcl::PointCloud< pcl::Normal >::Ptr &cloud_normals)
Estimate surface normals for each point in the point cloud.
static const double ALIGNMENT_DIST_RADIUS
CurvatureEstimationTaubin estimates the curvature for a set of point neighborhoods in the cloud using...
bool use_occlusion_filter
TFSIMD_FORCE_INLINE const tfScalar & getY() const
static const int ALIGNMENT_RUNS
void setExtent(double extent)
Set the extent of the cylindrical shell.
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::vector< CylindricalShell > searchAffordancesNormalsOrPCA(const PointCloud::Ptr &cloud, tf::StampedTransform *transform=NULL)
Search grasp affordances (cylindrical shells) in a given point cloud using surface normals...
TFSIMD_FORCE_INLINE const tfScalar & getZ() const
std::vector< CylindricalShell > searchAffordances(const PointCloud::Ptr &cloud, tf::StampedTransform *transform=NULL)
Search grasp affordances (cylindrical shells) in a given point cloud.
static const double TARGET_RADIUS
int numInFront(const PointCloud::Ptr &cloud, int center_index, double radius)
Find the number of points in the point cloud that lie in front of a point neighborhood with a given c...
PointCloud::Ptr workspaceFilter(const PointCloud::Ptr &cloud_in, tf::StampedTransform *transform=NULL)
Filter out all points from a given cloud that are outside of a cube defined by the workspace limits o...
void computeFeature(const Eigen::MatrixXd &samples, PointCloudOut &output)
Estimate the curvature for a set of point neighborhoods with given centroids.
static const double NEIGHBOR_RADIUS
void setNumSamples(int num_samples)
Set the number of samples (point neighborhoods).
std::vector< int > createRandomIndices(const PointCloud::Ptr &cloud, int size)
static const bool USE_CLEARANCE_FILTER
void fitCylinder(const PointCloud::Ptr &cloud, const std::vector< int > &indices, const Eigen::Vector3d &normal, const Eigen::Vector3d &curvature_axis)
Fit a cylinder to a set of points in the cloud, using their indices, and the normal and the curvature...
INLINE Rall1d< T, V, S > atan(const Rall1d< T, V, S > &x)
bool use_clearance_filter
bool hasClearance(const PointCloud::Ptr &cloud, const std::vector< int > &nn_indices, double maxHandAperture, double handleGap)
Check whether the gap between the inner and outer cylinder of the shell is free of obstacles and wide...
void estimateCurvatureAxisNormals(const pcl::PointCloud< pcl::Normal >::Ptr &cloud_normals, const std::vector< int > &nn_indices, Eigen::Vector3d &axis, Eigen::Vector3d &normal)
Estimate the cylinder's curvature axis and normal using surface normals.
pcl::PointCloud< pcl::PointXYZRGBA > PointCloud
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void findBestColinearSet(const std::vector< CylindricalShell > &list, std::vector< int > &inliersMaxSet, std::vector< int > &outliersMaxSet)
Find the best (largest number of inliers) set of colinear cylindrical shells given a list of shells...
TFSIMD_FORCE_INLINE const tfScalar & x() const
void estimateCurvatureAxisPCA(const PointCloud::Ptr &cloud, int nn_center_idx, std::vector< int > nn_indices, Eigen::Vector3d &axis, Eigen::Vector3d &normal)
Estimate the cylinder's curvature axis and normal using PCA.
std::vector< std::vector< CylindricalShell > > searchHandles(const PointCloud::Ptr &cloud, std::vector< CylindricalShell > shells)
Search handles in a set of cylindrical shells. If occlusion filtering is turned on (using the corresp...
pcl::PointCloud< pcl::PointXYZRGBA > PointCloud
double alignment_orient_radius
static const int ALIGNMENT_MIN_INLIERS
TFSIMD_FORCE_INLINE const tfScalar & z() const
Eigen::Vector3d getCentroid() const
Get the centroid of the cylindrical shell.
std::vector< int > const & getNeighborhoodCentroids() const
Get the centroid indices of each point neighborhood.
static const int NUM_NEAREST_NEIGHBORS
std::vector< CylindricalShell > searchAffordancesTaubin(const PointCloud::Ptr &cloud, const Eigen::MatrixXd &samples, bool is_logging=true)
Search grasp affordances (cylindrical shells) using a set of samples in a given point cloud...
static const bool USE_OCCLUSION_FILTER
double alignment_dist_radius
TFSIMD_FORCE_INLINE const tfScalar & getX() const
static const double MAX_RANGE
double alignment_radius_radius
double getRadius() const
Get the radius of the cylindrical shell.
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
static const double WORKSPACE_MAX
static const double ALIGNMENT_ORIENT_RADIUS
static const double HANDLE_GAP
void setNumThreads(int num_threads)
Set the number of threads used for parallelizing Taubin Quadric Fitting.
void setNeighborhoodCentroidIndex(int index)
Set the index of the centroid of the neighborhood associated with the cylindrical shell...
static const int MAX_NUM_IN_FRONT
static const int CURVATURE_ESTIMATOR
static const int NUM_SAMPLES
bool isPointInWorkspace(double x, double y, double z, tf::StampedTransform *transform=NULL)
Check whether a given point, using its x, y, and z coordinates, is within the workspace of the robot...