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 _pointcloud_to_mesh_alg_h_ 00026 #define _pointcloud_to_mesh_alg_h_ 00027 00028 #include <iri_pointcloud_to_mesh/PointCloudToMeshConfig.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 #include <pcl/filters/voxel_grid.h> 00040 00041 //include pointcloud_to_mesh_alg main library 00042 00048 class PointCloudToMeshAlgorithm 00049 { 00050 private: 00051 double down_res_; 00052 double radius_; 00053 double mu_; 00054 unsigned int num_neigh_; 00055 double max_surf_angle_; 00056 double min_ang_; 00057 double max_ang_; 00058 bool norm_consistency_; 00059 00060 protected: 00067 CMutex alg_mutex_; 00068 00069 // private attributes and methods 00070 00071 public: 00078 typedef iri_pointcloud_to_mesh::PointCloudToMeshConfig Config; 00079 00086 Config config_; 00087 00096 PointCloudToMeshAlgorithm(void); 00097 00103 void lock(void) { alg_mutex_.enter(); }; 00104 00110 void unlock(void) { alg_mutex_.exit(); }; 00111 00119 bool try_enter(void) { return alg_mutex_.try_enter(); }; 00120 00132 void config_update(Config& new_cfg, uint32_t level=0); 00133 00134 // here define all pointcloud_to_mesh_alg interface methods to retrieve and set 00135 // the driver parameters 00136 00137 bool compute_mesh(const sensor_msgs::PointCloud2::ConstPtr& msg); 00138 bool compute_mesh(pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud); 00139 void set_down_res(double down_res); 00140 void set_radius(double radius); 00141 void set_mu(double mu); 00142 void set_num_of_neigh(unsigned int num_neigh); 00143 void set_max_surface_angle(double max_surf_angle); 00144 void set_min_angle(double min_ang); 00145 void set_max_angle(double max_ang); 00146 void set_normal_consistency(bool norm_consistency); 00147 00154 ~PointCloudToMeshAlgorithm(void); 00155 }; 00156 00157 #endif