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_jump_edge_alg_h_ 00026 #define _filter_jump_edge_alg_h_ 00027 00028 #include <iri_filter_jump_edge/FilterJumpEdgeConfig.h> 00029 #include "mutex.h" 00030 #include <sensor_msgs/PointCloud2.h> 00031 #include <sensor_msgs/image_encodings.h> 00032 #include <pcl_ros/point_cloud.h> 00033 #include <pcl/point_types.h> 00034 #include <pcl/io/pcd_io.h> 00035 00036 //include filter_jump_edge_alg main library 00037 00043 class FilterJumpEdgeAlgorithm 00044 { 00045 private: 00046 00047 // Intrinsec Parameters 00048 double sx_, sy_, u0_, v0_, skw_, ang_thr_; 00049 00050 // Output Variables 00051 //pcl::PointCloud<pcl::PointXYZRGB> filtered_pc_; 00052 //pcl::PointCloud<pcl::PointXYZRGB> residual_pc_; 00053 sensor_msgs::PointCloud2 filtered_pc_; 00054 sensor_msgs::PointCloud2 residual_pc_; 00055 sensor_msgs::Image residual_img_; 00056 00057 00058 protected: 00065 CMutex alg_mutex_; 00066 00067 // private attributes and methods 00068 00069 public: 00076 typedef iri_filter_jump_edge::FilterJumpEdgeConfig Config; 00077 00084 Config config_; 00085 00094 FilterJumpEdgeAlgorithm(void); 00095 00101 void lock(void) { alg_mutex_.enter(); }; 00102 00108 void unlock(void) { alg_mutex_.exit(); }; 00109 00117 bool try_enter(void) { return alg_mutex_.try_enter(); }; 00118 00130 void config_update(Config& new_cfg, uint32_t level=0); 00131 00132 bool apply_jump_edge_filter(const sensor_msgs::PointCloud2::ConstPtr& msg); 00133 00134 00135 // here define all filter_jump_edge_alg interface methods to retrieve and set 00136 // the driver parameters 00137 sensor_msgs::PointCloud2* get_filtered_pc(void); 00138 sensor_msgs::PointCloud2* get_residual_pc(void); 00139 sensor_msgs::Image* get_residual_img(void); 00140 00141 void set_sx(double sx); 00142 void set_sy(double sy); 00143 void set_u0(double u0); 00144 void set_v0(double v0); 00145 void set_skw(double skw); 00146 void set_ang_thr(double ang_thr); 00147 00154 ~FilterJumpEdgeAlgorithm(void); 00155 }; 00156 00157 #endif