00001 #include "handle_detector/sampling.h"
00002
00003
00004 const int SUM = 1;
00005 const int MAX = 2;
00006
00007 const int Sampling::NUM_ITERATIONS = 10;
00008 const int Sampling::NUM_SAMPLES = 100;
00009 const int Sampling::NUM_INIT_SAMPLES = 100;
00010 const double Sampling::PROB_RAND_SAMPLES = 0.2;
00011 const bool Sampling::VISUALIZE_STEPS = false;
00012 const int Sampling::METHOD = SUM;
00013
00014 void Sampling::illustrate(const PointCloud::Ptr &cloud, double target_radius)
00015 {
00016
00017 int num_samples = 200;
00018 int num_init_samples = 1000;
00019 double sigma = 2.0 * target_radius;
00020
00021
00022 std::vector<int> indices = this->affordances.createRandomIndices(cloud, num_init_samples);
00023 std::vector<CylindricalShell> all_shells = this->affordances.searchAffordances(cloud, indices);
00024
00025 double term = 1.0 / sqrt(pow(2.0 * M_PI, 3.0) * pow(sigma, 3.0));
00026
00027
00028 boost::mt19937 *rng = new boost::mt19937();
00029 rng->seed(time(NULL));
00030 boost::normal_distribution<> distribution(0.0, 1.0);
00031 boost::variate_generator<boost::mt19937, boost::normal_distribution<> > generator(*rng, distribution);
00032
00033
00034 Eigen::MatrixXd samples_sum(3, num_samples);
00035 for (int j = 0; j < num_samples; j++)
00036 {
00037 int idx = rand() % all_shells.size();
00038 samples_sum(0, j) = all_shells[idx].getCentroid()(0) + generator() * sigma;
00039 samples_sum(1, j) = all_shells[idx].getCentroid()(1) + generator() * sigma;
00040 samples_sum(2, j) = all_shells[idx].getCentroid()(2) + generator() * sigma;
00041 }
00042
00043
00044 Eigen::MatrixXd samples_max(3, num_samples);
00045 int j = 0;
00046 int count[all_shells.size()];
00047 for (std::size_t k = 0; k < all_shells.size(); k++)
00048 count[k] = 0;
00049 while (j < num_samples)
00050 {
00051
00052 int idx = rand() % all_shells.size();
00053 Eigen::Vector3d x;
00054 x(0) = all_shells[idx].getCentroid()(0) + generator() * sigma;
00055 x(1) = all_shells[idx].getCentroid()(1) + generator() * sigma;
00056 x(2) = all_shells[idx].getCentroid()(2) + generator() * sigma;
00057
00058 double maxp = 0;
00059 for (std::size_t k = 0; k < all_shells.size(); k++)
00060 {
00061 double p = (x - all_shells[k].getCentroid()).transpose() * (x - all_shells[k].getCentroid());
00062 p = term * exp((-1.0 / (2.0 * sigma)) * p);
00063 if (p > maxp)
00064 maxp = p;
00065 }
00066
00067 double p = (x - all_shells[idx].getCentroid()).transpose() * (x - all_shells[idx].getCentroid());
00068 p = term * exp((-1.0 / (2.0 * sigma)) * p);
00069 if (p >= maxp)
00070 {
00071 samples_max.col(j) = x;
00072 count[idx]++;
00073 j++;
00074 }
00075 }
00076
00077 SamplingVisualizer sum_visualizer;
00078 sum_visualizer.createViewer(cloud, all_shells, samples_sum, target_radius);
00079 sum_visualizer.getViewer()->setSize(800, 600);
00080 sum_visualizer.getViewer()->setCameraPosition(0.255106, -0.903705, -0.538521, 0.255053, -0.902864, -0.537242,
00081 -0.0206334, -0.835517, 0.549076);
00082 sum_visualizer.getViewer()->addText("Samples drawn from sum of Gaussians", 10, 20, 16, 1.0, 1.0, 1.0);
00083 while (!sum_visualizer.getViewer()->wasStopped())
00084 {
00085 sum_visualizer.getViewer()->spinOnce(100);
00086 boost::this_thread::sleep(boost::posix_time::microseconds(100000));
00087 }
00088
00089 SamplingVisualizer max_visualizer;
00090 max_visualizer.createViewer(cloud, all_shells, samples_max, target_radius);
00091 max_visualizer.getViewer()->setSize(800, 600);
00092 max_visualizer.getViewer()->setCameraPosition(0.255106, -0.903705, -0.538521, 0.255053, -0.902864, -0.537242,
00093 -0.0206334, -0.835517, 0.549076);
00094 max_visualizer.getViewer()->addText("Samples drawn from sum of Gaussians", 10, 20, 16, 1.0, 1.0, 1.0);
00095 while (!max_visualizer.getViewer()->wasStopped())
00096 {
00097 max_visualizer.getViewer()->spinOnce(100);
00098 boost::this_thread::sleep(boost::posix_time::microseconds(100000));
00099 }
00100 }
00101
00102 std::vector<CylindricalShell> Sampling::searchAffordances(const PointCloud::Ptr &cloud, double target_radius)
00103 {
00104 double start_time = omp_get_wtime();
00105 double sigma = 2.0 * target_radius;
00106
00107
00108 std::vector<int> indices = this->affordances.createRandomIndices(cloud, num_init_samples);
00109 std::vector<CylindricalShell> all_shells = this->affordances.searchAffordances(cloud, indices);
00110
00111
00112 if (this->is_visualized)
00113 {
00114 Eigen::MatrixXd init_samples(3, num_init_samples);
00115 for (std::size_t i = 0; i < num_init_samples; i++)
00116 {
00117 init_samples(0, i) = cloud->points[indices[i]].x;
00118 init_samples(1, i) = cloud->points[indices[i]].y;
00119 init_samples(2, i) = cloud->points[indices[i]].z;
00120 }
00121 std::vector<CylindricalShell> no_shells;
00122 no_shells.resize(0);
00123
00124 SamplingVisualizer visualizer;
00125 visualizer.createViewer(cloud, no_shells, init_samples, target_radius);
00126 visualizer.getViewer()->setSize(800, 600);
00127 visualizer.getViewer()->setCameraPosition(0.255106, -0.903705, -0.538521, 0.255053, -0.902864, -0.537242,
00128 -0.0206334, -0.835517, 0.549076);
00129
00130 while (!visualizer.getViewer()->wasStopped())
00131 {
00132 visualizer.getViewer()->spinOnce(100);
00133 boost::this_thread::sleep(boost::posix_time::microseconds(100000));
00134 }
00135 }
00136
00137 int num_rand_samples = prob_rand_samples * num_samples;
00138 int num_gauss_samples = num_samples - num_rand_samples;
00139
00140 Eigen::Matrix3d diag_sigma = Eigen::Matrix3d::Zero();
00141 diag_sigma.diagonal() << sigma, sigma, sigma;
00142 Eigen::Matrix3d inv_sigma = diag_sigma.inverse();
00143 double term = 1.0 / sqrt(pow(2.0 * M_PI, 3.0) * pow(sigma, 3.0));
00144
00145
00146 boost::mt19937 *rng = new boost::mt19937();
00147 rng->seed(time(NULL));
00148 boost::normal_distribution<> distribution(0.0, 1.0);
00149 boost::variate_generator<boost::mt19937, boost::normal_distribution<> > generator(*rng, distribution);
00150 Eigen::MatrixXd samples(3, num_samples);
00151
00152
00153 for (std::size_t i = 0; i < num_iterations; i++)
00154 {
00155 double iteration_start_time = omp_get_wtime();
00156
00157
00158 if (this->method == SUM)
00159 {
00160 for (std::size_t j = 0; j < num_gauss_samples; j++)
00161 {
00162 int idx = rand() % all_shells.size();
00163 samples(0, j) = all_shells[idx].getCentroid()(0) + generator() * sigma;
00164 samples(1, j) = all_shells[idx].getCentroid()(1) + generator() * sigma;
00165 samples(2, j) = all_shells[idx].getCentroid()(2) + generator() * sigma;
00166 }
00167 }
00168 else
00169 {
00170 int j = 0;
00171 while (j < num_gauss_samples)
00172 {
00173
00174 int idx = rand() % all_shells.size();
00175 Eigen::Vector3d x;
00176 x(0) = all_shells[idx].getCentroid()(0) + generator() * sigma;
00177 x(1) = all_shells[idx].getCentroid()(1) + generator() * sigma;
00178 x(2) = all_shells[idx].getCentroid()(2) + generator() * sigma;
00179
00180 double maxp = 0;
00181 for (std::size_t k = 0; k < all_shells.size(); k++)
00182 {
00183 double p = (x - all_shells[k].getCentroid()).transpose() * (x - all_shells[k].getCentroid());
00184 p = term * exp((-1.0 / (2.0 * sigma)) * p);
00185 if (p > maxp)
00186 maxp = p;
00187 }
00188
00189 double p = (x - all_shells[idx].getCentroid()).transpose() * (x - all_shells[idx].getCentroid());
00190 p = term * exp((-1.0 / (2.0 * sigma)) * p);
00191 if (p >= maxp)
00192 {
00193 samples.col(j) = x;
00194 j++;
00195 }
00196 }
00197 }
00198
00199
00200 for (int j = num_samples - num_rand_samples; j < num_samples; j++)
00201 {
00202 int r = std::rand() % cloud->points.size();
00203 while (!pcl::isFinite((*cloud)[r])
00204 || !this->affordances.isPointInWorkspace(cloud->points[r].x, cloud->points[r].y, cloud->points[r].z))
00205 r = std::rand() % cloud->points.size();
00206 samples.col(j) = cloud->points[r].getVector3fMap().cast<double>();
00207 }
00208
00209
00210 if (is_visualized)
00211 {
00212 SamplingVisualizer visualizer;
00213
00214 visualizer.createViewer(cloud, all_shells, samples.block(0, 0, 3, num_gauss_samples), target_radius);
00215 visualizer.getViewer()->setSize(800, 600);
00216 visualizer.getViewer()->setCameraPosition(0.255106, -0.903705, -0.538521, 0.255053, -0.902864, -0.537242,
00217 -0.0206334, -0.835517, 0.549076);
00218 visualizer.getViewer()->addText(
00219 "Iteration " + boost::lexical_cast < std::string > (i) + ", shells: " + boost::lexical_cast < std::string
00220 > (all_shells.size()) + ", num_gauss_samples: " + boost::lexical_cast < std::string
00221 > (num_gauss_samples) + ", num_rand_samples: " + boost::lexical_cast < std::string > (num_rand_samples),
00222 10, 20, 16, 1.0, 1.0, 1.0);
00223
00224 while (!visualizer.getViewer()->wasStopped())
00225 {
00226 visualizer.getViewer()->spinOnce(100);
00227 boost::this_thread::sleep(boost::posix_time::microseconds(100000));
00228 }
00229 }
00230
00231
00232 std::vector<CylindricalShell> shells = this->affordances.searchAffordancesTaubin(cloud, samples);
00233 all_shells.insert(all_shells.end(), shells.begin(), shells.end());
00234 printf("ELAPSED TIME (ITERATION %i): %.3f\n", (int)i, omp_get_wtime() - iteration_start_time);
00235 }
00236
00237 printf("elapsed time (affordance search): %.3f sec, total # of affordances found: %i\n", omp_get_wtime() - start_time,
00238 (int)all_shells.size());
00239 return all_shells;
00240 }
00241
00242 void Sampling::initParams(const ros::NodeHandle& node)
00243 {
00244 node.param("num_iterations", this->num_iterations, this->NUM_ITERATIONS);
00245 node.param("num_samples", this->num_samples, this->NUM_SAMPLES);
00246 node.param("num_init_samples", this->num_init_samples, this->NUM_INIT_SAMPLES);
00247 node.param("prob_rand_samples", this->prob_rand_samples, this->PROB_RAND_SAMPLES);
00248 node.param("visualize_steps", this->is_visualized, this->VISUALIZE_STEPS);
00249 node.param("sampling_method", this->method, this->METHOD);
00250 }