38 #include <pcl/features/feature.h> 39 #include <pcl/features/normal_3d.h> 40 #include <pcl/features/normal_3d_omp.h> 41 #include <pcl/kdtree/kdtree_flann.h> 42 #include <pcl/point_cloud.h> 43 #include <pcl/point_types.h> 88 maxRangeFilter(
const PointCloud::Ptr &cloud_in);
100 std::vector<CylindricalShell>
107 std::vector<CylindricalShell>
108 searchAffordances(
const PointCloud::Ptr &cloud,
const std::vector<int> &indices);
115 std::vector<CylindricalShell>
116 searchAffordancesTaubin(
const PointCloud::Ptr &cloud,
const Eigen::MatrixXd &samples,
117 bool is_logging =
true);
125 std::vector< std::vector<CylindricalShell> >
126 searchHandles(
const PointCloud::Ptr &cloud, std::vector<CylindricalShell> shells);
129 createRandomIndices(
const PointCloud::Ptr &cloud,
int size);
160 estimateNormals(
const PointCloud::Ptr &cloud,
161 const pcl::PointCloud<pcl::Normal>::Ptr &cloud_normals);
172 estimateCurvatureAxisPCA(
const PointCloud::Ptr &cloud,
int nn_center_idx,
173 std::vector<int> nn_indices, Eigen::Vector3d &axis,
174 Eigen::Vector3d &normal);
183 estimateCurvatureAxisNormals(
const pcl::PointCloud<pcl::Normal>::Ptr &cloud_normals,
184 const std::vector<int> &nn_indices,
185 Eigen::Vector3d &axis, Eigen::Vector3d &normal);
191 std::vector<CylindricalShell>
192 searchAffordancesNormalsOrPCA(
const PointCloud::Ptr &cloud,
199 std::vector<CylindricalShell>
209 void findBestColinearSet(
const std::vector<CylindricalShell> &list,
210 std::vector<int> &inliersMaxSet,
211 std::vector<int> &outliersMaxSet);
220 int numInFront(
const PointCloud::Ptr &cloud,
int center_index,
double radius);
static const double ALIGNMENT_RADIUS_RADIUS
int getNumSamples()
Return the number of samples, i.e., the number of neighborhoods to be searched for.
static const double RADIUS_ERROR
static const double WORKSPACE_MIN
int alignment_min_inliers
double getTargetRadius()
Return the target radius.
WorkspaceLimits workspace_limits
static const double ALIGNMENT_DIST_RADIUS
bool use_occlusion_filter
static const int ALIGNMENT_RUNS
TFSIMD_FORCE_INLINE const tfScalar & y() const
static const double TARGET_RADIUS
static const double NEIGHBOR_RADIUS
static const bool USE_CLEARANCE_FILTER
bool use_clearance_filter
std::string getPCDFile()
Return the *.pcd file given by the corresponding parameter in the ROS launch file.
pcl::PointCloud< pcl::PointXYZRGBA > PointCloud
TFSIMD_FORCE_INLINE const tfScalar & x() const
Affordances localizes grasp affordances and handles in a point cloud. It also provides helper methods...
double alignment_orient_radius
static const int ALIGNMENT_MIN_INLIERS
TFSIMD_FORCE_INLINE const tfScalar & z() const
static const int NUM_NEAREST_NEIGHBORS
static const bool USE_OCCLUSION_FILTER
double alignment_dist_radius
static const double MAX_RANGE
double alignment_radius_radius
static const double WORKSPACE_MAX
static const double ALIGNMENT_ORIENT_RADIUS
static const double HANDLE_GAP
static const int MAX_NUM_IN_FRONT
static const int CURVATURE_ESTIMATOR
static const int NUM_SAMPLES