mesh_from_pointcloud_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 _mesh_from_pointcloud_alg_h_
00026 #define _mesh_from_pointcloud_alg_h_
00027 
00028 #include <iri_mesh_from_pointcloud/MeshFromPointcloudConfig.h>
00029 #include "mutex.h"
00030 
00031 // [PCL_ROS]
00032 #include "pcl/point_types.h"
00033 #include "pcl/io/pcd_io.h"
00034 #include "pcl/kdtree/kdtree_flann.h"
00035 #include "pcl/features/normal_3d.h"
00036 #include "pcl/surface/gp3.h"
00037 #include <pcl/io/vtk_io.h>
00038 #include <pcl/filters/filter.h>
00039 
00040 //include mesh_from_pointcloud_alg main library
00041 
00047 class MeshFromPointcloudAlgorithm
00048 {
00049   protected:
00056     CMutex alg_mutex_;
00057 
00058     // private attributes and methods
00059 
00060   public:
00067     typedef iri_mesh_from_pointcloud::MeshFromPointcloudConfig Config;
00068 
00075     Config config_;
00076 
00085     MeshFromPointcloudAlgorithm(void);
00086 
00092     void lock(void) { alg_mutex_.enter(); };
00093 
00099     void unlock(void) { alg_mutex_.exit(); };
00100 
00108     bool try_enter(void) { return alg_mutex_.try_enter(); };
00109 
00121     void config_update(Config& new_cfg, uint32_t level=0);
00122 
00123     // here define all mesh_from_pointcloud_alg interface methods to retrieve and set
00124     // the driver parameters
00125 
00126     bool compute_mesh(const sensor_msgs::PointCloud2::ConstPtr& msg);
00127     bool compute_mesh(pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud);
00128 //    bool compute_mesh(pcl::PointCloud<pcl::PointXYZI>::Ptr& cloud);
00129 //    bool compute_mesh(pcl::PointCloud<pcl::PointWithRange>::Ptr& cloud);
00130 //    bool compute_mesh(pcl::PointCloud<pcl::PointXYZRGB>::Ptr& cloud);
00131 
00138     ~MeshFromPointcloudAlgorithm(void);
00139 };
00140 
00141 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


iri_mesh_from_pointcloud
Author(s): Sergi Foix
autogenerated on Thu Mar 7 2013 11:30:06