CConnectionManager.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) | |
3  http://www.mrpt.org/ | | | | Copyright (c)
4  2005-2016, Individual contributors, see AUTHORS file | | See:
5  http://www.mrpt.org/Authors - All rights reserved. | |
6  Released under BSD License. See details in http://www.mrpt.org/License |
7  +---------------------------------------------------------------------------+
8  */
9 
10 #pragma once
11 
12 #include <ros/ros.h>
13 #include <fkie_multimaster_msgs/DiscoverMasters.h>
14 #include <mrpt_msgs/GraphSlamAgent.h>
15 #include <mrpt_msgs/GraphSlamAgents.h>
16 
17 #include <mrpt/system/COutputLogger.h>
18 #include <mrpt/system/datetime.h>
19 #include <mrpt/system/os.h>
20 #include <mrpt/system/string_utils.h>
21 #include <mrpt/math/utils.h>
22 
23 #include <algorithm>
24 #include <iterator>
25 #include <iostream>
26 #include <string>
27 #include <vector>
28 
29 #include <cstdlib>
30 
31 namespace mrpt
32 {
33 namespace graphslam
34 {
35 namespace detail
36 {
41 {
42  public:
43  // typedef std::vector<mrpt_msgs::GraphSlamAgent>::iterator agents_it;
44  // typedef std::vector<mrpt_msgs::GraphSlamAgent>::const_iterator
45  // agents_cit;
46  typedef mrpt_msgs::GraphSlamAgents::_list_type::iterator agents_it;
47  typedef mrpt_msgs::GraphSlamAgents::_list_type::const_iterator agents_cit;
48 
51  mrpt::system::COutputLogger* logger, ros::NodeHandle* nh_in);
64  mrpt_msgs::GraphSlamAgents* agents_vec, bool ignore_self = true);
67  const mrpt_msgs::GraphSlamAgents& getNearbySlamAgents();
72  const mrpt_msgs::GraphSlamAgents& getNearbySlamAgentsCached() const;
73 
80  void setupComm();
82  const std::string& getTrimmedNs() const;
83 
84  private:
88  std::string own_ns;
101  void setupSubs();
102  void setupPubs();
103  void setupSrvs();
116  static bool convert(
117  const fkie_multimaster_msgs::ROSMaster& ros_master,
118  mrpt_msgs::GraphSlamAgent* slam_agent);
120  static void convert(
121  const mrpt_msgs::GraphSlamAgent& slam_agent,
122  fkie_multimaster_msgs::ROSMaster* ros_master);
129  static std::string extractHostnameOrIP(
130  const std::string& str, unsigned short* agent_port = NULL);
131 
133  mrpt::system::COutputLogger* m_logger;
136 
143  mrpt_msgs::GraphSlamAgents m_nearby_slam_agents;
144 
146 };
147 
148 } // namespace detail
149 } // namespace graphslam
150 } // namespace mrpt
151 
156 bool operator==(
157  const fkie_multimaster_msgs::ROSMaster& master1,
158  const fkie_multimaster_msgs::ROSMaster& master2);
159 bool operator!=(
160  const fkie_multimaster_msgs::ROSMaster& master1,
161  const fkie_multimaster_msgs::ROSMaster& master2);
168 bool operator==(
169  const mrpt_msgs::GraphSlamAgent& agent1,
170  const mrpt_msgs::GraphSlamAgent& agent2);
171 bool operator!=(
172  const mrpt_msgs::GraphSlamAgent& agent1,
173  const mrpt_msgs::GraphSlamAgent& agent2);
174 bool operator<(
175  const mrpt_msgs::GraphSlamAgent& agent1,
176  const mrpt_msgs::GraphSlamAgent& agent2);
183 bool operator==(
184  const fkie_multimaster_msgs::ROSMaster& master,
185  const mrpt_msgs::GraphSlamAgent& agent);
186 bool operator==(
187  const mrpt_msgs::GraphSlamAgent& agent,
188  const fkie_multimaster_msgs::ROSMaster& master);
189 bool operator!=(
190  const fkie_multimaster_msgs::ROSMaster& master,
191  const mrpt_msgs::GraphSlamAgent& agent);
192 bool operator!=(
193  const mrpt_msgs::GraphSlamAgent& agent,
194  const fkie_multimaster_msgs::ROSMaster& master);
195 
mrpt::graphslam::detail::CConnectionManager::m_nh
ros::NodeHandle * m_nh
Pointer to the Ros NodeHanle instance.
Definition: CConnectionManager.h:135
mrpt::graphslam::detail::CConnectionManager::~CConnectionManager
~CConnectionManager()
Destructor.
Definition: CConnectionManager.cpp:104
mrpt::graphslam::detail::CConnectionManager::own_ns
std::string own_ns
Namespace under which we are running. Corresponds to the agent_ID_str with which the nodes are going ...
Definition: CConnectionManager.h:88
mrpt::graphslam::detail::CConnectionManager::m_DiscoverMasters_client
ros::ServiceClient m_DiscoverMasters_client
Definition: CConnectionManager.h:137
ros.h
mrpt::graphslam::detail::CConnectionManager::convert
static bool convert(const fkie_multimaster_msgs::ROSMaster &ros_master, mrpt_msgs::GraphSlamAgent *slam_agent)
ROSMaster ==> mrpt_msgs::GraphSlamAgent.
Definition: CConnectionManager.cpp:226
mrpt::graphslam::detail::CConnectionManager::getTrimmedNs
const std::string & getTrimmedNs() const
Get the agent ROS namespace.
Definition: CConnectionManager.cpp:106
mrpt
Definition: CConnectionManager.h:31
operator!=
bool operator!=(const fkie_multimaster_msgs::ROSMaster &master1, const fkie_multimaster_msgs::ROSMaster &master2)
Definition: CConnectionManager.cpp:24
rename_rviz_topics.logger
logger
Definition: rename_rviz_topics.py:31
operator==
bool operator==(const fkie_multimaster_msgs::ROSMaster &master1, const fkie_multimaster_msgs::ROSMaster &master2)
ROSMaster instances are considered the same if the "uri" field is the same.
Definition: CConnectionManager.cpp:18
mrpt::graphslam::detail::CConnectionManager::setupSubs
void setupSubs()
Definition: CConnectionManager.cpp:213
mrpt::graphslam::detail::CConnectionManager::CConnectionManager
CConnectionManager(mrpt::system::COutputLogger *logger, ros::NodeHandle *nh_in)
Constructor.
Definition: CConnectionManager.cpp:85
mrpt::graphslam::detail::CConnectionManager::agents_it
mrpt_msgs::GraphSlamAgents::_list_type::iterator agents_it
Definition: CConnectionManager.h:46
mrpt::graphslam::detail::CConnectionManager
Class responsible of handling the network communication between SLAM agents in the Multi-Robot graphS...
Definition: CConnectionManager.h:40
mrpt::graphslam::detail::CConnectionManager::getNearbySlamAgentsCached
const mrpt_msgs::GraphSlamAgents & getNearbySlamAgentsCached() const
Read-only method for accessing list of nearby agents. This doesn't update the internal list of GraphS...
Definition: CConnectionManager.cpp:143
ros::ServiceClient
mrpt::graphslam::detail::CConnectionManager::m_logger
mrpt::system::COutputLogger * m_logger
Pointer to the logging instance.
Definition: CConnectionManager.h:133
mrpt::graphslam::detail::CConnectionManager::m_nearby_slam_agents
mrpt_msgs::GraphSlamAgents m_nearby_slam_agents
List of slam agents in the current agent's neighborhood.
Definition: CConnectionManager.h:143
mrpt::graphslam::detail::CConnectionManager::setupComm
void setupComm()
Wrapper method around the private setup* class methods.
Definition: CConnectionManager.cpp:204
mrpt::graphslam::detail::CConnectionManager::setupPubs
void setupPubs()
Definition: CConnectionManager.cpp:214
mrpt::graphslam::detail::CConnectionManager::has_setup_comm
bool has_setup_comm
Definition: CConnectionManager.h:145
mrpt::graphslam::detail::CConnectionManager::getNearbySlamAgents
const mrpt_msgs::GraphSlamAgents & getNearbySlamAgents()
Read-only method for accessing list of nearby agents.
Definition: CConnectionManager.cpp:148
mrpt::graphslam::detail::CConnectionManager::agents_cit
mrpt_msgs::GraphSlamAgents::_list_type::const_iterator agents_cit
Definition: CConnectionManager.h:47
mrpt::graphslam::detail::CConnectionManager::extractHostnameOrIP
static std::string extractHostnameOrIP(const std::string &str, unsigned short *agent_port=NULL)
Remove http:// prefix and port suffix from the string and return result.
Definition: CConnectionManager.cpp:303
operator<
bool operator<(const mrpt_msgs::GraphSlamAgent &agent1, const mrpt_msgs::GraphSlamAgent &agent2)
Definition: CConnectionManager.cpp:48
mrpt::graphslam::detail::CConnectionManager::updateNearbySlamAgents
void updateNearbySlamAgents()
Update the internal list of nearby SLAM agents.
Definition: CConnectionManager.cpp:154
mrpt::graphslam::detail::CConnectionManager::setupSrvs
void setupSrvs()
Definition: CConnectionManager.cpp:215
ros::NodeHandle


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Thu Sep 19 2024 02:26:31