Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef AFFORDANCES_H
00033 #define AFFORDANCES_H
00034
00035 #include <fstream>
00036 #include <iostream>
00037 #include <omp.h>
00038 #include <pcl/features/feature.h>
00039 #include <pcl/features/normal_3d.h>
00040 #include <pcl/features/normal_3d_omp.h>
00041 #include <pcl/kdtree/kdtree_flann.h>
00042 #include <pcl/point_cloud.h>
00043 #include <pcl/point_types.h>
00044 #include <ros/ros.h>
00045 #include <stdlib.h>
00046 #include <string>
00047 #include <tf/transform_datatypes.h>
00048 #include "curvature_estimation_taubin.h"
00049 #include "curvature_estimation_taubin.hpp"
00050 #include "cylindrical_shell.h"
00051
00052
00053 typedef pcl::PointCloud<pcl::PointXYZRGBA> PointCloud;
00054
00055
00056
00057 struct WorkspaceLimits
00058 {
00059 double min_x;
00060 double max_x;
00061 double min_y;
00062 double max_y;
00063 double min_z;
00064 double max_z;
00065 };
00066
00067
00073 class Affordances
00074 {
00075 public:
00076
00080 void
00081 initParams(ros::NodeHandle node);
00082
00087 PointCloud::Ptr
00088 maxRangeFilter(const PointCloud::Ptr &cloud_in);
00089
00094 PointCloud::Ptr
00095 workspaceFilter(const PointCloud::Ptr &cloud_in, tf::StampedTransform *transform = NULL);
00096
00100 std::vector<CylindricalShell>
00101 searchAffordances(const PointCloud::Ptr &cloud, tf::StampedTransform *transform = NULL);
00102
00107 std::vector<CylindricalShell>
00108 searchAffordances(const PointCloud::Ptr &cloud, const std::vector<int> &indices);
00109
00115 std::vector<CylindricalShell>
00116 searchAffordancesTaubin(const PointCloud::Ptr &cloud, const Eigen::MatrixXd &samples,
00117 bool is_logging = true);
00118
00125 std::vector< std::vector<CylindricalShell> >
00126 searchHandles(const PointCloud::Ptr &cloud, std::vector<CylindricalShell> shells);
00127
00128 std::vector<int>
00129 createRandomIndices(const PointCloud::Ptr &cloud, int size);
00130
00137 bool
00138 isPointInWorkspace(double x, double y, double z, tf::StampedTransform *transform = NULL);
00139
00142 std::string getPCDFile() { return this->file; }
00143
00146 int getNumSamples() { return this->num_samples; }
00147
00150 double getTargetRadius() { return this->target_radius; }
00151
00152
00153 private:
00154
00159 void
00160 estimateNormals(const PointCloud::Ptr &cloud,
00161 const pcl::PointCloud<pcl::Normal>::Ptr &cloud_normals);
00162
00171 void
00172 estimateCurvatureAxisPCA(const PointCloud::Ptr &cloud, int nn_center_idx,
00173 std::vector<int> nn_indices, Eigen::Vector3d &axis,
00174 Eigen::Vector3d &normal);
00175
00182 void
00183 estimateCurvatureAxisNormals(const pcl::PointCloud<pcl::Normal>::Ptr &cloud_normals,
00184 const std::vector<int> &nn_indices,
00185 Eigen::Vector3d &axis, Eigen::Vector3d &normal);
00186
00191 std::vector<CylindricalShell>
00192 searchAffordancesNormalsOrPCA(const PointCloud::Ptr &cloud,
00193 tf::StampedTransform *transform = NULL);
00194
00199 std::vector<CylindricalShell>
00200 searchAffordancesTaubin(const PointCloud::Ptr &cloud, tf::StampedTransform *transform = NULL);
00201
00209 void findBestColinearSet(const std::vector<CylindricalShell> &list,
00210 std::vector<int> &inliersMaxSet,
00211 std::vector<int> &outliersMaxSet);
00212
00220 int numInFront(const PointCloud::Ptr &cloud, int center_index, double radius);
00221
00222
00223 double target_radius;
00224 double radius_error;
00225 double handle_gap;
00226 int num_samples;
00227 double max_range;
00228 bool use_clearance_filter;
00229 bool use_occlusion_filter;
00230 int curvature_estimator;
00231 int alignment_runs;
00232 int alignment_min_inliers;
00233 double alignment_dist_radius;
00234 double alignment_orient_radius;
00235 double alignment_radius_radius;
00236 WorkspaceLimits workspace_limits;
00237 int num_threads;
00238 std::string file;
00239
00240
00241 static const int CURVATURE_ESTIMATOR;
00242 static const int NUM_SAMPLES;
00243 static const int NUM_NEAREST_NEIGHBORS;
00244 static const double NEIGHBOR_RADIUS;
00245 static const int MAX_NUM_IN_FRONT;
00246 static const double TARGET_RADIUS;
00247 static const double RADIUS_ERROR;
00248 static const double HANDLE_GAP;
00249 static const double MAX_RANGE;
00250 static const bool USE_CLEARANCE_FILTER;
00251 static const bool USE_OCCLUSION_FILTER;
00252 static const int ALIGNMENT_RUNS;
00253 static const int ALIGNMENT_MIN_INLIERS;
00254 static const double ALIGNMENT_DIST_RADIUS;
00255 static const double ALIGNMENT_ORIENT_RADIUS;
00256 static const double ALIGNMENT_RADIUS_RADIUS;
00257 static const double WORKSPACE_MIN;
00258 static const double WORKSPACE_MAX;
00259 };
00260
00261 #endif