affordances.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2014, Andreas ten Pas
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *
00018  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00019  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00020  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00021  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00022  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00023  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00024  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00026  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00027  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00028  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  *  POSSIBILITY OF SUCH DAMAGE.
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 // workspace limits of the robot
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     // parameters (read-in from ROS launch file)
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                 // standard parameters
00241                 static const int CURVATURE_ESTIMATOR; // curvature axis estimation method
00242                 static const int NUM_SAMPLES; // number of neighborhoods
00243                 static const int NUM_NEAREST_NEIGHBORS; // number of nearest neighbors to be found
00244                 static const double NEIGHBOR_RADIUS;
00245                 static const int MAX_NUM_IN_FRONT; // max. threshold of allowed points in front of a neighborhood center point (occlusion filtering)
00246                 static const double TARGET_RADIUS; // approx. radius of the target handle
00247                 static const double RADIUS_ERROR; // allowed deviation from target radius
00248                 static const double HANDLE_GAP; // min. gap around affordances
00249                 static const double MAX_RANGE; // max. range of robot arms
00250                 static const bool USE_CLEARANCE_FILTER; // whether the clearance filter is used
00251                 static const bool USE_OCCLUSION_FILTER; // whether the occlusion filter is used
00252                 static const int ALIGNMENT_RUNS; // number of RANSAC runs
00253                 static const int ALIGNMENT_MIN_INLIERS; // min. number of inliers for colinear cylinder set
00254                 static const double ALIGNMENT_DIST_RADIUS; // distance threshold
00255                 static const double ALIGNMENT_ORIENT_RADIUS; // orientation threshold
00256                 static const double ALIGNMENT_RADIUS_RADIUS; // radius threshold
00257                 static const double WORKSPACE_MIN;
00258                 static const double WORKSPACE_MAX;
00259 };
00260 
00261 #endif


handle_detector
Author(s):
autogenerated on Thu Jun 6 2019 17:36:23