32 #ifndef CYLINDRICAL_SHELL_H 33 #define CYLINDRICAL_SHELL_H 35 #include "Eigen/Dense" 36 #include <pcl/kdtree/kdtree_flann.h> 37 #include <pcl/point_cloud.h> 38 #include <pcl/search/organized.h> 62 fitCylinder(
const PointCloud::Ptr &cloud,
const std::vector<int> &indices,
const Eigen::Vector3d &
normal,
72 hasClearance(
const PointCloud::Ptr &cloud,
const std::vector<int>& nn_indices,
double maxHandAperture,
double getExtent() const
Get the extent of the cylindrical shell.
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 neighborhood_centroid_index
void setExtent(double extent)
Set the extent of the cylindrical shell.
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...
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...
Eigen::Vector3d getNormal() const
Get the normal axis of the cylindrical shell.
Eigen::Vector3d getCurvatureAxis() const
Get the curvature axis of the cylindrical shell.
pcl::PointCloud< pcl::PointXYZRGBA > PointCloud
Eigen::Vector3d getCentroid() const
Get the centroid of the cylindrical shell.
double getRadius() const
Get the radius of the cylindrical shell.
Eigen::Vector3d curvature_axis
void setNeighborhoodCentroidIndex(int index)
Set the index of the centroid of the neighborhood associated with the cylindrical shell...
int getNeighborhoodCentroidIndex() const
Get the index of the centroid of the neighborhood associated with the cylindrical shell...