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 _finddd_alg_node_h_ 00026 #define _finddd_alg_node_h_ 00027 00028 #include <iri_base_algorithm/iri_base_algorithm.h> 00029 #include "finddd_alg.h" 00030 #include <vector> 00031 #include <time.h> 00032 00033 00034 // [publisher subscriber headers] 00035 00036 // [service client headers] 00037 #include <iri_perception_msgs/PclToDescriptorSet.h> 00038 00039 // [action server client headers] 00040 00045 class FindddAlgNode : public algorithm_base::IriBaseAlgorithm<FindddAlgorithm> 00046 { 00047 private: 00048 // [publisher attributes] 00049 ros::Publisher descriptor_publisher_; 00050 00051 // [subscriber attributes] 00052 ros::Subscriber points_subscriber_; 00053 void points_callback(const sensor_msgs::PointCloud2::ConstPtr& msg); 00054 00055 // [service attributes] 00056 ros::ServiceServer get_finddd_from_pointcloud_server_; 00057 bool get_finddd_from_pointcloudCallback(iri_perception_msgs::PclToDescriptorSet::Request &req, iri_perception_msgs::PclToDescriptorSet::Response &res); 00058 CMutex get_finddd_from_pointcloud_mutex_; 00059 00060 // [client attributes] 00061 00062 // [action server attributes] 00063 00064 // [action client attributes] 00065 00066 // [other] 00067 float accumulated_time; 00068 00069 iri_perception_msgs::DescriptorSet get_finddd_from_pointcloud(const sensor_msgs::PointCloud2& ros_pointcloud); 00070 00071 public: 00078 FindddAlgNode(void); 00079 00086 ~FindddAlgNode(void); 00087 00088 protected: 00101 void mainNodeThread(void); 00102 00115 void node_config_update(Config &config, uint32_t level); 00116 00123 void addNodeDiagnostics(void); 00124 00125 // [diagnostic functions] 00126 00127 // [test functions] 00128 }; 00129 00130 #endif