CGraphSlamEngine_MR.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/callback_queue.h>
13 
19 
20 #include <mrpt_msgs/NodeIDWithPoseVec.h>
21 #include <mrpt_msgs/NodeIDWithLaserScan.h>
22 #include <mrpt_msgs/NetworkOfPoses.h>
23 #include <mrpt_msgs/GetCMGraph.h> // service
25 #include <mrpt/ros1bridge/laser_scan.h>
26 #include <sensor_msgs/LaserScan.h>
27 #include <std_msgs/String.h>
28 #include <mrpt/poses/CPosePDFGaussian.h>
29 #include <mrpt/poses/CPosePDFSOG.h>
30 #include <mrpt/math/utils.h>
31 #include <mrpt/system/os.h>
32 #include <mrpt/slam/CGridMapAligner.h>
33 #include <mrpt/graphs/TMRSlamNodeAnnotations.h>
34 #include <mrpt/graphslam/misc/TUncertaintyPath.h>
35 #include <mrpt/graphslam/misc/TNodeProps.h>
36 #include <mrpt/img/TColorManager.h>
37 #include <mrpt/img/TColor.h>
38 #include <mrpt/graphs/TNodeID.h>
39 #include <mrpt/config/CConfigFileBase.h>
40 #include <mrpt/system/COutputLogger.h>
41 #include <mrpt/containers/stl_containers_utils.h>
42 
43 #include <set>
44 #include <iterator>
45 #include <algorithm>
46 
47 using namespace mrpt::img;
48 using namespace mrpt::graphs;
49 using namespace mrpt::config;
50 using namespace mrpt::system;
51 using namespace mrpt::containers;
52 
53 namespace mrpt
54 {
55 namespace graphslam
56 {
60 template <class GRAPH_T>
62 {
63  public:
66  typedef typename GRAPH_T::constraint_t constraint_t;
67  typedef typename constraint_t::type_value pose_t;
68  typedef std::pair<TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr>
70  typedef std::map<TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr>
72  typedef std::vector<std::vector<TNodeID>> partitions_t;
73  typedef typename mrpt::graphs::detail::THypothesis<GRAPH_T> hypot_t;
74  typedef std::vector<hypot_t> hypots_t;
75  typedef std::vector<hypot_t*> hypotsp_t;
76  typedef typename GRAPH_T::global_pose_t global_pose_t;
77  typedef typename mrpt::graphslam::detail::TNodeProps<GRAPH_T> node_props_t;
78  typedef mrpt::graphslam::TUncertaintyPath<GRAPH_T> path_t;
79  typedef std::vector<path_t> paths_t;
82 
84  ros::NodeHandle* nh, const std::string& config_file,
85  const std::string& rawlog_fname = "", const std::string& fname_GT = "",
86  mrpt::graphslam::CWindowManager* win_manager = NULL,
87  mrpt::graphslam::deciders::CNodeRegistrationDecider<GRAPH_T>* node_reg =
88  NULL,
89  mrpt::graphslam::deciders::CEdgeRegistrationDecider<GRAPH_T>* edge_reg =
90  NULL,
91  mrpt::graphslam::optimizers::CGraphSlamOptimizer<GRAPH_T>* optimizer =
92  NULL);
93 
95 
96  bool _execGraphSlamStep(
97  mrpt::obs::CActionCollection::Ptr& action,
98  mrpt::obs::CSensoryFrame::Ptr& observations,
99  mrpt::obs::CObservation::Ptr& observation, size_t& rawlog_entry);
100 
101  void initClass();
102 
108  {
111  CGraphSlamEngine_MR<GRAPH_T>& engine_in,
112  const mrpt_msgs::GraphSlamAgent& agent_in);
115 
118  void setupComm();
122  void setupSubs();
125  void setupSrvs();
131  void fetchUpdatedNodesList(
132  const mrpt_msgs::NodeIDWithPoseVec::ConstPtr& nodes);
133 
135  void fetchLastRegdIDScan(
136  const mrpt_msgs::NodeIDWithLaserScan::ConstPtr& last_regd_id_scan);
153  void getCachedNodes(
154  std::vector<TNodeID>* nodeIDs = NULL,
155  std::map<TNodeID, node_props_t>* nodes_params = NULL,
156  bool only_unused = true) const;
160  void fillOptPaths(
161  const std::set<TNodeID>& nodeIDs, paths_t* opt_paths) const;
165  void computeGridMap() const;
166  const mrpt::maps::COccupancyGridMap2D::Ptr& getGridMap() const;
170  void getGridMap(mrpt::maps::COccupancyGridMap2D::Ptr& map) const;
178  bool hasNewData() const;
179  std::string getAgentNs() const
180  {
181  return this->agent.topic_namespace.data;
182  }
183  void resetFlags() const;
184  bool operator==(const TNeighborAgentProps& other) const
185  {
186  return (this->agent == other.agent);
187  }
188  bool operator<(const TNeighborAgentProps& other) const
189  {
190  return (this->agent < other.agent);
191  }
195  const sensor_msgs::LaserScan* getLaserScanByNodeID(
196  const TNodeID nodeID) const;
197 
200 
204  const mrpt_msgs::GraphSlamAgent agent;
213  bool hasNewNodesBatch(int new_batch_size);
214 
219  void setTColor(const TColor& color_in) { color = color_in; }
222  TColor color;
223 
227  std::set<TNodeID> nodeIDs_set;
229  typename GRAPH_T::global_poses_t poses;
232  std::vector<mrpt_msgs::NodeIDWithLaserScan> ros_scans;
237  std::map<TNodeID, bool> nodeID_to_is_integrated;
244 
255 
256  std::string cm_graph_service;
261  mutable mrpt::maps::COccupancyGridMap2D::Ptr gridmap_cached;
262 
263  mutable bool has_new_nodes;
264  mutable bool has_new_scans;
265 
270 
279  std::pair<TNodeID, mrpt::poses::CPose2D>
281  };
282  typedef std::vector<TNeighborAgentProps*> neighbors_t;
283 
285  {
286  return m_neighbors;
287  }
294  bool isOwnNodeID(
295  const TNodeID nodeID, const global_pose_t* pose_out = NULL) const;
296 
297  private:
301  bool addNodeBatchesFromAllNeighbors();
312  bool addNodeBatchFromNeighbor(TNeighborAgentProps* neighbor);
322  bool findTFsWithAllNeighbors();
331  bool findTFWithNeighbor(TNeighborAgentProps* neighbor);
338  bool getNeighborByAgentID(
339  const std::string& agent_ID_str, TNeighborAgentProps*& neighbor) const;
351  bool pubUpdatedNodesList();
361  bool pubLastRegdIDScan();
362 
363  void usePublishersBroadcasters();
364 
365  void setupSubs();
366  void setupPubs();
367  void setupSrvs();
368 
371  bool getCMGraph(
372  mrpt_msgs::GetCMGraph::Request& req,
373  mrpt_msgs::GetCMGraph::Response& res);
374 
375  void readParams();
376  void readROSParameters();
377  void printParams() const;
378  mrpt::poses::CPose3D getLSPoseForGridMapVisualization(
379  const TNodeID nodeID) const;
380  void setObjectPropsFromNodeID(
381  const TNodeID nodeID, mrpt::opengl::CSetOfObjects::Ptr& viz_object);
386  void monitorNodeRegistration(
387  bool registered = false, std::string class_name = "Class");
391  void getAllOwnNodes(std::set<TNodeID>* nodes_set) const;
392  void getNodeIDsOfEstimatedTrajectory(std::set<TNodeID>* nodes_set) const;
393  void getRobotEstimatedTrajectory(
394  typename GRAPH_T::global_poses_t* graph_poses) const;
395 
409  std::map<TNeighborAgentProps*, bool> m_neighbor_to_found_initial_tf;
410 
428 
439  std::string m_mr_ns;
452 
456  std::string m_cm_graph_service;
457 
462 
465 
472 
481 
493 
498 
501  mrpt::slam::CGridMapAligner::TConfigParams m_alignment_options;
502 
504 
506  std::string m_sec_mr_slam_params;
507 
508  struct TOptions : CLoadableOptions
509  {
511 
512  TOptions(const engine_mr_t& engine_in);
513  ~TOptions();
514  void loadFromConfigFile(
515  const CConfigFileBase& source, const std::string& section);
516  void dumpToTextStream(std::ostream& out) const;
517 
551 
554 
555  } m_opts;
556 };
557 
558 } // namespace graphslam
559 } // namespace mrpt
560 
561 // pseudo-split decleration from implementation
mrpt::graphslam::CGraphSlamEngine_MR::m_offset_y_nrd
double m_offset_y_nrd
Display the Deciders/Optimizers with which we are running as well as the namespace of the current age...
Definition: CGraphSlamEngine_MR.h:477
CGraphSlamEngine_ROS.h
mrpt::graphslam::CGraphSlamEngine_MR::m_alignment_options
mrpt::slam::CGridMapAligner::TConfigParams m_alignment_options
Parameters used during the alignment operation.
Definition: CGraphSlamEngine_MR.h:501
mrpt::graphslam::CGraphSlamEngine_MR::m_text_index_namespace
int m_text_index_namespace
Definition: CGraphSlamEngine_MR.h:485
mrpt::graphslam::CGraphSlamEngine_MR::m_neighbor_colors_manager
TColorManager m_neighbor_colors_manager
Definition: CGraphSlamEngine_MR.h:503
ros::Publisher
mrpt::graphslam::CGraphSlamEngine_MR::m_offset_y_gso
double m_offset_y_gso
Definition: CGraphSlamEngine_MR.h:479
mrpt::graphslam::CGraphSlamEngine_MR::m_sec_mr_slam_params
std::string m_sec_mr_slam_params
Definition: CGraphSlamEngine_MR.h:506
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::operator==
bool operator==(const TNeighborAgentProps &other) const
Definition: CGraphSlamEngine_MR.h:184
CConnectionManager.h
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::last_regd_nodes_sub
ros::Subscriber last_regd_nodes_sub
Definition: CGraphSlamEngine_MR.h:242
mrpt::graphslam::CGraphSlamEngine_MR::TOptions::inter_group_node_count_thresh
size_t inter_group_node_count_thresh
Lowest number of nodes that should exist in a group of nodes before evaluating it....
Definition: CGraphSlamEngine_MR.h:546
mrpt::graphslam::CGraphSlamEngine_MR::m_last_regd_id_scan_topic
std::string m_last_regd_id_scan_topic
Name of the topic that the last registered laser scan (+ corresponding nodeID) is published at.
Definition: CGraphSlamEngine_MR.h:447
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::has_new_scans
bool has_new_scans
Definition: CGraphSlamEngine_MR.h:264
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::color
TColor color
Unique color of current TNeighborAgentProps instance.
Definition: CGraphSlamEngine_MR.h:222
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::nodeIDs_set
std::set< TNodeID > nodeIDs_set
NodeIDs that I have received from this graphSLAM agent.
Definition: CGraphSlamEngine_MR.h:227
mrpt::graphslam::CGraphSlamEngine_MR::hypots_t
std::vector< hypot_t > hypots_t
Definition: CGraphSlamEngine_MR.h:74
mrpt::graphslam::CGraphSlamEngine_MR::self_t
CGraphSlamEngine_MR< GRAPH_T > self_t
Definition: CGraphSlamEngine_MR.h:65
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::cm_graph_srvclient
ros::ServiceClient cm_graph_srvclient
Definition: CGraphSlamEngine_MR.h:245
mrpt::graphslam::CGraphSlamEngine_MR::m_offset_y_erd
double m_offset_y_erd
Definition: CGraphSlamEngine_MR.h:478
mrpt::graphslam::CGraphSlamEngine_MR::TOptions::nodes_integration_batch_size
int nodes_integration_batch_size
After an inter-graph transformation is found between own graph and a neighbor's map,...
Definition: CGraphSlamEngine_MR.h:530
ros::AsyncSpinner
network_of_poses.h
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::nh
ros::NodeHandle * nh
NodeHandle passed by the calling CGraphSlamEngine_MR class.
Definition: CGraphSlamEngine_MR.h:268
mrpt::graphslam::CGraphSlamEngine_MR::node_props_t
mrpt::graphslam::detail::TNodeProps< GRAPH_T > node_props_t
Definition: CGraphSlamEngine_MR.h:77
mrpt::graphslam::CGraphSlamEngine_MR::m_nh
ros::NodeHandle * m_nh
NodeHandle pointer - inherited by the parent. Redefined here for convenience.
Definition: CGraphSlamEngine_MR.h:469
mrpt::graphslam::CGraphSlamEngine_MR::m_cm_graph_service
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 r...
Definition: CGraphSlamEngine_MR.h:456
mrpt::graphslam::CGraphSlamEngine_MR::hypotsp_t
std::vector< hypot_t * > hypotsp_t
Definition: CGraphSlamEngine_MR.h:75
mrpt::graphslam::CGraphSlamEngine_MR::m_last_regd_id_scan_pub
ros::Publisher m_last_regd_id_scan_pub
Publisher of the laserScan + the corresponding (last) registered node.
Definition: CGraphSlamEngine_MR.h:421
mrpt
Definition: CConnectionManager.h:31
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::ros_scans
std::vector< mrpt_msgs::NodeIDWithLaserScan > ros_scans
ROS LaserScans that I have received from this graphSLAM agent.
Definition: CGraphSlamEngine_MR.h:232
mrpt::graphslam::CGraphSlamEngine_MR::neighbors_t
std::vector< TNeighborAgentProps * > neighbors_t
Definition: CGraphSlamEngine_MR.h:282
CEdgeRegistrationDecider_MR.h
ros::ServiceServer
mrpt::graphslam::CGraphSlamEngine_MR::TOptions::inter_group_node_count_thresh_minadv
size_t inter_group_node_count_thresh_minadv
Minimum advised limit of inter_group_node_count_thresh.
Definition: CGraphSlamEngine_MR.h:550
mrpt::graphslam::CGraphSlamEngine_MR::m_text_index_nrd
int m_text_index_nrd
Definition: CGraphSlamEngine_MR.h:482
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::operator<
bool operator<(const TNeighborAgentProps &other) const
Definition: CGraphSlamEngine_MR.h:188
CRegistrationDeciderOrOptimizer_MR.h
mrpt::graphslam::CGraphSlamEngine_MR::m_text_index_erd
int m_text_index_erd
Definition: CGraphSlamEngine_MR.h:483
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::setTColor
void setTColor(const TColor &color_in)
Set the color related to the current neighbor agent.
Definition: CGraphSlamEngine_MR.h:219
mrpt::graphslam::CGraphSlamEngine_MR::m_mr_ns
std::string m_mr_ns
Condensed Measurements topic namespace.
Definition: CGraphSlamEngine_MR.h:439
mrpt::graphslam::CGraphSlamEngine_MR::path_t
mrpt::graphslam::TUncertaintyPath< GRAPH_T > path_t
Definition: CGraphSlamEngine_MR.h:78
mrpt::graphslam::CGraphSlamEngine_MR::TOptions::engine
const engine_mr_t & engine
Definition: CGraphSlamEngine_MR.h:553
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::agent
const mrpt_msgs::GraphSlamAgent agent
Definition: CGraphSlamEngine_MR.h:204
mrpt::graphslam::CGraphSlamEngine_ROS
Class template that provides a wrapper around the MRPT CGraphSlamEngine class template and implements...
Definition: CGraphSlamEngine_ROS.h:25
mrpt::graphslam::CGraphSlamEngine_MR::m_graph_nodes_last_size
size_t m_graph_nodes_last_size
Last known size of the m_nodes map.
Definition: CGraphSlamEngine_MR.h:471
mrpt::graphslam::CGraphSlamEngine_MR::m_neighbors
neighbors_t m_neighbors
GraphSlamAgent instance pointer to TNeighborAgentProps.
Definition: CGraphSlamEngine_MR.h:401
mrpt::graphslam::CGraphSlamEngine_MR::m_nodes_to_laser_scans2D_last_size
size_t m_nodes_to_laser_scans2D_last_size
Last known size of the m_nodes_to_laser_scans2D map.
Definition: CGraphSlamEngine_MR.h:461
mrpt::graphslam::CGraphSlamEngine_MR::cm_graph_async_spinner
ros::AsyncSpinner cm_graph_async_spinner
AsyncSpinner that is used to query the CM-Graph service in case a new request arrives.
Definition: CGraphSlamEngine_MR.h:497
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::last_integrated_pair_neighbor_frame
std::pair< TNodeID, mrpt::poses::CPose2D > last_integrated_pair_neighbor_frame
Last nodeID/CPose2D of neighbor that was integrated - Pose is taken with regards to neighbor's frame ...
Definition: CGraphSlamEngine_MR.h:280
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::tf_self_to_neighbor_first_integrated_pose
mrpt::poses::CPose2D tf_self_to_neighbor_first_integrated_pose
CPose2D connecting own graph origin to neighbor first received and integrated node....
Definition: CGraphSlamEngine_MR.h:275
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps
Struct responsible for holding properties (nodeIDs, node positions, LaserScans) that have been regist...
Definition: CGraphSlamEngine_MR.h:107
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::CGraphSlamEngine_MR::TNeighborAgentProps::nodeID_to_is_integrated
std::map< TNodeID, bool > nodeID_to_is_integrated
Have I already integrated this node in my graph?
Definition: CGraphSlamEngine_MR.h:237
mrpt::graphslam::CGraphSlamEngine_MR::TOptions::engine_mr_t
self_t engine_mr_t
Definition: CGraphSlamEngine_MR.h:510
ros::ServiceClient
mrpt::graphslam::CGraphSlamEngine_MR::TOptions
Definition: CGraphSlamEngine_MR.h:508
mrpt::graphslam::CGraphSlamEngine_MR::m_neighbor_to_found_initial_tf
std::map< TNeighborAgentProps *, bool > m_neighbor_to_found_initial_tf
Map from neighbor instance to transformation from own to neighbor's graph.
Definition: CGraphSlamEngine_MR.h:409
mrpt::graphslam::CGraphSlamEngine_MR::nodes_to_scans2D_t
std::map< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > nodes_to_scans2D_t
Definition: CGraphSlamEngine_MR.h:71
mrpt::graphslam::CGraphSlamEngine_MR::getVecOfNeighborAgentProps
const neighbors_t & getVecOfNeighborAgentProps() const
Definition: CGraphSlamEngine_MR.h:284
mrpt::graphslam::CGraphSlamEngine_MR::m_last_regd_nodes_topic
std::string m_last_regd_nodes_topic
Name of the topic that the last X registered nodes + positions are going to be published at.
Definition: CGraphSlamEngine_MR.h:451
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::engine
CGraphSlamEngine_MR< GRAPH_T > & engine
Definition: CGraphSlamEngine_MR.h:199
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::gridmap_cached
mrpt::maps::COccupancyGridMap2D::Ptr gridmap_cached
Pointer to the gridmap object of the neighbor.
Definition: CGraphSlamEngine_MR.h:261
callback_queue.h
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::poses
GRAPH_T::global_poses_t poses
Poses that I have received from this graphSLAM agent.
Definition: CGraphSlamEngine_MR.h:229
mrpt::graphslam::CGraphSlamEngine_MR::partitions_t
std::vector< std::vector< TNodeID > > partitions_t
Definition: CGraphSlamEngine_MR.h:72
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::getAgentNs
std::string getAgentNs() const
Definition: CGraphSlamEngine_MR.h:179
mrpt::graphslam::CGraphSlamEngine_MR::MRPT_NodeIDWithLaserScan
std::pair< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > MRPT_NodeIDWithLaserScan
Definition: CGraphSlamEngine_MR.h:69
mrpt::graphslam::CGraphSlamEngine_MR::m_list_neighbors_pub
ros::Publisher m_list_neighbors_pub
Definition: CGraphSlamEngine_MR.h:417
common.h
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::last_regd_id_scan_sub
ros::Subscriber last_regd_id_scan_sub
Definition: CGraphSlamEngine_MR.h:243
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::last_regd_id_scan_topic
std::string last_regd_id_scan_topic
Definition: CGraphSlamEngine_MR.h:254
mrpt::graphslam::CGraphSlamEngine_MR::edge_reg_mr_t
mrpt::graphslam::deciders::CEdgeRegistrationDecider_MR< GRAPH_T > edge_reg_mr_t
Definition: CGraphSlamEngine_MR.h:81
mrpt::graphslam::CGraphSlamEngine_MR::TOptions::num_last_regd_nodes
int num_last_regd_nodes
Max number of last registered NodeIDs + corresponding positions to publish.
Definition: CGraphSlamEngine_MR.h:538
mrpt::graphslam::CGraphSlamEngine_MR::parent_t
CGraphSlamEngine_ROS< GRAPH_T > parent_t
Definition: CGraphSlamEngine_MR.h:64
mrpt::graphslam::CGraphSlamEngine_MR::TOptions::conservative_find_initial_tfs_to_neighbors
bool conservative_find_initial_tfs_to_neighbors
Be conservative when it comes to deciding the initial transformation of own graph with regards to gra...
Definition: CGraphSlamEngine_MR.h:525
mrpt::graphslam::CGraphSlamEngine_MR::m_cm_graph_srvserver
ros::ServiceServer m_cm_graph_srvserver
Definition: CGraphSlamEngine_MR.h:429
mrpt::graphslam::CGraphSlamEngine_MR::m_last_regd_nodes_pub
ros::Publisher m_last_regd_nodes_pub
Publisher of the last registered nodeIDs and positions.
Definition: CGraphSlamEngine_MR.h:427
mrpt::graphslam::CGraphSlamEngine_MR
mrpt::graphslam::CGraphSlamEngine derived class for executing multi-robot graphSLAM
Definition: CGraphSlamEngine_MR.h:61
mrpt::graphslam::CGraphSlamEngine_MR::m_sec_alignment_params
std::string m_sec_alignment_params
Definition: CGraphSlamEngine_MR.h:505
mrpt::graphslam::CGraphSlamEngine_MR::m_registered_multiple_nodes
bool m_registered_multiple_nodes
Indicates whether multiple nodes were just registered. Used for checking correct node registration in...
Definition: CGraphSlamEngine_MR.h:492
mrpt::graphslam::CGraphSlamEngine_MR::pose_t
constraint_t::type_value pose_t
Definition: CGraphSlamEngine_MR.h:67
CGraphSlamEngine_MR_impl.h
mrpt::graphslam::CGraphSlamEngine_MR::m_conn_manager
mrpt::graphslam::detail::CConnectionManager m_conn_manager
CConnectionManager instance.
Definition: CGraphSlamEngine_MR.h:464
mrpt::graphslam::CGraphSlamEngine_MR::m_offset_y_namespace
double m_offset_y_namespace
Definition: CGraphSlamEngine_MR.h:480
mrpt::graphslam::deciders::CEdgeRegistrationDecider_MR
Edge Registration Decider virtual method.
Definition: CEdgeRegistrationDecider_MR.h:43
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::has_setup_comm
bool has_setup_comm
Definition: CGraphSlamEngine_MR.h:269
mrpt::graphslam::CGraphSlamEngine_MR::constraint_t
GRAPH_T::constraint_t constraint_t
Definition: CGraphSlamEngine_MR.h:66
mrpt::graphslam::CGraphSlamEngine_MR::m_text_index_gso
int m_text_index_gso
Definition: CGraphSlamEngine_MR.h:484
mrpt::graphslam::CGraphSlamEngine_MR::paths_t
std::vector< path_t > paths_t
Definition: CGraphSlamEngine_MR.h:79
mrpt::graphslam::CGraphSlamEngine_MR::hypot_t
mrpt::graphs::detail::THypothesis< GRAPH_T > hypot_t
Definition: CGraphSlamEngine_MR.h:73
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::last_regd_nodes_topic
std::string last_regd_nodes_topic
Definition: CGraphSlamEngine_MR.h:253
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::has_new_nodes
bool has_new_nodes
Definition: CGraphSlamEngine_MR.h:263
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::m_queue_size
int m_queue_size
Definition: CGraphSlamEngine_MR.h:266
mrpt::graphslam::CGraphSlamEngine_MR::TNeighborAgentProps::cm_graph_service
std::string cm_graph_service
Definition: CGraphSlamEngine_MR.h:256
ros::NodeHandle
ros::Subscriber
mrpt::graphslam::CGraphSlamEngine_MR::global_pose_t
GRAPH_T::global_pose_t global_pose_t
Definition: CGraphSlamEngine_MR.h:76
mrpt::graphslam::CGraphSlamEngine_MR::m_list_neighbors_topic
std::string m_list_neighbors_topic
Name of topic at which we publish information about the agents that we can currently communicate with...
Definition: CGraphSlamEngine_MR.h:443


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