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::utils::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
| |
void | setupSubs () |
void | setupPubs () |
void | setupSrvs () |
Static Private Member Functions | |
static bool | convert (const multimaster_msgs_fkie::ROSMaster &ros_master, mrpt_msgs::GraphSlamAgent *slam_agent) |
ROSMaster ==> mrpt_msgs::GraphSlamAgent. More... | |
static void | convert (const mrpt_msgs::GraphSlamAgent &slam_agent, multimaster_msgs_fkie::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::utils::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::NodeHandle * | m_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... | |
Class responsible of handling the network communication between SLAM agents in the Multi-Robot graphSLAM algorithm.
Definition at line 37 of file CConnectionManager.h.
typedef mrpt_msgs::GraphSlamAgents::_list_type::const_iterator mrpt::graphslam::detail::CConnectionManager::agents_cit |
Definition at line 43 of file CConnectionManager.h.
typedef mrpt_msgs::GraphSlamAgents::_list_type::iterator mrpt::graphslam::detail::CConnectionManager::agents_it |
Definition at line 42 of file CConnectionManager.h.
CConnectionManager::CConnectionManager | ( | mrpt::utils::COutputLogger * | logger, |
ros::NodeHandle * | nh_in | ||
) |
Constructor.
Definition at line 77 of file CConnectionManager.cpp.
CConnectionManager::~CConnectionManager | ( | ) |
Destructor.
Definition at line 101 of file CConnectionManager.cpp.
|
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>/...
Definition at line 220 of file CConnectionManager.cpp.
|
staticprivate |
GraphSlamAgent ==> ROSMaster.
Definition at line 276 of file CConnectionManager.cpp.
|
staticprivate |
Remove http:// prefix and port suffix from the string and return result.
[out] | agent_port | Port that the agent is running on. Extracted from the overall string |
Definition at line 294 of file CConnectionManager.cpp.
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.
[in] | ignore_self | If true the GraphSlamAgent instance that is under the same namespace as the CConnectionManager is not going to be inserted in the agents_vec |
Definition at line 107 of file CConnectionManager.cpp.
const mrpt_msgs::GraphSlamAgents & CConnectionManager::getNearbySlamAgents | ( | ) |
Read-only method for accessing list of nearby agents.
Definition at line 146 of file CConnectionManager.cpp.
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 141 of file CConnectionManager.cpp.
const std::string & CConnectionManager::getTrimmedNs | ( | ) | const |
Get the agent ROS namespace.
Definition at line 103 of file CConnectionManager.cpp.
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 199 of file CConnectionManager.cpp.
|
private |
Definition at line 209 of file CConnectionManager.cpp.
|
private |
Definition at line 210 of file CConnectionManager.cpp.
|
private |
Definition at line 208 of file CConnectionManager.cpp.
|
private |
Update the internal list of nearby SLAM agents.
Definition at line 151 of file CConnectionManager.cpp.
|
private |
Definition at line 142 of file CConnectionManager.h.
|
private |
Definition at line 134 of file CConnectionManager.h.
|
private |
Pointer to the logging instance.
Definition at line 130 of file CConnectionManager.h.
|
private |
List of slam agents in the current agent's neighborhood.
Definition at line 140 of file CConnectionManager.h.
|
private |
Pointer to the Ros NodeHanle instance.
Definition at line 132 of file CConnectionManager.h.
|
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 85 of file CConnectionManager.h.