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 _apply_tof_calibration_alg_node_h_ 00026 #define _apply_tof_calibration_alg_node_h_ 00027 00028 #include <iri_base_algorithm/iri_base_algorithm.h> 00029 #include "apply_tof_calibration_alg.h" 00030 00031 // [publisher subscriber headers] 00032 #include <sensor_msgs/PointCloud2.h> 00033 00034 // [service client headers] 00035 #include <iri_perception_msgs/CapturePointCloud2.h> 00036 00037 // [action server client headers] 00038 00043 class ApplyTofCalibrationAlgNode : public algorithm_base::IriBaseAlgorithm<ApplyTofCalibrationAlgorithm> 00044 { 00045 private: 00046 // [publisher attributes] 00047 ros::Publisher calibrated_pcl2_publisher_; 00048 sensor_msgs::PointCloud2 PointCloud2_msg_; 00049 00050 // [subscriber attributes] 00051 ros::Subscriber uncalibrated_pcl2_subscriber_; 00052 void uncalibrated_pcl2_callback(const sensor_msgs::PointCloud2::ConstPtr& msg); 00053 CMutex uncalibrated_pcl2_mutex_; 00054 00055 // [service attributes] 00056 ros::ServiceServer get_pointcloud_server_; 00057 bool get_pointcloudCallback(iri_perception_msgs::CapturePointCloud2::Request &req, iri_perception_msgs::CapturePointCloud2::Response &res); 00058 CMutex get_pointcloud_mutex_; 00059 00060 // [client attributes] 00061 00062 // [action server attributes] 00063 00064 // [action client attributes] 00065 00066 public: 00073 ApplyTofCalibrationAlgNode(void); 00074 00081 ~ApplyTofCalibrationAlgNode(void); 00082 00083 protected: 00096 void mainNodeThread(void); 00097 00110 void node_config_update(Config &config, uint32_t level); 00111 00118 void addNodeDiagnostics(void); 00119 00120 // [diagnostic functions] 00121 00122 // [test functions] 00123 }; 00124 00125 #endif