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


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Thu Jun 6 2019 19:37:48