obstacle_detection_normals_alg.h
Go to the documentation of this file.
00001 // Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC.
00002 // Author 
00003 // All rights reserved.
00004 //
00005 // This file is part of iri-ros-pkg
00006 // iri-ros-pkg is free software: you can redistribute it and/or modify
00007 // it under the terms of the GNU Lesser General Public License as published by
00008 // the Free Software Foundation, either version 3 of the License, or
00009 // at your option) any later version.
00010 //
00011 // This program is distributed in the hope that it will be useful,
00012 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00013 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014 // GNU Lesser General Public License for more details.
00015 //
00016 // You should have received a copy of the GNU Lesser General Public License
00017 // along with this program.  If not, see <http://www.gnu.org/licenses/>.
00018 // 
00019 // IMPORTANT NOTE: This code has been generated through a script from the 
00020 // iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness
00021 // of the scripts. ROS topics can be easly add by using those scripts. Please
00022 // refer to the IRI wiki page for more information:
00023 // http://wikiri.upc.es/index.php/Robotics_Lab
00024 
00025 #ifndef _obstacle_detection_normals_alg_h_
00026 #define _obstacle_detection_normals_alg_h_
00027 
00028 #include <iri_obstacle_detection_normals/ObstacleDetectionNormalsConfig.h>
00029 #include "mutex.h"
00030 
00031 
00032 #include <pcl/point_types.h>
00033 #include <pcl/io/pcd_io.h>
00034 #include <pcl/features/normal_3d.h>
00035 #include <pcl/features/integral_image_normal.h>
00036 #include <pcl/kdtree/kdtree_flann.h>
00037 #include <pcl/impl/point_types.hpp>
00038 
00039 #include <boost/make_shared.hpp>
00040 
00041 using namespace pcl;
00042 using namespace std;
00043 
00044 typedef KdTree<PointXYZ>::Ptr KdTreePtr;
00045 
00046 //include obstacle_detection_normals_alg main library
00047 
00053 class ObstacleDetectionNormalsAlgorithm
00054 {
00055   protected:
00062     CMutex alg_mutex_;
00063 
00064     // private attributes and methods
00065     int KSearch;
00066     float normal_z,normal_y,normal_x,min_dist;
00067 
00068     KdTreePtr tree;
00069     
00070     // pcl::PointCloud<pcl::PointXYZ> cloud;
00071     // pcl::PointCloud<pcl::PointXYZRGBNormal> cloud_out;
00072     // pcl::PointCloud<pcl::PointXYZRGBNormal> cloud_obs;  
00073 
00074 
00075   public:
00082     typedef iri_obstacle_detection_normals::ObstacleDetectionNormalsConfig Config;
00083 
00090     Config config_;
00091 
00100     ObstacleDetectionNormalsAlgorithm(void);
00101 
00107     void lock(void) { alg_mutex_.enter(); };
00108 
00114     void unlock(void) { alg_mutex_.exit(); };
00115 
00123     bool try_enter(void) { return alg_mutex_.try_enter(); };
00124 
00136     void config_update(Config& new_cfg, uint32_t level=0);
00137 
00138     // here define all obstacle_detection_normals_alg interface methods to retrieve and set
00139     // the driver parameters
00140 
00147     ~ObstacleDetectionNormalsAlgorithm(void);
00148     
00149     // void cloud_all(int KSearch, float normal_z, 
00150     //  float normal_y, float normal_x, float min_intens, float min_dist, 
00151     //  const pcl::PointCloud<pcl::PointXYZ>& cloud, 
00152     //  pcl::PointCloud<pcl::PointXYZRGBNormal>& cloud_out, pcl::PointCloud<pcl::PointXYZRGBNormal>& cloud_obs);   
00153 
00154     void cloud_all(int KSearch, float normal_z, 
00155      float normal_y, float normal_x, float min_dist, 
00156      const pcl::PointCloud<pcl::PointXYZ>& cloud, 
00157      pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr& cloud_out, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr& cloud_obs); 
00158 
00159 };
00160 
00161 #endif


iri_obstacle_detection_normals
Author(s): asantamaria
autogenerated on Fri Dec 6 2013 21:12:38