Public Member Functions | Private Attributes | Static Private Attributes
Sampling Class Reference

Sampling localizes grasp affordances using importance sampling. More...

#include <sampling.h>

List of all members.

Public Member Functions

void illustrate (const PointCloud::Ptr &cloud, const PointCloudRGB::Ptr &cloudrgb, double target_radius)
void initParams (const ros::NodeHandle &node)
std::vector< CylindricalShellsearchAffordances (const PointCloud::Ptr &cloud, const PointCloudRGB::Ptr &cloudrgb, double target_radius)
void setAffordances (Affordances &affordances)

Private Attributes

Affordances affordances
bool is_visualized
int method
int num_init_samples
int num_iterations
int num_samples
double prob_rand_samples

Static Private Attributes

static const int METHOD = SUM
static const int NUM_INIT_SAMPLES = 100
static const int NUM_ITERATIONS = 10
static const int NUM_SAMPLES = 100
static const double PROB_RAND_SAMPLES = 0.2
static const bool VISUALIZE_STEPS = false

Detailed Description

Sampling localizes grasp affordances using importance sampling.

Author:
Andreas ten Pas

Definition at line 48 of file sampling.h.


Member Function Documentation

void Sampling::illustrate ( const PointCloud::Ptr &  cloud,
const PointCloudRGB::Ptr &  cloudrgb,
double  target_radius 
)

Illustrates the different sampling methods.

Parameters:
cloudthe point cloud
cloudrgbthe colored point cloud
target_radiusthe target radius

Definition at line 14 of file sampling.cpp.

void Sampling::initParams ( const ros::NodeHandle node)

Initializes the importance sampling parameters based on the parameters given by a ROS node.

Parameters:
nodethe ROS node

Definition at line 243 of file sampling.cpp.

std::vector< CylindricalShell > Sampling::searchAffordances ( const PointCloud::Ptr &  cloud,
const PointCloudRGB::Ptr &  cloudrgb,
double  target_radius 
)

Search affordances using importance sampling.

Parameters:
cloudthe point cloud
cloudrgbthe colored point cloud
target_radiusthe target radius

Definition at line 102 of file sampling.cpp.

void Sampling::setAffordances ( Affordances affordances) [inline]

Definition at line 51 of file sampling.h.


Member Data Documentation

Definition at line 84 of file sampling.h.

bool Sampling::is_visualized [private]

Definition at line 89 of file sampling.h.

int Sampling::method [private]

Definition at line 90 of file sampling.h.

const int Sampling::METHOD = SUM [static, private]

Definition at line 98 of file sampling.h.

Definition at line 87 of file sampling.h.

const int Sampling::NUM_INIT_SAMPLES = 100 [static, private]

Definition at line 95 of file sampling.h.

int Sampling::num_iterations [private]

Definition at line 85 of file sampling.h.

const int Sampling::NUM_ITERATIONS = 10 [static, private]

Definition at line 93 of file sampling.h.

int Sampling::num_samples [private]

Definition at line 86 of file sampling.h.

const int Sampling::NUM_SAMPLES = 100 [static, private]

Definition at line 94 of file sampling.h.

double Sampling::prob_rand_samples [private]

Definition at line 88 of file sampling.h.

const double Sampling::PROB_RAND_SAMPLES = 0.2 [static, private]

Definition at line 96 of file sampling.h.

const bool Sampling::VISUALIZE_STEPS = false [static, private]

Definition at line 97 of file sampling.h.


The documentation for this class was generated from the following files:


handle_detector
Author(s):
autogenerated on Fri Aug 28 2015 10:59:15