sampling.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, Andreas ten Pas
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
19  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
20  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
21  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
22  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
23  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
24  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
27  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
28  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #ifndef SAMPLING_H_
33 #define SAMPLING_H_
34 
38 #include <pcl/point_cloud.h>
39 #include <pcl/point_types.h>
40 #include <pcl/visualization/pcl_visualizer.h>
41 
42 typedef pcl::PointCloud<pcl::PointXYZRGBA> PointCloud;
43 
47 class Sampling
48 {
49 public:
51  {
52  this->affordances = affordances;
53  }
54  ;
55 
61  void
62  initParams(const ros::NodeHandle& node);
63 
70  void
71  illustrate(const PointCloud::Ptr &cloud, double target_radius);
72 
79  std::vector<CylindricalShell>
80  searchAffordances(const PointCloud::Ptr &cloud, double target_radius);
81 
82 private:
89  int method;
90 
91  // standard parameters
92  static const int NUM_ITERATIONS;
93  static const int NUM_SAMPLES;
94  static const int NUM_INIT_SAMPLES;
95  static const double PROB_RAND_SAMPLES;
96  static const bool VISUALIZE_STEPS;
97  static const int METHOD;
98 };
99 
100 #endif /* SAMPLING_H_ */
int num_iterations
Definition: sampling.h:84
static const bool VISUALIZE_STEPS
Definition: sampling.h:96
static const int METHOD
Definition: sampling.h:97
pcl::PointCloud< pcl::PointXYZRGBA > PointCloud
Definition: sampling.h:42
Sampling localizes grasp affordances using importance sampling.
Definition: sampling.h:47
static const int NUM_INIT_SAMPLES
Definition: sampling.h:94
static const int NUM_SAMPLES
Definition: sampling.h:93
int num_init_samples
Definition: sampling.h:86
static const int NUM_ITERATIONS
Definition: sampling.h:92
Affordances affordances
Definition: sampling.h:83
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
Affordances localizes grasp affordances and handles in a point cloud. It also provides helper methods...
Definition: affordances.h:73
void setAffordances(Affordances &affordances)
Definition: sampling.h:50
int method
Definition: sampling.h:89
void illustrate(const PointCloud::Ptr &cloud, double target_radius)
Definition: sampling.cpp:14
void initParams(const ros::NodeHandle &node)
Definition: sampling.cpp:242
int num_samples
Definition: sampling.h:85
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