CGraphSlamEngine_MR_impl.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 <chrono>
13 #include <thread>
14 #include <mrpt_msgs/GetCMGraph.h>
16 #include <mrpt/ros1bridge/pose.h>
17 
18 #include <mrpt/math/CMatrixFixed.h>
19 namespace mrpt::math
20 {
21 // backwards compatible
22 template <typename T, std::size_t ROWS, std::size_t COLS>
23 using CMatrixFixedNumeric = CMatrixFixed<T, ROWS, COLS>;
24 } // namespace mrpt::math
25 
26 namespace mrpt
27 {
28 namespace graphslam
29 {
30 template <class GRAPH_T>
32  ros::NodeHandle* nh, const std::string& config_file,
33  const std::string& rawlog_fname /* ="" */,
34  const std::string& fname_GT /* ="" */,
35  mrpt::graphslam::CWindowManager* win_manager /* = NULL */,
36  mrpt::graphslam::deciders::CNodeRegistrationDecider<GRAPH_T>*
37  node_reg /* = NULL */,
38  mrpt::graphslam::deciders::CEdgeRegistrationDecider<GRAPH_T>*
39  edge_reg /* = NULL */,
40  mrpt::graphslam::optimizers::CGraphSlamOptimizer<GRAPH_T>*
41  optimizer /* = NULL */)
43  nh, config_file, rawlog_fname, fname_GT, win_manager, node_reg,
44  edge_reg, optimizer),
45  m_conn_manager(dynamic_cast<mrpt::system::COutputLogger*>(this), nh),
46  m_nh(nh),
47  m_graph_nodes_last_size(0),
48  m_registered_multiple_nodes(false),
49  cm_graph_async_spinner(/* threads_num: */ 1, &this->custom_service_queue),
50  m_sec_alignment_params("AlignmentParameters"),
51  m_sec_mr_slam_params("MultiRobotParameters"),
52  m_opts(*this)
53 {
54  this->initClass();
55 }
56 
57 template <class GRAPH_T>
59 {
60  MRPT_LOG_DEBUG_STREAM(
61  "In Destructor: Deleting CGraphSlamEngine_MR instance...");
63 
64  for (typename neighbors_t::iterator neighbors_it = m_neighbors.begin();
65  neighbors_it != m_neighbors.end(); ++neighbors_it)
66  {
67  delete *neighbors_it;
68  }
69 }
70 
71 template <class GRAPH_T>
73 {
74  MRPT_START;
75  using namespace mrpt::graphslam::detail;
76 
77  bool ret_val = false;
78  for (const auto& neighbor : m_neighbors)
79  {
80  if (!isEssentiallyZero(
81  neighbor
82  ->tf_self_to_neighbor_first_integrated_pose) && // inter-graph
83  // TF found
84  neighbor->hasNewData() &&
85  neighbor->hasNewNodesBatch(m_opts.nodes_integration_batch_size))
86  {
87  bool loc_ret_val = this->addNodeBatchFromNeighbor(neighbor);
88  if (loc_ret_val)
89  {
90  ret_val = true;
91  }
92  }
93  }
94 
95  return ret_val;
96  MRPT_END;
97 } // end of addNodeBatchesFromAllNeighbors
98 
99 template <class GRAPH_T>
101  TNeighborAgentProps* neighbor)
102 {
103  MRPT_START;
104  ASSERT_(neighbor);
105  using namespace mrpt::poses;
106  using namespace mrpt::math;
107  using namespace std;
108 
109  std::vector<TNodeID> nodeIDs;
110  std::map<TNodeID, node_props_t> nodes_params;
111  neighbor->getCachedNodes(&nodeIDs, &nodes_params, /*only unused=*/true);
112 
113  //
114  // get the condensed measurements graph of the new nodeIDs
115  //
116  mrpt_msgs::GetCMGraph cm_graph_srv;
117  // mrpt_msgs::GetCMGraphRequest::_nodeIDs_type& cm_graph_nodes =
118  // cm_graph_srv.request.node_ids;
119  for (const auto n : nodeIDs)
120  {
121  cm_graph_srv.request.node_ids.push_back(n);
122  }
123 
124  MRPT_LOG_DEBUG_STREAM("Asking for the graph.");
125  bool res = neighbor->cm_graph_srvclient.call(cm_graph_srv); // blocking
126  if (!res)
127  {
128  MRPT_LOG_ERROR_STREAM("Service call for CM_Graph failed.");
129  return false; // skip this if failed to fetch other's graph
130  }
131  MRPT_LOG_DEBUG_STREAM("Fetched graph successfully.");
132  MRPT_LOG_DEBUG_STREAM(cm_graph_srv.response.cm_graph);
133 
134  GRAPH_T other_graph;
135  mrpt_msgs_bridge::fromROS(cm_graph_srv.response.cm_graph, other_graph);
136 
137  //
138  // merge batch of nodes in own graph
139  //
140  MRPT_LOG_WARN_STREAM(
141  "Merging new batch from \""
142  << neighbor->getAgentNs() << "\"..." << endl
143  << "Batch: " << getSTLContainerAsString(cm_graph_srv.request.node_ids));
144  hypots_t graph_conns;
145  // build a hypothesis connecting the new batch with the last integrated
146  // pose of the neighbor
147  {
148  pair<TNodeID, node_props_t> node_props_to_connect =
149  *nodes_params.begin();
150 
151  hypot_t graph_conn;
152  constraint_t c;
153  c.mean = node_props_to_connect.second.pose -
154  neighbor->last_integrated_pair_neighbor_frame.second;
155  c.cov_inv.setIdentity();
156  graph_conn.setEdge(c);
157 
158  graph_conn.from = INVALID_NODEID;
159  // get the nodeID of the last integrated neighbor node after remapping
160  // in own graph numbering
161  for (const auto n : this->m_graph.nodes)
162  {
163  if (n.second.agent_ID_str == neighbor->getAgentNs() &&
164  n.second.nodeID_loc ==
165  neighbor->last_integrated_pair_neighbor_frame.first)
166  {
167  graph_conn.from = n.first;
168  break;
169  }
170  }
171  ASSERT_(graph_conn.from != INVALID_NODEID);
172  graph_conn.to = node_props_to_connect.first; // other
173 
174  MRPT_LOG_DEBUG_STREAM(
175  "Hypothesis for adding the batch of nodes: " << graph_conn);
176  graph_conns.push_back(graph_conn);
177  }
178 
179  std::map<TNodeID, TNodeID> old_to_new_mappings;
180  this->m_graph.mergeGraph(
181  other_graph, graph_conns,
182  /*hypots_from_other_to_self=*/false, &old_to_new_mappings);
183 
184  //
185  // Mark Nodes/LaserScans as integrated
186  //
187  MRPT_LOG_WARN_STREAM("Marking used nodes as integrated - Integrating LSs");
188  nodes_to_scans2D_t new_nodeIDs_to_scans_pairs;
189  for (typename std::vector<TNodeID>::const_iterator n_cit = nodeIDs.begin();
190  n_cit != nodeIDs.end(); ++n_cit)
191  {
192  // Mark the neighbor's used nodes as integrated
193  neighbor->nodeID_to_is_integrated.at(*n_cit) = true;
194 
195  // Integrate LaserScans at the newly integrated nodeIDs in own
196  // nodes_to_laser_scans2D map
197  new_nodeIDs_to_scans_pairs.insert(make_pair(
198  old_to_new_mappings.at(*n_cit), nodes_params.at(*n_cit).scan));
199  MRPT_LOG_INFO_STREAM(
200  "Adding nodeID-LS of nodeID: "
201  << "\t[old:] " << *n_cit << endl
202  << "| [new:] " << old_to_new_mappings.at(*n_cit));
203  }
204 
205  this->m_nodes_to_laser_scans2D.insert(
206  new_nodeIDs_to_scans_pairs.begin(), new_nodeIDs_to_scans_pairs.end());
207  edge_reg_mr_t* edge_reg_mr = dynamic_cast<edge_reg_mr_t*>(this->m_edge_reg);
208  edge_reg_mr->addBatchOfNodeIDsAndScans(new_nodeIDs_to_scans_pairs);
209 
210  this->execDijkstraNodesEstimation();
211  neighbor->resetFlags();
212 
213  // keep track of the last integrated nodeID
214  {
215  TNodeID last_node = *nodeIDs.rbegin();
217  make_pair(last_node, nodes_params.at(last_node).pose);
218  }
219 
220  return true;
221  MRPT_END;
222 } // end of addNodeBatchFromNeighbor
223 
224 template <class GRAPH_T>
226 {
227  MRPT_START;
228  using namespace mrpt::math;
229 
230  if (this->m_graph.nodeCount() < m_opts.inter_group_node_count_thresh)
231  {
232  return false;
233  }
234 
235  // cache the gridmap so that it is computed only once during all the
236  // findMatches* calls
237  this->computeMap();
238 
239  bool ret_val = false; // at *any* node registration, change to true
240 
241  // iterate over all neighbors - run map-matching proc.
242  for (typename neighbors_t::iterator neighbors_it = m_neighbors.begin();
243  neighbors_it != m_neighbors.end(); ++neighbors_it)
244  {
245  // run matching proc with neighbor only if I haven't found an initial
246  // inter-graph TF
247  if (!m_neighbor_to_found_initial_tf.at(*neighbors_it))
248  {
249  bool loc_ret_val = findTFWithNeighbor(*neighbors_it);
250  if (loc_ret_val)
251  {
252  MRPT_LOG_DEBUG_STREAM(
253  "Updating own cached map after successful node "
254  "registration...");
255  // update own map if new nodes have been added.
256  this->computeMap();
257 
258  // mark current neighbor tf as found.
259  m_neighbor_to_found_initial_tf.at(*neighbors_it) = true;
260 
261  ret_val = true;
262  }
263  }
264  }
265 
266  return ret_val;
267  MRPT_END;
268 } // end of findTFsWithAllNeighbors
269 
270 template <class GRAPH_T>
272  TNeighborAgentProps* neighbor)
273 {
274  MRPT_START;
275  using namespace mrpt::slam;
276  using namespace mrpt::math;
277  using namespace mrpt::poses;
278  using namespace mrpt::maps;
279  using namespace mrpt::graphslam::detail;
280 
281  bool ret_val = false;
282 
283  std::vector<TNodeID> neighbor_nodes;
284  std::map<TNodeID, node_props_t> nodes_params;
285  neighbor->getCachedNodes(
286  &neighbor_nodes, &nodes_params,
287  /*only unused=*/false);
288  if (neighbor_nodes.size() < m_opts.inter_group_node_count_thresh ||
289  !neighbor->hasNewData())
290  {
291  return false;
292  }
293 
294  //
295  // run alignment procedure
296  //
297  COccupancyGridMap2D::Ptr neighbor_gridmap = neighbor->getGridMap();
298  CGridMapAligner gridmap_aligner;
299  gridmap_aligner.options = m_alignment_options;
300 
301  CGridMapAligner::TReturnInfo results;
302 
303  // TODO - make use of agents' rendez-vous in the initial estimation
304  CPosePDFGaussian init_estim;
305  init_estim.mean = neighbor->tf_self_to_neighbor_first_integrated_pose;
306  this->logFmt(
307  LVL_INFO, "Trying to align the maps, initial estimation: %s",
308  init_estim.mean.asString().c_str());
309 
310  // Save them for debugging reasons
311  // neighbor_gridmap->saveMetricMapRepresentationToFile(this->getLoggerName()
312  // +
313  // "_other");
314  // this->m_gridmap_cached->saveMetricMapRepresentationToFile(this->getLoggerName()
315  // + "_self");
316 
317  TMetricMapAlignmentResult alignRes;
318 
319  const CPosePDF::Ptr pdf_tmp = gridmap_aligner.AlignPDF(
320  this->m_gridmap_cached.get(), neighbor_gridmap.get(), init_estim,
321  alignRes);
322 
323  const auto run_time = alignRes.executionTime;
324 
325  this->logFmt(LVL_INFO, "Elapsed Time: %f", run_time);
326  CPosePDFSOG::Ptr pdf_out = CPosePDFSOG::Create();
327  pdf_out->copyFrom(*pdf_tmp);
328 
329  CPose2D pose_out;
330  CMatrixDouble33 cov_out;
331  pdf_out->getMostLikelyCovarianceAndMean(cov_out, pose_out);
332 
333  this->logFmt(
334  LVL_INFO, "%s\n",
335  getGridMapAlignmentResultsAsString(*pdf_tmp, results).c_str());
336 
337  // dismiss this?
338  if (results.goodness > 0.999 || isEssentiallyZero(pose_out))
339  {
340  return false;
341  }
342 
343  //
344  //
345  // Map-merging operation is successful. Integrate graph into own.
347 
348  //
349  // ask for condensed measurements graph
350  //
351  mrpt_msgs::GetCMGraph cm_graph_srv;
352  typedef mrpt_msgs::GetCMGraphRequest::_node_ids_type node_id_type;
353  node_id_type& matched_nodeIDs = cm_graph_srv.request.node_ids;
354 
355  // which nodes to ask the condensed graph for
356  // I assume that no nodes of the other graph have been integrated yet.
357  for (typename std::vector<TNodeID>::const_iterator n_cit =
358  neighbor_nodes.begin();
359  n_cit != neighbor_nodes.end(); ++n_cit)
360  {
361  matched_nodeIDs.push_back(*n_cit); // all used nodes
362  }
363 
364  MRPT_LOG_DEBUG_STREAM("Asking for the graph.");
365  bool res = neighbor->cm_graph_srvclient.call(cm_graph_srv); // blocking
366  if (!res)
367  {
368  MRPT_LOG_ERROR_STREAM("Service call for CM_Graph failed.");
369  return false; // skip this if failed to fetch other's graph
370  }
371  MRPT_LOG_DEBUG_STREAM("Fetched graph successfully.");
372  MRPT_LOG_DEBUG_STREAM(cm_graph_srv.response.cm_graph);
373 
374  GRAPH_T other_graph;
375  mrpt_msgs_bridge::fromROS(cm_graph_srv.response.cm_graph, other_graph);
376 
377  //
378  // merge graphs
379  //
380  MRPT_LOG_WARN_STREAM(
381  "Merging graph of \"" << neighbor->getAgentNs() << "\"...");
382  hypots_t graph_conns;
383  // build the only hypothesis connecting graph with neighbor subgraph
384  // own origin -> first valid nodeID of neighbor
385  {
386  hypot_t graph_conn;
387  constraint_t c;
388  c.mean = pose_out;
389  // assign the inverse of the found covariance to c
390  cov_out = c.cov_inv.inverse();
391  graph_conn.setEdge(c);
392  // TODO - change this.
393  graph_conn.from = 0; // self
394  graph_conn.to = *neighbor_nodes.begin(); // other
395 
396  graph_conn.goodness = results.goodness;
397  graph_conns.push_back(graph_conn);
398  }
399 
400  std::map<TNodeID, TNodeID> old_to_new_mappings;
401  this->m_graph.mergeGraph(
402  other_graph, graph_conns,
403  /*hypots_from_other_to_self=*/false, &old_to_new_mappings);
404 
405  //
406  // Mark Nodes/LaserScans as integrated
407  //
408  MRPT_LOG_WARN_STREAM("Marking used nodes as integrated - Integrating LSs");
409  nodes_to_scans2D_t new_nodeIDs_to_scans_pairs;
410  for (typename std::vector<TNodeID>::const_iterator n_cit =
411  neighbor_nodes.begin();
412  n_cit != neighbor_nodes.end(); ++n_cit)
413  {
414  // Mark the neighbor's used nodes as integrated
415  neighbor->nodeID_to_is_integrated.at(*n_cit) = true;
416 
417  // Integrate LaserScans at the newly integrated nodeIDs in own
418  // nodes_to_laser_scans2D map
419  new_nodeIDs_to_scans_pairs.insert(make_pair(
420  old_to_new_mappings.at(*n_cit), nodes_params.at(*n_cit).scan));
421  MRPT_LOG_INFO_STREAM(
422  "Adding nodeID-LS of nodeID: "
423  << "\t[old:] " << *n_cit << endl
424  << "| [new:] " << old_to_new_mappings.at(*n_cit));
425  }
426 
427  this->m_nodes_to_laser_scans2D.insert(
428  new_nodeIDs_to_scans_pairs.begin(), new_nodeIDs_to_scans_pairs.end());
429  edge_reg_mr_t* edge_reg_mr = dynamic_cast<edge_reg_mr_t*>(this->m_edge_reg);
430  edge_reg_mr->addBatchOfNodeIDsAndScans(new_nodeIDs_to_scans_pairs);
431 
432  // Call for a Full graph visualization update and Dijkstra update -
433  // CGraphSlamOptimizer
434  // MRPT_LOG_WARN_STREAM("Optimizing graph..." << endl);
435  // this->m_optimizer->optimizeGraph();
436  MRPT_LOG_WARN_STREAM("Executing Dijkstra..." << endl);
437  this->execDijkstraNodesEstimation();
438 
439  neighbor->resetFlags();
440 
441  // update the initial tf estimation
442  neighbor->tf_self_to_neighbor_first_integrated_pose = pose_out;
443 
444  // keep track of the last integrated nodeID
445  {
446  TNodeID last_node = *neighbor_nodes.rbegin();
448  make_pair(last_node, nodes_params.at(last_node).pose);
449  }
450 
451  MRPT_LOG_WARN_STREAM(
452  "Nodes of neighbor [" << neighbor->getAgentNs()
453  << "] have been integrated successfully");
454 
455  ret_val = true;
456 
457  return ret_val;
458  MRPT_END;
459 } // end if findTFWithNeighbor
460 
461 template <class GRAPH_T>
463  mrpt::obs::CActionCollection::Ptr& action,
464  mrpt::obs::CSensoryFrame::Ptr& observations,
465  mrpt::obs::CObservation::Ptr& observation, size_t& rawlog_entry)
466 {
467  MRPT_START;
468  using namespace mrpt::graphslam::deciders;
469  using namespace mrpt;
470 
471  // call parent method
472  bool continue_exec = parent_t::_execGraphSlamStep(
473  action, observations, observation, rawlog_entry);
474 
475  // find matches between own nodes and those of the neighbors
476  bool did_register_from_map_merge;
478  {
479  did_register_from_map_merge = this->findTFsWithAllNeighbors();
480  }
481  else
482  { // inter-graph TF is available - add new nodes
483  THROW_EXCEPTION(
484  "Conservative inter-graph TF computation is not yet implemented.");
485  }
486 
487  bool did_register_from_batches = this->addNodeBatchesFromAllNeighbors();
489  (did_register_from_map_merge || did_register_from_batches);
490 
492  {
493  if (this->m_enable_visuals)
494  {
495  this->updateAllVisuals();
496  }
497  }
498 
499  return continue_exec;
500  MRPT_END;
501 } // end of _execGraphSlamStep
502 
503 template <class GRAPH_T>
505 {
506  using namespace mrpt::graphslam;
507  using namespace std;
508 
509  // initialization of topic namespace names
510  // TODO - put these into seperate method
511  m_mr_ns = "mr_info";
512 
513  // initialization of topic names / services
514  m_list_neighbors_topic = m_mr_ns + "/" + "neighbors";
515  m_last_regd_id_scan_topic = m_mr_ns + "/" + "last_nodeID_laser_scan";
516  m_last_regd_nodes_topic = m_mr_ns + "/" + "last_regd_nodes";
517  m_cm_graph_service = m_mr_ns + "/" + "get_cm_graph";
518 
519  this->m_class_name = "CGraphSlamEngine_MR_" + m_conn_manager.getTrimmedNs();
520  this->setLoggerName(this->m_class_name);
521  this->setupComm();
522 
523  // Make sure that master_discovery and master_sync are up before trying to
524  // connect to other agents
525  std::vector<string> nodes_up;
526  ros::master::getNodes(nodes_up);
527  // If both master_dicovery and master_sync are running, then the
528  // /master_sync/get_sync_info service should be available
529  MRPT_LOG_INFO_STREAM(
530  "Waiting for master_discovery, master_sync nodes to come up....");
532  "/master_sync/get_sync_info"); // block until it is
533  MRPT_LOG_INFO_STREAM("master_discovery, master_sync are available.");
534 
535  this->m_node_reg->setClassName(
536  this->m_node_reg->getClassName() + "_" + m_conn_manager.getTrimmedNs());
537  this->m_edge_reg->setClassName(
538  this->m_edge_reg->getClassName() + "_" + m_conn_manager.getTrimmedNs());
539  this->m_optimizer->setClassName(
540  this->m_optimizer->getClassName() + "_" +
542 
543  // in case of Multi-robot specific deciders/optimizers (they
544  // inherit from the CDeciderOrOptimizer_ROS interface) set the
545  // CConnectionManager*
546  // NOTE: It's not certain, even though we are running multi-robot graphSLAM
547  // that all these classes do inherit from the
548  // CRegistrationDeciderOrOptimizer_MR base class. They might be more generic
549  // and not care about the multi-robot nature of the algorithm (e.g.
550  // optimization scheme)
551  { // NRD
554  this->m_node_reg);
555 
556  if (dec_opt_mr)
557  {
559  }
560  }
561  { // ERD
564  this->m_edge_reg);
565  ASSERT_(dec_opt_mr);
567  dec_opt_mr->setCGraphSlamEnginePtr(this);
568  }
569  { // GSO
572  this->m_optimizer);
573  if (dec_opt_mr)
574  {
576  }
577  }
578  // display messages with the names of the deciders, optimizer and agent
579  // string ID
580  if (this->m_enable_visuals)
581  {
582  // NRD
583  this->m_win_manager->assignTextMessageParameters(
584  /* offset_y* = */ &m_offset_y_nrd,
585  /* text_index* = */ &m_text_index_nrd);
586  this->m_win_manager->addTextMessage(
587  this->m_offset_x_left, -m_offset_y_nrd,
588  mrpt::format("NRD: %s", this->m_node_reg->getClassName().c_str()),
589  TColorf(0, 0, 0),
590  /* unique_index = */ m_text_index_nrd);
591 
592  // ERD
593  this->m_win_manager->assignTextMessageParameters(
594  /* offset_y* = */ &m_offset_y_erd,
595  /* text_index* = */ &m_text_index_erd);
596  this->m_win_manager->addTextMessage(
597  this->m_offset_x_left, -m_offset_y_erd,
598  mrpt::format("ERD: %s", this->m_edge_reg->getClassName().c_str()),
599  TColorf(0, 0, 0),
600  /* unique_index = */ m_text_index_erd);
601 
602  // GSO
603  this->m_win_manager->assignTextMessageParameters(
604  /* offset_y* = */ &m_offset_y_gso,
605  /* text_index* = */ &m_text_index_gso);
606  this->m_win_manager->addTextMessage(
607  this->m_offset_x_left, -m_offset_y_gso,
608  mrpt::format("GSO: %s", this->m_optimizer->getClassName().c_str()),
609  TColorf(0, 0, 0),
610  /* unique_index = */ m_text_index_gso);
611 
612  // Agent Namespace
613  this->m_win_manager->assignTextMessageParameters(
614  /* offset_y* = */ &m_offset_y_namespace,
615  /* text_index* = */ &m_text_index_namespace);
616  this->m_win_manager->addTextMessage(
617  this->m_offset_x_left, -m_offset_y_namespace,
618  mrpt::format("Agent ID: %s", m_conn_manager.getTrimmedNs().c_str()),
619  TColorf(0, 0, 0),
620  /* unique_index = */ m_text_index_namespace);
621  }
622  this->readParams();
623 
624  this->m_optimized_map_color = m_neighbor_colors_manager.getNextTColor();
625 
626  // start the spinner for asynchronously servicing cm_graph requests
628 } // end of initClass
629 
630 template <class GRAPH_T>
631 mrpt::poses::CPose3D
633  const TNodeID nodeID) const
634 {
635  MRPT_START;
636  using namespace mrpt::graphs::detail;
637 
638  // if this is my own node ID return the corresponding CPose2D, otherwise
639  // return the pose connecting own graph with the neighbor's graph
640 
641  const TMRSlamNodeAnnotations* node_annots =
642  dynamic_cast<const TMRSlamNodeAnnotations*>(
643  &this->m_graph.nodes.at(nodeID));
644 
645  // Is the current nodeID registered by a neighboring agent or is it my own?
646  TNeighborAgentProps* neighbor = NULL;
647  this->getNeighborByAgentID(node_annots->agent_ID_str, neighbor);
648 
649  CPose3D laser_pose;
650  if (!neighbor)
651  { // own node
652  laser_pose = parent_t::getLSPoseForGridMapVisualization(nodeID);
653  }
654  else
655  { // not by me - return TF to neighbor graph
656  laser_pose =
658  }
659  return laser_pose;
660 
661  MRPT_END;
662 }
663 
664 template <class GRAPH_T>
666  const std::string& agent_ID_str, TNeighborAgentProps*& neighbor) const
667 {
668  MRPT_START;
669 
670  bool ret = false;
671  for (auto neighbors_it = m_neighbors.begin();
672  neighbors_it != m_neighbors.end(); ++neighbors_it)
673  {
674  if ((*neighbors_it)->getAgentNs() == agent_ID_str)
675  {
676  ret = true;
677  neighbor = *neighbors_it;
678  break;
679  }
680  }
681 
682  return ret;
683  MRPT_END;
684 }
685 
686 template <class GRAPH_T>
688 {
689  MRPT_START;
690  using namespace mrpt_msgs;
691  using namespace std;
692  using namespace mrpt::math;
693  using ::operator==;
694 
695  // call the parent class
697 
698  // update list of neighbors that the current agent can communicate with.
699  mrpt_msgs::GraphSlamAgents nearby_slam_agents;
701  &nearby_slam_agents,
702  /*ignore_self = */ true);
703  m_list_neighbors_pub.publish(nearby_slam_agents);
704 
705  // Initialize TNeighborAgentProps
706  // for each *new* GraphSlamAgent we should add a TNeighborAgentProps
707  // instance, and initialize its subscribers so that we fetch every new
708  // LaserScan and list of modified nodes it publishes
709  {
710  for (GraphSlamAgents::_list_type::const_iterator it =
711  nearby_slam_agents.list.begin();
712  it != nearby_slam_agents.list.end(); ++it)
713  {
714  const GraphSlamAgent& gsa = *it;
715 
716  // Is the current GraphSlamAgent already registered?
717  const auto search = [gsa](const TNeighborAgentProps* neighbor) {
718  return (neighbor->agent == gsa);
719  };
720  typename neighbors_t::const_iterator neighbor_it =
721  find_if(m_neighbors.begin(), m_neighbors.end(), search);
722 
723  if (neighbor_it == m_neighbors.end())
724  { // current gsa not found, add it
725 
726  MRPT_LOG_DEBUG_STREAM(
727  "Initializing NeighborAgentProps instance for "
728  << gsa.name.data);
729  m_neighbors.push_back(new TNeighborAgentProps(*this, gsa));
730  TNeighborAgentProps* latest_neighbor = m_neighbors.back();
731  latest_neighbor->setTColor(
732  m_neighbor_colors_manager.getNextTColor());
734  make_pair(latest_neighbor, false));
735  latest_neighbor->setupComm();
736  }
737  }
738  }
739 
740  this->pubUpdatedNodesList();
741  this->pubLastRegdIDScan();
742 
743  MRPT_END;
744 } // end of usePublishersBroadcasters
745 
746 template <class GRAPH_T>
748 {
749  MRPT_START;
750  using namespace mrpt_msgs;
751 
752  // update the last X NodeIDs + positions; Do it only when a new node is
753  // inserted. notified of this change anyway after a new node addition
754  if (this->m_graph_nodes_last_size == this->m_graph.nodes.size())
755  {
756  return false;
757  }
758  MRPT_LOG_DEBUG_STREAM("Updating list of node poses");
759 
760  // send at most m_num_last_rgd_nodes
761  typename GRAPH_T::global_poses_t poses_to_send;
762  int poses_counter = 0;
763  // fill the NodeIDWithPoseVec msg
764  NodeIDWithPoseVec ros_nodes;
765 
766  // send up to num_last_regd_nodes Nodes - start from end.
767  for (typename GRAPH_T::global_poses_t::const_reverse_iterator cit =
768  this->m_graph.nodes.rbegin();
769  (poses_counter <= m_opts.num_last_regd_nodes &&
770  cit != this->m_graph.nodes.rend());
771  ++cit)
772  {
773  // Do not resend nodes of others, registered in own graph.
774  if (cit->second.agent_ID_str != m_conn_manager.getTrimmedNs())
775  {
776  continue; // skip this.
777  }
778 
779  NodeIDWithPose curr_node_w_pose;
780  // send basics - NodeID, Pose
781  curr_node_w_pose.node_id = cit->first;
782  curr_node_w_pose.pose = mrpt::ros1bridge::toROS_Pose(cit->second);
783 
784  // send mr-fields
785  curr_node_w_pose.str_id.data = cit->second.agent_ID_str;
786  curr_node_w_pose.node_id_loc = cit->second.nodeID_loc;
787 
788  ros_nodes.vec.push_back(curr_node_w_pose);
789 
790  poses_counter++;
791  }
792 
793  m_last_regd_nodes_pub.publish(ros_nodes);
794 
795  // update the last known size
796  m_graph_nodes_last_size = this->m_graph.nodeCount();
797 
798  bool res = false;
799  if (poses_counter)
800  {
801  res = true;
802  }
803 
804  return res;
805  MRPT_END;
806 } // end of pubUpdatedNodesList
807 
808 template <class GRAPH_T>
810 {
811  MRPT_START;
812  using namespace mrpt_msgs;
813 
814  // Update the last registered scan + associated nodeID
815  // Last registered scan always corresponds to the *last* element of the of
816  // the published NodeIDWithPoseVec that is published above.
817  //
818  // - Check if map is empty
819  // - Have I already published the last laser scan?
820  if (!this->m_nodes_to_laser_scans2D.empty() &&
822  this->m_nodes_to_laser_scans2D.size())
823  {
824  // last registered scan
825  MRPT_NodeIDWithLaserScan mrpt_last_regd_id_scan =
826  *(this->m_nodes_to_laser_scans2D.rbegin());
827 
828  // if this is a mr-registered nodeID+LS, skip it.
829  if (!this->isOwnNodeID(mrpt_last_regd_id_scan.first))
830  {
831  return false;
832  }
833 
834  // MRPT_LOG_DEBUG_STREAM
835  //<< "Publishing LaserScan of nodeID \""
836  //<< mrpt_last_regd_id_scan.first << "\"";
837  ASSERT_(mrpt_last_regd_id_scan.second);
838 
839  // convert to ROS msg
840  mrpt_msgs::NodeIDWithLaserScan ros_last_regd_id_scan;
841  mrpt::ros1bridge::toROS(
842  *(mrpt_last_regd_id_scan.second), ros_last_regd_id_scan.scan);
843  ros_last_regd_id_scan.node_id = mrpt_last_regd_id_scan.first;
844 
845  m_last_regd_id_scan_pub.publish(ros_last_regd_id_scan);
846 
847  // update the last known size.
849  this->m_nodes_to_laser_scans2D.size();
850 
851  return true;
852  }
853  else
854  {
855  return false;
856  }
857 
858  MRPT_END;
859 } // end of pubLastRegdIDScan
860 
861 template <class GRAPH_T>
863  const TNodeID nodeID, const global_pose_t* pose_out /*=NULL*/) const
864 {
865  MRPT_START;
866  using namespace mrpt::graphs::detail;
867 
868  // make sure give node is in the graph
869  typename GRAPH_T::global_poses_t::const_iterator global_pose_search =
870  this->m_graph.nodes.find(nodeID);
871  ASSERTMSG_(
872  global_pose_search != this->m_graph.nodes.end(),
873  mrpt::format(
874  "isOwnNodeID called for nodeID \"%lu\" which is not "
875  "found in the graph",
876  static_cast<unsigned long>(nodeID)));
877 
878  // fill pointer to global_pose_t
879  if (pose_out)
880  {
881  pose_out = &global_pose_search->second;
882  }
883 
884  bool res = false;
885  const TMRSlamNodeAnnotations* node_annots =
886  dynamic_cast<const TMRSlamNodeAnnotations*>(
887  &global_pose_search->second);
888  if ((node_annots &&
889  node_annots->agent_ID_str == m_conn_manager.getTrimmedNs()) ||
890  (!node_annots))
891  {
892  res = true;
893  }
894 
895  return res;
896 
897  MRPT_END;
898 } // end of isOwnNodeID
899 
900 template <class GRAPH_T>
902 {
903  using namespace mrpt::slam;
904 
905  this->readROSParameters();
906 
907  // GridMap Alignment
908  m_alignment_options.loadFromConfigFileName(
909  this->m_config_fname, m_sec_alignment_params);
910 
911  // Thu Jun 8 17:02:17 EEST 2017, Nikos Koukis
912  // other option ends up in segfault.
913  m_alignment_options.methodSelection = CGridMapAligner::amModifiedRANSAC;
914 
915  m_opts.loadFromConfigFileName(this->m_config_fname, m_sec_mr_slam_params);
916 } // end of readParams
917 
918 template <class GRAPH_T>
920 {
921  // call parent method first in case the parent wants to ask for any ROS
922  // parameters
924 }
925 
926 template <class GRAPH_T>
928 {
929  parent_t::printParams();
930  m_alignment_options.dumpToConsole();
931  m_opts.dumpToConsole();
932 }
933 
934 template <class GRAPH_T>
936 {
937 }
938 
939 template <class GRAPH_T>
941 {
942  using namespace mrpt_msgs;
943  using namespace sensor_msgs;
944 
945  m_list_neighbors_pub = m_nh->advertise<GraphSlamAgents>(
947  /*latch = */ true);
948 
949  // last registered laser scan - by default this corresponds to the last
950  // nodeID of the vector of last registered nodes.
951  m_last_regd_id_scan_pub = m_nh->advertise<NodeIDWithLaserScan>(
953  /*latch = */ true);
954 
955  // last X nodeIDs + positions
956  m_last_regd_nodes_pub = m_nh->advertise<NodeIDWithPoseVec>(
958  /*latch = */ true);
959 }
960 
961 template <class GRAPH_T>
963 {
964  // cm_graph service requests are handled by the custom custom_service_queue
965  // CallbackQueue
968 
971 
972  m_nh->setCallbackQueue(global_queue);
973 }
974 
975 template <class GRAPH_T>
977  mrpt_msgs::GetCMGraph::Request& req, mrpt_msgs::GetCMGraph::Response& res)
978 {
979  using namespace std;
980  using namespace mrpt::math;
981 
982  set<TNodeID> nodes_set(req.node_ids.begin(), req.node_ids.end());
983  MRPT_LOG_INFO_STREAM(
984  "Called the GetCMGraph service for nodeIDs: "
985  << getSTLContainerAsString(nodes_set));
986 
987  if (nodes_set.size() < 2)
988  {
989  return false;
990  }
991 
992  // fill the given Response with the ROS NetworkOfPoses
993  GRAPH_T mrpt_subgraph;
994  this->m_graph.extractSubGraph(
995  nodes_set, &mrpt_subgraph,
996  /*root_node = */ INVALID_NODEID,
997  /*auto_expand_set=*/false);
998  mrpt_msgs_bridge::toROS(mrpt_subgraph, res.cm_graph);
999  return true;
1000 } // end of getCMGraph
1001 
1002 template <class GRAPH_T>
1004  const TNodeID nodeID, mrpt::opengl::CSetOfObjects::Ptr& viz_object)
1005 {
1006  MRPT_START;
1007 
1008  // who registered this node?
1009  TNeighborAgentProps* neighbor = NULL;
1010  std::string& agent_ID_str = this->m_graph.nodes.at(nodeID).agent_ID_str;
1011  bool is_not_own = getNeighborByAgentID(agent_ID_str, neighbor);
1012 
1013  TColor obj_color;
1014  if (!is_not_own)
1015  { // I registered this.
1016  // use the standard maps color
1017  obj_color = this->m_optimized_map_color;
1018  }
1019  else
1020  {
1021  ASSERT_(neighbor);
1022  obj_color = neighbor->color;
1023  }
1024  viz_object->setColor_u8(obj_color);
1025 
1026  MRPT_END;
1027 } // end of setObjectPropsFromNodeID
1028 
1029 template <class GRAPH_T>
1031  bool registered /*=false*/, std::string class_name /*="Class"*/)
1032 {
1033  MRPT_START;
1034 
1036  {
1037  MRPT_LOG_ERROR_STREAM("m_registered_multiple_nodes = TRUE!");
1039  this->m_nodeID_max = this->m_graph.nodeCount() - 1;
1040  }
1041  else
1042  {
1043  parent_t::monitorNodeRegistration(registered, class_name);
1044  }
1045 
1046  MRPT_END;
1047 } // end of monitorNodeRegistration
1048 
1049 template <class GRAPH_T>
1051  typename GRAPH_T::global_poses_t* graph_poses) const
1052 {
1053  MRPT_START;
1054  ASSERT_(graph_poses);
1055 
1056  for (const auto& n : this->m_graph.nodes)
1057  {
1058  if (n.second.agent_ID_str == m_conn_manager.getTrimmedNs())
1059  {
1060  graph_poses->insert(n);
1061  }
1062  }
1063 
1064  MRPT_END;
1065 } // end of getRobotEstimatedTrajectory
1066 
1067 template <class GRAPH_T>
1069  std::set<TNodeID>* nodes_set) const
1070 {
1071  ASSERT_(nodes_set);
1072  nodes_set->clear();
1073 
1074  for (const auto& n : this->m_graph.nodes)
1075  {
1076  if (n.second.agent_ID_str == m_conn_manager.getTrimmedNs())
1077  {
1078  nodes_set->insert(n.first);
1079  }
1080  }
1081 } // end of getAllOwnNodes
1082 
1083 template <class GRAPH_T>
1085  std::set<TNodeID>* nodes_set) const
1086 {
1087  ASSERT_(nodes_set);
1088  this->getAllOwnNodes(nodes_set);
1089 } // end of getNodeIDsOfEstimatedTrajectory
1090 
1092 
1093 template <class GRAPH_T>
1095  CGraphSlamEngine_MR<GRAPH_T>& engine_in,
1096  const mrpt_msgs::GraphSlamAgent& agent_in)
1097  : engine(engine_in), agent(agent_in), has_setup_comm(false)
1098 {
1099  nh = engine.m_nh;
1100  m_queue_size = engine.m_queue_size;
1101  this->resetFlags();
1102 
1103  // fill the full paths of the topics to subscribe
1104  // ASSUMPTION: agents namespaces start at the root "/"
1105  this->last_regd_nodes_topic =
1106  "/" + agent.topic_namespace.data + "/" + engine.m_last_regd_nodes_topic;
1107  this->last_regd_id_scan_topic = "/" + agent.topic_namespace.data + "/" +
1108  engine.m_last_regd_id_scan_topic;
1109  this->cm_graph_service =
1110  "/" + agent.topic_namespace.data + "/" + engine.m_cm_graph_service;
1111 
1112  engine.logFmt(
1113  LVL_DEBUG,
1114  "In constructor of TNeighborAgentProps for topic namespace: %s",
1115  agent.topic_namespace.data.c_str());
1116 
1117  // initialize the occupancy map based on the engine's gridmap properties
1118  gridmap_cached = mrpt::maps::COccupancyGridMap2D::Create();
1119  mrpt::maps::COccupancyGridMap2D::Ptr eng_gridmap = engine.m_gridmap_cached;
1120  gridmap_cached->setSize(
1121  eng_gridmap->getXMin(), eng_gridmap->getXMax(), eng_gridmap->getYMin(),
1122  eng_gridmap->getYMax(), eng_gridmap->getResolution());
1123 
1124 } // TNeighborAgentProps::TNeighborAgentProps
1125 
1126 template <class GRAPH_T>
1128 {
1129 }
1130 
1131 template <class GRAPH_T>
1133 {
1134  this->setupSubs();
1135  this->setupSrvs();
1136 
1137  engine.logFmt(
1138  LVL_DEBUG,
1139  "TNeighborAgentProps: Successfully set up subscribers/services "
1140  "to agent topics for namespace [%s].",
1141  agent.topic_namespace.data.c_str());
1142 
1143  has_setup_comm = true;
1144 }
1145 
1146 template <class GRAPH_T>
1148 {
1150  nh->serviceClient<mrpt_msgs::GetCMGraph>(cm_graph_service);
1151 }
1152 
1153 template <class GRAPH_T>
1155 {
1156  using namespace mrpt_msgs;
1157 
1158  last_regd_nodes_sub = nh->subscribe<NodeIDWithPoseVec>(
1161  last_regd_id_scan_sub = nh->subscribe<NodeIDWithLaserScan>(
1164 }
1165 
1166 template <class GRAPH_T>
1168  const mrpt_msgs::NodeIDWithPoseVec::ConstPtr& nodes)
1169 {
1170  MRPT_START;
1171  using namespace mrpt_msgs;
1172  using namespace std;
1173 
1174  typedef typename GRAPH_T::constraint_t::type_value pose_t;
1175  engine.logFmt(LVL_DEBUG, "In fetchUpdatedNodesList method.");
1176 
1177  for (NodeIDWithPoseVec::_vec_type::const_iterator n_it = nodes->vec.begin();
1178  n_it != nodes->vec.end(); ++n_it)
1179  {
1180  // insert in the set if not already there.
1181  TNodeID nodeID = static_cast<TNodeID>(n_it->node_id);
1182  std::pair<set<TNodeID>::iterator, bool> res =
1183  nodeIDs_set.insert(nodeID);
1184  // if I just inserted this node mark it as not used (in own graph)
1185  if (res.second)
1186  { // insertion took place.
1187  engine.logFmt(
1188  LVL_INFO, "Just fetched a new nodeID: %lu",
1189  static_cast<unsigned long>(nodeID));
1190  nodeID_to_is_integrated.insert(make_pair(n_it->node_id, false));
1191  }
1192 
1193  // update the poses
1194  pose_t curr_pose;
1195  curr_pose = pose_t(mrpt::ros1bridge::fromROS(n_it->pose));
1196 
1197  // note: use "operator[]" instead of "insert" so that if the key already
1198  // exists, the corresponding value is changed rather than ignored.
1199  poses[static_cast<TNodeID>(n_it->node_id)] = pose_t(curr_pose);
1200  }
1201  has_new_nodes = true;
1202 
1204  // TODO When using 3 graphSLAM agents GDB Shows that it crashes on
1205  // engine.logFmt lines. Fix this.
1206  //
1207  // engine.logFmt(LVL_DEBUG, // THIS CRASHES - GDB WHERE
1208  //"NodeIDs for topic namespace: %s -> [%s]",
1209  // agent.topic_namespace.data.c_str(),
1210  // mrpt::math::getSTLContainerAsString(vector<TNodeID>(
1211  // nodeIDs_set.begin(), nodeIDs_set.end())).c_str());
1212  // print poses just for verification
1213  // engine.logFmt(LVL_DEBUG, "Poses for topic namespace: %s",
1214  // agent.topic_namespace.data.c_str());
1215  // for (typename GRAPH_T::global_poses_t::const_iterator
1216  // p_it = poses.begin();
1217  // p_it != poses.end();
1218  //++p_it) {
1219  // std::string p_str; p_it->second.asString(p_str);
1220  // engine.logFmt(LVL_DEBUG, "nodeID: %lu | pose: %s",
1221  // static_cast<unsigned long>(p_it->first),
1222  // p_str.c_str());
1223  //}
1224  // TODO - These also seem to crash sometimes
1225  // cout << "Agent information: " << agent << endl;
1226  // cout << "Nodes: " <<
1227  // mrpt::math::getSTLContainerAsString(vector<TNodeID>(nodeIDs_set.begin(),
1228  // nodeIDs_set.end()));
1229  // print nodeIDs just for verification
1230 
1231  MRPT_END;
1232 } // end of fetchUpdatedNodesList
1233 
1234 template <class GRAPH_T>
1236  const mrpt_msgs::NodeIDWithLaserScan::ConstPtr& last_regd_id_scan)
1237 {
1238  MRPT_START;
1239  using namespace std;
1240  ASSERT_(last_regd_id_scan);
1241  engine.logFmt(LVL_DEBUG, "In fetchLastRegdIDScan method.");
1242 
1243  // Pose may not be available due to timing in publishing of the
1244  // corresponding topics. Just keep it in ROS form and then convert them to
1245  // MRPT form when needed.
1246  ros_scans.push_back(*last_regd_id_scan);
1247  has_new_scans = true;
1248 
1249  MRPT_END;
1250 } // end of fetchLastRegdIDScan
1251 
1252 template <class GRAPH_T>
1254  std::vector<TNodeID>* nodeIDs /*=NULL*/,
1255  std::map<TNodeID, node_props_t>* nodes_params /*=NULL*/,
1256  bool only_unused /*=true*/) const
1257 {
1258  MRPT_START;
1259  using namespace mrpt::obs;
1260  using namespace mrpt::math;
1261  using namespace std;
1262  using namespace mrpt::poses;
1263 
1264  // at least one of the two args should be given.
1265  ASSERT_(nodeIDs || nodes_params);
1266 
1267  // traverse all nodes
1268  for (std::set<TNodeID>::const_iterator n_it = nodeIDs_set.begin();
1269  n_it != nodeIDs_set.end(); ++n_it)
1270  {
1271  // Should I return only the unused ones?
1272  // If so, if the current nodeID is integrated, skip it.
1273  if (only_unused && nodeID_to_is_integrated.at(*n_it))
1274  {
1275  continue;
1276  }
1277 
1278  // add the node properties
1279  if (nodes_params)
1280  {
1281  std::pair<TNodeID, node_props_t>
1282  params; // current pair to be inserted.
1283  const pose_t* p = &poses.at(*n_it);
1284 
1285  params.first = *n_it;
1286  params.second.pose = *p;
1287  CObservation2DRangeScan::Ptr mrpt_scan =
1288  CObservation2DRangeScan::Create();
1289  const sensor_msgs::LaserScan* ros_laser_scan =
1290  this->getLaserScanByNodeID(*n_it);
1291 
1292  // if LaserScan not found, skip nodeID altogether.
1293  //
1294  // Its natural to have more poses than LaserScans since on every
1295  // node registration I send a modified list of X node positions and
1296  // just one LaserScan
1297  if (!ros_laser_scan)
1298  {
1299  continue;
1300  }
1301 
1302  mrpt::ros1bridge::fromROS(*ros_laser_scan, CPose3D(*p), *mrpt_scan);
1303  params.second.scan = mrpt_scan;
1304 
1305  // insert the pair
1306  nodes_params->insert(params);
1307 
1308  // debugging message
1309  // std::stringstream ss;
1310  // ss << "\ntID: " << nodes_params->rbegin()->first
1311  //<< " ==> Props: " << nodes_params->rbegin()->second;
1312  // engine.logFmt(LVL_DEBUG, "%s", ss.str().c_str());
1313  }
1314 
1315  // add the nodeID
1316  if (nodeIDs)
1317  {
1318  // do not return nodeIDs that don't have valid laserScans
1319  // this is also checked at the prior if
1320  if (!nodes_params && !this->getLaserScanByNodeID(*n_it))
1321  {
1322  continue;
1323  }
1324 
1325  nodeIDs->push_back(*n_it);
1326  }
1327  }
1328 
1329  MRPT_END;
1330 } // end of TNeighborAgentProps::getCachedNodes
1331 
1332 template <class GRAPH_T>
1334 {
1335  has_new_nodes = false;
1336  has_new_scans = false;
1337 }
1338 
1339 template <class GRAPH_T>
1341  int new_batch_size)
1342 {
1343  MRPT_START;
1344 
1345  auto is_not_integrated = [this](const std::pair<TNodeID, bool> pair) {
1346  return (pair.second == false && getLaserScanByNodeID(pair.first));
1347  };
1348  int not_integrated_num = count_if(
1350  is_not_integrated);
1351 
1352  return (not_integrated_num >= new_batch_size);
1353 
1354  MRPT_END;
1355 }
1356 
1357 template <class GRAPH_T>
1358 const sensor_msgs::LaserScan*
1360  const TNodeID nodeID) const
1361 {
1362  MRPT_START;
1363 
1364  // assert that the current nodeID exists in the nodeIDs_set
1365  ASSERT_(nodeIDs_set.find(nodeID) != nodeIDs_set.end());
1366 
1367  for (std::vector<mrpt_msgs::NodeIDWithLaserScan>::const_iterator it =
1368  ros_scans.begin();
1369  it != ros_scans.end(); ++it)
1370  {
1371  if (it->node_id == nodeID)
1372  {
1373  return &it->scan;
1374  }
1375  }
1376 
1377  // if out here, LaserScan doesn't exist.
1378  return 0;
1379  MRPT_END;
1380 } // end of TNeighborAgentProps::getLaserScanByNodeID
1381 
1382 template <class GRAPH_T>
1384  const std::set<TNodeID>& nodeIDs, paths_t* opt_paths) const
1385 {
1386  MRPT_START;
1387  using namespace std;
1388  typedef std::set<TNodeID>::const_iterator set_cit;
1389 
1390  // make sure that all given nodes belong in the nodeIDs_set.
1391  ASSERTMSG_(
1392  includes(
1393  nodeIDs_set.begin(), nodeIDs_set.end(), nodeIDs.begin(),
1394  nodeIDs.end()),
1395  "nodeIDs is not a strict subset of the current neighbor's nodes");
1396  ASSERT_(opt_paths);
1397 
1398  for (set_cit cit = nodeIDs.begin(); cit != std::prev(nodeIDs.end()); ++cit)
1399  {
1400  for (set_cit cit2 = std::next(cit); cit2 != nodeIDs.end(); ++cit2)
1401  {
1402  constraint_t c = constraint_t(poses.at(*cit2) - poses.at(*cit));
1403  c.cov_inv = mrpt::math::CMatrixFixedNumeric<
1404  double, constraint_t::state_length,
1405  constraint_t::state_length>();
1406  c.cov_inv.unit();
1407  c.cov_inv *= 500;
1408 
1409  opt_paths->push_back(path_t(
1410  /*start=*/*cit,
1411  /*end=*/*cit2,
1412  /*constraint=*/c));
1413 
1414  engine.logFmt(
1415  LVL_DEBUG, "Filling optimal path for nodes: %lu => %lu: %s",
1416  static_cast<unsigned long>(*cit),
1417  static_cast<unsigned long>(*cit2),
1418  opt_paths->back()
1419  .curr_pose_pdf.getMeanVal()
1420  .asString()
1421  .c_str());
1422  }
1423  }
1424  MRPT_END;
1425 } // end of TNeighborAgentProps::fillOptPaths
1426 
1427 template <class GRAPH_T>
1429 {
1430  MRPT_START;
1431  using namespace mrpt::poses;
1432  using namespace mrpt;
1433  using namespace mrpt::math;
1434  using namespace std;
1435 
1436  gridmap_cached->clear();
1437 
1438  std::vector<TNodeID> nodeIDs;
1439  std::map<TNodeID, node_props_t> nodes_params;
1440  // get list of nodes, laser scans
1441  this->getCachedNodes(&nodeIDs, &nodes_params, false);
1442 
1443  // iterate over poses, scans. Add them to the gridmap.
1444  for (typename map<TNodeID, node_props_t>::const_iterator it =
1445  nodes_params.begin();
1446  it != nodes_params.end(); ++it)
1447  {
1448  const CPose3D curr_pose_3d; // do not add the actual pose!
1449  auto obs = it->second.scan.get();
1450  gridmap_cached->insertObservation(*obs, curr_pose_3d);
1451  }
1452 
1453  MRPT_END;
1454 } // end of TNeighborAgentProps::computeGridMap
1455 
1456 template <class GRAPH_T>
1457 const mrpt::maps::COccupancyGridMap2D::Ptr&
1459 {
1460  MRPT_START;
1461  if (hasNewData())
1462  {
1463  this->computeGridMap();
1464  }
1465 
1466  return gridmap_cached;
1467  MRPT_END;
1468 } // end of TNeighborAgentProps::getGridMap
1469 
1470 template <class GRAPH_T>
1472  mrpt::maps::COccupancyGridMap2D::Ptr& map) const
1473 {
1474  MRPT_START;
1475  ASSERT_(map);
1476 
1477  if (hasNewData())
1478  {
1479  this->computeGridMap();
1480  }
1481 
1482  map->copyMapContentFrom(*gridmap_cached);
1483  MRPT_END;
1484 } // end of TNeighborAgentProps::getGridMap
1485 
1486 template <class GRAPH_T>
1488 {
1489  return has_new_nodes && has_new_scans;
1490 } // end of hasNewData
1491 
1492 template <class GRAPH_T>
1494  : conservative_find_initial_tfs_to_neighbors(false),
1495  nodes_integration_batch_size(4),
1496  num_last_regd_nodes(10),
1497  inter_group_node_count_thresh(40),
1498  inter_group_node_count_thresh_minadv(25),
1499  engine(engine_in)
1500 {
1501 } // end of TOptions::TOptions
1502 
1503 template <class GRAPH_T>
1505 {
1506 } // end of TOptions::~TOptions
1507 
1508 template <class GRAPH_T>
1510  const CConfigFileBase& source, const std::string& section)
1511 {
1512  MRPT_LOAD_CONFIG_VAR(nodes_integration_batch_size, int, source, section);
1513  MRPT_LOAD_CONFIG_VAR(num_last_regd_nodes, int, source, section);
1514 
1515  MRPT_LOAD_CONFIG_VAR(
1516  conservative_find_initial_tfs_to_neighbors, bool, source, section);
1517  ASSERTMSG_(
1519  "Conservative behavior is not yet implemented.");
1520 
1521  MRPT_LOAD_CONFIG_VAR(inter_group_node_count_thresh, int, source, section);
1522  // warn user if they choose smaller threshold.
1524  {
1525  engine.logFmt(
1526  LVL_ERROR,
1527  "inter_group_node_count_thresh [%d]"
1528  "is set lower than the advised minimum [%d]",
1529  static_cast<int>(inter_group_node_count_thresh),
1530  static_cast<int>(inter_group_node_count_thresh_minadv));
1531 
1532  std::this_thread::sleep_for(std::chrono::milliseconds(2000));
1533  }
1534 
1535 } // end of TOptions::loadFromConfigFile
1536 
1537 template <class GRAPH_T>
1539  std::ostream& out) const
1540 {
1541  LOADABLEOPTS_DUMP_VAR(nodes_integration_batch_size, int);
1542  LOADABLEOPTS_DUMP_VAR(num_last_regd_nodes, int);
1543  LOADABLEOPTS_DUMP_VAR(conservative_find_initial_tfs_to_neighbors, bool);
1544  LOADABLEOPTS_DUMP_VAR(static_cast<int>(inter_group_node_count_thresh), int)
1545  LOADABLEOPTS_DUMP_VAR(inter_group_node_count_thresh_minadv, int)
1546 
1547 } // end of TOptions::dumpToTextStream
1548 
1549 } // namespace graphslam
1550 } // namespace mrpt
CMatrixFixed< T, ROWS, COLS > CMatrixFixedNumeric
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
mrpt::poses::CPose3D getLSPoseForGridMapVisualization(const TNodeID nodeID) const
bool pubUpdatedNodesList()
Update the last registered NodeIDs and corresponding positions of the current agent.
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...
std::string m_list_neighbors_topic
Name of topic at which we publish information about the agents that we can currently communicate with...
ros::AsyncSpinner cm_graph_async_spinner
AsyncSpinner that is used to query the CM-Graph service in case a new request arrives.
void getNodeIDsOfEstimatedTrajectory(std::set< TNodeID > *nodes_set) const
const std::string & getTrimmedNs() const
Get the agent ROS namespace.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool hasNewNodesBatch(int new_batch_size)
Decide whether there are enough new nodes + scans that have not been integrated in the graph yet...
ros::Publisher m_last_regd_id_scan_pub
Publisher of the laserScan + the corresponding (last) registered node.
std::map< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > nodes_to_scans2D_t
bool m_registered_multiple_nodes
Indicates whether multiple nodes were just registered. Used for checking correct node registration in...
bool addNodeBatchesFromAllNeighbors()
Traverse all neighbors for which I know the inter-graph transformation, run addNodeBatchFromNeighbor...
bool call(MReq &req, MRes &res)
std::set< TNodeID > nodeIDs_set
NodeIDs that I have received from this graphSLAM agent.
ros::NodeHandle * nh
NodeHandle passed by the calling CGraphSlamEngine_MR class.
std::vector< mrpt_msgs::NodeIDWithLaserScan > ros_scans
ROS LaserScans that I have received from this graphSLAM agent.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::pair< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > MRPT_NodeIDWithLaserScan
TColor color
Unique color of current TNeighborAgentProps instance.
bool findTFsWithAllNeighbors()
Using map-merging find a potentuial transofrmation between own graph map to another agent&#39;s map and u...
void fillOptPaths(const std::set< TNodeID > &nodeIDs, paths_t *opt_paths) const
Fill the optimal paths for each combination of the given nodeIDs.
mrpt::graphslam::TUncertaintyPath< GRAPH_T > path_t
std::map< TNeighborAgentProps *, bool > m_neighbor_to_found_initial_tf
Map from neighbor instance to transformation from own to neighbor&#39;s graph.
void getCachedNodes(std::vector< TNodeID > *nodeIDs=NULL, std::map< TNodeID, node_props_t > *nodes_params=NULL, bool only_unused=true) const
Return cached list of nodeIDs (with their corresponding poses, LaserScans)
std::string getGridMapAlignmentResultsAsString(const mrpt::poses::CPosePDF &pdf, const mrpt::slam::CGridMapAligner::TReturnInfo &ret_info)
Definition: common.cpp:20
TNeighborAgentProps(CGraphSlamEngine_MR< GRAPH_T > &engine_in, const mrpt_msgs::GraphSlamAgent &agent_in)
Constructor.
void fetchLastRegdIDScan(const mrpt_msgs::NodeIDWithLaserScan::ConstPtr &last_regd_id_scan)
Fill the LaserScan of the last registered nodeID.
void getRobotEstimatedTrajectory(typename GRAPH_T::global_poses_t *graph_poses) const
mrpt::graphs::detail::THypothesis< GRAPH_T > hypot_t
void setupSubs()
Setup the necessary subscribers for fetching nodes, laserScans for the current neighbor.
size_t m_graph_nodes_last_size
Last known size of the m_nodes map.
mrpt::poses::CPose2D tf_self_to_neighbor_first_integrated_pose
CPose2D connecting own graph origin to neighbor first received and integrated node. If this pose is 0 then it is not yet computed.
void publish(const boost::shared_ptr< M > &message) const
const mrpt::maps::COccupancyGridMap2D::Ptr & getGridMap() const
std::map< TNodeID, bool > nodeID_to_is_integrated
Have I already integrated this node in my graph?
bool _execGraphSlamStep(mrpt::obs::CActionCollection::Ptr &action, mrpt::obs::CSensoryFrame::Ptr &observations, mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry)
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.
mrpt::slam::CGridMapAligner::TConfigParams m_alignment_options
Parameters used during the alignment operation.
size_t inter_group_node_count_thresh
Lowest number of nodes that should exist in a group of nodes before evaluating it. These nodes are fetched by the other running graphSLAM agents.
virtual void setCConnectionManagerPtr(mrpt::graphslam::detail::CConnectionManager *conn_manager)
mrpt::graphslam::detail::CConnectionManager m_conn_manager
CConnectionManager instance.
void setCallbackQueue(CallbackQueueInterface *queue)
void setTColor(const TColor &color_in)
Set the color related to the current neighbor agent.
bool isEssentiallyZero(const mrpt::poses::CPose2D &p)
Definition: common.cpp:46
void fetchUpdatedNodesList(const mrpt_msgs::NodeIDWithPoseVec::ConstPtr &nodes)
Update nodeIDs + corresponding estimated poses.
ros::NodeHandle * m_nh
NodeHandle pointer - inherited by the parent. Redefined here for convenience.
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&#39;s frame ...
bool pubLastRegdIDScan()
Update the last registered NodeID and LaserScan of the current agent.
int num_last_regd_nodes
Max number of last registered NodeIDs + corresponding positions to publish.
virtual bool _execGraphSlamStep(mrpt::obs::CActionCollection::Ptr &action, mrpt::obs::CSensoryFrame::Ptr &observations, mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry)
bool toROS(const mrpt::obs::CObservationBeaconRanges &_obj, mrpt_msgs::ObservationRangeBeacon &_msg)
void usePublishersBroadcasters()
Provide feedback about the SLAM operation.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void loadFromConfigFile(const CConfigFileBase &source, const std::string &section)
CallbackQueueInterface * getCallbackQueue() const
Interface for implementing deciders/optimizers related to the Condensed Measurements multi-robot grap...
mrpt::graphslam::CGraphSlamEngine_MR::TOptions m_opts
ros::CallbackQueue custom_service_queue
Custom Callback queue for processing requests for the services outside the standard CallbackQueue...
virtual void usePublishersBroadcasters()
Provide feedback about the SLAM operation.
void monitorNodeRegistration(bool registered=false, std::string class_name="Class")
Overriden method that takes in account registration of multiple nodes of other running graphSLAM agen...
bool findTFWithNeighbor(TNeighborAgentProps *neighbor)
Method is used only when I haven&#39;t found any transformation between mine and the current neighbor&#39;s g...
bool conservative_find_initial_tfs_to_neighbors
Be conservative when it comes to deciding the initial transformation of own graph with regards to gra...
std::string m_mr_ns
Condensed Measurements topic namespace.
int nodes_integration_batch_size
After an inter-graph transformation is found between own graph and a neighbor&#39;s map, newly fetched neighbor&#39;s nodes are added in batches.
mrpt::maps::COccupancyGridMap2D::Ptr gridmap_cached
Pointer to the gridmap object of the neighbor.
ros::Publisher m_last_regd_nodes_pub
Publisher of the last registered nodeIDs and positions.
bool getCMGraph(mrpt_msgs::GetCMGraph::Request &req, mrpt_msgs::GetCMGraph::Response &res)
Compute and fill the Condensed Measurements Graph.
const sensor_msgs::LaserScan * getLaserScanByNodeID(const TNodeID nodeID) const
void setObjectPropsFromNodeID(const TNodeID nodeID, mrpt::opengl::CSetOfObjects::Ptr &viz_object)
void computeGridMap() const
Using the fetched LaserScans and nodeID positions, compute the occupancy gridmap of the given neighbo...
void setupSrvs()
Setup necessary services for neighbor.
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...
bool fromROS(const marker_msgs::MarkerDetection &_msg, const mrpt::poses::CPose3D &sensorPoseOnRobot, mrpt::obs::CObservationBearingRange &_obj)
virtual void addBatchOfNodeIDsAndScans(const std::map< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > &nodeIDs_to_scans2D)
neighbors_t m_neighbors
GraphSlamAgent instance pointer to TNeighborAgentProps.
size_t inter_group_node_count_thresh_minadv
Minimum advised limit of inter_group_node_count_thresh.
double m_offset_y_nrd
Display the Deciders/Optimizers with which we are running as well as the namespace of the current age...
void setupComm()
Wrapper for calling setupSubs, setupSrvs.
void getAllOwnNodes(std::set< TNodeID > *nodes_set) const
Fill given set with the nodeIDs that were initially registered by the current graphSLAM engine (and n...
GRAPH_T::global_poses_t poses
Poses that I have received from this graphSLAM agent.
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...
ROSCPP_DECL bool getNodes(V_string &nodes)
mrpt::graphslam::CGraphSlamEngine derived class for executing multi-robot graphSLAM ...
std::string m_last_regd_id_scan_topic
Name of the topic that the last registered laser scan (+ corresponding nodeID) is published at...
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
size_t m_nodes_to_laser_scans2D_last_size
Last known size of the m_nodes_to_laser_scans2D map.
Struct responsible for holding properties (nodeIDs, node positions, LaserScans) that have been regist...
void readROSParameters()
Read configuration parameters from the ROS parameter server.
bool addNodeBatchFromNeighbor(TNeighborAgentProps *neighbor)
neighbors for which I know the inter-graph transformation, add new batches of fetches nodeIDs and sca...
std::string m_last_regd_nodes_topic
Name of the topic that the last X registered nodes + positions are going to be published at...
void setupComm()
Wrapper method around the protected setup* class methods.
bool hasNewData() const
Return True if there are new data (node positions and corresponding LaserScans available) ...
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)


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