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 _filter_pointcloud2_z_value_alg_h_ 00026 #define _filter_pointcloud2_z_value_alg_h_ 00027 00028 #include <iri_filter_pointcloud2_z_value/FilterPointcloud2ZValueConfig.h> 00029 #include "mutex.h" 00030 #include <sensor_msgs/PointCloud2.h> 00031 00032 //include filter_pointcloud2_z_value_alg main library 00033 00039 class FilterPointcloud2ZValueAlgorithm 00040 { 00041 private: 00042 float z_thr_; 00043 sensor_msgs::PointCloud2 nan_pc_; 00044 sensor_msgs::PointCloud2 max_pc_; 00045 00046 protected: 00053 CMutex alg_mutex_; 00054 00055 // private attributes and methods 00056 00057 public: 00064 typedef iri_filter_pointcloud2_z_value::FilterPointcloud2ZValueConfig Config; 00065 00072 Config config_; 00073 00082 FilterPointcloud2ZValueAlgorithm(void); 00083 00089 void lock(void) { alg_mutex_.enter(); }; 00090 00096 void unlock(void) { alg_mutex_.exit(); }; 00097 00105 bool try_enter(void) { return alg_mutex_.try_enter(); }; 00106 00118 void config_update(Config& new_cfg, uint32_t level=0); 00119 00120 bool apply_z_value_filter(const sensor_msgs::PointCloud2::ConstPtr& msg); 00121 00122 sensor_msgs::PointCloud2* get_nan_pc(void); 00123 00124 sensor_msgs::PointCloud2* get_max_pc(void); 00125 00126 void set_z_thr(double z_thr); 00127 00128 // here define all filter_pointcloud2_z_value_alg interface methods to retrieve and set 00129 // the driver parameters 00130 00137 ~FilterPointcloud2ZValueAlgorithm(void); 00138 }; 00139 00140 #endif