19 double sigma = 2.0 * target_radius;
25 double term = 1.0 /
sqrt(
pow(2.0 * M_PI, 3.0) *
pow(sigma, 3.0));
28 boost::mt19937 *rng =
new boost::mt19937();
29 rng->seed(time(NULL));
30 boost::normal_distribution<> distribution(0.0, 1.0);
31 boost::variate_generator<boost::mt19937, boost::normal_distribution<> > generator(*rng, distribution);
34 Eigen::MatrixXd samples_sum(3, num_samples);
37 int idx = rand() % all_shells.size();
38 samples_sum(0, j) = all_shells[idx].getCentroid()(0) + generator() * sigma;
39 samples_sum(1, j) = all_shells[idx].getCentroid()(1) + generator() * sigma;
40 samples_sum(2, j) = all_shells[idx].getCentroid()(2) + generator() * sigma;
44 Eigen::MatrixXd samples_max(3, num_samples);
46 int count[all_shells.size()];
47 for (std::size_t k = 0; k < all_shells.size(); k++)
49 while (j < num_samples)
52 int idx = rand() % all_shells.size();
54 x(0) = all_shells[idx].getCentroid()(0) + generator() * sigma;
55 x(1) = all_shells[idx].getCentroid()(1) + generator() * sigma;
56 x(2) = all_shells[idx].getCentroid()(2) + generator() * sigma;
59 for (std::size_t k = 0; k < all_shells.size(); k++)
61 double p = (x - all_shells[k].getCentroid()).transpose() * (x - all_shells[k].getCentroid());
62 p = term *
exp((-1.0 / (2.0 * sigma)) * p);
67 double p = (x - all_shells[idx].getCentroid()).transpose() * (x - all_shells[idx].getCentroid());
68 p = term *
exp((-1.0 / (2.0 * sigma)) * p);
71 samples_max.col(j) = x;
78 sum_visualizer.
createViewer(cloud, all_shells, samples_sum, target_radius);
79 sum_visualizer.
getViewer()->setSize(800, 600);
80 sum_visualizer.
getViewer()->setCameraPosition(0.255106, -0.903705, -0.538521, 0.255053, -0.902864, -0.537242,
81 -0.0206334, -0.835517, 0.549076);
82 sum_visualizer.
getViewer()->addText(
"Samples drawn from sum of Gaussians", 10, 20, 16, 1.0, 1.0, 1.0);
83 while (!sum_visualizer.
getViewer()->wasStopped())
85 sum_visualizer.
getViewer()->spinOnce(100);
86 boost::this_thread::sleep(boost::posix_time::microseconds(100000));
90 max_visualizer.
createViewer(cloud, all_shells, samples_max, target_radius);
91 max_visualizer.
getViewer()->setSize(800, 600);
92 max_visualizer.
getViewer()->setCameraPosition(0.255106, -0.903705, -0.538521, 0.255053, -0.902864, -0.537242,
93 -0.0206334, -0.835517, 0.549076);
94 max_visualizer.
getViewer()->addText(
"Samples drawn from sum of Gaussians", 10, 20, 16, 1.0, 1.0, 1.0);
95 while (!max_visualizer.
getViewer()->wasStopped())
97 max_visualizer.
getViewer()->spinOnce(100);
98 boost::this_thread::sleep(boost::posix_time::microseconds(100000));
104 double start_time = omp_get_wtime();
105 double sigma = 2.0 * target_radius;
117 init_samples(0, i) = cloud->points[indices[i]].x;
118 init_samples(1, i) = cloud->points[indices[i]].y;
119 init_samples(2, i) = cloud->points[indices[i]].z;
121 std::vector<CylindricalShell> no_shells;
125 visualizer.
createViewer(cloud, no_shells, init_samples, target_radius);
126 visualizer.
getViewer()->setSize(800, 600);
127 visualizer.
getViewer()->setCameraPosition(0.255106, -0.903705, -0.538521, 0.255053, -0.902864, -0.537242,
128 -0.0206334, -0.835517, 0.549076);
130 while (!visualizer.
getViewer()->wasStopped())
133 boost::this_thread::sleep(boost::posix_time::microseconds(100000));
138 int num_gauss_samples = num_samples - num_rand_samples;
140 Eigen::Matrix3d diag_sigma = Eigen::Matrix3d::Zero();
141 diag_sigma.diagonal() << sigma, sigma, sigma;
142 Eigen::Matrix3d inv_sigma = diag_sigma.inverse();
143 double term = 1.0 /
sqrt(
pow(2.0 * M_PI, 3.0) *
pow(sigma, 3.0));
146 boost::mt19937 *rng =
new boost::mt19937();
147 rng->seed(time(NULL));
148 boost::normal_distribution<> distribution(0.0, 1.0);
149 boost::variate_generator<boost::mt19937, boost::normal_distribution<> > generator(*rng, distribution);
150 Eigen::MatrixXd samples(3, num_samples);
155 double iteration_start_time = omp_get_wtime();
160 for (std::size_t j = 0; j < num_gauss_samples; j++)
162 int idx = rand() % all_shells.size();
163 samples(0, j) = all_shells[idx].getCentroid()(0) + generator() * sigma;
164 samples(1, j) = all_shells[idx].getCentroid()(1) + generator() * sigma;
165 samples(2, j) = all_shells[idx].getCentroid()(2) + generator() * sigma;
171 while (j < num_gauss_samples)
174 int idx = rand() % all_shells.size();
176 x(0) = all_shells[idx].getCentroid()(0) + generator() * sigma;
177 x(1) = all_shells[idx].getCentroid()(1) + generator() * sigma;
178 x(2) = all_shells[idx].getCentroid()(2) + generator() * sigma;
181 for (std::size_t k = 0; k < all_shells.size(); k++)
183 double p = (x - all_shells[k].getCentroid()).transpose() * (x - all_shells[k].getCentroid());
184 p = term *
exp((-1.0 / (2.0 * sigma)) * p);
189 double p = (x - all_shells[idx].getCentroid()).transpose() * (x - all_shells[idx].getCentroid());
190 p = term *
exp((-1.0 / (2.0 * sigma)) * p);
200 for (
int j = num_samples - num_rand_samples; j <
num_samples; j++)
202 int r = std::rand() % cloud->points.size();
203 while (!pcl::isFinite((*cloud)[r])
205 r = std::rand() % cloud->points.size();
206 samples.col(j) = cloud->points[r].getVector3fMap().cast<
double>();
214 visualizer.
createViewer(cloud, all_shells, samples.block(0, 0, 3, num_gauss_samples), target_radius);
215 visualizer.
getViewer()->setSize(800, 600);
216 visualizer.
getViewer()->setCameraPosition(0.255106, -0.903705, -0.538521, 0.255053, -0.902864, -0.537242,
217 -0.0206334, -0.835517, 0.549076);
219 "Iteration " + boost::lexical_cast < std::string > (i) +
", shells: " + boost::lexical_cast < std::string
220 > (all_shells.size()) +
", num_gauss_samples: " + boost::lexical_cast < std::string
221 > (num_gauss_samples) +
", num_rand_samples: " + boost::lexical_cast < std::string > (num_rand_samples),
222 10, 20, 16, 1.0, 1.0, 1.0);
224 while (!visualizer.
getViewer()->wasStopped())
227 boost::this_thread::sleep(boost::posix_time::microseconds(100000));
233 all_shells.insert(all_shells.end(), shells.begin(), shells.end());
234 printf(
"ELAPSED TIME (ITERATION %i): %.3f\n", (
int)i, omp_get_wtime() - iteration_start_time);
237 printf(
"elapsed time (affordance search): %.3f sec, total # of affordances found: %i\n", omp_get_wtime() - start_time,
238 (
int)all_shells.size());
void createViewer(PointCloud::ConstPtr cloud, std::vector< CylindricalShell > shells, Eigen::MatrixXd samples, double target_radius)
static const bool VISUALIZE_STEPS
static const int NUM_INIT_SAMPLES
static const int NUM_SAMPLES
std::vector< CylindricalShell > searchAffordances(const PointCloud::Ptr &cloud, tf::StampedTransform *transform=NULL)
Search grasp affordances (cylindrical shells) in a given point cloud.
static const int NUM_ITERATIONS
std::vector< int > createRandomIndices(const PointCloud::Ptr &cloud, int size)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
static const double PROB_RAND_SAMPLES
TFSIMD_FORCE_INLINE const tfScalar & x() const
boost::shared_ptr< pcl::visualization::PCLVisualizer > getViewer()
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > exp(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
void illustrate(const PointCloud::Ptr &cloud, double target_radius)
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...
void initParams(const ros::NodeHandle &node)
SamplingVisualizer visualizes individual steps of importance sampling. This can be used to illustrate...
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...
std::vector< CylindricalShell > searchAffordances(const PointCloud::Ptr &cloud, double target_radius)