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_node_h_ 00026 #define _filter_jump_edge_alg_node_h_ 00027 00028 #include <iri_base_algorithm/iri_base_algorithm.h> 00029 #include "filter_jump_edge_alg.h" 00030 00031 // [publisher subscriber headers] 00032 #include <sensor_msgs/CameraInfo.h> 00033 #include <sensor_msgs/Image.h> 00034 #include <sensor_msgs/image_encodings.h> 00035 #include <sensor_msgs/PointCloud2.h> 00036 00037 // [service client headers] 00038 #include <iri_filter_jump_edge/ApplyPointCloudFilter.h> 00039 00040 // [action server client headers] 00041 00042 00047 class FilterJumpEdgeAlgNode : public algorithm_base::IriBaseAlgorithm<FilterJumpEdgeAlgorithm> 00048 { 00049 private: 00050 00051 // Intrinsec Parameters 00052 double sx_, sy_, u0_, v0_, skw_, ang_thr_; 00053 00054 // [publisher attributes] 00055 ros::Publisher residual_pc_publisher_; 00056 ros::Publisher filtered_pc_publisher_; 00057 ros::Publisher residual_img_publisher_; 00058 00059 // [subscriber attributes] 00060 ros::Subscriber camera_info_subscriber_; 00061 void camera_info_callback(const sensor_msgs::CameraInfo::ConstPtr& msg); 00062 CMutex camera_info_mutex_; 00063 ros::Subscriber pcl_input_subscriber_; 00064 void pcl_input_callback(const sensor_msgs::PointCloud2::ConstPtr& msg); 00065 CMutex pcl_input_mutex_; 00066 00067 // [service attributes] 00068 ros::ServiceServer apply_jump_edge_filter_server_; 00069 bool apply_jump_edge_filterCallback(iri_filter_jump_edge::ApplyPointCloudFilter::Request &req, iri_filter_jump_edge::ApplyPointCloudFilter::Response &res); 00070 CMutex apply_jump_edge_filter_mutex_; 00071 00072 // [client attributes] 00073 00074 // [action server attributes] 00075 00076 // [action client attributes] 00077 00078 public: 00085 FilterJumpEdgeAlgNode(void); 00086 00093 ~FilterJumpEdgeAlgNode(void); 00094 00095 protected: 00108 void mainNodeThread(void); 00109 00122 void node_config_update(Config &config, uint32_t level); 00123 00130 void addNodeDiagnostics(void); 00131 00132 // [diagnostic functions] 00133 00134 // [test functions] 00135 }; 00136 00137 #endif