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 _laser_icp_alg_node_h_ 00026 #define _laser_icp_alg_node_h_ 00027 00028 #include <iri_base_algorithm/iri_base_algorithm.h> 00029 #include "laser_icp_alg.h" 00030 00031 // [publisher subscriber headers] 00032 00033 // [service client headers] 00034 #include <iri_laser_icp/GetRelativePose.h> 00035 00036 // [action server client headers] 00037 00038 #include <tf/transform_datatypes.h> 00039 #include <csm/csm_all.h> // csm defines min and max, but Eigen complains 00040 #undef min 00041 #undef max 00042 00047 class LaserIcpAlgNode : public algorithm_base::IriBaseAlgorithm<LaserIcpAlgorithm> 00048 { 00049 private: 00050 // [publisher attributes] 00051 00052 // [subscriber attributes] 00053 00054 // [service attributes] 00055 ros::ServiceServer get_relative_pose_server_; 00056 bool get_relative_poseCallback(iri_laser_icp::GetRelativePose::Request &req, iri_laser_icp::GetRelativePose::Response &res); 00057 CMutex get_relative_pose_mutex_; 00058 00059 // [client attributes] 00060 00061 // [action server attributes] 00062 00063 // [action client attributes] 00064 bool use_alpha_beta_; 00065 double alpha_; 00066 double beta_; 00067 double max_laser_range_; 00068 double min_laser_range_; 00069 sm_params input_; 00070 sm_result output_; 00071 LDP ref_ldp_scan_; 00072 LDP sens_ldp_scan_; 00073 void initParams(); 00074 void processScans(); 00075 void laserScanToLDP(const sensor_msgs::LaserScan& scan_msg, 00076 LDP& ldp); 00077 void ROS_INFO_XYT(const std::string & str,const float & x,const float & y,const float & th); 00078 00079 00080 public: 00087 LaserIcpAlgNode(void); 00088 00095 ~LaserIcpAlgNode(void); 00096 00097 protected: 00110 void mainNodeThread(void); 00111 00124 void node_config_update(Config &config, uint32_t level); 00125 00132 void addNodeDiagnostics(void); 00133 00134 // [diagnostic functions] 00135 00136 // [test functions] 00137 }; 00138 00139 #endif