affordances.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 AFFORDANCES_H
33 #define AFFORDANCES_H
34 
35 #include <fstream>
36 #include <iostream>
37 #include <omp.h>
38 #include <pcl/features/feature.h>
39 #include <pcl/features/normal_3d.h>
40 #include <pcl/features/normal_3d_omp.h>
41 #include <pcl/kdtree/kdtree_flann.h>
42 #include <pcl/point_cloud.h>
43 #include <pcl/point_types.h>
44 #include <ros/ros.h>
45 #include <stdlib.h>
46 #include <string>
47 #include <tf/transform_datatypes.h>
50 #include "cylindrical_shell.h"
51 
52 
53 typedef pcl::PointCloud<pcl::PointXYZRGBA> PointCloud;
54 
55 
56 // workspace limits of the robot
58 {
59  double min_x;
60  double max_x;
61  double min_y;
62  double max_y;
63  double min_z;
64  double max_z;
65 };
66 
67 
74 {
75  public:
76 
80  void
81  initParams(ros::NodeHandle node);
82 
87  PointCloud::Ptr
88  maxRangeFilter(const PointCloud::Ptr &cloud_in);
89 
94  PointCloud::Ptr
95  workspaceFilter(const PointCloud::Ptr &cloud_in, tf::StampedTransform *transform = NULL);
96 
100  std::vector<CylindricalShell>
101  searchAffordances(const PointCloud::Ptr &cloud, tf::StampedTransform *transform = NULL);
102 
107  std::vector<CylindricalShell>
108  searchAffordances(const PointCloud::Ptr &cloud, const std::vector<int> &indices);
109 
115  std::vector<CylindricalShell>
116  searchAffordancesTaubin(const PointCloud::Ptr &cloud, const Eigen::MatrixXd &samples,
117  bool is_logging = true);
118 
125  std::vector< std::vector<CylindricalShell> >
126  searchHandles(const PointCloud::Ptr &cloud, std::vector<CylindricalShell> shells);
127 
128  std::vector<int>
129  createRandomIndices(const PointCloud::Ptr &cloud, int size);
130 
137  bool
138  isPointInWorkspace(double x, double y, double z, tf::StampedTransform *transform = NULL);
139 
142  std::string getPCDFile() { return this->file; }
143 
146  int getNumSamples() { return this->num_samples; }
147 
150  double getTargetRadius() { return this->target_radius; }
151 
152 
153  private:
154 
159  void
160  estimateNormals(const PointCloud::Ptr &cloud,
161  const pcl::PointCloud<pcl::Normal>::Ptr &cloud_normals);
162 
171  void
172  estimateCurvatureAxisPCA(const PointCloud::Ptr &cloud, int nn_center_idx,
173  std::vector<int> nn_indices, Eigen::Vector3d &axis,
174  Eigen::Vector3d &normal);
175 
182  void
183  estimateCurvatureAxisNormals(const pcl::PointCloud<pcl::Normal>::Ptr &cloud_normals,
184  const std::vector<int> &nn_indices,
185  Eigen::Vector3d &axis, Eigen::Vector3d &normal);
186 
191  std::vector<CylindricalShell>
192  searchAffordancesNormalsOrPCA(const PointCloud::Ptr &cloud,
193  tf::StampedTransform *transform = NULL);
194 
199  std::vector<CylindricalShell>
200  searchAffordancesTaubin(const PointCloud::Ptr &cloud, tf::StampedTransform *transform = NULL);
201 
209  void findBestColinearSet(const std::vector<CylindricalShell> &list,
210  std::vector<int> &inliersMaxSet,
211  std::vector<int> &outliersMaxSet);
212 
220  int numInFront(const PointCloud::Ptr &cloud, int center_index, double radius);
221 
222  // parameters (read-in from ROS launch file)
224  double radius_error;
225  double handle_gap;
227  double max_range;
238  std::string file;
239 
240  // standard parameters
241  static const int CURVATURE_ESTIMATOR; // curvature axis estimation method
242  static const int NUM_SAMPLES; // number of neighborhoods
243  static const int NUM_NEAREST_NEIGHBORS; // number of nearest neighbors to be found
244  static const double NEIGHBOR_RADIUS;
245  static const int MAX_NUM_IN_FRONT; // max. threshold of allowed points in front of a neighborhood center point (occlusion filtering)
246  static const double TARGET_RADIUS; // approx. radius of the target handle
247  static const double RADIUS_ERROR; // allowed deviation from target radius
248  static const double HANDLE_GAP; // min. gap around affordances
249  static const double MAX_RANGE; // max. range of robot arms
250  static const bool USE_CLEARANCE_FILTER; // whether the clearance filter is used
251  static const bool USE_OCCLUSION_FILTER; // whether the occlusion filter is used
252  static const int ALIGNMENT_RUNS; // number of RANSAC runs
253  static const int ALIGNMENT_MIN_INLIERS; // min. number of inliers for colinear cylinder set
254  static const double ALIGNMENT_DIST_RADIUS; // distance threshold
255  static const double ALIGNMENT_ORIENT_RADIUS; // orientation threshold
256  static const double ALIGNMENT_RADIUS_RADIUS; // radius threshold
257  static const double WORKSPACE_MIN;
258  static const double WORKSPACE_MAX;
259 };
260 
261 #endif
static const double ALIGNMENT_RADIUS_RADIUS
Definition: affordances.h:256
int getNumSamples()
Return the number of samples, i.e., the number of neighborhoods to be searched for.
Definition: affordances.h:146
static const double RADIUS_ERROR
Definition: affordances.h:247
double handle_gap
Definition: affordances.h:225
static const double WORKSPACE_MIN
Definition: affordances.h:257
double target_radius
Definition: affordances.h:223
int alignment_min_inliers
Definition: affordances.h:232
double radius_error
Definition: affordances.h:224
double getTargetRadius()
Return the target radius.
Definition: affordances.h:150
WorkspaceLimits workspace_limits
Definition: affordances.h:236
static const double ALIGNMENT_DIST_RADIUS
Definition: affordances.h:254
bool use_occlusion_filter
Definition: affordances.h:229
static const int ALIGNMENT_RUNS
Definition: affordances.h:252
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::string file
Definition: affordances.h:238
static const double TARGET_RADIUS
Definition: affordances.h:246
static const double NEIGHBOR_RADIUS
Definition: affordances.h:244
int curvature_estimator
Definition: affordances.h:230
static const bool USE_CLEARANCE_FILTER
Definition: affordances.h:250
bool use_clearance_filter
Definition: affordances.h:228
std::string getPCDFile()
Return the *.pcd file given by the corresponding parameter in the ROS launch file.
Definition: affordances.h:142
pcl::PointCloud< pcl::PointXYZRGBA > PointCloud
Definition: affordances.h:53
TFSIMD_FORCE_INLINE const tfScalar & x() const
Affordances localizes grasp affordances and handles in a point cloud. It also provides helper methods...
Definition: affordances.h:73
double alignment_orient_radius
Definition: affordances.h:234
static const int ALIGNMENT_MIN_INLIERS
Definition: affordances.h:253
TFSIMD_FORCE_INLINE const tfScalar & z() const
static const int NUM_NEAREST_NEIGHBORS
Definition: affordances.h:243
static const bool USE_OCCLUSION_FILTER
Definition: affordances.h:251
double alignment_dist_radius
Definition: affordances.h:233
static const double MAX_RANGE
Definition: affordances.h:249
double alignment_radius_radius
Definition: affordances.h:235
static const double WORKSPACE_MAX
Definition: affordances.h:258
static const double ALIGNMENT_ORIENT_RADIUS
Definition: affordances.h:255
static const double HANDLE_GAP
Definition: affordances.h:248
static const int MAX_NUM_IN_FRONT
Definition: affordances.h:245
static const int CURVATURE_ESTIMATOR
Definition: affordances.h:241
int alignment_runs
Definition: affordances.h:231
static const int NUM_SAMPLES
Definition: affordances.h:242
double max_range
Definition: affordances.h:227


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