sampling.cpp
Go to the documentation of this file.
2 
3 // sampling methods
4 const int SUM = 1;
5 const int MAX = 2;
6 
7 const int Sampling::NUM_ITERATIONS = 10;
8 const int Sampling::NUM_SAMPLES = 100;
9 const int Sampling::NUM_INIT_SAMPLES = 100;
10 const double Sampling::PROB_RAND_SAMPLES = 0.2;
11 const bool Sampling::VISUALIZE_STEPS = false;
12 const int Sampling::METHOD = SUM;
13 
14 void Sampling::illustrate(const PointCloud::Ptr &cloud, double target_radius)
15 {
16  // parameters
17  int num_samples = 200;
18  int num_init_samples = 1000;
19  double sigma = 2.0 * target_radius;
20 
21  // find initial affordances
22  std::vector<int> indices = this->affordances.createRandomIndices(cloud, num_init_samples);
23  std::vector<CylindricalShell> all_shells = this->affordances.searchAffordances(cloud, indices);
24 
25  double term = 1.0 / sqrt(pow(2.0 * M_PI, 3.0) * pow(sigma, 3.0));
26 
27  // create random generator for normal distribution
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);
32 
33  // sum of Gaussians
34  Eigen::MatrixXd samples_sum(3, num_samples);
35  for (int j = 0; j < num_samples; j++)
36  {
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;
41  }
42 
43  // max of Gaussians
44  Eigen::MatrixXd samples_max(3, num_samples);
45  int j = 0;
46  int count[all_shells.size()];
47  for (std::size_t k = 0; k < all_shells.size(); k++)
48  count[k] = 0;
49  while (j < num_samples) // draw samples using rejection sampling
50  {
51  // draw from sum of Gaussians
52  int idx = rand() % all_shells.size();
53  Eigen::Vector3d x;
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;
57 
58  double maxp = 0;
59  for (std::size_t k = 0; k < all_shells.size(); k++)
60  {
61  double p = (x - all_shells[k].getCentroid()).transpose() * (x - all_shells[k].getCentroid());
62  p = term * exp((-1.0 / (2.0 * sigma)) * p);
63  if (p > maxp)
64  maxp = p;
65  }
66 
67  double p = (x - all_shells[idx].getCentroid()).transpose() * (x - all_shells[idx].getCentroid());
68  p = term * exp((-1.0 / (2.0 * sigma)) * p);
69  if (p >= maxp)
70  {
71  samples_max.col(j) = x;
72  count[idx]++;
73  j++;
74  }
75  }
76 
77  SamplingVisualizer sum_visualizer;
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())
84  {
85  sum_visualizer.getViewer()->spinOnce(100);
86  boost::this_thread::sleep(boost::posix_time::microseconds(100000));
87  }
88 
89  SamplingVisualizer max_visualizer;
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())
96  {
97  max_visualizer.getViewer()->spinOnce(100);
98  boost::this_thread::sleep(boost::posix_time::microseconds(100000));
99  }
100 }
101 
102 std::vector<CylindricalShell> Sampling::searchAffordances(const PointCloud::Ptr &cloud, double target_radius)
103 {
104  double start_time = omp_get_wtime();
105  double sigma = 2.0 * target_radius;
106 
107  // find initial affordances
108  std::vector<int> indices = this->affordances.createRandomIndices(cloud, num_init_samples);
109  std::vector<CylindricalShell> all_shells = this->affordances.searchAffordances(cloud, indices);
110 
111  // visualize
112  if (this->is_visualized)
113  {
114  Eigen::MatrixXd init_samples(3, num_init_samples);
115  for (std::size_t i = 0; i < num_init_samples; i++)
116  {
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;
120  }
121  std::vector<CylindricalShell> no_shells;
122  no_shells.resize(0);
123 
124  SamplingVisualizer visualizer;
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);
129 
130  while (!visualizer.getViewer()->wasStopped())
131  {
132  visualizer.getViewer()->spinOnce(100);
133  boost::this_thread::sleep(boost::posix_time::microseconds(100000));
134  }
135  }
136 
137  int num_rand_samples = prob_rand_samples * num_samples;
138  int num_gauss_samples = num_samples - num_rand_samples;
139 
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));
144 
145  // create random generator for normal distribution
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);
151 
152  // find affordances using importance sampling
153  for (std::size_t i = 0; i < num_iterations; i++)
154  {
155  double iteration_start_time = omp_get_wtime();
156 
157  // draw samples close to affordances (importance sampling)
158  if (this->method == SUM) // sum of Gaussians
159  {
160  for (std::size_t j = 0; j < num_gauss_samples; j++)
161  {
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;
166  }
167  }
168  else // max of Gaussians
169  {
170  int j = 0;
171  while (j < num_gauss_samples) // draw samples using rejection sampling
172  {
173  // draw from sum of Gaussians
174  int idx = rand() % all_shells.size();
175  Eigen::Vector3d x;
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;
179 
180  double maxp = 0;
181  for (std::size_t k = 0; k < all_shells.size(); k++)
182  {
183  double p = (x - all_shells[k].getCentroid()).transpose() * (x - all_shells[k].getCentroid());
184  p = term * exp((-1.0 / (2.0 * sigma)) * p);
185  if (p > maxp)
186  maxp = p;
187  }
188 
189  double p = (x - all_shells[idx].getCentroid()).transpose() * (x - all_shells[idx].getCentroid());
190  p = term * exp((-1.0 / (2.0 * sigma)) * p);
191  if (p >= maxp)
192  {
193  samples.col(j) = x;
194  j++;
195  }
196  }
197  }
198 
199  // draw random samples
200  for (int j = num_samples - num_rand_samples; j < num_samples; j++)
201  {
202  int r = std::rand() % cloud->points.size();
203  while (!pcl::isFinite((*cloud)[r])
204  || !this->affordances.isPointInWorkspace(cloud->points[r].x, cloud->points[r].y, cloud->points[r].z))
205  r = std::rand() % cloud->points.size();
206  samples.col(j) = cloud->points[r].getVector3fMap().cast<double>();
207  }
208 
209  // visualize
210  if (is_visualized)
211  {
212  SamplingVisualizer visualizer;
213 // visualizer.createViewer(cloud, all_shells, samples, target_radius);
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);
218  visualizer.getViewer()->addText(
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);
223 
224  while (!visualizer.getViewer()->wasStopped())
225  {
226  visualizer.getViewer()->spinOnce(100);
227  boost::this_thread::sleep(boost::posix_time::microseconds(100000));
228  }
229  }
230 
231  // find affordances
232  std::vector<CylindricalShell> shells = this->affordances.searchAffordancesTaubin(cloud, samples);
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);
235  }
236 
237  printf("elapsed time (affordance search): %.3f sec, total # of affordances found: %i\n", omp_get_wtime() - start_time,
238  (int)all_shells.size());
239  return all_shells;
240 }
241 
243 {
244  node.param("num_iterations", this->num_iterations, this->NUM_ITERATIONS);
245  node.param("num_samples", this->num_samples, this->NUM_SAMPLES);
246  node.param("num_init_samples", this->num_init_samples, this->NUM_INIT_SAMPLES);
247  node.param("prob_rand_samples", this->prob_rand_samples, this->PROB_RAND_SAMPLES);
248  node.param("visualize_steps", this->is_visualized, this->VISUALIZE_STEPS);
249  node.param("sampling_method", this->method, this->METHOD);
250 }
int num_iterations
Definition: sampling.h:84
void createViewer(PointCloud::ConstPtr cloud, std::vector< CylindricalShell > shells, Eigen::MatrixXd samples, double target_radius)
static const bool VISUALIZE_STEPS
Definition: sampling.h:96
static const int METHOD
Definition: sampling.h:97
static const int NUM_INIT_SAMPLES
Definition: sampling.h:94
static const int NUM_SAMPLES
Definition: sampling.h:93
const int SUM
Definition: sampling.cpp:4
int num_init_samples
Definition: sampling.h:86
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
Definition: sampling.h:92
Affordances affordances
Definition: sampling.h:83
std::vector< int > createRandomIndices(const PointCloud::Ptr &cloud, int size)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool is_visualized
Definition: sampling.h:88
double prob_rand_samples
Definition: sampling.h:87
static const double PROB_RAND_SAMPLES
Definition: sampling.h:95
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)
int method
Definition: sampling.h:89
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)
Definition: sampling.cpp:14
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)
Definition: sampling.cpp:242
SamplingVisualizer visualizes individual steps of importance sampling. This can be used to illustrate...
const int MAX
Definition: sampling.cpp:5
int num_samples
Definition: sampling.h:85
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...
Definition: affordances.cpp:95
std::vector< CylindricalShell > searchAffordances(const PointCloud::Ptr &cloud, double target_radius)
Definition: sampling.cpp:102


handle_detector
Author(s):
autogenerated on Mon Jun 10 2019 13:29:00