38 #include <pcl/point_cloud.h> 39 #include <pcl/point_types.h> 40 #include <pcl/visualization/pcl_visualizer.h> 71 illustrate(
const PointCloud::Ptr &cloud,
double target_radius);
79 std::vector<CylindricalShell>
static const bool VISUALIZE_STEPS
pcl::PointCloud< pcl::PointXYZRGBA > PointCloud
Sampling localizes grasp affordances using importance sampling.
static const int NUM_INIT_SAMPLES
static const int NUM_SAMPLES
static const int NUM_ITERATIONS
static const double PROB_RAND_SAMPLES
Affordances localizes grasp affordances and handles in a point cloud. It also provides helper methods...
void setAffordances(Affordances &affordances)
void illustrate(const PointCloud::Ptr &cloud, double target_radius)
void initParams(const ros::NodeHandle &node)
std::vector< CylindricalShell > searchAffordances(const PointCloud::Ptr &cloud, double target_radius)