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 _poseslam_alg_node_h_ 00026 #define _poseslam_alg_node_h_ 00027 00028 #include <iri_base_algorithm/iri_base_algorithm.h> 00029 #include "poseslam_alg.h" 00030 00031 // [publisher subscriber headers] 00032 #include <iri_poseslam/Trajectory.h> 00033 00034 // [service client headers] 00035 #include <iri_poseslam/GetLink.h> 00036 00037 // [action server client headers] 00038 00039 #include <std_msgs/Header.h> 00040 00045 class PoseslamAlgNode : public algorithm_base::IriBaseAlgorithm<PoseslamAlgorithm> 00046 { 00047 private: 00048 // [publisher attributes] 00049 ros::Publisher trajectory_publisher_; 00050 ros::Publisher no_loops_trajectory_publisher_; 00051 iri_poseslam::Trajectory Trajectory_msg_; 00052 iri_poseslam::Trajectory Trajectory_msg_no_loops_; 00053 std::vector<uint> loops_; 00054 std::vector<VectorXd> Trajectory_poses_; 00055 00056 // [subscriber attributes] 00057 00058 // [service attributes] 00059 00060 // [client attributes] 00061 ros::ServiceClient get_link_client_; 00062 iri_poseslam::GetLink get_link_srv_; 00063 00064 // [action server attributes] 00065 00066 // [action client attributes] 00067 00068 // POSE SLAM 00069 uint step_; 00070 uint ended; 00071 double dz_footprint_2_base_; 00072 00073 public: 00080 PoseslamAlgNode(void); 00081 00088 ~PoseslamAlgNode(void); 00089 00090 protected: 00103 void mainNodeThread(void); 00104 00117 void node_config_update(Config &config, uint32_t level); 00118 00125 void addNodeDiagnostics(void); 00126 00134 void augment_trajectories(const std_msgs::Header& header); 00135 00143 void update_trajectories(const bool& LoopClosed); 00144 00150 void print_results() const; 00151 00158 void recompute_trajectory(); 00159 00169 std::vector<VectorXd> recompute_segment(const VectorXd& new_initial_pose, const VectorXd& new_final_pose, const int& initial_step, const int& final_step); 00170 00179 geometry_msgs::PoseWithCovarianceStamped create_PoseWithCovarianceStamped(const std_msgs::Header& header, const VectorXd& last_pose, const std::vector<double>& last_cov); 00180 00188 geometry_msgs::PoseWithCovariance create_PoseWithCovariance(const VectorXd& last_pose, const std::vector<double>& last_cov); 00189 00199 MatrixXd rotation_matrix(const double &alpha) const; 00200 00209 double angle_between_2D_vectors(const Vector2d& v, const Vector2d& w) const; 00210 00218 double pi_2_pi(const double& angle) const; 00219 00220 // [diagnostic functions] 00221 00222 // [test functions] 00223 }; 00224 00225 #endif