laser_localisation_alg_node.h
Go to the documentation of this file.
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_localisation_alg_node_h_
00026 #define _laser_localisation_alg_node_h_
00027 
00028 #include <iri_base_algorithm/iri_base_algorithm.h>
00029 #include "laser_localisation_alg.h"
00030 
00031 // tf
00032 #include <tf/transform_broadcaster.h>
00033 #include <tf/transform_listener.h>
00034 
00035 // [publisher subscriber headers]
00036 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00037 #include <sensor_msgs/LaserScan.h>
00038 
00039 // [service client headers]
00040 #include <iri_laser_localisation/DoEstimation.h>
00041 #include <iri_laser_localisation/DoLocalisation.h>
00042 #include <iri_laser_icp/GetRelativePose.h>
00043 
00044 // [action server client headers]
00045 
00050 class LaserLocalisationAlgNode : public algorithm_base::IriBaseAlgorithm<LaserLocalisationAlgorithm>
00051 {
00052   private:
00053     tf::TransformBroadcaster tfb_;
00054     tf::TransformListener    tfl_;
00055 
00056     tf::Transform T_mapa_path_;
00057     tf::Transform T_path_base_;
00058     tf::Transform T_base_odom_;
00059     tf::Transform T_mapa_odom_;
00060     tf::Transform T_mapa_odom_init_est_;
00061 
00062     std::string map_frame_;
00063     std::string odom_frame_;
00064 
00065     void calc_T_mapa_odom_(sensor_msgs::LaserScan const& scan_ref,
00066                            sensor_msgs::LaserScan const& scan_sens,
00067                            geometry_msgs::Pose const& pose_ref);
00068 
00069     // [publisher attributes]
00070     ros::Publisher pose_publisher_;
00071     geometry_msgs::PoseWithCovarianceStamped PoseWithCovarianceStamped_msg_;
00072 
00073     // [subscriber attributes]
00074     ros::Subscriber scan_ref_subscriber_;
00075     void scan_ref_callback(const sensor_msgs::LaserScan::ConstPtr& msg);
00076     CMutex scan_ref_mutex_;
00077     sensor_msgs::LaserScan scan_ref_;
00078     bool received_ref_;
00079 
00080     ros::Subscriber scan_sens_subscriber_;
00081     void scan_sens_callback(const sensor_msgs::LaserScan::ConstPtr& msg);
00082     CMutex scan_sens_mutex_;
00083     sensor_msgs::LaserScan scan_sens_;
00084     bool received_sens_;
00085 
00086     ros::Subscriber pose_ref_subscriber_;
00087     void pose_ref_callback(const geometry_msgs::Pose::ConstPtr& msg);
00088     CMutex pose_ref_mutex_;
00089     geometry_msgs::Pose pose_ref_;
00090     bool received_pose_ref_;
00091 
00092     // [service attributes]
00093     ros::ServiceServer estimate_server_;
00094     bool estimateCallback(iri_laser_localisation::DoEstimation::Request &req, iri_laser_localisation::DoEstimation::Response &res);
00095     CMutex estimate_mutex_;
00096     ros::ServiceServer localise_server_;
00097     bool localiseCallback(iri_laser_localisation::DoLocalisation::Request &req, iri_laser_localisation::DoLocalisation::Response &res);
00098     CMutex localise_mutex_;
00099 
00100     // [client attributes]
00101     ros::ServiceClient get_relative_pose_client_;
00102     iri_laser_icp::GetRelativePose get_relative_pose_srv_;
00103 
00104     // [action server attributes]
00105 
00106     // [action client attributes]
00107 
00108   public:
00115     LaserLocalisationAlgNode(void);
00116 
00123     ~LaserLocalisationAlgNode(void);
00124 
00125   protected:
00138     void mainNodeThread(void);
00139 
00152     void node_config_update(Config &config, uint32_t level);
00153 
00160     void addNodeDiagnostics(void);
00161 
00162     void ROS_INFO_XYR(const std::string & str,const tf::Transform & tftrans);
00163 
00164     // [diagnostic functions]
00165 
00166     // [test functions]
00167 };
00168 
00169 #endif


iri_laser_localisation
Author(s): Marti
autogenerated on Fri Dec 6 2013 22:51:11