cylindrical_shell.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 CYLINDRICAL_SHELL_H
00033 #define CYLINDRICAL_SHELL_H
00034 
00035 #include "Eigen/Dense"
00036 #include <pcl/kdtree/kdtree_flann.h>
00037 #include <pcl/point_cloud.h>
00038 #include <pcl/search/organized.h>
00039 
00040 typedef pcl::PointCloud<pcl::PointXYZRGBA> PointCloud;
00041 
00049 class CylindricalShell
00050 {
00051 public:
00052 
00061   void
00062   fitCylinder(const PointCloud::Ptr &cloud, const std::vector<int> &indices, const Eigen::Vector3d &normal,
00063               const Eigen::Vector3d &curvature_axis);
00064 
00071   bool
00072   hasClearance(const PointCloud::Ptr &cloud, const std::vector<int>& nn_indices, double maxHandAperture,
00073                double handleGap);
00074 
00077   inline double getExtent() const
00078   {
00079     return this->extent;
00080   }
00081   ;
00082 
00086   inline void setExtent(double extent)
00087   {
00088     this->extent = extent;
00089   }
00090   ;
00091 
00094   inline double getRadius() const
00095   {
00096     return this->radius;
00097   }
00098   ;
00099 
00103   inline int getNeighborhoodCentroidIndex() const
00104   {
00105     return this->neighborhood_centroid_index;
00106   }
00107   ;
00108 
00113   inline void setNeighborhoodCentroidIndex(int index)
00114   {
00115     this->neighborhood_centroid_index = index;
00116   }
00117   ;
00118 
00121   inline Eigen::Vector3d getCentroid() const
00122   {
00123     return this->centroid;
00124   }
00125   ;
00126 
00129   inline Eigen::Vector3d getCurvatureAxis() const
00130   {
00131     return this->curvature_axis;
00132   }
00133   ;
00134 
00137   inline Eigen::Vector3d getNormal() const
00138   {
00139     return this->normal;
00140   }
00141   ;
00142 
00143 private:
00144 
00145   Eigen::Vector3d centroid;
00146   Eigen::Vector3d curvature_axis;
00147   double extent;
00148   double radius;
00149   Eigen::Vector3d normal;
00150   int neighborhood_centroid_index;
00151 };
00152 
00153 #endif


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