CConnectionManager.h
Go to the documentation of this file.
00001 /* +---------------------------------------------------------------------------+
00002          |                     Mobile Robot Programming Toolkit (MRPT)               |
00003          |                          http://www.mrpt.org/                             |
00004          |                                                                           |
00005          | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file        |
00006          | See: http://www.mrpt.org/Authors - All rights reserved.                   |
00007          | Released under BSD License. See details in http://www.mrpt.org/License    |
00008          +---------------------------------------------------------------------------+ */
00009 
00010 #ifndef CCONNECTIONMANAGER_H
00011 #define CCONNECTIONMANAGER_H
00012 
00013 #include <ros/ros.h>
00014 #include <multimaster_msgs_fkie/DiscoverMasters.h>
00015 #include <mrpt_msgs/GraphSlamAgent.h>
00016 #include <mrpt_msgs/GraphSlamAgents.h>
00017 #include <mrpt_bridge/mrpt_bridge.h>
00018 
00019 #include <mrpt/utils/COutputLogger.h>
00020 #include <mrpt/system/datetime.h>
00021 #include <mrpt/system/os.h>
00022 #include <mrpt/system/string_utils.h>
00023 #include <mrpt/math/utils.h>
00024 
00025 #include <algorithm>
00026 #include <iterator>
00027 #include <iostream>
00028 #include <string>
00029 #include <vector>
00030 
00031 #include <cstdlib>
00032 
00033 namespace mrpt { namespace graphslam { namespace detail {
00034 
00038 class CConnectionManager
00039 {
00040 public:
00041         //typedef std::vector<mrpt_msgs::GraphSlamAgent>::iterator agents_it;
00042         //typedef std::vector<mrpt_msgs::GraphSlamAgent>::const_iterator agents_cit;
00043         typedef mrpt_msgs::GraphSlamAgents::_list_type::iterator agents_it;
00044         typedef mrpt_msgs::GraphSlamAgents::_list_type::const_iterator agents_cit;
00045 
00047         CConnectionManager(
00048                         mrpt::utils::COutputLogger* logger,
00049                         ros::NodeHandle* nh_in);
00051         ~CConnectionManager();
00061         void getNearbySlamAgents(mrpt_msgs::GraphSlamAgents* agents_vec,
00062                         bool ignore_self=true);
00065         const mrpt_msgs::GraphSlamAgents&  getNearbySlamAgents();
00070         const mrpt_msgs::GraphSlamAgents&  getNearbySlamAgentsCached() const;
00071 
00078         void setupComm();
00080         const std::string& getTrimmedNs() const;
00081 
00082 private:
00086         std::string own_ns;
00091         void updateNearbySlamAgents();
00099         void setupSubs();
00100         void setupPubs();
00101         void setupSrvs();
00115         static bool convert(
00116                         const multimaster_msgs_fkie::ROSMaster& ros_master,
00117                         mrpt_msgs::GraphSlamAgent* slam_agent);
00119         static void convert(
00120                         const mrpt_msgs::GraphSlamAgent& slam_agent,
00121                         multimaster_msgs_fkie::ROSMaster* ros_master);
00127         static std::string extractHostnameOrIP(const std::string& str,
00128                         unsigned short* agent_port=NULL);
00129 
00131         mrpt::utils::COutputLogger* m_logger;
00133         ros::NodeHandle* m_nh;
00134 
00135         ros::ServiceClient m_DiscoverMasters_client;
00141         mrpt_msgs::GraphSlamAgents m_nearby_slam_agents;
00142 
00143         bool has_setup_comm;
00144 
00145 };
00146 
00147 } } } // end of namespaces
00148 
00153 bool operator==(
00154                 const multimaster_msgs_fkie::ROSMaster& master1,
00155                 const multimaster_msgs_fkie::ROSMaster& master2);
00156 bool operator!=(
00157                 const multimaster_msgs_fkie::ROSMaster& master1,
00158                 const multimaster_msgs_fkie::ROSMaster& master2);
00165 bool operator==(
00166                 const mrpt_msgs::GraphSlamAgent& agent1,
00167                 const mrpt_msgs::GraphSlamAgent& agent2);
00168 bool operator!=(
00169                 const mrpt_msgs::GraphSlamAgent& agent1,
00170                 const mrpt_msgs::GraphSlamAgent& agent2);
00171 bool operator<(
00172                 const mrpt_msgs::GraphSlamAgent& agent1,
00173                 const mrpt_msgs::GraphSlamAgent& agent2);
00180 bool operator==(
00181                 const multimaster_msgs_fkie::ROSMaster& master,
00182                 const mrpt_msgs::GraphSlamAgent& agent);
00183 bool operator==(
00184                 const mrpt_msgs::GraphSlamAgent& agent,
00185                 const multimaster_msgs_fkie::ROSMaster& master);
00186 bool operator!=(
00187                 const multimaster_msgs_fkie::ROSMaster& master,
00188                 const mrpt_msgs::GraphSlamAgent& agent);
00189 bool operator!=(
00190                 const mrpt_msgs::GraphSlamAgent& agent,
00191                 const multimaster_msgs_fkie::ROSMaster& master);
00192 
00195 #endif /* end of include guard: CCONNECTIONMANAGER_H */


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Sun Sep 17 2017 03:02:04