Public Types | Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
mrpt::graphslam::detail::CConnectionManager Class Reference

Class responsible of handling the network communication between SLAM agents in the Multi-Robot graphSLAM algorithm. More...

#include <CConnectionManager.h>

Public Types

typedef mrpt_msgs::GraphSlamAgents::_list_type::const_iterator agents_cit
 
typedef mrpt_msgs::GraphSlamAgents::_list_type::iterator agents_it
 

Public Member Functions

 CConnectionManager (mrpt::system::COutputLogger *logger, ros::NodeHandle *nh_in)
 Constructor. More...
 
void getNearbySlamAgents (mrpt_msgs::GraphSlamAgents *agents_vec, bool ignore_self=true)
 Fill the given vector with the SLAM Agents that the current manager can see and communicate with. More...
 
const mrpt_msgs::GraphSlamAgents & getNearbySlamAgents ()
 Read-only method for accessing list of nearby agents. More...
 
const mrpt_msgs::GraphSlamAgents & getNearbySlamAgentsCached () const
 Read-only method for accessing list of nearby agents. This doesn't update the internal list of GraphSlamAgents but just the returns its latest cached version. More...
 
const std::string & getTrimmedNs () const
 Get the agent ROS namespace. More...
 
void setupComm ()
 Wrapper method around the private setup* class methods. More...
 
 ~CConnectionManager ()
 Destructor. More...
 

Private Member Functions

void updateNearbySlamAgents ()
 Update the internal list of nearby SLAM agents. More...
 
setup* ROS-related methods

Methods for setting up topic subscribers, publishers, and corresponding services

See also
setupComm
void setupSubs ()
 
void setupPubs ()
 
void setupSrvs ()
 

Static Private Member Functions

static bool convert (const fkie_multimaster_msgs::ROSMaster &ros_master, mrpt_msgs::GraphSlamAgent *slam_agent)
 ROSMaster ==> mrpt_msgs::GraphSlamAgent. More...
 
static void convert (const mrpt_msgs::GraphSlamAgent &slam_agent, fkie_multimaster_msgs::ROSMaster *ros_master)
 GraphSlamAgent ==> ROSMaster. More...
 
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. More...
 

Private Attributes

bool has_setup_comm
 
ros::ServiceClient m_DiscoverMasters_client
 
mrpt::system::COutputLogger * m_logger
 Pointer to the logging instance. More...
 
mrpt_msgs::GraphSlamAgents m_nearby_slam_agents
 List of slam agents in the current agent's neighborhood. More...
 
ros::NodeHandlem_nh
 Pointer to the Ros NodeHanle instance. More...
 
std::string own_ns
 Namespace under which we are running. Corresponds to the agent_ID_str with which the nodes are going to be registered in the graph. More...
 

Detailed Description

Class responsible of handling the network communication between SLAM agents in the Multi-Robot graphSLAM algorithm.

Definition at line 40 of file CConnectionManager.h.

Member Typedef Documentation

◆ agents_cit

typedef mrpt_msgs::GraphSlamAgents::_list_type::const_iterator mrpt::graphslam::detail::CConnectionManager::agents_cit

Definition at line 47 of file CConnectionManager.h.

◆ agents_it

typedef mrpt_msgs::GraphSlamAgents::_list_type::iterator mrpt::graphslam::detail::CConnectionManager::agents_it

Definition at line 46 of file CConnectionManager.h.

Constructor & Destructor Documentation

◆ CConnectionManager()

CConnectionManager::CConnectionManager ( mrpt::system::COutputLogger *  logger,
ros::NodeHandle nh_in 
)

Constructor.

Definition at line 85 of file CConnectionManager.cpp.

◆ ~CConnectionManager()

CConnectionManager::~CConnectionManager ( )

Destructor.

Definition at line 104 of file CConnectionManager.cpp.

Member Function Documentation

◆ convert() [1/2]

bool CConnectionManager::convert ( const fkie_multimaster_msgs::ROSMaster &  ros_master,
mrpt_msgs::GraphSlamAgent *  slam_agent 
)
staticprivate

ROSMaster ==> mrpt_msgs::GraphSlamAgent.

Assumption is that each ROSMaster instance holds exactly one mrpt_graphslam_2d node which publshes at a specific toic namespace -> /<hostname>_<last_IP_field>/...

Returns
False if the ros_master specified doesn't correspond to a valid GraphSlamAgent node. Should at least have a feedback topic namespace under its main topic namespace

Definition at line 226 of file CConnectionManager.cpp.

◆ convert() [2/2]

void CConnectionManager::convert ( const mrpt_msgs::GraphSlamAgent &  slam_agent,
fkie_multimaster_msgs::ROSMaster *  ros_master 
)
staticprivate

GraphSlamAgent ==> ROSMaster.

Definition at line 285 of file CConnectionManager.cpp.

◆ extractHostnameOrIP()

std::string CConnectionManager::extractHostnameOrIP ( const std::string &  str,
unsigned short *  agent_port = NULL 
)
staticprivate

Remove http:// prefix and port suffix from the string and return result.

Parameters
[out]agent_portPort that the agent is running on. Extracted from the overall string

Definition at line 303 of file CConnectionManager.cpp.

◆ getNearbySlamAgents() [1/2]

void CConnectionManager::getNearbySlamAgents ( mrpt_msgs::GraphSlamAgents *  agents_vec,
bool  ignore_self = true 
)

Fill the given vector with the SLAM Agents that the current manager can see and communicate with.

Parameters
[in]ignore_selfIf true the GraphSlamAgent instance that is under the same namespace as the CConnectionManager is not going to be inserted in the agents_vec
See also
updateNearbySlamAgents

Definition at line 108 of file CConnectionManager.cpp.

◆ getNearbySlamAgents() [2/2]

const mrpt_msgs::GraphSlamAgents & CConnectionManager::getNearbySlamAgents ( )

Read-only method for accessing list of nearby agents.

Definition at line 148 of file CConnectionManager.cpp.

◆ getNearbySlamAgentsCached()

const mrpt_msgs::GraphSlamAgents & CConnectionManager::getNearbySlamAgentsCached ( ) const

Read-only method for accessing list of nearby agents. This doesn't update the internal list of GraphSlamAgents but just the returns its latest cached version.

Definition at line 143 of file CConnectionManager.cpp.

◆ getTrimmedNs()

const std::string & CConnectionManager::getTrimmedNs ( ) const

Get the agent ROS namespace.

Definition at line 106 of file CConnectionManager.cpp.

◆ setupComm()

void CConnectionManager::setupComm ( )

Wrapper method around the private setup* class methods.

Handy for setting up publishers, subscribers, services, TF-related stuff all at once from the user application

Definition at line 204 of file CConnectionManager.cpp.

◆ setupPubs()

void CConnectionManager::setupPubs ( )
private

Definition at line 214 of file CConnectionManager.cpp.

◆ setupSrvs()

void CConnectionManager::setupSrvs ( )
private

Definition at line 215 of file CConnectionManager.cpp.

◆ setupSubs()

void CConnectionManager::setupSubs ( )
private

Definition at line 213 of file CConnectionManager.cpp.

◆ updateNearbySlamAgents()

void CConnectionManager::updateNearbySlamAgents ( )
private

Update the internal list of nearby SLAM agents.

See also
getNearbySlamAgents

Definition at line 154 of file CConnectionManager.cpp.

Member Data Documentation

◆ has_setup_comm

bool mrpt::graphslam::detail::CConnectionManager::has_setup_comm
private

Definition at line 145 of file CConnectionManager.h.

◆ m_DiscoverMasters_client

ros::ServiceClient mrpt::graphslam::detail::CConnectionManager::m_DiscoverMasters_client
private

Definition at line 137 of file CConnectionManager.h.

◆ m_logger

mrpt::system::COutputLogger* mrpt::graphslam::detail::CConnectionManager::m_logger
private

Pointer to the logging instance.

Definition at line 133 of file CConnectionManager.h.

◆ m_nearby_slam_agents

mrpt_msgs::GraphSlamAgents mrpt::graphslam::detail::CConnectionManager::m_nearby_slam_agents
private

List of slam agents in the current agent's neighborhood.

Note
vector includes the GraphSlamAgent that is at the same namespace as the current CConnectionManager instance

Definition at line 143 of file CConnectionManager.h.

◆ m_nh

ros::NodeHandle* mrpt::graphslam::detail::CConnectionManager::m_nh
private

Pointer to the Ros NodeHanle instance.

Definition at line 135 of file CConnectionManager.h.

◆ own_ns

std::string mrpt::graphslam::detail::CConnectionManager::own_ns
private

Namespace under which we are running. Corresponds to the agent_ID_str with which the nodes are going to be registered in the graph.

Definition at line 88 of file CConnectionManager.h.


The documentation for this class was generated from the following files:


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Sun Jun 26 2022 02:12:26