Classes | Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T > Class Template Reference

mrpt::graphslam::CGraphSlamEngine derived class for executing multi-robot graphSLAM More...

#include <CGraphSlamEngine_MR.h>

Inheritance diagram for mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >:
Inheritance graph
[legend]

Classes

struct  TNeighborAgentProps
 Struct responsible for holding properties (nodeIDs, node positions, LaserScans) that have been registered by a nearby GraphSlamAgent. More...
 
struct  TOptions
 

Public Types

typedef GRAPH_T::constraint_t constraint_t
 
typedef mrpt::graphslam::deciders::CEdgeRegistrationDecider_MR< GRAPH_T > edge_reg_mr_t
 
typedef GRAPH_T::global_pose_t global_pose_t
 
typedef mrpt::graphs::detail::THypothesis< GRAPH_T > hypot_t
 
typedef std::vector< hypot_thypots_t
 
typedef std::vector< hypot_t * > hypotsp_t
 
typedef std::pair< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > MRPT_NodeIDWithLaserScan
 
typedef std::vector< TNeighborAgentProps * > neighbors_t
 
typedef mrpt::graphslam::detail::TNodeProps< GRAPH_T > node_props_t
 
typedef std::map< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > nodes_to_scans2D_t
 
typedef CGraphSlamEngine_ROS< GRAPH_T > parent_t
 
typedef std::vector< std::vector< TNodeID > > partitions_t
 
typedef mrpt::graphslam::TUncertaintyPath< GRAPH_T > path_t
 
typedef std::vector< path_tpaths_t
 
typedef constraint_t::type_value pose_t
 
typedef CGraphSlamEngine_MR< GRAPH_T > self_t
 
- Public Types inherited from mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_T >
typedef CGraphSlamEngine< GRAPH_T > parent
 

Public Member Functions

bool _execGraphSlamStep (mrpt::obs::CActionCollection::Ptr &action, mrpt::obs::CSensoryFrame::Ptr &observations, mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry)
 
 CGraphSlamEngine_MR (ros::NodeHandle *nh, const std::string &config_file, const std::string &rawlog_fname="", const std::string &fname_GT="", mrpt::graphslam::CWindowManager *win_manager=NULL, mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T > *node_reg=NULL, mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_T > *edge_reg=NULL, mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T > *optimizer=NULL)
 
const neighbors_tgetVecOfNeighborAgentProps () const
 
void initClass ()
 
bool isOwnNodeID (const TNodeID nodeID, const global_pose_t *pose_out=NULL) const
 Return true if current CGraphSlamEngine_MR object initially registered this nodeID, false otherwise. More...
 
 ~CGraphSlamEngine_MR ()
 
- Public Member Functions inherited from mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_T >
 CGraphSlamEngine_ROS (ros::NodeHandle *nh, const std::string &config_file, const std::string &rawlog_fname="", const std::string &fname_GT="", mrpt::graphslam::CWindowManager *win_manager=NULL, mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T > *node_reg=NULL, mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_T > *edge_reg=NULL, mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T > *optimizer=NULL)
 
void initClass ()
 Initialize object instance. More...
 
void setupComm ()
 Wrapper method around the protected setup* class methods. More...
 
virtual ~CGraphSlamEngine_ROS ()
 

Private Member Functions

bool addNodeBatchesFromAllNeighbors ()
 Traverse all neighbors for which I know the inter-graph transformation, run addNodeBatchFromNeighbor. More...
 
bool addNodeBatchFromNeighbor (TNeighborAgentProps *neighbor)
 neighbors for which I know the inter-graph transformation, add new batches of fetches nodeIDs and scans More...
 
bool findTFsWithAllNeighbors ()
 Using map-merging find a potentuial transofrmation between own graph map to another agent's map and using that transformation add other agent's nodes to own graph. More...
 
bool findTFWithNeighbor (TNeighborAgentProps *neighbor)
 Method is used only when I haven't found any transformation between mine and the current neighbor's graph. When I do find one, I just add every new nodeID + LS directly in own graph since I can now connect the new ones with the already integrated nodes of the neighbor. More...
 
void getAllOwnNodes (std::set< TNodeID > *nodes_set) const
 Fill given set with the nodeIDs that were initially registered by the current graphSLAM engine (and not by any neighboring agent. More...
 
bool getCMGraph (mrpt_msgs::GetCMGraph::Request &req, mrpt_msgs::GetCMGraph::Response &res)
 Compute and fill the Condensed Measurements Graph. More...
 
mrpt::poses::CPose3D getLSPoseForGridMapVisualization (const TNodeID nodeID) const
 
bool getNeighborByAgentID (const std::string &agent_ID_str, TNeighborAgentProps *&neighbor) const
 Fill the TNeighborAgentProps instance based on the given agent_ID_str string that is provided. More...
 
void getNodeIDsOfEstimatedTrajectory (std::set< TNodeID > *nodes_set) const
 
void getRobotEstimatedTrajectory (typename GRAPH_T::global_poses_t *graph_poses) const
 
void monitorNodeRegistration (bool registered=false, std::string class_name="Class")
 Overriden method that takes in account registration of multiple nodes of other running graphSLAM agents. More...
 
void printParams () const
 
bool pubLastRegdIDScan ()
 Update the last registered NodeID and LaserScan of the current agent. More...
 
bool pubUpdatedNodesList ()
 Update the last registered NodeIDs and corresponding positions of the current agent. More...
 
void readParams ()
 
void readROSParameters ()
 
void setObjectPropsFromNodeID (const TNodeID nodeID, mrpt::opengl::CSetOfObjects::Ptr &viz_object)
 
void setupPubs ()
 
void setupSrvs ()
 
void setupSubs ()
 
void usePublishersBroadcasters ()
 Provide feedback about the SLAM operation. More...
 

Private Attributes

ros::AsyncSpinner cm_graph_async_spinner
 AsyncSpinner that is used to query the CM-Graph service in case a new request arrives. More...
 
mrpt::slam::CGridMapAligner::TConfigParams m_alignment_options
 Parameters used during the alignment operation. More...
 
mrpt::graphslam::detail::CConnectionManager m_conn_manager
 CConnectionManager instance. More...
 
size_t m_graph_nodes_last_size
 Last known size of the m_nodes map. More...
 
TColorManager m_neighbor_colors_manager
 
std::map< TNeighborAgentProps *, bool > m_neighbor_to_found_initial_tf
 Map from neighbor instance to transformation from own to neighbor's graph. More...
 
neighbors_t m_neighbors
 GraphSlamAgent instance pointer to TNeighborAgentProps. More...
 
ros::NodeHandlem_nh
 NodeHandle pointer - inherited by the parent. Redefined here for convenience. More...
 
size_t m_nodes_to_laser_scans2D_last_size
 Last known size of the m_nodes_to_laser_scans2D map. More...
 
mrpt::graphslam::CGraphSlamEngine_MR::TOptions m_opts
 
bool m_registered_multiple_nodes
 Indicates whether multiple nodes were just registered. Used for checking correct node registration in the monitorNodeRgistration method. More...
 
std::string m_sec_alignment_params
 
std::string m_sec_mr_slam_params
 
Subscribers - Publishers

ROS Topic Subscriber/Publisher/Service instances

ros::Publisher m_list_neighbors_pub
 
ros::Publisher m_last_regd_id_scan_pub
 Publisher of the laserScan + the corresponding (last) registered node. More...
 
ros::Publisher m_last_regd_nodes_pub
 Publisher of the last registered nodeIDs and positions. More...
 
ros::ServiceServer m_cm_graph_srvserver
 
Topic Names

Names of the topics that the class instance subscribes or publishes to

std::string m_mr_ns
 Condensed Measurements topic namespace. More...
 
std::string m_list_neighbors_topic
 Name of topic at which we publish information about the agents that we can currently communicate with. More...
 
std::string m_last_regd_id_scan_topic
 Name of the topic that the last registered laser scan (+ corresponding nodeID) is published at. More...
 
std::string m_last_regd_nodes_topic
 Name of the topic that the last X registered nodes + positions are going to be published at. More...
 
std::string m_cm_graph_service
 Name of the server which is to be called when other agent wants to have a subgraph of certain nodes returned. More...
 
double m_offset_y_nrd
 Display the Deciders/Optimizers with which we are running as well as the namespace of the current agent. More...
 
double m_offset_y_erd
 
double m_offset_y_gso
 
double m_offset_y_namespace
 
int m_text_index_nrd
 
int m_text_index_erd
 
int m_text_index_gso
 
int m_text_index_namespace
 

Additional Inherited Members

- Public Attributes inherited from mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_T >
ros::NodeHandlem_nh
 
- Protected Member Functions inherited from mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_T >
void readParams ()
 Read the problem configuration parameters. More...
 
void readROSParameters ()
 Read configuration parameters from the ROS parameter server. More...
 
- Protected Attributes inherited from mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_T >
ros::CallbackQueue custom_service_queue
 Custom Callback queue for processing requests for the services outside the standard CallbackQueue. More...
 
int m_queue_size
 

Detailed Description

template<class GRAPH_T>
class mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >

mrpt::graphslam::CGraphSlamEngine derived class for executing multi-robot graphSLAM

Definition at line 61 of file CGraphSlamEngine_MR.h.

Member Typedef Documentation

◆ constraint_t

template<class GRAPH_T >
typedef GRAPH_T::constraint_t mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::constraint_t

Definition at line 66 of file CGraphSlamEngine_MR.h.

◆ edge_reg_mr_t

Definition at line 81 of file CGraphSlamEngine_MR.h.

◆ global_pose_t

template<class GRAPH_T >
typedef GRAPH_T::global_pose_t mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::global_pose_t

Definition at line 76 of file CGraphSlamEngine_MR.h.

◆ hypot_t

template<class GRAPH_T >
typedef mrpt::graphs::detail::THypothesis<GRAPH_T> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::hypot_t

Definition at line 73 of file CGraphSlamEngine_MR.h.

◆ hypots_t

template<class GRAPH_T >
typedef std::vector<hypot_t> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::hypots_t

Definition at line 74 of file CGraphSlamEngine_MR.h.

◆ hypotsp_t

template<class GRAPH_T >
typedef std::vector<hypot_t*> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::hypotsp_t

Definition at line 75 of file CGraphSlamEngine_MR.h.

◆ MRPT_NodeIDWithLaserScan

template<class GRAPH_T >
typedef std::pair<TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::MRPT_NodeIDWithLaserScan

Definition at line 69 of file CGraphSlamEngine_MR.h.

◆ neighbors_t

template<class GRAPH_T >
typedef std::vector<TNeighborAgentProps*> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::neighbors_t

Definition at line 282 of file CGraphSlamEngine_MR.h.

◆ node_props_t

template<class GRAPH_T >
typedef mrpt::graphslam::detail::TNodeProps<GRAPH_T> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::node_props_t

Definition at line 77 of file CGraphSlamEngine_MR.h.

◆ nodes_to_scans2D_t

template<class GRAPH_T >
typedef std::map<TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::nodes_to_scans2D_t

Definition at line 71 of file CGraphSlamEngine_MR.h.

◆ parent_t

template<class GRAPH_T >
typedef CGraphSlamEngine_ROS<GRAPH_T> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::parent_t

Definition at line 64 of file CGraphSlamEngine_MR.h.

◆ partitions_t

template<class GRAPH_T >
typedef std::vector<std::vector<TNodeID> > mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::partitions_t

Definition at line 72 of file CGraphSlamEngine_MR.h.

◆ path_t

template<class GRAPH_T >
typedef mrpt::graphslam::TUncertaintyPath<GRAPH_T> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::path_t

Definition at line 78 of file CGraphSlamEngine_MR.h.

◆ paths_t

template<class GRAPH_T >
typedef std::vector<path_t> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::paths_t

Definition at line 79 of file CGraphSlamEngine_MR.h.

◆ pose_t

template<class GRAPH_T >
typedef constraint_t::type_value mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::pose_t

Definition at line 67 of file CGraphSlamEngine_MR.h.

◆ self_t

template<class GRAPH_T >
typedef CGraphSlamEngine_MR<GRAPH_T> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::self_t

Definition at line 65 of file CGraphSlamEngine_MR.h.

Constructor & Destructor Documentation

◆ CGraphSlamEngine_MR()

template<class GRAPH_T >
mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::CGraphSlamEngine_MR ( ros::NodeHandle nh,
const std::string &  config_file,
const std::string &  rawlog_fname = "",
const std::string &  fname_GT = "",
mrpt::graphslam::CWindowManager *  win_manager = NULL,
mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T > *  node_reg = NULL,
mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_T > *  edge_reg = NULL,
mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T > *  optimizer = NULL 
)

Definition at line 31 of file CGraphSlamEngine_MR_impl.h.

◆ ~CGraphSlamEngine_MR()

template<class GRAPH_T >
mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::~CGraphSlamEngine_MR

Definition at line 58 of file CGraphSlamEngine_MR_impl.h.

Member Function Documentation

◆ _execGraphSlamStep()

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::_execGraphSlamStep ( mrpt::obs::CActionCollection::Ptr &  action,
mrpt::obs::CSensoryFrame::Ptr &  observations,
mrpt::obs::CObservation::Ptr &  observation,
size_t &  rawlog_entry 
)
virtual

Reimplemented from mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_T >.

Definition at line 462 of file CGraphSlamEngine_MR_impl.h.

◆ addNodeBatchesFromAllNeighbors()

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::addNodeBatchesFromAllNeighbors
private

Traverse all neighbors for which I know the inter-graph transformation, run addNodeBatchFromNeighbor.

Definition at line 72 of file CGraphSlamEngine_MR_impl.h.

◆ addNodeBatchFromNeighbor()

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::addNodeBatchFromNeighbor ( TNeighborAgentProps neighbor)
private

neighbors for which I know the inter-graph transformation, add new batches of fetches nodeIDs and scans

Try to integrate the newly received nodeIDs and laser Scans in own graph as a batch

Note
Batch integration (instead of individual nodeID + LaserScan every time a new one is received) is preferred since the neighbor is given time to optimize the node positions

Definition at line 100 of file CGraphSlamEngine_MR_impl.h.

◆ findTFsWithAllNeighbors()

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::findTFsWithAllNeighbors
private

Using map-merging find a potentuial transofrmation between own graph map to another agent's map and using that transformation add other agent's nodes to own graph.

Method delegates task to the findMatchesWithNeighboor method.

Returns
True on successful graph integration with any neighbor, false otherwise

Definition at line 225 of file CGraphSlamEngine_MR_impl.h.

◆ findTFWithNeighbor()

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::findTFWithNeighbor ( TNeighborAgentProps neighbor)
private

Method is used only when I haven't found any transformation between mine and the current neighbor's graph. When I do find one, I just add every new nodeID + LS directly in own graph since I can now connect the new ones with the already integrated nodes of the neighbor.

See also
findTFsWithAllNeighbors

Definition at line 271 of file CGraphSlamEngine_MR_impl.h.

◆ getAllOwnNodes()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::getAllOwnNodes ( std::set< TNodeID > *  nodes_set) const
private

Fill given set with the nodeIDs that were initially registered by the current graphSLAM engine (and not by any neighboring agent.

Definition at line 1068 of file CGraphSlamEngine_MR_impl.h.

◆ getCMGraph()

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::getCMGraph ( mrpt_msgs::GetCMGraph::Request &  req,
mrpt_msgs::GetCMGraph::Response &  res 
)
private

Compute and fill the Condensed Measurements Graph.

Definition at line 976 of file CGraphSlamEngine_MR_impl.h.

◆ getLSPoseForGridMapVisualization()

template<class GRAPH_T >
mrpt::poses::CPose3D mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::getLSPoseForGridMapVisualization ( const TNodeID  nodeID) const
private

Definition at line 632 of file CGraphSlamEngine_MR_impl.h.

◆ getNeighborByAgentID()

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::getNeighborByAgentID ( const std::string &  agent_ID_str,
TNeighborAgentProps *&  neighbor 
) const
private

Fill the TNeighborAgentProps instance based on the given agent_ID_str string that is provided.

Returns
False if the agent_ID_str doesn't correspond to any registered TNeighborAgentProps, True otherwise

Definition at line 665 of file CGraphSlamEngine_MR_impl.h.

◆ getNodeIDsOfEstimatedTrajectory()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::getNodeIDsOfEstimatedTrajectory ( std::set< TNodeID > *  nodes_set) const
private

Definition at line 1084 of file CGraphSlamEngine_MR_impl.h.

◆ getRobotEstimatedTrajectory()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::getRobotEstimatedTrajectory ( typename GRAPH_T::global_poses_t *  graph_poses) const
private

Definition at line 1050 of file CGraphSlamEngine_MR_impl.h.

◆ getVecOfNeighborAgentProps()

template<class GRAPH_T >
const neighbors_t& mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::getVecOfNeighborAgentProps ( ) const
inline

Definition at line 284 of file CGraphSlamEngine_MR.h.

◆ initClass()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::initClass

Definition at line 504 of file CGraphSlamEngine_MR_impl.h.

◆ isOwnNodeID()

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::isOwnNodeID ( const TNodeID  nodeID,
const global_pose_t pose_out = NULL 
) const

Return true if current CGraphSlamEngine_MR object initially registered this nodeID, false otherwise.

Parameters
[in]nodeIDnodeID for which the query is made. \exc runtime_error In case given nodeID isn't registered at all in the graph

Definition at line 862 of file CGraphSlamEngine_MR_impl.h.

◆ monitorNodeRegistration()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::monitorNodeRegistration ( bool  registered = false,
std::string  class_name = "Class" 
)
private

Overriden method that takes in account registration of multiple nodes of other running graphSLAM agents.

Definition at line 1030 of file CGraphSlamEngine_MR_impl.h.

◆ printParams()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::printParams
private

Definition at line 927 of file CGraphSlamEngine_MR_impl.h.

◆ pubLastRegdIDScan()

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::pubLastRegdIDScan
private

Update the last registered NodeID and LaserScan of the current agent.

Note
Method is automatically called from usePublishersBroadcasters, but it publishes to the corresponding topics only on new node/LS additions
Returns
true on publication to corresponding topics, false otherwise
See also
pubUpdatedNodesList

Definition at line 809 of file CGraphSlamEngine_MR_impl.h.

◆ pubUpdatedNodesList()

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::pubUpdatedNodesList
private

Update the last registered NodeIDs and corresponding positions of the current agent.

Note
Method is automatically called from usePublishersBroadcasters, but it publishes to the corresponding topics only on new node additions. Node positions may change due to optimization but we will be notified of this change anyway after a new node addition.
Returns
true on publication to corresponding topics, false otherwise
See also
pubLastRegdIDScan

Definition at line 747 of file CGraphSlamEngine_MR_impl.h.

◆ readParams()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::readParams
private

Definition at line 901 of file CGraphSlamEngine_MR_impl.h.

◆ readROSParameters()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::readROSParameters
private

Definition at line 919 of file CGraphSlamEngine_MR_impl.h.

◆ setObjectPropsFromNodeID()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::setObjectPropsFromNodeID ( const TNodeID  nodeID,
mrpt::opengl::CSetOfObjects::Ptr &  viz_object 
)
private

Definition at line 1003 of file CGraphSlamEngine_MR_impl.h.

◆ setupPubs()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::setupPubs
privatevirtual

Reimplemented from mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_T >.

Definition at line 940 of file CGraphSlamEngine_MR_impl.h.

◆ setupSrvs()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::setupSrvs
privatevirtual

Reimplemented from mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_T >.

Definition at line 962 of file CGraphSlamEngine_MR_impl.h.

◆ setupSubs()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::setupSubs
privatevirtual

Reimplemented from mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_T >.

Definition at line 935 of file CGraphSlamEngine_MR_impl.h.

◆ usePublishersBroadcasters()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::usePublishersBroadcasters
privatevirtual

Provide feedback about the SLAM operation.

Method makes the necessary calls to all the publishers of the class and broadcaster instances

Reimplemented from mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_T >.

Definition at line 687 of file CGraphSlamEngine_MR_impl.h.

Member Data Documentation

◆ cm_graph_async_spinner

template<class GRAPH_T >
ros::AsyncSpinner mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::cm_graph_async_spinner
private

AsyncSpinner that is used to query the CM-Graph service in case a new request arrives.

Definition at line 497 of file CGraphSlamEngine_MR.h.

◆ m_alignment_options

template<class GRAPH_T >
mrpt::slam::CGridMapAligner::TConfigParams mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_alignment_options
private

Parameters used during the alignment operation.

Definition at line 501 of file CGraphSlamEngine_MR.h.

◆ m_cm_graph_service

template<class GRAPH_T >
std::string mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_cm_graph_service
private

Name of the server which is to be called when other agent wants to have a subgraph of certain nodes returned.

Definition at line 456 of file CGraphSlamEngine_MR.h.

◆ m_cm_graph_srvserver

template<class GRAPH_T >
ros::ServiceServer mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_cm_graph_srvserver
private

Definition at line 429 of file CGraphSlamEngine_MR.h.

◆ m_conn_manager

template<class GRAPH_T >
mrpt::graphslam::detail::CConnectionManager mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_conn_manager
private

CConnectionManager instance.

Definition at line 464 of file CGraphSlamEngine_MR.h.

◆ m_graph_nodes_last_size

template<class GRAPH_T >
size_t mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_graph_nodes_last_size
private

Last known size of the m_nodes map.

Definition at line 471 of file CGraphSlamEngine_MR.h.

◆ m_last_regd_id_scan_pub

template<class GRAPH_T >
ros::Publisher mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_last_regd_id_scan_pub
private

Publisher of the laserScan + the corresponding (last) registered node.

Definition at line 421 of file CGraphSlamEngine_MR.h.

◆ m_last_regd_id_scan_topic

template<class GRAPH_T >
std::string mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_last_regd_id_scan_topic
private

Name of the topic that the last registered laser scan (+ corresponding nodeID) is published at.

Definition at line 447 of file CGraphSlamEngine_MR.h.

◆ m_last_regd_nodes_pub

template<class GRAPH_T >
ros::Publisher mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_last_regd_nodes_pub
private

Publisher of the last registered nodeIDs and positions.

Note
see m_num_last_regd_nodes variable for the exact number of published nodeID and position pairs.

Definition at line 427 of file CGraphSlamEngine_MR.h.

◆ m_last_regd_nodes_topic

template<class GRAPH_T >
std::string mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_last_regd_nodes_topic
private

Name of the topic that the last X registered nodes + positions are going to be published at.

Definition at line 451 of file CGraphSlamEngine_MR.h.

◆ m_list_neighbors_pub

template<class GRAPH_T >
ros::Publisher mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_list_neighbors_pub
private

Definition at line 417 of file CGraphSlamEngine_MR.h.

◆ m_list_neighbors_topic

template<class GRAPH_T >
std::string mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_list_neighbors_topic
private

Name of topic at which we publish information about the agents that we can currently communicate with.

Definition at line 443 of file CGraphSlamEngine_MR.h.

◆ m_mr_ns

template<class GRAPH_T >
std::string mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_mr_ns
private

Condensed Measurements topic namespace.

Definition at line 439 of file CGraphSlamEngine_MR.h.

◆ m_neighbor_colors_manager

template<class GRAPH_T >
TColorManager mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_neighbor_colors_manager
private

Definition at line 503 of file CGraphSlamEngine_MR.h.

◆ m_neighbor_to_found_initial_tf

template<class GRAPH_T >
std::map<TNeighborAgentProps*, bool> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_neighbor_to_found_initial_tf
private

Map from neighbor instance to transformation from own to neighbor's graph.

As long as the corresponding variable for a specific agent is False current engine keeps trying the map-matching proc to find a common transformation between own and neighbor graphs.

Definition at line 409 of file CGraphSlamEngine_MR.h.

◆ m_neighbors

template<class GRAPH_T >
neighbors_t mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_neighbors
private

GraphSlamAgent instance pointer to TNeighborAgentProps.

Note
elements of vector should persist even if the neighbor is no longer in range since they contain previous laser scans.

Definition at line 401 of file CGraphSlamEngine_MR.h.

◆ m_nh

template<class GRAPH_T >
ros::NodeHandle* mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_nh
private

NodeHandle pointer - inherited by the parent. Redefined here for convenience.

Definition at line 469 of file CGraphSlamEngine_MR.h.

◆ m_nodes_to_laser_scans2D_last_size

template<class GRAPH_T >
size_t mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_nodes_to_laser_scans2D_last_size
private

Last known size of the m_nodes_to_laser_scans2D map.

Definition at line 461 of file CGraphSlamEngine_MR.h.

◆ m_offset_y_erd

template<class GRAPH_T >
double mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_offset_y_erd
private

Definition at line 478 of file CGraphSlamEngine_MR.h.

◆ m_offset_y_gso

template<class GRAPH_T >
double mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_offset_y_gso
private

Definition at line 479 of file CGraphSlamEngine_MR.h.

◆ m_offset_y_namespace

template<class GRAPH_T >
double mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_offset_y_namespace
private

Definition at line 480 of file CGraphSlamEngine_MR.h.

◆ m_offset_y_nrd

template<class GRAPH_T >
double mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_offset_y_nrd
private

Display the Deciders/Optimizers with which we are running as well as the namespace of the current agent.

Definition at line 477 of file CGraphSlamEngine_MR.h.

◆ m_opts

template<class GRAPH_T >
mrpt::graphslam::CGraphSlamEngine_MR::TOptions mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_opts
private

◆ m_registered_multiple_nodes

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_registered_multiple_nodes
private

Indicates whether multiple nodes were just registered. Used for checking correct node registration in the monitorNodeRgistration method.

Definition at line 492 of file CGraphSlamEngine_MR.h.

◆ m_sec_alignment_params

template<class GRAPH_T >
std::string mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_sec_alignment_params
private

Definition at line 505 of file CGraphSlamEngine_MR.h.

◆ m_sec_mr_slam_params

template<class GRAPH_T >
std::string mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_sec_mr_slam_params
private

Definition at line 506 of file CGraphSlamEngine_MR.h.

◆ m_text_index_erd

template<class GRAPH_T >
int mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_text_index_erd
private

Definition at line 483 of file CGraphSlamEngine_MR.h.

◆ m_text_index_gso

template<class GRAPH_T >
int mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_text_index_gso
private

Definition at line 484 of file CGraphSlamEngine_MR.h.

◆ m_text_index_namespace

template<class GRAPH_T >
int mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_text_index_namespace
private

Definition at line 485 of file CGraphSlamEngine_MR.h.

◆ m_text_index_nrd

template<class GRAPH_T >
int mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::m_text_index_nrd
private

Definition at line 482 of file CGraphSlamEngine_MR.h.


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


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