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 _localization3d_alg_node_h_ 00026 #define _localization3d_alg_node_h_ 00027 00028 //common headers 00029 00030 //external localization library and iri-ros 00031 #include <iri_base_algorithm/iri_base_algorithm.h> 00032 #include "localization3d_alg.h" 00033 #include "basicPF.h" 00034 //#include "position3d.h" 00035 00036 // [publisher subscriber headers] 00037 #include <nav_msgs/Odometry.h> 00038 #include <sensor_msgs/LaserScan.h> 00039 #include <geometry_msgs/PoseArray.h> 00040 #include <geometry_msgs/PoseWithCovarianceStamped.h> 00041 #include <tf/tfMessage.h> 00042 #include <tf/transform_broadcaster.h> 00043 #include <tf/transform_listener.h> 00044 #include <iri_segway_rmp_msgs/SegwayRMP200Status.h> 00045 00046 // [service client headers] 00047 00048 // [action server client headers] 00049 00050 //CONSTANTS 00051 static const unsigned int MAX_RANGE_DEVICES = 3; 00052 static const string mapFrame = "/map"; 00053 static const string odomFrame = "odom"; 00054 static const string baseFrame = "base_link"; 00055 00056 //specification of a range device (i.e. laser scanner) to be modelled 00057 struct rangeDeviceConfig 00058 { 00059 //unsigned int deviceId; 00060 string frameName; 00061 int deviceType; 00062 int nRays; 00063 double aperture; 00064 double rangeMin; 00065 double rangeMax; 00066 double stdDev; 00067 }; 00068 00073 class Localization3dAlgNode : public algorithm_base::IriBaseAlgorithm<Localization3dAlgorithm> 00074 { 00075 private: 00076 // [publisher attributes] 00077 ros::Publisher tf_publisher_; 00078 tf::tfMessage tfMessage_msg_; 00079 ros::Publisher particleSet_publisher_; 00080 geometry_msgs::PoseArray PoseArray_msg_; 00081 ros::Publisher position_publisher_; 00082 geometry_msgs::PoseWithCovarianceStamped PoseWithCovarianceStamped_msg_; 00083 00084 // [tf broadcaster and listener] 00085 tf::TransformBroadcaster tfBroadcaster; 00086 tf::TransformListener tfListener; 00087 00088 // [subscriber attributes] 00089 ros::Subscriber platformData_subscriber_; 00090 void platformData_callback(const iri_segway_rmp_msgs::SegwayRMP200Status::ConstPtr& msg); 00091 CMutex platformData_mutex_; 00092 ros::Subscriber platformOdometry_subscriber_; 00093 void platformOdometry_callback(const nav_msgs::Odometry::ConstPtr& msg); 00094 CMutex platformOdometry_mutex_; 00095 ros::Subscriber laser0_subscriber_; 00096 void laser0_callback(const sensor_msgs::LaserScan::ConstPtr& msg); 00097 //CMutex laser0_mutex_; 00098 ros::Subscriber laser1_subscriber_; 00099 void laser1_callback(const sensor_msgs::LaserScan::ConstPtr& msg); 00100 //CMutex laser1_mutex_; 00101 ros::Subscriber laser2_subscriber_; 00102 void laser2_callback(const sensor_msgs::LaserScan::ConstPtr& msg); 00103 //CMutex laser1_mutex_; 00104 CMutex laser_mutex[MAX_RANGE_DEVICES];//callback mutexes 00105 00106 // [service attributes] 00107 00108 // [client attributes] 00109 00110 // [action server attributes] 00111 00112 // [action client attributes] 00113 00114 //dynamic reconfigure mutex 00115 CMutex config_mutex; 00116 00117 //map_localization library objects 00118 CodometryObservation odometry; 00119 Ccompass3axisObservation inclinometers; 00120 ClaserObservation laserObs[MAX_RANGE_DEVICES]; 00121 rangeDeviceConfig rDevConfig[MAX_RANGE_DEVICES]; 00122 CposCovObservation locEstimate; 00123 CbasicPF *pFilter; 00124 int numberOfParticles;//number of particles 00125 int resamplingStyle; 00126 double initX,initY,initH; //initial estimate (tracking case) 00127 string mapFileName, gridFileName; //file names for environment models (3D and grid) 00128 tf::Pose odoPose;//odometry pose starting at 0. Updated at each odometry callback 00129 ros::Time odoTime; //keeps the last odometry time stamp 00130 ros::Time priorTime; //keeps the time stamp of the prior estimate (after odometry propagation) 00131 double infoGain; //accumulates all info gain of each iteration; 00132 ros::Duration transform_tolerance_; 00133 double dT; //DEBUGGING!!; this variable should be local at platformOdometry_callback(); 00134 00135 void initDevicePositions();//initializes device positions with respect to base_link frame. It is assumed that they are constant during the operation 00136 void printUserConfiguration();//prints user configurations 00137 00138 public: 00145 Localization3dAlgNode(void); 00146 00153 ~Localization3dAlgNode(void); 00154 00155 protected: 00168 void mainNodeThread(void); 00169 00182 void node_config_update(Config &config, uint32_t level); 00183 00190 void addNodeDiagnostics(void); 00191 00192 // [diagnostic functions] 00193 00194 // [test functions] 00195 00196 //other member functions 00197 //setLaserObservation(const sensor_msgs::LaserScan::ConstPtr& msg, ClaserObservation & laserData); 00198 }; 00199 00200 #endif