Main MRPT website > C++ reference for MRPT 1.9.9
CLoopCloserERD_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-2017, 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 #ifndef CLOOPCLOSERERD_IMPL_H
11 #define CLOOPCLOSERERD_IMPL_H
12 #include <mrpt/math/utils.h>
13 
14 namespace mrpt
15 {
16 namespace graphslam
17 {
18 namespace deciders
19 {
20 // Ctors, Dtors
21 // //////////////////////////////////
22 template <class GRAPH_T>
24  : m_visualize_curr_node_covariance(false),
25  m_curr_node_covariance_color(160, 160, 160, /*alpha = */ 255),
26  m_partitions_full_update(false),
27  m_is_first_time_node_reg(true),
28  m_dijkstra_node_count_thresh(3)
29 {
30  this->initializeLoggers("CLoopCloserERD");
31  m_edge_types_to_nums["ICP2D"] = 0;
32  m_edge_types_to_nums["LC"] = 0;
33  MRPT_LOG_DEBUG_STREAM("Initialized class object");
34 }
35 
36 template <class GRAPH_T>
38 {
39  using namespace mrpt::graphslam;
40 
41  // release memory of m_node_optimal_paths map.
42  MRPT_LOG_DEBUG_STREAM("Releasing memory of m_node_optimal_paths map...");
44  m_node_optimal_paths.begin();
45  it != m_node_optimal_paths.end(); ++it)
46  {
47  delete it->second;
48  }
49 }
50 
51 // Methods implementations
52 // //////////////////////////////////
53 
54 template <class GRAPH_T>
57  mrpt::obs::CSensoryFrame::Ptr observations,
58  mrpt::obs::CObservation::Ptr observation)
59 {
60  MRPT_START;
61  MRPT_UNUSED_PARAM(action);
62  this->m_time_logger.enter("updateState");
63  using namespace std;
64  using namespace mrpt;
65  using namespace mrpt::obs;
66  using namespace mrpt::obs::utils;
67  using namespace mrpt::opengl;
68  using namespace mrpt::poses;
69  using namespace mrpt::math;
70 
71  // Track the last recorded laser scan
72  {
74  getObservation<CObservation2DRangeScan>(observations, observation);
75  if (scan)
76  {
77  m_last_laser_scan2D = scan;
78  }
79  }
80 
81  if (!m_first_laser_scan)
82  {
83  m_first_laser_scan = m_last_laser_scan2D;
84  }
85 
86  // check possible prior node registration
87  size_t num_registered =
88  absDiff(this->m_last_total_num_nodes, this->m_graph->nodeCount());
89  bool registered_new_node = num_registered > 0;
90 
91  if (registered_new_node)
92  {
93  MRPT_LOG_DEBUG_STREAM("New node has been registered in the graph!");
94  registered_new_node = true;
95 
96  // either single node registration, or double node registration for the
97  // first time only, unless we override this check.
98  if (!this->m_override_registered_nodes_check)
99  {
100  if (!((num_registered == 1) ^
101  (num_registered == 2 && m_is_first_time_node_reg)))
102  {
104  "Invalid number of registered nodes since last call to "
105  "updateStates| "
106  "Found \""
107  << num_registered << "\" new nodes.");
108  THROW_EXCEPTION("Invalid number of registered nodes.");
109  }
110  }
111 
112  // first time call:
113  // NRD should have registered *2* nodes; one for the root node and one
114  // for
115  // the first added constraint. Add the first measurement taken to the
116  // root
117  // and the second as usual
118  if (m_is_first_time_node_reg)
119  {
121  "Assigning first laserScan to the graph root node.");
122  this->m_nodes_to_laser_scans2D[this->m_graph->root] =
123  m_first_laser_scan;
124  m_is_first_time_node_reg = false;
125  }
126 
127  // register the new node-laserScan pair
128  this->m_nodes_to_laser_scans2D[this->m_graph->nodeCount() - 1] =
129  m_last_laser_scan2D;
130 
131  if (m_laser_params.use_scan_matching)
132  {
133  // scan match with previous X nodes
134  this->addScanMatchingEdges(this->m_graph->nodeCount() - 1);
135  }
136 
137  // update partitioning scheme with the latest pose/measurement
138  m_partitions_full_update =
139  ((this->m_graph->nodeCount() %
140  m_lc_params.full_partition_per_nodes) == 0 ||
141  this->m_just_inserted_lc)
142  ? true
143  : false;
144 
145  this->updateMapPartitions(
146  m_partitions_full_update,
147  /* is_first_time_node_reg = */ num_registered == 2);
148 
149  // check for loop closures
150  partitions_t partitions_for_LC;
151  this->checkPartitionsForLC(&partitions_for_LC);
152  this->evaluatePartitionsForLC(partitions_for_LC);
153 
154  if (m_visualize_curr_node_covariance)
155  {
156  this->execDijkstraProjection();
157  }
158 
159  this->m_last_total_num_nodes = this->m_graph->nodeCount();
160  }
161 
162  this->m_time_logger.leave("updateState");
163  return true;
164  MRPT_END;
165 }
166 
167 template <class GRAPH_T>
169  const mrpt::utils::TNodeID& curr_nodeID,
170  std::set<mrpt::utils::TNodeID>* nodes_set)
171 {
172  ASSERT_(nodes_set);
173 
174  // deal with the case that less than `prev_nodes_for_ICP` nodes have been
175  // registered
176  int fetched_nodeIDs = 0;
177  for (int nodeID_i = static_cast<int>(curr_nodeID) - 1;
178  ((fetched_nodeIDs <= this->m_laser_params.prev_nodes_for_ICP) &&
179  (nodeID_i >= 0)); // <----- I *have* to use int (instead of unsigned)
180  // if I use this condition
181  --nodeID_i)
182  {
183  nodes_set->insert(nodeID_i);
184  fetched_nodeIDs++;
185  }
186 } // end of fetchNodeIDsForScanMatching
187 
188 template <class GRAPH_T>
190  const mrpt::utils::TNodeID& curr_nodeID)
191 {
192  MRPT_START;
193  using namespace std;
194  using namespace mrpt;
195  using namespace mrpt::utils;
196  using namespace mrpt::obs;
197  using namespace mrpt::math;
198 
199  // get a list of nodes to check ICP against
200  MRPT_LOG_DEBUG_STREAM("Adding ICP Constraints for nodeID: " << curr_nodeID);
201 
202  std::set<TNodeID> nodes_set;
203  this->fetchNodeIDsForScanMatching(curr_nodeID, &nodes_set);
204 
205  // try adding ICP constraints with each node in the previous set
206  for (std::set<TNodeID>::const_iterator node_it = nodes_set.begin();
207  node_it != nodes_set.end(); ++node_it)
208  {
209  constraint_t rel_edge;
211 
213  "Fetching laser scan for nodes: " << *node_it << "==> "
214  << curr_nodeID);
215 
216  bool found_edge =
217  this->getICPEdge(*node_it, curr_nodeID, &rel_edge, &icp_info);
218  if (!found_edge) continue;
219 
220  // keep track of the recorded goodness values
221  // TODO - rethink on these condition.
222  if (!isnan(icp_info.goodness) ||
223  !approximatelyEqual(static_cast<double>(icp_info.goodness), 0.0))
224  {
225  m_laser_params.goodness_threshold_win.addNewMeasurement(
226  icp_info.goodness);
227  }
228  double goodness_thresh =
229  m_laser_params.goodness_threshold_win.getMedian() *
230  m_consec_icp_constraint_factor;
231  bool accept_goodness = icp_info.goodness > goodness_thresh;
233  "Curr. Goodness: " << icp_info.goodness
234  << "|\t Threshold: " << goodness_thresh << " => "
235  << (accept_goodness ? "ACCEPT" : "REJECT"));
236 
237  // make sure that the suggested edge makes sense with regards to current
238  // graph config - check against the current position difference
239  bool accept_mahal_distance = this->mahalanobisDistanceOdometryToICPEdge(
240  *node_it, curr_nodeID, rel_edge);
241 
242  // criterion for registering a new node
243  if (accept_goodness && accept_mahal_distance)
244  {
245  this->registerNewEdge(*node_it, curr_nodeID, rel_edge);
246  }
247  }
248 
249  MRPT_END;
250 } // end of addScanMatchingEdges
251 template <class GRAPH_T>
253  const mrpt::utils::TNodeID& from, const mrpt::utils::TNodeID& to,
254  constraint_t* rel_edge, mrpt::slam::CICP::TReturnInfo* icp_info,
255  const TGetICPEdgeAdParams* ad_params /*=NULL*/)
256 {
257  MRPT_START;
258  ASSERT_(rel_edge);
259  this->m_time_logger.enter("getICPEdge");
260 
261  using namespace mrpt::obs;
262  using namespace mrpt::utils;
263  using namespace std;
264  using namespace mrpt::graphslam::detail;
265 
266  // fetch the relevant laser scans and poses of the nodeIDs
267  // If given in the additional params struct, use those values instead of
268  // searching in the class std::map(s)
269  CObservation2DRangeScan::Ptr from_scan, to_scan;
270  global_pose_t from_pose;
271  global_pose_t to_pose;
272 
273  MRPT_LOG_DEBUG_STREAM("****In getICPEdge method: ");
274  if (ad_params)
275  {
277  "TGetICPEdgeAdParams:\n"
278  << ad_params->getAsString() << endl);
279  }
280 
281  // from-node parameters
282  const node_props_t* from_params =
283  ad_params ? &ad_params->from_params : NULL;
284  bool from_success = this->getPropsOfNodeID(
285  from, &from_pose, from_scan, from_params); // TODO
286  // to-node parameters
287  const node_props_t* to_params = ad_params ? &ad_params->to_params : NULL;
288  bool to_success = this->getPropsOfNodeID(to, &to_pose, to_scan, to_params);
289 
290  if (!from_success || !to_success)
291  {
293  "Either node #"
294  << from << " or node #" << to
295  << " doesn't contain a valid LaserScan. Ignoring this...");
296  return false;
297  }
298 
299  // make use of initial node position difference for the ICP edge
300  // from_node pose
301  pose_t initial_estim;
302  if (ad_params)
303  {
304  initial_estim = ad_params->init_estim;
305  }
306  else
307  {
308  initial_estim = to_pose - from_pose;
309  }
310 
312  "from_pose: " << from_pose << "| to_pose: " << to_pose
313  << "| init_estim: " << initial_estim);
314 
315  range_ops_t::getICPEdge(
316  *from_scan, *to_scan, rel_edge, &initial_estim, icp_info);
317  MRPT_LOG_DEBUG_STREAM("*************");
318 
319  this->m_time_logger.leave("getICPEdge");
320  return true;
321  MRPT_END;
322 } // end of getICPEdge
323 
324 template <class GRAPH_T>
326  const mrpt::utils::TNodeID& nodeID,
327  const std::map<mrpt::utils::TNodeID, node_props_t>& group_params,
328  node_props_t* node_props)
329 {
330  ASSERT_(node_props);
331 
332  // MRPT_LOG_DEBUG_STREAM(">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>");
333  // MRPT_LOG_DEBUG_STREAM("Running fillNodePropsFromGroupParams for nodeID
334  // \""
335  //<< nodeID << "\"");
336 
337  // Make sure that the given nodeID exists in the group_params
339  search = group_params.find(nodeID);
340  bool res = false;
341  if (search == group_params.end())
342  {
343  // MRPT_LOG_DEBUG_STREAM("Operation failed.");
344  }
345  else
346  {
347  *node_props = search->second;
348  res = true;
349  // MRPT_LOG_DEBUG_STREAM("Properties filled: " <<
350  // node_props->getAsString());
351  }
352 
353  // MRPT_LOG_DEBUG_STREAM("<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<");
354  return res;
355 }
356 
357 template <class GRAPH_T>
359  const mrpt::utils::TNodeID& nodeID, global_pose_t* pose,
361  const node_props_t* node_props /*=NULL*/) const
362 {
363  // make sure output instances are valid
364  ASSERT_(pose);
365 
366  bool filled_pose = false;
367  bool filled_scan = false;
368 
369  if (node_props)
370  {
371  // Pose
372  if (node_props->pose != global_pose_t())
373  {
374  *pose = node_props->pose;
375  filled_pose = true;
376  }
377  // LaserScan
378  if (node_props->scan)
379  {
380  scan = node_props->scan;
381  filled_scan = true;
382  }
383  }
384 
385  // TODO - What if the node_props->pose is indeed 0?
386  ASSERTMSG_(
387  !(filled_pose ^ filled_scan),
388  format(
389  "Either BOTH or NONE of the filled_pose, filled_scan should be set."
390  "NodeID: [%lu]",
391  static_cast<unsigned long>(nodeID)));
392 
393  //
394  // fill with class data if not yet available
395  //
396  if (!filled_pose)
397  {
398  // fill with class data if not yet available
400  this->m_graph->nodes.find(nodeID);
401  if (search != this->m_graph->nodes.end())
402  {
403  *pose = search->second;
404  filled_pose = true;
405  }
406  else
407  {
408  MRPT_LOG_WARN_STREAM("pose not found for nodeID: " << nodeID);
409  }
410  }
411  if (!filled_scan)
412  {
413  typename nodes_to_scans2D_t::const_iterator search =
414  this->m_nodes_to_laser_scans2D.find(nodeID);
415  if (search != this->m_nodes_to_laser_scans2D.end())
416  {
417  scan = search->second;
418  filled_scan = true;
419  }
420  }
421 
422  return filled_pose && filled_scan;
423 }
424 
425 template <class GRAPH_T>
427  partitions_t* partitions_for_LC)
428 {
429  MRPT_START;
430  this->m_time_logger.enter("LoopClosureEvaluation");
431 
432  using namespace std;
433  using namespace mrpt;
434  using namespace mrpt::utils;
435 
436  ASSERT_(partitions_for_LC);
437  partitions_for_LC->clear();
438 
439  // keep track of the previous nodes list of every partition. If this is not
440  // changed - do not mark it as potential for loop closure
442  // reset the previous list if full partitioning was issued
443  if (m_partitions_full_update)
444  {
445  m_partitionID_to_prev_nodes_list.clear();
446  }
447 
448  int partitionID = 0;
449  // for every partition...
450  for (partitions_t::const_iterator partitions_it = m_curr_partitions.begin();
451  partitions_it != m_curr_partitions.end();
452  ++partitions_it, ++partitionID)
453  {
454  // check whether the last registered node is in the currently traversed
455  // partition - if not, ignore it.
456  if (m_lc_params.LC_check_curr_partition_only)
457  {
458  bool curr_node_in_curr_partition =
459  ((find(
460  partitions_it->begin(), partitions_it->end(),
461  this->m_graph->nodeCount() - 1)) != partitions_it->end());
462  if (!curr_node_in_curr_partition)
463  {
464  continue;
465  }
466  }
467 
468  // keep track of the previous nodes list
469  finder = m_partitionID_to_prev_nodes_list.find(partitionID);
470  if (finder == m_partitionID_to_prev_nodes_list.end())
471  {
472  // nodes list is not registered yet
473  m_partitionID_to_prev_nodes_list.insert(
474  make_pair(partitionID, *partitions_it));
475  }
476  else
477  {
478  if (*partitions_it == finder->second)
479  {
480  // MRPT_LOG_DEBUG_STREAM("Partition " << partitionID
481  //<< " remained unchanged. ");
482  continue; // same list as before.. no need to check this...
483  }
484  else
485  { // list was changed - update the previous nodes list
486  // MRPT_LOG_DEBUG_STREAM("Partition " << partitionID << "
487  // CHANGED. ");
488  finder->second = *partitions_it;
489  }
490  }
491 
492  // investigate each partition
493  int curr_node_index = 1;
494  size_t prev_nodeID = *(partitions_it->begin());
495  for (vector_uint::const_iterator it = partitions_it->begin() + 1;
496  it != partitions_it->end(); ++it, ++curr_node_index)
497  {
498  size_t curr_nodeID = *it;
499 
500  // are there consecutive nodes with large difference inside this
501  // partition? Are these nodes enough to consider LC?
502  if ((curr_nodeID - prev_nodeID) > m_lc_params.LC_min_nodeid_diff)
503  {
504  // there is at least one divergent node..
505 
506  int num_after_nodes = partitions_it->size() - curr_node_index;
507  int num_before_nodes = partitions_it->size() - num_after_nodes;
508  if (num_after_nodes >= m_lc_params.LC_min_remote_nodes &&
509  num_before_nodes >= m_lc_params.LC_min_remote_nodes)
510  { // at least X LC nodes
512  "Found potential loop closures:"
513  << endl
514  << "\tPartitionID: " << partitionID << endl
515  << "\tPartition: "
516  << getSTLContainerAsString(*partitions_it).c_str()
517  << endl
518  << "\t" << prev_nodeID << " ==> " << curr_nodeID << endl
519  << "\tNumber of LC nodes: " << num_after_nodes);
520  partitions_for_LC->push_back(*partitions_it);
521  break; // no need to check the rest of the nodes in this
522  // partition
523  }
524  }
525 
526  // update the previous node
527  prev_nodeID = curr_nodeID;
528  }
529  this->logFmt(
530  LVL_DEBUG, "Successfully checked partition: %d", partitionID);
531  }
532 
533  this->m_time_logger.leave("LoopClosureEvaluation");
534  MRPT_END;
535 }
536 
537 template <class GRAPH_T>
539  const partitions_t& partitions)
540 {
541  MRPT_START;
542  using namespace mrpt;
543  using namespace mrpt::utils;
544  using namespace mrpt::graphslam::detail;
545  using namespace mrpt::math;
546  using namespace std;
547  this->m_time_logger.enter("LoopClosureEvaluation");
548 
549  if (partitions.size() == 0) return;
550 
551  this->logFmt(
552  LVL_DEBUG, "Evaluating partitions for loop closures...\n%s\n",
553  this->header_sep.c_str());
554 
555  // for each partition to be evaulated...
556  for (partitions_t::const_iterator p_it = partitions.begin();
557  p_it != partitions.end(); ++p_it)
558  {
559  vector_uint partition(*p_it);
560 
561  // split the partition to groups
562  vector_uint groupA, groupB;
563  this->splitPartitionToGroups(
564  partition, &groupA, &groupB,
565  /*max_nodes_in_group=*/5);
566 
567  // generate hypotheses pool
568  hypotsp_t hypots_pool;
569  this->generateHypotsPool(groupA, groupB, &hypots_pool);
570 
571  // compute the pair-wise consistency matrix
572  CMatrixDouble consist_matrix(hypots_pool.size(), hypots_pool.size());
573  this->generatePWConsistenciesMatrix(
574  groupA, groupB, hypots_pool, &consist_matrix);
575 
576  // evaluate resulting matrix - fill valid hypotheses
577  hypotsp_t valid_hypots;
578  this->evalPWConsistenciesMatrix(
579  consist_matrix, hypots_pool, &valid_hypots);
580 
581  // registering the indicated/valid hypotheses
582  if (valid_hypots.size())
583  {
584  MRPT_LOG_WARN_STREAM("Registering Hypotheses...");
585  for (typename hypotsp_t::iterator it = valid_hypots.begin();
586  it != valid_hypots.end(); ++it)
587  {
588  this->registerHypothesis(**it);
589  }
590  }
591  // delete all hypotheses - generated in the heap...
592  MRPT_LOG_DEBUG_STREAM("Deleting the generated hypotheses pool...");
593  for (typename hypotsp_t::iterator it = hypots_pool.begin();
594  it != hypots_pool.end(); ++it)
595  {
596  delete *it;
597  }
598  } // for each partition
599 
600  MRPT_LOG_DEBUG_STREAM("\n" << this->header_sep);
601  this->m_time_logger.leave("LoopClosureEvaluation");
602 
603  MRPT_END;
604 }
605 
606 template <class GRAPH_T>
608  const mrpt::math::CMatrixDouble& consist_matrix,
609  const hypotsp_t& hypots_pool, hypotsp_t* valid_hypots)
610 {
611  MRPT_START;
612  using namespace std;
613  using namespace mrpt::utils;
614  using namespace mrpt::math;
615 
616  ASSERT_(valid_hypots);
617  valid_hypots->clear();
618 
619  // evaluate the pair-wise consistency matrix
620  // compute dominant eigenvector
622  bool valid_lambda_ratio = this->computeDominantEigenVector(
623  consist_matrix, &u,
624  /*use_power_method=*/false);
625  if (!valid_lambda_ratio) return;
626 
627  // cout << "Dominant eigenvector: " << u.transpose() << endl;
628 
629  // discretize the indicator vector - maximize the dot product of
630  // w_unit .* u
631  ASSERT_(u.size());
632  dynamic_vector<double> w(u.size(), 0); // discretized indicator vector
633  double dot_product = 0;
634  for (int i = 0; i != w.size(); ++i)
635  {
636  // stream for debugging reasons
637  stringstream ss;
638 
639  // make the necessary change and see if the dot product increases
640  w(i) = 1;
641  double potential_dot_product =
642  ((w.transpose() * u) / w.squaredNorm()).value();
643  ss << mrpt::format(
644  "current: %f | potential_dot_product: %f", dot_product,
645  potential_dot_product);
646  if (potential_dot_product > dot_product)
647  {
648  ss << " ==> ACCEPT";
649  dot_product = potential_dot_product;
650  }
651  else
652  {
653  ss << " ==> REJECT";
654  w(i) = 0; // revert the change
655  }
656  ss << endl;
657  // MRPT_LOG_DEBUG_STREAM(ss.str());
658  }
659  cout << "Outcome of discretization: " << w.transpose() << endl;
660  // mrpt::system::pause();
661 
662  // Current hypothesis is to be registered.
663  if (!w.isZero())
664  {
665  for (int wi = 0; wi != w.size(); ++wi)
666  {
667  if (w(wi) == 1)
668  {
669  // search through the potential hypotheses, find the one with
670  // the
671  // correct ID and register it.
672  valid_hypots->push_back(this->findHypotByID(hypots_pool, wi));
673  }
674  }
675  }
676  // mrpt::system::pause();
677 
678  MRPT_END;
679 }
680 
681 template <class GRAPH_T>
683  vector_uint& partition, vector_uint* groupA, vector_uint* groupB,
684  int max_nodes_in_group /*=5*/)
685 {
686  MRPT_START;
687 
688  using namespace mrpt;
689  using namespace mrpt::utils;
690  using namespace mrpt::math;
691 
692  // assertions
693  ASSERTMSG_(groupA, "Pointer to groupA is not valid");
694  ASSERTMSG_(groupB, "Pointer to groupB is not valid");
695  ASSERTMSG_(
696  max_nodes_in_group == -1 || max_nodes_in_group > 0,
697  format(
698  "Value %d not permitted for max_nodes_in_group"
699  "Either use a positive integer, "
700  "or -1 for non-restrictive partition size",
701  max_nodes_in_group));
702 
703  // find a large difference between successive nodeIDs - that's where the cut
704  // is going to be
705  TNodeID prev_nodeID = 0;
706  size_t index_to_split = 1;
707  for (vector_uint::const_iterator it = partition.begin() + 1;
708  it != partition.end(); ++it, ++index_to_split)
709  {
710  TNodeID curr_nodeID = *it;
711 
712  if ((curr_nodeID - prev_nodeID) > m_lc_params.LC_min_nodeid_diff)
713  {
714  break;
715  }
716  // update the last nodeID
717  prev_nodeID = curr_nodeID;
718  }
719  ASSERT_(partition.size() > index_to_split);
720 
721  // Fill the groups
722  *groupA =
723  vector_uint(partition.begin(), partition.begin() + index_to_split);
724  *groupB = vector_uint(partition.begin() + index_to_split, partition.end());
725  // limit the number of nodes in each group
726  if (max_nodes_in_group != -1)
727  {
728  // groupA
729  if (groupA->size() > static_cast<size_t>(max_nodes_in_group))
730  {
731  *groupA = vector_uint(
732  groupA->begin(), groupA->begin() + max_nodes_in_group);
733  }
734  // groupB
735  if (groupB->size() > static_cast<size_t>(max_nodes_in_group))
736  {
737  *groupB =
738  vector_uint(groupB->end() - max_nodes_in_group, groupB->end());
739  }
740  }
741 
742  // mrpt::system::pause();
743  MRPT_END;
744 }
745 
746 template <class GRAPH_T>
748  const vector_uint& groupA, const vector_uint& groupB,
749  hypotsp_t* generated_hypots,
750  const TGenerateHypotsPoolAdParams* ad_params /*=NULL*/)
751 {
752  MRPT_START;
753  using namespace mrpt::utils;
754  using namespace mrpt;
755 
756  ASSERTMSG_(
757  generated_hypots,
758  "generateHypotsPool: Given hypotsp_t pointer is invalid.");
759  generated_hypots->clear();
760 
761  MRPT_LOG_DEBUG_STREAM("Generating hypotheses for groups: " << endl);
763  "- groupA:\t" << getSTLContainerAsString(groupA)
764  << " - size: " << groupA.size() << endl);
766  "- groupB:\t" << getSTLContainerAsString(groupB)
767  << " - size: " << groupB.size() << endl);
768 
769  // verify that the number of laserScans is the same as the number of poses
770  // if
771  // the TGenerateHyptsPoolAdParams is used
772  // formulate into function and pass vector_uint and ad_params->group
773  // TODO
774  if (ad_params)
775  {
777  ad_params->groupA_params;
778  if (params.size())
779  {
780  size_t nodes_count = groupA.size();
781 
782  // map should have same size
783  ASSERTMSG_(
784  nodes_count == params.size(),
785  format(
786  "Size mismatch between nodeIDs in group [%lu]"
787  " and corresponding properties map [%lu]",
788  nodes_count, params.size()));
789  }
790  }
791 
792  // use a hypothesis ID with which the consistency matrix will then be
793  // formed
794  int hypot_counter = 0;
795  int invalid_hypots = 0; // just for keeping track of them.
796  {
797  // iterate over all the nodes in both groups
798  for (vector_uint::const_iterator // B - from
799  b_it = groupB.begin();
800  b_it != groupB.end(); ++b_it)
801  {
802  for (vector_uint::const_iterator // A - to
803  a_it = groupA.begin();
804  a_it != groupA.end(); ++a_it)
805  {
806  // by default hypotheses will direct bi => ai; If the hypothesis
807  // is
808  // traversed the opposite way, take the opposite of the
809  // constraint
810  hypot_t* hypot = new hypot_t;
811  hypot->from = *b_it;
812  hypot->to = *a_it;
813  hypot->id = hypot_counter++;
814 
815  // [from] *b_it ====[edge]===> [to] *a_it
816 
817  // Fetch and set the pose and LaserScan of from, to nodeIDs
818  //
819  // even if icp_ad_params NULL, it will be handled appropriately
820  // by the
821  // getICPEdge fun.
822  // bool from_success, to_success;
823  TGetICPEdgeAdParams* icp_ad_params = NULL;
824  if (ad_params)
825  {
826  icp_ad_params = new TGetICPEdgeAdParams;
827  // from_success = fillNodePropsFromGroupParams(
828  fillNodePropsFromGroupParams(
829  *b_it, ad_params->groupB_params,
830  &icp_ad_params->from_params);
831  // to_success = fillNodePropsFromGroupParams(
832  fillNodePropsFromGroupParams(
833  *a_it, ad_params->groupA_params,
834  &icp_ad_params->to_params);
835 
836  // MRPT_LOG_DEBUG_STREAM(">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>");
837  // MRPT_LOG_DEBUG_STREAM("From nodeID (other): " << *b_it);
838  // MRPT_LOG_DEBUG_STREAM("From params (other): "
839  //<< icp_ad_params->from_params.getAsString());
840  // MRPT_LOG_DEBUG_STREAM("from_success: " << (from_success?
841  // "TRUE" : "FALSE"));
842  // MRPT_LOG_DEBUG_STREAM("**********");
843  // MRPT_LOG_DEBUG_STREAM("To nodeID (own) : " << *a_it);
844  // MRPT_LOG_DEBUG_STREAM("To params (own) : "
845  //<< icp_ad_params->to_params.getAsString());
846  // MRPT_LOG_DEBUG_STREAM("to_success: " << (to_success?
847  // "TRUE" : "FALSE"));
848  // MRPT_LOG_DEBUG_STREAM("<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<");
849  }
850 
851  // fetch the ICP constraint bi => ai
853  constraint_t edge;
854  bool found_edge = this->getICPEdge(
855  *b_it, *a_it, &edge, &icp_info, icp_ad_params);
856 
857  hypot->setEdge(edge);
858  hypot->goodness =
859  icp_info.goodness; // goodness related to the edge
860 
861  // Check if invalid
862  //
863  // Goodness Threshold
864  double goodness_thresh =
865  m_laser_params.goodness_threshold_win.getMedian() *
866  m_lc_icp_constraint_factor;
867  bool accept_goodness = icp_info.goodness > goodness_thresh;
869  "generateHypotsPool:\nCurr. Goodness: "
870  << icp_info.goodness << "|\t Threshold: " << goodness_thresh
871  << " => " << (accept_goodness ? "ACCEPT" : "REJECT")
872  << endl);
873 
874  if (!found_edge || !accept_goodness)
875  {
876  hypot->is_valid = false;
877  invalid_hypots++;
878  }
879  generated_hypots->push_back(hypot);
881 
882  // delete pointer to getICPEdge additional parameters if they
883  // were
884  // initialized
885  delete icp_ad_params;
886  }
887  }
889  "Generated pool of hypotheses...\tsize = "
890  << generated_hypots->size()
891  << "\tinvalid hypotheses: " << invalid_hypots);
892  }
893  // mrpt::system::pause();
894 
895  MRPT_END;
896 } // end of generateHypotsPool
897 
898 template <class GRAPH_T>
900  const mrpt::math::CMatrixDouble& consist_matrix,
901  mrpt::math::dynamic_vector<double>* eigvec, bool use_power_method /*=true*/)
902 {
903  MRPT_START;
904  using namespace mrpt;
905  using namespace mrpt::utils;
906  using namespace mrpt::math;
907  using namespace std;
908  ASSERT_(eigvec);
909 
910  this->m_time_logger.enter("DominantEigenvectorComputation");
911 
912  double lambda1, lambda2; // eigenvalues to use
913  bool is_valid_lambda_ratio = false;
914 
915  if (use_power_method)
916  {
918  "\nPower method for computing the first two "
919  "eigenvectors/eigenvalues hasn't been implemented yet\n");
920  }
921  else
922  { // call to eigenVectors method
923  CMatrixDouble eigvecs, eigvals;
924  consist_matrix.eigenVectors(eigvecs, eigvals);
925 
926  // assert that the eivenvectors, eigenvalues, consistency matrix are of
927  // the
928  // same size
929  ASSERTMSG_(
930  eigvecs.size() == eigvals.size() &&
931  consist_matrix.size() == eigvals.size(),
932  mrpt::format(
933  "Size of eigvecs \"%lu\","
934  "eigvalues \"%lu\","
935  "consist_matrix \"%lu\" don't match",
936  static_cast<unsigned long>(eigvecs.size()),
937  static_cast<unsigned long>(eigvals.size()),
938  static_cast<unsigned long>(consist_matrix.size())));
939 
940  eigvecs.extractCol(eigvecs.getColCount() - 1, *eigvec);
941  lambda1 = eigvals(eigvals.getRowCount() - 1, eigvals.getColCount() - 1);
942  lambda2 = eigvals(eigvals.getRowCount() - 2, eigvals.getColCount() - 2);
943  }
944 
945  // I don't care about the sign of the eigenvector element
946  for (int i = 0; i != eigvec->size(); ++i)
947  {
948  (*eigvec)(i) = abs((*eigvec)(i));
949  }
950 
951  // check the ratio of the two eigenvalues - reject hypotheses set if ratio
952  // smaller than threshold
953  if (approximatelyEqual(0.0, lambda2, /**limit = */ 0.00001))
954  {
956  "Bad lambda2 value: "
957  << lambda2 << " => Skipping current evaluation." << endl);
958  return false;
959  }
960  double curr_lambda_ratio = lambda1 / lambda2;
962  "lambda1 = " << lambda1 << " | lambda2 = " << lambda2
963  << "| ratio = " << curr_lambda_ratio << endl);
964 
965  is_valid_lambda_ratio =
966  (curr_lambda_ratio > m_lc_params.LC_eigenvalues_ratio_thresh);
967 
968  this->m_time_logger.leave("DominantEigenvectorComputation");
969  return is_valid_lambda_ratio;
970 
971  MRPT_END;
972 } // end of computeDominantEigenVector
973 
974 template <class GRAPH_T>
976  const vector_uint& groupA, const vector_uint& groupB,
977  const hypotsp_t& hypots_pool, mrpt::math::CMatrixDouble* consist_matrix,
978  const paths_t* groupA_opt_paths /*=NULL*/,
979  const paths_t* groupB_opt_paths /*=NULL*/)
980 {
981  MRPT_START;
982 
983  using namespace mrpt;
984  using namespace mrpt::math;
985  using namespace mrpt::utils;
986  using namespace std;
987  ASSERTMSG_(
988  consist_matrix, "Invalid pointer to the Consistency matrix is given");
989  ASSERTMSG_(
990  static_cast<unsigned long>(consist_matrix->rows()) ==
991  hypots_pool.size() &&
992  static_cast<unsigned long>(consist_matrix->rows()) ==
993  hypots_pool.size(),
994  "Consistency matrix dimensions aren't equal to the hypotheses pool "
995  "size");
996 
998  ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>"
999  << endl
1000  << "In generatePWConsistencyMatrix:\n"
1001  << "\tgroupA: " << getSTLContainerAsString(groupA) << endl
1002  << "\tgroupB: " << getSTLContainerAsString(groupB) << endl
1003  << "\tHypots pool Size: " << hypots_pool.size());
1004 
1005  // b1
1006  for (vector_uint::const_iterator b1_it = groupB.begin();
1007  b1_it != groupB.end(); ++b1_it)
1008  {
1009  TNodeID b1 = *b1_it;
1010 
1011  // b2
1012  for (vector_uint::const_iterator b2_it = b1_it + 1;
1013  b2_it != groupB.end(); ++b2_it)
1014  {
1015  TNodeID b2 = *b2_it;
1016 
1017  // a1
1018  for (vector_uint::const_iterator a1_it = groupA.begin();
1019  a1_it != groupA.end(); ++a1_it)
1020  {
1021  TNodeID a1 = *a1_it;
1022  hypot_t* hypot_b2_a1 =
1023  this->findHypotByEnds(hypots_pool, b2, a1);
1024  // MRPT_LOG_DEBUG_STREAM("hypot_b2_a1: " <<
1025  // hypot_b2_a1->getAsString());
1026 
1027  // a2
1028  for (vector_uint::const_iterator a2_it = a1_it + 1;
1029  a2_it != groupA.end(); ++a2_it)
1030  {
1031  TNodeID a2 = *a2_it;
1032  hypot_t* hypot_b1_a2 =
1033  this->findHypotByEnds(hypots_pool, b1, a2);
1034  // MRPT_LOG_DEBUG_STREAM("hypot_b1_a2: " <<
1035  // hypot_b1_a2->getAsString());
1036 
1037  double consistency;
1038 
1039  // compute consistency element
1040  if (hypot_b2_a1->is_valid && hypot_b1_a2->is_valid)
1041  {
1042  // extract vector of hypotheses that connect the given
1043  // nodes,
1044  // instead of passing the whole hypothesis pool.
1045  hypotsp_t extracted_hypots;
1046  extracted_hypots.push_back(hypot_b2_a1);
1047  extracted_hypots.push_back(hypot_b1_a2);
1048 
1049  paths_t* curr_opt_paths = NULL;
1050  if (groupA_opt_paths || groupB_opt_paths)
1051  { // fill curr_opt_paths
1052  curr_opt_paths = new paths_t();
1053  }
1054 
1055  // decide on additional optimal paths
1056  if (curr_opt_paths)
1057  {
1058  // groupA
1059  if (groupA_opt_paths)
1060  { // a1 -> a2 optimal path
1061  const path_t* p = this->findPathByEnds(
1062  *groupA_opt_paths, a1, a2,
1063  /*throw_exc=*/true);
1064  curr_opt_paths->push_back(*p);
1065  }
1066  else
1067  { // empty
1068  curr_opt_paths->push_back(path_t());
1069  }
1070 
1071  if (groupB_opt_paths)
1072  { // b1 -> b2 optimal path
1073  const path_t* p = this->findPathByEnds(
1074  *groupB_opt_paths, b1, b2,
1075  /*throw_exc=*/true);
1076  curr_opt_paths->push_back(*p);
1077  }
1078  else
1079  { // empty
1080  curr_opt_paths->push_back(path_t());
1081  }
1082  }
1083 
1084  consistency = this->generatePWConsistencyElement(
1085  a1, a2, b1, b2, extracted_hypots, curr_opt_paths);
1086 
1087  delete curr_opt_paths;
1088  }
1089  else
1090  { // null those that don't look good
1091  consistency = 0;
1092  }
1093 
1094  // MRPT_LOG_DEBUG_STREAM(
1095  //"Adding hypothesis consistency for nodeIDs: "
1096  //<< "[b1] " << b1 << ", [b2] -> " << b2
1097  //<< ", [a1] -> " << a1 << ", [a2] -> " << a2
1098  //<< " ==> " << consistency << endl);
1099 
1100  // fill the PW consistency matrix corresponding element -
1101  // symmetrical
1102  int id1 = hypot_b2_a1->id;
1103  int id2 = hypot_b1_a2->id;
1104 
1105  (*consist_matrix)(id1, id2) = consistency;
1106  (*consist_matrix)(id2, id1) = consistency;
1107 
1108  // MRPT_LOG_DEBUG_STREAM("id1 = " << id1 << "\t|"
1109  //<< "id2 = " << id2 << "\t|"
1110  //<< "consistency = " << consistency);
1111  }
1112  }
1113  }
1114  }
1115 
1116  // MRPT_LOG_WARN_STREAM("Consistency matrix:" << endl
1117  //<< this->header_sep << endl
1118  //<< *consist_matrix << endl);
1119 
1120  MRPT_END;
1121 } // end of generatePWConsistenciesMatrix
1122 
1123 template <class GRAPH_T>
1127  const hypotsp_t& hypots, const paths_t* opt_paths /*=NULL*/)
1128 {
1129  MRPT_START;
1130  using namespace std;
1131  using namespace mrpt;
1132  using namespace mrpt::math;
1133  using namespace mrpt::utils;
1134  using namespace mrpt::graphslam;
1135  using namespace mrpt::graphslam::detail;
1136 
1137  // MRPT_LOG_DEBUG_STREAM("In generatePWConsistencyElement.\n"
1138  //<< "\t[" << a1 << ", " << a2 << "]\n"
1139  //<< "\t[" << b1 << ", " << b2 << "]");
1140  // MRPT_LOG_DEBUG_STREAM("a1->a2 optimal path:"
1141  //<< (opt_paths && !opt_paths->begin()->isEmpty()?
1142  // opt_paths->begin()->getAsString() :
1143  //"NONE"));
1144  // MRPT_LOG_DEBUG_STREAM("b1->b2 optimal path: "
1145  //<< (opt_paths && !opt_paths->rbegin()->isEmpty()?
1146  // opt_paths->rbegin()->getAsString() :
1147  //"NONE"));
1148 
1149  // standard size assertions
1150  ASSERT_(hypots.size() == 2);
1151  if (opt_paths)
1152  {
1153  ASSERT_(opt_paths->size() == 2);
1154  }
1155 
1156  //
1157  // get the Dijkstra links
1158  //
1159  // a1 ==> a2
1160  const path_t* path_a1_a2;
1161  if (!opt_paths || opt_paths->begin()->isEmpty())
1162  {
1164  "Running dijkstra [a1] " << a1 << " => [a2] " << a2);
1165  execDijkstraProjection(/*starting_node=*/a1, /*ending_node=*/a2);
1166  path_a1_a2 = this->queryOptimalPath(a2);
1167  }
1168  else
1169  { // fetch the path from the opt_paths arg
1170  // TODO dubious practice
1171  path_a1_a2 = &(*opt_paths->begin());
1172  }
1173  ASSERT_(path_a1_a2);
1174  path_a1_a2->assertIsBetweenNodeIDs(/*start=*/a1, /*end*/ a2);
1175 
1176  // b1 ==> b2
1177  const path_t* path_b1_b2;
1178  if (!opt_paths || opt_paths->rend()->isEmpty())
1179  {
1181  "Running djkstra [b1] " << b1 << " => [b2] " << b2);
1182  execDijkstraProjection(/*starting_node=*/b1, /*ending_node=*/b2);
1183  path_b1_b2 = this->queryOptimalPath(b2);
1184  }
1185  else
1186  { // fetch the path from the opt_paths arg
1187  path_b1_b2 = &(*opt_paths->rbegin());
1188  }
1189  ASSERT_(path_b1_b2);
1190  path_b1_b2->assertIsBetweenNodeIDs(/*start=*/b1, /*end*/ b2);
1191  // get the edges of the hypotheses
1192  // by default hypotheses are stored bi => ai
1193  //
1194  // Backwards edge: a2=>b1
1195  hypot_t* hypot_b1_a2 = this->findHypotByEnds(hypots, b1, a2);
1196  // forward edge b2=>a1
1197  hypot_t* hypot_b2_a1 = this->findHypotByEnds(hypots, b2, a1);
1198 
1199  // Composition of Poses
1200  // Order : a1 ==> a2 ==> b1 ==> b2 ==> a1
1201  constraint_t res_transform(path_a1_a2->curr_pose_pdf);
1202  res_transform += hypot_b1_a2->getInverseEdge();
1203  res_transform += path_b1_b2->curr_pose_pdf;
1204  res_transform += hypot_b2_a1->getEdge();
1205 
1207  "\n-----------Resulting Transformation----------- Hypots: #"
1208  << hypot_b1_a2->id << ", #" << hypot_b2_a1->id << endl
1209  << "a1 --> a2 => b1 --> b2 => a1: " << a1 << " --> " << a2 << " => "
1210  << b1 << " --> " << b2 << " => " << a1 << endl
1211  << res_transform << endl
1212  << endl
1213  << "DIJKSTRA: " << a1 << " --> " << a2 << ": "
1214  << path_a1_a2->curr_pose_pdf << endl
1215  << "DIJKSTRA: " << b1 << " --> " << b2 << ": "
1216  << path_b1_b2->curr_pose_pdf << endl
1217  << "hypot_b1_a2(inv):\n"
1218  << hypot_b1_a2->getInverseEdge() << endl
1219  << "hypot_b2_a1:\n"
1220  << hypot_b2_a1->getEdge() << endl);
1221 
1222  // get the vector of the corresponding transformation - [x, y, phi] form
1224  res_transform.getMeanVal().getAsVector(T);
1225 
1226  // information matrix
1227  CMatrixDouble33 cov_mat;
1228  res_transform.getCovariance(cov_mat);
1229 
1230  // there has to be an error with the initial Olson formula - p.15.
1231  // There must be a minus in the exponent and the covariance matrix instead
1232  // of
1233  // the information matrix.
1234  double exponent = (-T.transpose() * cov_mat * T).value();
1235  double consistency_elem = exp(exponent);
1236 
1237  // cout << "T = " << endl << T << endl;
1238  // cout << "exponent = " << exponent << endl;
1239  // cout << "consistency_elem = " << consistency_elem << endl;
1240  // mrpt::system::pause();
1241 
1242  return consistency_elem;
1243  MRPT_END;
1244 } // end of generatePWConsistencyElement
1245 
1246 template <class GRAPH_T>
1249  const paths_t& vec_paths, const mrpt::utils::TNodeID& src,
1250  const mrpt::utils::TNodeID& dst, bool throw_exc /*=true*/)
1251 {
1252  using namespace mrpt;
1253 
1254  ASSERT_(vec_paths.size());
1255  const path_t* res = NULL;
1256 
1257  for (typename paths_t::const_iterator cit = vec_paths.begin();
1258  cit != vec_paths.end(); ++cit)
1259  {
1260  if (cit->getSource() == src && cit->getDestination() == dst)
1261  {
1262  res = &(*cit);
1263  break;
1264  }
1265  }
1266  if (throw_exc && !res)
1267  {
1269  format(
1270  "Path for %lu => %lu is not found. Exiting...\n",
1271  static_cast<unsigned long>(src),
1272  static_cast<unsigned long>(dst)));
1273  }
1274 
1275  return res;
1276 }
1277 
1278 template <class GRAPH_T>
1281  const hypotsp_t& vec_hypots, const mrpt::utils::TNodeID& from,
1282  const mrpt::utils::TNodeID& to, bool throw_exc /*=true*/)
1283 {
1284  using namespace mrpt::graphslam::detail;
1285  using namespace std;
1286 
1287  for (typename hypotsp_t::const_iterator v_cit = vec_hypots.begin();
1288  v_cit != vec_hypots.end(); v_cit++)
1289  {
1290  if ((*v_cit)->hasEnds(from, to))
1291  {
1292  // cout << "findHypotByEnds: Found hypot " << from
1293  //<< " => " << to << " : " << (*v_cit)->getAsString() << endl;
1294  return *v_cit;
1295  }
1296  }
1297 
1298  // not found.
1299  if (throw_exc)
1300  {
1301  throw HypothesisNotFoundException(from, to);
1302  }
1303  else
1304  {
1305  return NULL;
1306  }
1307 } // end of findHypotByEnds
1308 
1309 template <class GRAPH_T>
1312  const hypotsp_t& vec_hypots, const size_t& id, bool throw_exc /*=true*/)
1313 {
1314  using namespace mrpt::graphslam::detail;
1315 
1316  for (typename hypotsp_t::const_iterator v_cit = vec_hypots.begin();
1317  v_cit != vec_hypots.end(); v_cit++)
1318  {
1319  if ((*v_cit)->id == id)
1320  {
1321  return *v_cit;
1322  }
1323  }
1324 
1325  // not found.
1326  if (throw_exc)
1327  {
1328  throw HypothesisNotFoundException(id);
1329  }
1330  else
1331  {
1332  return NULL;
1333  }
1334 }
1335 
1336 template <class GRAPH_T>
1338  mrpt::utils::TNodeID starting_node /*=0*/,
1339  mrpt::utils::TNodeID ending_node /*=INVALID_NODEID*/)
1340 {
1341  MRPT_START;
1342  using namespace std;
1343  using namespace mrpt;
1344  using namespace mrpt::utils;
1345  using namespace mrpt::math;
1346 
1347  // for the full algorithm see
1348  // - Recognizing places using spectrally clustered local matches - E.Olson,
1349  // p.6
1350 
1351  this->m_time_logger.enter("Dijkstra Projection");
1352  const std::string dijkstra_end =
1353  "----------- Done with Dijkstra Projection... ----------";
1354 
1355  // ending_node is either INVALID_NODEID or one of the already registered
1356  // nodeIDs
1357  ASSERT_(
1358  ending_node == INVALID_NODEID ||
1359  (ending_node >= 0 && ending_node < this->m_graph->nodeCount()));
1360  ASSERTMSG_(
1361  starting_node != ending_node, "Starting and Ending nodes coincede");
1362 
1363  // debugging message
1364  stringstream ss_debug("");
1365  ss_debug << "Executing Dijkstra Projection: " << starting_node << " => ";
1366  if (ending_node == INVALID_NODEID)
1367  {
1368  ss_debug << "..." << endl;
1369  }
1370  else
1371  {
1372  ss_debug << ending_node << endl;
1373  }
1374 
1375  if (this->m_graph->nodeCount() < m_dijkstra_node_count_thresh)
1376  {
1377  return;
1378  }
1379 
1380  // keep track of the nodes that I have visited
1381  std::vector<bool> visited_nodes(this->m_graph->nodeCount(), false);
1382  m_node_optimal_paths.clear();
1383 
1384  // get the neighbors of each node
1385  std::map<TNodeID, std::set<TNodeID>> neighbors_of;
1386  this->m_graph->getAdjacencyMatrix(neighbors_of);
1387 
1388  // initialize a pool of TUncertaintyPaths - draw the minimum-uncertainty
1389  // path during
1390  // execution
1391  std::set<path_t*> pool_of_paths;
1392  // get the edge to each one of the neighboring nodes of the starting node
1393  std::set<TNodeID> starting_node_neighbors(neighbors_of.at(starting_node));
1395  starting_node_neighbors.begin();
1396  n_it != starting_node_neighbors.end(); ++n_it)
1397  {
1398  path_t* path_between_neighbors = new path_t();
1399  this->getMinUncertaintyPath(
1400  starting_node, *n_it, path_between_neighbors);
1401 
1402  pool_of_paths.insert(path_between_neighbors);
1403  }
1404  // just visited the first node
1405  visited_nodes.at(starting_node) = true;
1406 
1407  //// TODO Remove these - >>>>>>>>>>>>>>>>>>>>
1408  //// printing the pool for verification
1409  // cout << "Pool of Paths: " << endl;
1410  // for (typename std::set<path_t*>::const_iterator it =
1411  // pool_of_paths.begin();
1412  // it != pool_of_paths.end(); ++it) {
1413  // printSTLContainer((*it)->nodes_traversed);
1414  //}
1415  // cout << "------ Done with the starting node ... ------" << endl;
1416  // int iters = 0;
1417  //// TODO Remove these - <<<<<<<<<<<<<<<<<<<<< vvvUNCOMMENT BELOW AS WELLvvv
1418 
1419  while (true)
1420  {
1421  // if there is at least one false, exit loop
1422  for (std::vector<bool>::const_iterator it = visited_nodes.begin();
1423  it != visited_nodes.end(); ++it)
1424  {
1425  if (!*it)
1426  {
1427  break;
1428  }
1429  }
1430 
1431  // if an ending nodeID has been specified, end the method when the path
1432  // to
1433  // it is found.
1434  if (ending_node != INVALID_NODEID)
1435  {
1436  if (visited_nodes.at(ending_node))
1437  {
1438  // MRPT_LOG_DEBUG_STREAM(dijkstra_end);
1439  this->m_time_logger.leave("Dijkstra Projection");
1440  return;
1441  }
1442  }
1443 
1444  path_t* optimal_path = this->popMinUncertaintyPath(&pool_of_paths);
1445  TNodeID dest = optimal_path->getDestination();
1446 
1447  //// TODO Remove these - >>>>>>>>>>>>>>>>>>>> ^^^UNCOMMENT ABOVE AS
1448  /// WELL^^^
1449  // cout << iters << " " << std::string(40, '>') << endl;
1450  // cout << "current path Destination: " << dest << endl;
1451  //// printing the pool for verification
1452  // cout << "Pool of Paths: " << endl;
1453  // for (typename std::set<path_t*>::const_iterator
1454  // it = pool_of_paths.begin();
1455  // it != pool_of_paths.end(); ++it) {
1456  // printSTLContainer((*it)->nodes_traversed);
1457  //}
1458  // cout << "Nodes visited: " << endl;
1459  // std::vector<int> tmp_vec;
1460  // for (int i = 0; i != visited_nodes.size(); ++i) {
1461  // tmp_vec.push_back(i);
1462  //}
1463  // printSTLContainer(tmp_vec); cout << endl; // indices of numbers
1464  // printSTLContainer(visited_nodes); // actual flags
1465  // cout << std::string(40, '<') << " " << iters++ << endl;
1466  // mrpt::system::pause();
1467  //// TODO Remove these - <<<<<<<<<<<<<<<<<<<<<
1468 
1469  if (!visited_nodes.at(dest))
1470  {
1471  m_node_optimal_paths[dest] = optimal_path;
1472  visited_nodes.at(dest) = true;
1473 
1474  // for all the edges leaving this node .. compose the transforms
1475  // with the
1476  // current pool of paths.
1477  this->addToPaths(
1478  &pool_of_paths, *optimal_path, neighbors_of.at(dest));
1479  }
1480  }
1481 
1482  // MRPT_LOG_DEBUG_STREAM(dijkstra_end);
1483  this->m_time_logger.leave("Dijkstra Projection");
1484  MRPT_END;
1485 }
1486 
1487 template <class GRAPH_T>
1489  std::set<path_t*>* pool_of_paths, const path_t& current_path,
1490  const std::set<mrpt::utils::TNodeID>& neighbors) const
1491 {
1492  MRPT_START;
1493  using namespace mrpt::utils;
1494  using namespace std;
1495  using namespace mrpt::graphslam;
1496 
1497  TNodeID node_to_append_from = current_path.getDestination();
1498 
1499  // compose transforms for every neighbor of node_to_append_from *except*
1500  // for the link connecting node_to_append_from and the second to last node
1501  // in
1502  // the current_path
1503  TNodeID second_to_last_node = current_path.nodes_traversed.rbegin()[1];
1504  for (std::set<TNodeID>::const_iterator neigh_it = neighbors.begin();
1505  neigh_it != neighbors.end(); ++neigh_it)
1506  {
1507  if (*neigh_it == second_to_last_node) continue;
1508 
1509  // get the path between node_to_append_from, *node_it
1510  path_t path_between_nodes;
1511  this->getMinUncertaintyPath(
1512  node_to_append_from, *neigh_it, &path_between_nodes);
1513 
1514  // format the path to append
1515  path_t* path_to_append = new path_t();
1516  *path_to_append = current_path;
1517  *path_to_append += path_between_nodes;
1518 
1519  pool_of_paths->insert(path_to_append);
1520  }
1521 
1522  MRPT_END;
1523 }
1524 
1525 template <class GRAPH_T>
1527  GRAPH_T>::queryOptimalPath(const mrpt::utils::TNodeID node) const
1528 {
1529  using namespace std;
1530 
1531  path_t* path = NULL;
1533  search = m_node_optimal_paths.find(node);
1534  if (search != m_node_optimal_paths.end())
1535  {
1536  path = search->second;
1537  }
1538 
1539  // MRPT_LOG_DEBUG_STREAM("Queried optimal path for nodeID: " << node
1540  //<< " ==> Path: " << (path? "Found" : "NOT Found"));
1541  return path;
1542 }
1543 
1544 template <class GRAPH_T>
1546  const mrpt::utils::TNodeID from, const mrpt::utils::TNodeID to,
1547  path_t* path_between_nodes) const
1548 {
1549  MRPT_START;
1550  using namespace mrpt::utils;
1551  using namespace mrpt::math;
1552  using namespace std;
1553 
1554  ASSERTMSG_(
1555  this->m_graph->edgeExists(from, to) ||
1556  this->m_graph->edgeExists(to, from),
1557  mrpt::format(
1558  "\nEdge between the provided nodeIDs"
1559  "(%lu <-> %lu) does not exist\n",
1560  from, to));
1561  ASSERT_(path_between_nodes);
1562 
1563  // cout << "getMinUncertaintyPath: " << from << " => " << to << endl;
1564 
1565  // don't add to the path_between_nodes, just fill it in afterwards
1566  path_between_nodes->clear();
1567 
1568  // iterate over all the edges, ignore the ones that are all 0s - find the
1569  // one that is with the lowest uncertainty
1570  double curr_determinant = 0;
1571  // forward edges from -> to
1572  std::pair<edges_citerator, edges_citerator> fwd_edges_pair =
1573  this->m_graph->getEdges(from, to);
1574 
1575  // cout << "Forward edges: " << endl;
1576  // for (edges_citerator e_it = fwd_edges_pair.first; e_it !=
1577  // fwd_edges_pair.second;
1578  //++e_it) {
1579  // cout << e_it->second << endl;
1580  //}
1581 
1582  for (edges_citerator edges_it = fwd_edges_pair.first;
1583  edges_it != fwd_edges_pair.second; ++edges_it)
1584  {
1585  // operate on a temporary object instead of the real edge - otherwise
1586  // function is non-const
1587  constraint_t curr_edge;
1588  curr_edge.copyFrom(edges_it->second);
1589 
1590  // is it all 0s?
1591  CMatrixDouble33 inf_mat;
1592  curr_edge.getInformationMatrix(inf_mat);
1593 
1594  if (inf_mat == CMatrixDouble33() || std::isnan(inf_mat(0, 0)))
1595  {
1596  inf_mat.unit();
1597  curr_edge.cov_inv = inf_mat;
1598  }
1599 
1600  path_t curr_path(from); // set the starting node
1601  curr_path.addToPath(to, curr_edge);
1602 
1603  // update the resulting path_between_nodes if its determinant is smaller
1604  // than the determinant of the current path_between_nodes
1605  if (curr_determinant < curr_path.getDeterminant())
1606  {
1607  curr_determinant = curr_path.getDeterminant();
1608  *path_between_nodes = curr_path;
1609  }
1610  }
1611  // backwards edges to -> from
1612  std::pair<edges_citerator, edges_citerator> bwd_edges_pair =
1613  this->m_graph->getEdges(to, from);
1614 
1615  // cout << "Backwards edges: " << endl;
1616  // for (edges_citerator e_it = bwd_edges_pair.first; e_it !=
1617  // bwd_edges_pair.second;
1618  //++e_it) {
1619  // cout << e_it->second << endl;
1620  //}
1621 
1622  for (edges_citerator edges_it = bwd_edges_pair.first;
1623  edges_it != bwd_edges_pair.second; ++edges_it)
1624  {
1625  // operate on a temporary object instead of the real edge - otherwise
1626  // function is non-const
1627  constraint_t curr_edge;
1628  (edges_it->second).inverse(curr_edge);
1629 
1630  // is it all 0s?
1631  CMatrixDouble33 inf_mat;
1632  curr_edge.getInformationMatrix(inf_mat);
1633 
1634  if (inf_mat == CMatrixDouble33() || std::isnan(inf_mat(0, 0)))
1635  {
1636  inf_mat.unit();
1637  curr_edge.cov_inv = inf_mat;
1638  }
1639 
1640  path_t curr_path(from); // set the starting node
1641  curr_path.addToPath(to, curr_edge);
1642 
1643  // update the resulting path_between_nodes if its determinant is smaller
1644  // than the determinant of the current path_between_nodes
1645  if (curr_determinant < curr_path.getDeterminant())
1646  {
1647  curr_determinant = curr_path.getDeterminant();
1648  *path_between_nodes = curr_path;
1649  }
1650  }
1651 
1652  MRPT_END;
1653 }
1654 
1655 template <class GRAPH_T>
1657  typename std::set<path_t*>* pool_of_paths) const
1658 {
1659  MRPT_START;
1660  using namespace std;
1661 
1662  // cout << "Determinants: ";
1663  path_t* optimal_path = NULL;
1664  double curr_determinant = 0;
1665  for (typename std::set<path_t*>::const_iterator it = pool_of_paths->begin();
1666  it != pool_of_paths->end(); ++it)
1667  {
1668  // cout << (*it)->getDeterminant() << ", ";
1669 
1670  // keep the largest determinant - we are in INFORMATION form.
1671  if (curr_determinant < (*it)->getDeterminant())
1672  {
1673  curr_determinant = (*it)->getDeterminant();
1674  optimal_path = *it;
1675  }
1676  }
1677 
1678  ASSERT_(optimal_path);
1679  pool_of_paths->erase(optimal_path); // erase it from the pool
1680 
1681  return optimal_path;
1682  MRPT_END;
1683 }
1684 
1685 template <class GRAPH_T>
1687  const mrpt::utils::TNodeID& from, const mrpt::utils::TNodeID& to,
1688  const constraint_t& rel_edge)
1689 {
1690  MRPT_START;
1691 
1692  using namespace std;
1693  using namespace mrpt::math;
1694  using namespace mrpt::utils;
1695 
1696  // mean difference
1697  pose_t initial_estim =
1698  this->m_graph->nodes.at(to) - this->m_graph->nodes.at(from);
1699  dynamic_vector<double> mean_diff;
1700  (rel_edge.getMeanVal() - initial_estim).getAsVector(mean_diff);
1701 
1702  // covariance matrix
1703  CMatrixDouble33 cov_mat;
1704  rel_edge.getCovariance(cov_mat);
1705 
1706  // mahalanobis distance computation
1707  double mahal_distance =
1708  mrpt::math::mahalanobisDistance2(mean_diff, cov_mat);
1709  bool mahal_distance_null = std::isnan(mahal_distance);
1710  if (!mahal_distance_null)
1711  {
1712  m_laser_params.mahal_distance_ICP_odom_win.addNewMeasurement(
1713  mahal_distance);
1714  }
1715 
1716  // double threshold = m_laser_params.mahal_distance_ICP_odom_win.getMean() +
1717  // 2*m_laser_params.mahal_distance_ICP_odom_win.getStdDev();
1718  double threshold =
1719  m_laser_params.mahal_distance_ICP_odom_win.getMedian() * 4;
1720  bool accept_edge =
1721  (threshold >= mahal_distance && !mahal_distance_null) ? true : false;
1722 
1723  // cout << "Suggested Edge: " << rel_edge.getMeanVal() << "|\tInitial
1724  // Estim.: " << initial_estim
1725  //<< "|\tMahalanobis Dist: " << mahal_distance << "|\tThresh.: " <<
1726  // threshold
1727  //<< " => " << (accept_edge? "ACCEPT": "REJECT") << endl;
1728 
1729  return accept_edge;
1730  MRPT_END;
1731 }
1732 
1733 template <class GRAPH_T>
1735 {
1736  // MRPT_LOG_DEBUG_STREAM("Registering hypothesis: " <<
1737  // hypot.getAsString([>oneline=<] true));
1738  this->registerNewEdge(hypot.from, hypot.to, hypot.getEdge());
1739 }
1740 
1741 template <class GRAPH_T>
1743  const mrpt::utils::TNodeID& from, const mrpt::utils::TNodeID& to,
1744  const constraint_t& rel_edge)
1745 {
1746  MRPT_START;
1747  using namespace mrpt::utils;
1748  using namespace mrpt::math;
1749  using namespace std;
1750  parent_t::registerNewEdge(from, to, rel_edge);
1751 
1752  // keep track of the registered edges...
1753  m_edge_types_to_nums["ICP2D"]++;
1754 
1755  // keep track of the registered edges...
1756  if (absDiff(to, from) > m_lc_params.LC_min_nodeid_diff)
1757  {
1758  m_edge_types_to_nums["LC"]++;
1759  this->m_just_inserted_lc = true;
1760  this->logFmt(LVL_INFO, "\tLoop Closure edge!");
1761  }
1762  else
1763  {
1764  this->m_just_inserted_lc = false;
1765  }
1766 
1767  // actuall registration
1768  this->m_graph->insertEdge(from, to, rel_edge);
1769 
1770  MRPT_END;
1771 }
1772 
1773 template <class GRAPH_T>
1775  mrpt::graphslam::CWindowManager* win_manager)
1776 {
1777  // call parent_t class method
1778  parent_t::setWindowManagerPtr(win_manager);
1779 
1780  using namespace mrpt::utils;
1781 
1782  // may still be null..
1783  if (this->m_win_manager)
1784  {
1785  if (this->m_win_observer)
1786  {
1787  this->m_win_observer->registerKeystroke(
1788  m_laser_params.keystroke_laser_scans,
1789  "Toggle LaserScans Visualization");
1790  this->m_win_observer->registerKeystroke(
1791  m_lc_params.keystroke_map_partitions,
1792  "Toggle Map Partitions Visualization");
1793  }
1794 
1795  this->logFmt(
1796  LVL_DEBUG,
1797  "Fetched the window manager, window observer successfully.");
1798  }
1799 }
1800 template <class GRAPH_T>
1802  const std::map<std::string, bool>& events_occurred)
1803 {
1804  MRPT_START;
1805  parent_t::notifyOfWindowEvents(events_occurred);
1806 
1807  // laser scans
1808  if (events_occurred.at(m_laser_params.keystroke_laser_scans))
1809  {
1810  this->toggleLaserScansVisualization();
1811  }
1812  // map partitions
1813  if (events_occurred.at(m_lc_params.keystroke_map_partitions))
1814  {
1815  this->toggleMapPartitionsVisualization();
1816  }
1817 
1818  MRPT_END;
1819 }
1820 
1821 template <class GRAPH_T>
1823 {
1824  using namespace mrpt;
1825  using namespace mrpt::gui;
1826  using namespace mrpt::math;
1827  using namespace mrpt::opengl;
1828 
1829  // textmessage - display the number of partitions
1830  if (!m_lc_params.LC_check_curr_partition_only)
1831  {
1832  this->m_win_manager->assignTextMessageParameters(
1833  /* offset_y* = */ &m_lc_params.offset_y_map_partitions,
1834  /* text_index* = */ &m_lc_params.text_index_map_partitions);
1835  }
1836 
1837  // just add an empty CSetOfObjects in the scene - going to populate it later
1838  CSetOfObjects::Ptr map_partitions_obj =
1839  mrpt::make_aligned_shared<CSetOfObjects>();
1840  map_partitions_obj->setName("map_partitions");
1841 
1842  COpenGLScene::Ptr& scene = this->m_win->get3DSceneAndLock();
1843  scene->insert(map_partitions_obj);
1844  this->m_win->unlockAccess3DScene();
1845  this->m_win->forceRepaint();
1846 }
1847 
1848 template <class GRAPH_T>
1850 {
1851  using namespace mrpt;
1852  using namespace mrpt::gui;
1853  using namespace mrpt::math;
1854  using namespace mrpt::opengl;
1855  using namespace mrpt::poses;
1856 
1857  // textmessage
1858  // ////////////////////////////////////////////////////////////
1859  if (!m_lc_params.LC_check_curr_partition_only)
1860  {
1861  std::stringstream title;
1862  title << "# Partitions: " << m_curr_partitions.size();
1863  this->m_win_manager->addTextMessage(
1864  5, -m_lc_params.offset_y_map_partitions, title.str(),
1865  mrpt::utils::TColorf(m_lc_params.balloon_std_color),
1866  /* unique_index = */ m_lc_params.text_index_map_partitions);
1867  }
1868 
1869  // update the partitioning visualization
1870  // ////////////////////////////////////////////////////////////
1871  COpenGLScene::Ptr& scene = this->m_win->get3DSceneAndLock();
1872 
1873  // fetch the partitions CSetOfObjects
1874  CSetOfObjects::Ptr map_partitions_obj;
1875  {
1876  CRenderizable::Ptr obj = scene->getByName("map_partitions");
1877  // do not check for null ptr - must be properly created in the init*
1878  // method
1879  map_partitions_obj = std::dynamic_pointer_cast<CSetOfObjects>(obj);
1880  }
1881 
1882  int partitionID = 0;
1883  bool partition_contains_last_node = false;
1884  bool found_last_node =
1885  false; // last node must exist in one partition at all cost TODO
1887  "Searching for the partition of the last nodeID: "
1888  << (this->m_graph->nodeCount() - 1));
1889 
1890  for (partitions_t::const_iterator p_it = m_curr_partitions.begin();
1891  p_it != m_curr_partitions.end(); ++p_it, ++partitionID)
1892  {
1893  // MRPT_LOG_DEBUG_STREAM("Working on Partition #" << partitionID);
1894  vector_uint nodes_list = *p_it;
1895 
1896  // finding the partition in which the last node is in
1897  if (std::find(
1898  nodes_list.begin(), nodes_list.end(),
1899  this->m_graph->nodeCount() - 1) != nodes_list.end())
1900  {
1901  partition_contains_last_node = true;
1902 
1903  found_last_node = true;
1904  }
1905  else
1906  {
1907  partition_contains_last_node = false;
1908  }
1909 
1910  // fetch the current partition object if it exists - create otherwise
1911  std::string partition_obj_name =
1912  mrpt::format("partition_%d", partitionID);
1913  std::string balloon_obj_name = mrpt::format("#%d", partitionID);
1914 
1916  map_partitions_obj->getByName(partition_obj_name);
1917  CSetOfObjects::Ptr curr_partition_obj;
1918  if (obj)
1919  {
1920  // MRPT_LOG_DEBUG_STREAM(
1921  //"\tFetching CSetOfObjects partition object for partition #" <<
1922  // partitionID);
1923  curr_partition_obj = std::dynamic_pointer_cast<CSetOfObjects>(obj);
1924  if (m_lc_params.LC_check_curr_partition_only)
1925  { // make all but the last partition invisible
1926  curr_partition_obj->setVisibility(partition_contains_last_node);
1927  }
1928  }
1929  else
1930  {
1932  "\tCreating a new CSetOfObjects partition object for partition "
1933  "#"
1934  << partitionID);
1935  curr_partition_obj = mrpt::make_aligned_shared<CSetOfObjects>();
1936  curr_partition_obj->setName(partition_obj_name);
1937  if (m_lc_params.LC_check_curr_partition_only)
1938  {
1939  // make all but the last partition invisible
1940  curr_partition_obj->setVisibility(partition_contains_last_node);
1941  }
1942 
1943  // MRPT_LOG_DEBUG_STREAM("\t\tCreating a new CSphere balloon
1944  // object");
1945  CSphere::Ptr balloon_obj = mrpt::make_aligned_shared<CSphere>();
1946  balloon_obj->setName(balloon_obj_name);
1947  balloon_obj->setRadius(m_lc_params.balloon_radius);
1948  balloon_obj->setColor_u8(m_lc_params.balloon_std_color);
1949  balloon_obj->enableShowName();
1950 
1951  curr_partition_obj->insert(balloon_obj);
1952 
1953  // set of lines connecting the graph nodes to the balloon
1954  // MRPT_LOG_DEBUG_STREAM(
1955  //"\t\tCreating set of lines that will connect to the Balloon");
1956  CSetOfLines::Ptr connecting_lines_obj =
1957  mrpt::make_aligned_shared<CSetOfLines>();
1958  connecting_lines_obj->setName("connecting_lines");
1959  connecting_lines_obj->setColor_u8(
1960  m_lc_params.connecting_lines_color);
1961  connecting_lines_obj->setLineWidth(0.1f);
1962 
1963  curr_partition_obj->insert(connecting_lines_obj);
1964 
1965  // add the created CSetOfObjects to the total CSetOfObjects
1966  // responsible
1967  // for the map partitioning
1968  map_partitions_obj->insert(curr_partition_obj);
1969  // MRPT_LOG_DEBUG_STREAM("\tInserted new CSetOfObjects
1970  // successfully");
1971  }
1972  // up to now the CSetOfObjects exists and the balloon inside it as
1973  // well..
1974 
1975  std::pair<double, double> centroid_coords;
1976  this->computeCentroidOfNodesVector(nodes_list, &centroid_coords);
1977 
1978  TPoint3D balloon_location(
1979  centroid_coords.first, centroid_coords.second,
1980  m_lc_params.balloon_elevation);
1981 
1982  // MRPT_LOG_DEBUG_STREAM("\tUpdating the balloon position");
1983  // set the balloon properties
1984  CSphere::Ptr balloon_obj;
1985  {
1986  // place the partitions baloon at the centroid elevated by a fixed Z
1987  // value
1989  curr_partition_obj->getByName(balloon_obj_name);
1990  balloon_obj = std::dynamic_pointer_cast<CSphere>(obj);
1991  balloon_obj->setLocation(balloon_location);
1992  if (partition_contains_last_node)
1993  balloon_obj->setColor_u8(m_lc_params.balloon_curr_color);
1994  else
1995  balloon_obj->setColor_u8(m_lc_params.balloon_std_color);
1996  }
1997 
1998  // MRPT_LOG_DEBUG_STREAM("\tUpdating the lines connecting nodes to
1999  // balloon");
2000  // set the lines connecting the nodes of the partition to the partition
2001  // balloon - set it from scratch all the times since the node positions
2002  // tend to change according to the dijkstra position estimation
2003  CSetOfLines::Ptr connecting_lines_obj;
2004  {
2005  // place the partitions baloon at the centroid elevated by a fixed Z
2006  // value
2008  curr_partition_obj->getByName("connecting_lines");
2009  connecting_lines_obj = std::dynamic_pointer_cast<CSetOfLines>(obj);
2010 
2011  connecting_lines_obj->clear();
2012 
2013  for (vector_uint::const_iterator it = nodes_list.begin();
2014  it != nodes_list.end(); ++it)
2015  {
2016  CPose3D curr_pose(this->m_graph->nodes.at(*it));
2017  TPoint3D curr_node_location(curr_pose);
2018 
2019  TSegment3D connecting_line(
2020  curr_node_location, balloon_location);
2021  connecting_lines_obj->appendLine(connecting_line);
2022  }
2023  }
2024  // MRPT_LOG_DEBUG_STREAM("Done working on partition #" << partitionID);
2025  }
2026 
2027  if (!found_last_node)
2028  {
2030  "Last inserted nodeID was not found in any partition.");
2031  ASSERT_(found_last_node);
2032  }
2033 
2034  // remove outdated partitions
2035  // these occur when more partitions existed during the previous
2036  // visualization
2037  // update, thus the partitions with higher ID than the maximum partitionID
2038  // would otherwise remain in the visual as zombie partitions
2039  size_t prev_size = m_last_partitions.size();
2040  size_t curr_size = m_curr_partitions.size();
2041  if (curr_size < prev_size)
2042  {
2043  MRPT_LOG_DEBUG_STREAM("Removing outdated partitions in visual");
2044  for (size_t partitionID = curr_size; partitionID != prev_size;
2045  ++partitionID)
2046  {
2047  MRPT_LOG_DEBUG_STREAM("\tRemoving partition " << partitionID);
2048  std::string partition_obj_name = mrpt::format(
2049  "partition_%lu", static_cast<unsigned long>(partitionID));
2050 
2052  map_partitions_obj->getByName(partition_obj_name);
2053  if (!obj)
2054  {
2056  "Partition : " << partition_obj_name << " was not found.");
2057  ASSERT_(!obj);
2058  }
2059  map_partitions_obj->removeObject(obj);
2060  }
2061  }
2062  MRPT_LOG_DEBUG_STREAM("Done working on the partitions visualization.");
2063 
2064  this->m_win->unlockAccess3DScene();
2065  this->m_win->forceRepaint();
2066 } // end of updateMapPartitionsVisualization
2067 
2068 template <class GRAPH_T>
2070 {
2071  MRPT_START;
2072  ASSERTMSG_(this->m_win, "No CDisplayWindow3D* was provided");
2073  ASSERTMSG_(this->m_win_manager, "No CWindowManager* was provided");
2074  using namespace mrpt::utils;
2075  using namespace mrpt::opengl;
2076 
2077  this->logFmt(LVL_INFO, "Toggling map partitions visualization...");
2078  mrpt::opengl::COpenGLScene::Ptr scene = this->m_win->get3DSceneAndLock();
2079 
2080  if (m_lc_params.visualize_map_partitions)
2081  {
2083  scene->getByName("map_partitions");
2084  obj->setVisibility(!obj->isVisible());
2085  }
2086  else
2087  {
2088  this->dumpVisibilityErrorMsg("visualize_map_partitions");
2089  }
2090 
2091  this->m_win->unlockAccess3DScene();
2092  this->m_win->forceRepaint();
2093 
2094  MRPT_END;
2095 } // end of toggleMapPartitionsVisualization
2096 
2097 template <class GRAPH_T>
2099  const vector_uint& nodes_list,
2100  std::pair<double, double>* centroid_coords) const
2101 {
2102  MRPT_START;
2103 
2104  // get the poses and find the centroid so that we can place the baloon over
2105  // and at their center
2106  double centroid_x = 0;
2107  double centroid_y = 0;
2108  for (vector_uint::const_iterator node_it = nodes_list.begin();
2109  node_it != nodes_list.end(); ++node_it)
2110  {
2111  pose_t curr_node_pos = this->m_graph->nodes.at(*node_it);
2112  centroid_x += curr_node_pos.x();
2113  centroid_y += curr_node_pos.y();
2114  }
2115 
2116  // normalize by the size - assign to the given pair
2117  centroid_coords->first =
2118  centroid_x / static_cast<double>(nodes_list.size());
2119  centroid_coords->second =
2120  centroid_y / static_cast<double>(nodes_list.size());
2121 
2122  MRPT_END;
2123 } // end of computeCentroidOfNodesVector
2124 
2125 template <class GRAPH_T>
2127 {
2128  MRPT_START;
2129 
2130  // laser scan visualization
2131  if (m_laser_params.visualize_laser_scans)
2132  {
2134  this->m_win->get3DSceneAndLock();
2135 
2136  mrpt::opengl::CPlanarLaserScan::Ptr laser_scan_viz =
2137  mrpt::make_aligned_shared<mrpt::opengl::CPlanarLaserScan>();
2138  laser_scan_viz->enablePoints(true);
2139  laser_scan_viz->enableLine(true);
2140  laser_scan_viz->enableSurface(true);
2141  laser_scan_viz->setSurfaceColor(
2142  m_laser_params.laser_scans_color.R,
2143  m_laser_params.laser_scans_color.G,
2144  m_laser_params.laser_scans_color.B,
2145  m_laser_params.laser_scans_color.A);
2146 
2147  laser_scan_viz->setName("laser_scan_viz");
2148 
2149  scene->insert(laser_scan_viz);
2150  this->m_win->unlockAccess3DScene();
2151  this->m_win->forceRepaint();
2152  }
2153 
2154  MRPT_END;
2155 }
2156 
2157 template <class GRAPH_T>
2159 {
2160  MRPT_START;
2161 
2162  // update laser scan visual
2163  if (m_laser_params.visualize_laser_scans && m_last_laser_scan2D)
2164  {
2166  this->m_win->get3DSceneAndLock();
2167 
2169  scene->getByName("laser_scan_viz");
2170  mrpt::opengl::CPlanarLaserScan::Ptr laser_scan_viz =
2171  std::dynamic_pointer_cast<mrpt::opengl::CPlanarLaserScan>(obj);
2172  ASSERT_(laser_scan_viz);
2173  laser_scan_viz->setScan(*m_last_laser_scan2D);
2174 
2175  // set the pose of the laser scan
2176  typename GRAPH_T::global_poses_t::const_iterator search =
2177  this->m_graph->nodes.find(this->m_graph->nodeCount() - 1);
2178  if (search != this->m_graph->nodes.end())
2179  {
2180  laser_scan_viz->setPose(search->second);
2181  // put the laser scan underneath the graph, so that you can still
2182  // visualize the loop closures with the nodes ahead
2183  laser_scan_viz->setPose(
2185  laser_scan_viz->getPoseX(), laser_scan_viz->getPoseY(),
2186  -0.15, mrpt::utils::DEG2RAD(laser_scan_viz->getPoseYaw()),
2187  mrpt::utils::DEG2RAD(laser_scan_viz->getPosePitch()),
2188  mrpt::utils::DEG2RAD(laser_scan_viz->getPoseRoll())));
2189  }
2190 
2191  this->m_win->unlockAccess3DScene();
2192  this->m_win->forceRepaint();
2193  }
2194 
2195  MRPT_END;
2196 }
2197 
2198 template <class GRAPH_T>
2200 {
2201  MRPT_START;
2202  ASSERTMSG_(this->m_win, "No CDisplayWindow3D* was provided");
2203  ASSERTMSG_(this->m_win_manager, "No CWindowManager* was provided");
2204  using namespace mrpt::utils;
2205 
2206  this->logFmt(LVL_INFO, "Toggling LaserScans visualization...");
2207 
2208  mrpt::opengl::COpenGLScene::Ptr scene = this->m_win->get3DSceneAndLock();
2209 
2210  if (m_laser_params.visualize_laser_scans)
2211  {
2213  scene->getByName("laser_scan_viz");
2214  obj->setVisibility(!obj->isVisible());
2215  }
2216  else
2217  {
2218  this->dumpVisibilityErrorMsg("visualize_laser_scans");
2219  }
2220 
2221  this->m_win->unlockAccess3DScene();
2222  this->m_win->forceRepaint();
2223 
2224  MRPT_END;
2225 }
2226 
2227 template <class GRAPH_T>
2229  std::map<std::string, int>* edge_types_to_num) const
2230 {
2231  MRPT_START;
2232  *edge_types_to_num = m_edge_types_to_nums;
2233  MRPT_END;
2234 }
2235 
2236 template <class GRAPH_T>
2238 {
2239  MRPT_START;
2240  parent_t::initializeVisuals();
2241  // MRPT_LOG_DEBUG_STREAM("Initializing visuals");
2242  this->m_time_logger.enter("Visuals");
2243 
2244  ASSERTMSG_(
2245  m_laser_params.has_read_config,
2246  "Configuration parameters aren't loaded yet");
2247  if (m_laser_params.visualize_laser_scans)
2248  {
2249  this->initLaserScansVisualization();
2250  }
2251  if (m_lc_params.visualize_map_partitions)
2252  {
2253  this->initMapPartitionsVisualization();
2254  }
2255 
2256  if (m_visualize_curr_node_covariance)
2257  {
2258  this->initCurrCovarianceVisualization();
2259  }
2260 
2261  this->m_time_logger.leave("Visuals");
2262  MRPT_END;
2263 }
2264 template <class GRAPH_T>
2266 {
2267  MRPT_START;
2268  parent_t::updateVisuals();
2269  // MRPT_LOG_DEBUG_STREAM("Updating visuals");
2270  this->m_time_logger.enter("Visuals");
2271 
2272  if (m_laser_params.visualize_laser_scans)
2273  {
2274  this->updateLaserScansVisualization();
2275  }
2276  if (m_lc_params.visualize_map_partitions)
2277  {
2278  this->updateMapPartitionsVisualization();
2279  }
2280  if (m_visualize_curr_node_covariance)
2281  {
2282  this->updateCurrCovarianceVisualization();
2283  }
2284 
2285  this->m_time_logger.leave("Visuals");
2286  MRPT_END;
2287 }
2288 
2289 template <class GRAPH_T>
2291 {
2292  MRPT_START;
2293  using namespace std;
2294  using namespace mrpt::opengl;
2295 
2296  // text message for covariance ellipsis
2297  this->m_win_manager->assignTextMessageParameters(
2298  /* offset_y* = */ &m_offset_y_curr_node_covariance,
2299  /* text_index* = */ &m_text_index_curr_node_covariance);
2300 
2301  std::string title("Position uncertainty");
2302  this->m_win_manager->addTextMessage(
2303  5, -m_offset_y_curr_node_covariance, title,
2304  mrpt::utils::TColorf(m_curr_node_covariance_color),
2305  /* unique_index = */ m_text_index_curr_node_covariance);
2306 
2307  // covariance ellipsis
2308  CEllipsoid::Ptr cov_ellipsis_obj = mrpt::make_aligned_shared<CEllipsoid>();
2309  cov_ellipsis_obj->setName("cov_ellipsis_obj");
2310  cov_ellipsis_obj->setColor_u8(m_curr_node_covariance_color);
2311  cov_ellipsis_obj->setLocation(0, 0, 0);
2312  // cov_ellipsis_obj->setQuantiles(2.0);
2313 
2314  mrpt::opengl::COpenGLScene::Ptr scene = this->m_win->get3DSceneAndLock();
2315  scene->insert(cov_ellipsis_obj);
2316  this->m_win->unlockAccess3DScene();
2317  this->m_win->forceRepaint();
2318 
2319  MRPT_END;
2320 }
2321 
2322 template <class GRAPH_T>
2324 {
2325  MRPT_START;
2326  using namespace std;
2327  using namespace mrpt::math;
2328  using namespace mrpt::opengl;
2329  using namespace mrpt::gui;
2330  using namespace mrpt::utils;
2331 
2332  // get the optimal path to the current node
2333  mrpt::utils::TNodeID curr_node = this->m_graph->nodeCount() - 1;
2334  path_t* path = queryOptimalPath(curr_node);
2335  if (!path) return;
2336 
2337  ASSERT_(path);
2338  CMatrixDouble33 mat;
2339  path->curr_pose_pdf.getCovariance(mat);
2340  pose_t curr_position = this->m_graph->nodes.at(curr_node);
2341 
2342  stringstream ss_mat;
2343  ss_mat << mat;
2344  this->logFmt(
2345  LVL_DEBUG,
2346  "In updateCurrCovarianceVisualization\n"
2347  "Covariance matrix:\n%s\n"
2348  "determinant : %f",
2349  ss_mat.str().c_str(), mat.det());
2350 
2351  mrpt::opengl::COpenGLScene::Ptr scene = this->m_win->get3DSceneAndLock();
2352  CRenderizable::Ptr obj = scene->getByName("cov_ellipsis_obj");
2353  CEllipsoid::Ptr cov_ellipsis_obj =
2354  std::dynamic_pointer_cast<CEllipsoid>(obj);
2355 
2356  // set the pose and corresponding covariance matrix of the ellipsis
2357  cov_ellipsis_obj->setLocation(curr_position.x(), curr_position.y(), 0);
2358  // pose_t loc = path->curr_pose_pdf.getMeanVal();
2359  // cov_ellipsis_obj->setLocation(loc.x(), loc.y(), 0);
2360  cov_ellipsis_obj->setCovMatrix(mat, 2);
2361 
2362  this->m_win->unlockAccess3DScene();
2363  this->m_win->forceRepaint();
2364 
2365  MRPT_END;
2366 }
2367 
2368 template <class GRAPH_T>
2370  std::string viz_flag, int sleep_time /* = 500 milliseconds */)
2371 {
2372  MRPT_START;
2373 
2374  this->logFmt(
2375  mrpt::utils::LVL_ERROR,
2376  "Cannot toggle visibility of specified object.\n "
2377  "Make sure that the corresponding visualization flag ( %s "
2378  ") is set to true in the .ini file.\n",
2379  viz_flag.c_str());
2380  std::this_thread::sleep_for(std::chrono::milliseconds(sleep_time));
2381 
2382  MRPT_END;
2383 }
2384 
2385 template <class GRAPH_T>
2387 {
2388  MRPT_START;
2389  parent_t::loadParams(source_fname);
2390 
2391  m_partitioner.options.loadFromConfigFileName(
2392  source_fname, "EdgeRegistrationDeciderParameters");
2393  m_laser_params.loadFromConfigFileName(
2394  source_fname, "EdgeRegistrationDeciderParameters");
2395  m_lc_params.loadFromConfigFileName(
2396  source_fname, "EdgeRegistrationDeciderParameters");
2397 
2398  mrpt::utils::CConfigFile source(source_fname);
2399 
2400  m_consec_icp_constraint_factor = source.read_double(
2401  "EdgeRegistrationDeciderParameters", "consec_icp_constraint_factor",
2402  0.90, false);
2403  m_lc_icp_constraint_factor = source.read_double(
2404  "EdgeRegistrationDeciderParameters", "lc_icp_constraint_factor", 0.70,
2405  false);
2406 
2407  // set the logging level if given by the user
2408  int min_verbosity_level = source.read_int(
2409  "EdgeRegistrationDeciderParameters", "class_verbosity", 1, false);
2410 
2411  this->setMinLoggingLevel(mrpt::utils::VerbosityLevel(min_verbosity_level));
2412  MRPT_END;
2413 }
2414 template <class GRAPH_T>
2416 {
2417  MRPT_START;
2418  using namespace std;
2419 
2420  cout << "------------------[Pair-wise Consistency of ICP Edges - "
2421  "Registration Procedure Summary]------------------"
2422  << endl;
2423 
2424  parent_t::printParams();
2425  m_partitioner.options.dumpToConsole();
2426  m_laser_params.dumpToConsole();
2427  m_lc_params.dumpToConsole();
2428 
2429  cout << "Scan-matching ICP Constraint factor: "
2430  << m_consec_icp_constraint_factor << endl;
2431  cout << "Loop-closure ICP Constraint factor: "
2432  << m_lc_icp_constraint_factor << endl;
2433 
2434  MRPT_LOG_DEBUG_STREAM("Printed the relevant parameters");
2435  MRPT_END;
2436 }
2437 
2438 template <class GRAPH_T>
2440  std::string* report_str) const
2441 {
2442  MRPT_START;
2443 
2444  // Report on graph
2445  std::stringstream class_props_ss;
2446  class_props_ss << "Pair-wise Consistency of ICP Edges - Registration "
2447  "Procedure Summary: "
2448  << std::endl;
2449  class_props_ss << this->header_sep << std::endl;
2450 
2451  // time and output logging
2452  const std::string time_res = this->m_time_logger.getStatsAsText();
2453  const std::string output_res = this->getLogAsString();
2454 
2455  // merge the individual reports
2456  report_str->clear();
2457  parent_t::getDescriptiveReport(report_str);
2458 
2459  *report_str += class_props_ss.str();
2460  *report_str += this->report_sep;
2461 
2462  *report_str += time_res;
2463  *report_str += this->report_sep;
2464 
2465  *report_str += output_res;
2466  *report_str += this->report_sep;
2467 
2468  MRPT_END;
2469 } // end of getDescriptiveReport
2470 
2471 template <class GRAPH_T>
2473  partitions_t* partitions_out) const
2474 {
2475  ASSERT_(partitions_out);
2476  *partitions_out = this->getCurrPartitions();
2477 }
2478 
2479 template <class GRAPH_T>
2480 const std::vector<mrpt::vector_uint>&
2482 {
2483  return m_curr_partitions;
2484 }
2485 
2486 template <class GRAPH_T>
2488  bool full_update /* = false */, bool is_first_time_node_reg /* = false */)
2489 {
2490  MRPT_START;
2491  using namespace mrpt::utils;
2492  using namespace mrpt::math;
2493  using namespace std;
2494 
2495  this->m_time_logger.enter("updateMapPartitions");
2496 
2497  // Initialize the nodeIDs => LaserScans map
2498  nodes_to_scans2D_t nodes_to_scans;
2499  if (full_update)
2500  {
2501  this->logFmt(
2502  LVL_INFO,
2503  "updateMapPartitions: Full partitioning of map was issued");
2504  // clear the existing partitions and recompute the partitioned map for
2505  // all
2506  // the nodes
2507  m_partitioner.clear();
2508  nodes_to_scans = this->m_nodes_to_laser_scans2D;
2509  }
2510  else
2511  {
2512  // if registering measurement for root node as well...
2513  if (is_first_time_node_reg)
2514  {
2515  nodes_to_scans.insert(
2516  make_pair(
2517  this->m_graph->root,
2518  this->m_nodes_to_laser_scans2D.at(this->m_graph->root)));
2519  }
2520 
2521  // just use the last node-laser scan pair
2522  nodes_to_scans.insert(
2523  make_pair(
2524  this->m_graph->nodeCount() - 1,
2525  this->m_nodes_to_laser_scans2D.at(
2526  this->m_graph->nodeCount() - 1)));
2527  }
2528 
2529  // TODO - Should always exist.
2530  // for each one of the above nodes - add its position and correspoding
2531  // laserScan to the partitioner object
2532  for (typename nodes_to_scans2D_t::const_iterator it =
2533  nodes_to_scans.begin();
2534  it != nodes_to_scans.end(); ++it)
2535  {
2536  if (it->second)
2537  { // if laserScan invalid go to next...
2539  "nodeID \"" << it->first << "\" has invalid laserScan");
2540  continue;
2541  }
2542 
2543  // find pose of node, if it exists...
2544  // TODO - investigate this case. Why should this be happening?
2546  search = this->m_graph->nodes.find(it->first);
2547  if (search == this->m_graph->nodes.end())
2548  {
2549  MRPT_LOG_WARN_STREAM("Couldn't find pose for nodeID " << it->first);
2550  continue;
2551  }
2552 
2553  // pose
2554  pose_t curr_pose = search->second;
2555  mrpt::poses::CPosePDF::Ptr posePDF(new constraint_t(curr_pose));
2556 
2557  // laser scan
2559  mrpt::make_aligned_shared<mrpt::obs::CSensoryFrame>();
2560  sf->insert(it->second);
2561 
2562  m_partitioner.addMapFrame(sf, posePDF);
2563  // mrpt::system::pause();
2564  }
2565 
2566  // update the last partitions list
2567  size_t curr_size = m_curr_partitions.size();
2568  m_last_partitions.resize(curr_size);
2569  for (size_t i = 0; i < curr_size; i++)
2570  {
2571  m_last_partitions[i] = m_curr_partitions[i];
2572  }
2573  // update current partitions list
2574  m_partitioner.updatePartitions(m_curr_partitions);
2575 
2576  MRPT_LOG_DEBUG_STREAM("Updated map partitions successfully.");
2577  this->m_time_logger.leave("updateMapPartitions");
2578  MRPT_END;
2579 } // end of updateMapPartitions
2580 
2581 // TLaserParams
2582 // //////////////////////////////////
2583 
2584 template <class GRAPH_T>
2586  : laser_scans_color(0, 20, 255),
2587  keystroke_laser_scans("l"),
2588  has_read_config(false)
2589 {
2591  200); // use the last X mahalanobis distance values
2592  goodness_threshold_win.resizeWindow(200); // use the last X ICP values
2593 }
2594 
2595 template <class GRAPH_T>
2597 {
2598 }
2599 
2600 template <class GRAPH_T>
2602  mrpt::utils::CStream& out) const
2603 {
2604  MRPT_START;
2605 
2606  out.printf(
2607  "Use scan-matching constraints = %s\n",
2608  use_scan_matching ? "TRUE" : "FALSE");
2609  out.printf(
2610  "Num. of previous nodes to check ICP against = %d\n",
2611  prev_nodes_for_ICP);
2612  out.printf(
2613  "Visualize laser scans = %s\n",
2614  visualize_laser_scans ? "TRUE" : "FALSE");
2615 
2616  MRPT_END;
2617 }
2618 template <class GRAPH_T>
2620  const mrpt::utils::CConfigFileBase& source, const std::string& section)
2621 {
2622  MRPT_START;
2623 
2624  use_scan_matching =
2625  source.read_bool(section, "use_scan_matching", true, false);
2626  prev_nodes_for_ICP = source.read_int( // how many nodes to check ICP against
2627  section,
2628  "prev_nodes_for_ICP",
2629  10, false);
2630  visualize_laser_scans = source.read_bool(
2631  "VisualizationParameters", "visualize_laser_scans", true, false);
2632 
2633  has_read_config = true;
2634  MRPT_END;
2635 }
2636 // TLoopClosureParams
2637 // //////////////////////////////////
2638 
2639 template <class GRAPH_T>
2641  : keystroke_map_partitions("b"),
2642  balloon_elevation(3),
2643  balloon_radius(0.5),
2644  balloon_std_color(153, 0, 153),
2645  balloon_curr_color(62, 0, 80),
2646  connecting_lines_color(balloon_std_color),
2647  has_read_config(false)
2648 {
2649 }
2650 
2651 template <class GRAPH_T>
2653 {
2654 }
2655 
2656 template <class GRAPH_T>
2658  mrpt::utils::CStream& out) const
2659 {
2660  MRPT_START;
2661  using namespace std;
2662 
2663  stringstream ss;
2664  ss << "Min. node difference for loop closure = "
2665  << LC_min_nodeid_diff << endl;
2666  ss << "Remote NodeIDs to consider the potential loop closure = "
2667  << LC_min_remote_nodes << endl;
2668  ss << "Min EigenValues ratio for accepting a hypotheses set = "
2669  << LC_eigenvalues_ratio_thresh << endl;
2670  ss << "Check only current node's partition for loop closures = "
2671  << (LC_check_curr_partition_only ? "TRUE" : "FALSE") << endl;
2672  ss << "New registered nodes required for full partitioning = "
2673  << full_partition_per_nodes << endl;
2674  ss << "Visualize map partitions = "
2675  << (visualize_map_partitions ? "TRUE" : "FALSE") << endl;
2676 
2677  out.printf("%s", ss.str().c_str());
2678 
2679  MRPT_END;
2680 }
2681 template <class GRAPH_T>
2683  const mrpt::utils::CConfigFileBase& source, const std::string& section)
2684 {
2685  MRPT_START;
2686 
2687  LC_min_nodeid_diff = source.read_int(
2688  "GeneralConfiguration", "LC_min_nodeid_diff", 30, false);
2689  LC_min_remote_nodes =
2690  source.read_int(section, "LC_min_remote_nodes", 3, false);
2691  LC_eigenvalues_ratio_thresh =
2692  source.read_double(section, "LC_eigenvalues_ratio_thresh", 2, false);
2693  LC_check_curr_partition_only =
2694  source.read_bool(section, "LC_check_curr_partition_only", true, false);
2695  full_partition_per_nodes =
2696  source.read_int(section, "full_partition_per_nodes", 50, false);
2697  visualize_map_partitions = source.read_bool(
2698  "VisualizationParameters", "visualize_map_partitions", true, false);
2699 
2700  has_read_config = true;
2701  MRPT_END;
2702 }
2703 }
2704 }
2705 } // end of namespaces
2706 
2707 #endif /* end of include guard: CLOOPCLOSERERD_IMPL_H */
mrpt::obs::CObservation2DRangeScan::Ptr scan
Definition: TNodeProps.h:25
void toggleMapPartitionsVisualization()
Toggle the map partitions visualization objects.
std::vector< mrpt::utils::TNodeID > nodes_traversed
Nodes that the Path comprises of.
bool mahalanobisDistanceOdometryToICPEdge(const mrpt::utils::TNodeID &from, const mrpt::utils::TNodeID &to, const constraint_t &rel_edge)
brief Compare the suggested ICP edge against the initial node difference.
GRAPH_T::global_pose_t pose
Definition: TNodeProps.h:24
double goodness
Goodness value corresponding to the hypothesis edge.
Definition: THypothesis.h:103
parent_t::nodes_to_scans2D_t nodes_to_scans2D_t
Holds the data of an information path.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
void loadParams(const std::string &source_fname)
bool getPropsOfNodeID(const mrpt::utils::TNodeID &nodeID, global_pose_t *pose, mrpt::obs::CObservation2DRangeScan::Ptr &scan, const node_props_t *node_props=NULL) const
Fill the pose and LaserScan for the given nodeID.
void addToPath(const mrpt::utils::TNodeID &node, const constraint_t &edge)
add a new link in the current path.
static const path_t * findPathByEnds(const paths_t &vec_paths, const mrpt::utils::TNodeID &src, const mrpt::utils::TNodeID &dst, bool throw_exc=true)
Given a vector of TUncertaintyPath objects, find the one that has the given source and destination no...
std::vector< uint32_t > vector_uint
Definition: types_simple.h:29
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
double DEG2RAD(const double x)
Degrees to radians.
A set of object, which are referenced to the coordinates framework established in this object...
Definition: CSetOfObjects.h:30
void initMapPartitionsVisualization()
Initialize the visualization of the map partition objects.
void computeCentroidOfNodesVector(const vector_uint &nodes_list, std::pair< double, double > *centroid_coords) const
Compute the Centroid of a group of a vector of node positions.
void getEdge(constraint_t *edge) const
Getter methods for the underlying edge.
void resizeWindow(size_t new_size)
Resize the window.
This class allows loading and storing values and vectors of different types from ".ini" files easily.
Definition: CConfigFile.h:35
#define THROW_EXCEPTION(msg)
virtual bool updateState(mrpt::obs::CActionCollection::Ptr action, mrpt::obs::CSensoryFrame::Ptr observations, mrpt::obs::CObservation::Ptr observation)
Scalar * iterator
Definition: eigen_plugins.h:26
void getDescriptiveReport(std::string *report_str) const
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:42
#define INVALID_NODEID
CRenderizable & setLocation(double x, double y, double z)
Changes the location of the object, keeping untouched the orientation.
std::string getSTLContainerAsString(const T &t)
Return a STL container in std::string form.
std::shared_ptr< CRenderizable > Ptr
Definition: CRenderizable.h:45
STL namespace.
const Scalar * const_iterator
Definition: eigen_plugins.h:27
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section)
This method load the options from a ".ini"-like file or memory-stored string list.
const_iterator find(const KEY &key) const
Definition: ts_hash_map.h:220
TSlidingWindow mahal_distance_ICP_odom_win
Keep track of the mahalanobis distance between the initial pose difference and the suggested new edge...
std::shared_ptr< CObservation2DRangeScan > Ptr
CMatrixFixedNumeric< double, 3, 3 > CMatrixDouble33
Definition: eigen_frwds.h:55
static hypot_t * findHypotByID(const hypotsp_t &vec_hypots, const size_t &id, bool throw_exc=true)
Given a vector of THypothesis objects, find the one that has the given ID.
GRAPH_T::edges_map_t::const_iterator edges_citerator
virtual bool getICPEdge(const mrpt::utils::TNodeID &from, const mrpt::utils::TNodeID &to, constraint_t *rel_edge, mrpt::slam::CICP::TReturnInfo *icp_info=NULL, const TGetICPEdgeAdParams *ad_params=NULL)
Get the ICP Edge between the provided nodes.
GLuint src
Definition: glext.h:7278
GLsizei GLsizei GLuint * obj
Definition: glext.h:4070
Struct for passing additional parameters to the getICPEdge call.
void addToPaths(std::set< path_t *> *pool_of_paths, const path_t &curr_path, const std::set< mrpt::utils::TNodeID > &neibors) const
Append the paths starting from the current node.
void registerHypothesis(const hypot_t &h)
Wrapper around the registerNewEdge method which accepts a THypothesis object instead.
GLubyte GLubyte GLubyte GLubyte w
Definition: glext.h:4178
void evaluatePartitionsForLC(const partitions_t &partitions)
Evaluate the given partitions for loop closures.
mrpt::utils::TNodeID from
Starting node of the hypothesis.
Definition: THypothesis.h:91
This class allows loading and storing values and vectors of different types from a configuration text...
bool is_valid
Field that specifies if the hypothesis is to be considered.
Definition: THypothesis.h:95
float goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences...
Definition: CICP.h:202
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:41
SLAM methods related to graphs of pose constraints.
This base provides a set of functions for maths stuff.
Definition: CArrayNumeric.h:19
std::shared_ptr< CPosePDF > Ptr
Definition: CPosePDF.h:44
3D segment, consisting of two points.
GLuint dst
Definition: glext.h:7135
uint64_t TNodeID
The type for node IDs in graphs of different types.
#define MRPT_END
constraint_t curr_pose_pdf
Current path position + corresponding covariance.
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
virtual void addScanMatchingEdges(const mrpt::utils::TNodeID &curr_nodeID)
Addd ICP constraints from X previous nodeIDs up to the given nodeID.
virtual void fetchNodeIDsForScanMatching(const mrpt::utils::TNodeID &curr_nodeID, std::set< mrpt::utils::TNodeID > *nodes_set)
Fetch a list of nodes with regards prior to the given nodeID for which to try and add scan matching e...
std::shared_ptr< CPlanarLaserScan > Ptr
Eigen::Matrix< dataType, 4, 4 > inverse(Eigen::Matrix< dataType, 4, 4 > &pose)
Definition: Miscellaneous.h:82
std::shared_ptr< CSetOfObjects > Ptr
Definition: CSetOfObjects.h:32
This namespace contains representation of robot actions and observations.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:19
This object renders a 2D laser scan by means of three elements: the points, the line along end-points...
const partitions_t & getCurrPartitions() const
std::shared_ptr< CSensoryFrame > Ptr
Definition: CSensoryFrame.h:56
#define MRPT_LOG_WARN_STREAM(__CONTENTS)
uint64_t TNodeID
The type for node IDs in graphs of different types.
Definition: types_simple.h:49
std::map< std::string, int > m_edge_types_to_nums
Keep track of the registered edge types.
void clear()
Clear the list of segments.
Definition: CSetOfLines.h:49
std::shared_ptr< CObservation > Ptr
Definition: CObservation.h:43
GLsizei const GLchar ** string
Definition: glext.h:4101
bool computeDominantEigenVector(const mrpt::math::CMatrixDouble &consist_matrix, mrpt::math::dynamic_vector< double > *eigvec, bool use_power_method=false)
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
MAT::Scalar mahalanobisDistance2(const VECTORLIKE1 &X, const VECTORLIKE2 &MU, const MAT &COV)
Computes the squared mahalanobis distance of a vector X given the mean MU and the covariance inverse ...
Definition: data_utils.h:36
void setWindowManagerPtr(mrpt::graphslam::CWindowManager *win_manager)
void dumpToTextStream(mrpt::utils::CStream &out) const
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
void assertIsBetweenNodeIDs(const mrpt::utils::TNodeID &from, const mrpt::utils::TNodeID &to) const
Assert that the current path is between the given nodeIDs.
void evalPWConsistenciesMatrix(const mrpt::math::CMatrixDouble &consist_matrix, const hypotsp_t &hypots_pool, hypotsp_t *valid_hypots)
Evalute the consistencies matrix, fill the valid hypotheses.
void getInverseEdge(constraint_t *edge) const
Getter methods for the inverse of the underlying edge.
double generatePWConsistencyElement(const mrpt::utils::TNodeID &a1, const mrpt::utils::TNodeID &a2, const mrpt::utils::TNodeID &b1, const mrpt::utils::TNodeID &b2, const hypotsp_t &hypots, const paths_t *opt_paths=NULL)
Return the pair-wise consistency between the observations of the given nodes.
std::vector< mrpt::vector_uint > partitions_t
Typedef for referring to a list of partitions.
#define MRPT_START
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
std::shared_ptr< CActionCollection > Ptr
void setVisibility(bool visible=true)
Set object visibility (default=true)
Definition: CRenderizable.h:76
void registerNewEdge(const mrpt::utils::TNodeID &from, const mrpt::utils::TNodeID &to, const constraint_t &rel_edge)
void dumpToTextStream(mrpt::utils::CStream &out) const
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
void splitPartitionToGroups(vector_uint &partition, vector_uint *groupA, vector_uint *groupB, int max_nodes_in_group=5)
Split an existing partition to Groups.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
virtual CRenderizable & setColor_u8(const mrpt::utils::TColor &c)
mrpt::utils::TNodeID to
Ending node of the hypothesis.
Definition: THypothesis.h:93
A solid or wire-frame sphere.
Definition: CSphere.h:31
void checkPartitionsForLC(partitions_t *partitions_for_LC)
Check the registered so far partitions for potential loop closures.
std::shared_ptr< COpenGLScene > Ptr
Definition: COpenGLScene.h:62
Struct for passing additional parameters to the generateHypotsPool call.
The ICP algorithm return information.
Definition: CICP.h:195
void setEdge(const constraint_t &edge)
Setter method for the underlying edge.
void generatePWConsistenciesMatrix(const vector_uint &groupA, const vector_uint &groupB, const hypotsp_t &hypots_pool, mrpt::math::CMatrixDouble *consist_matrix, const paths_t *groupA_opt_paths=NULL, const paths_t *groupB_opt_paths=NULL)
Compute the pair-wise consistencies Matrix.
static hypot_t * findHypotByEnds(const hypotsp_t &vec_hypots, const mrpt::utils::TNodeID &from, const mrpt::utils::TNodeID &to, bool throw_exc=true)
Given a vector of THypothesis objects, find the one that has the given start and end nodes...
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:15
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
#define ASSERT_(f)
A RGB color - floats in the range [0,1].
Definition: TColor.h:78
void toggleLaserScansVisualization()
togle the LaserScans visualization on and off
void updateMapPartitions(bool full_update=false, bool is_first_time_node_reg=false)
Split the currently registered graph nodes into partitions.
GRAPH_T::constraint_t::type_value pose_t
type of underlying poses (2D/3D).
std::shared_ptr< CSetOfLines > Ptr
Definition: CSetOfLines.h:37
Edge Registration Decider scheme specialized in Loop Closing.
void getMinUncertaintyPath(const mrpt::utils::TNodeID from, const mrpt::utils::TNodeID to, path_t *path) const
Given two nodeIDs compute and return the path connecting them.
std::map< mrpt::utils::TNodeID, node_props_t > group_t
void generateHypotsPool(const vector_uint &groupA, const vector_uint &groupB, hypotsp_t *generated_hypots, const TGenerateHypotsPoolAdParams *ad_params=NULL)
Generate the hypothesis pool for all the inter-group constraints between two groups of nodes...
Classes for creating GUI windows for 2D and 3D visualization.
Definition: about_box.h:16
T absDiff(const T &lhs, const T &rhs)
Absolute difference between two numbers.
mrpt::graphslam::TUncertaintyPath< GRAPH_T > * popMinUncertaintyPath(std::set< path_t *> *pool_of_paths) const
Find the minimum uncertainty path from te given pool of TUncertaintyPath instances.
GLsizei const GLfloat * value
Definition: glext.h:4117
void execDijkstraProjection(mrpt::utils::TNodeID starting_node=0, mrpt::utils::TNodeID ending_node=INVALID_NODEID)
compute the minimum uncertainty of each node position with regards to the graph root.
void updateMapPartitionsVisualization()
Update the map partitions visualization.
GLuint res
Definition: glext.h:7268
A 2D ellipse or 3D ellipsoid, depending on the size of the m_cov matrix (2x2 or 3x3).
Definition: CEllipsoid.h:47
size_t id
ID of the current hypothesis.
Definition: THypothesis.h:89
void notifyOfWindowEvents(const std::map< std::string, bool > &events_occurred)
An edge hypothesis between two nodeIDs.
Definition: THypothesis.h:37
Lightweight 3D point.
A set of independent lines (or segments), one line with its own start and end positions (X...
Definition: CSetOfLines.h:35
void dumpVisibilityErrorMsg(std::string viz_flag, int sleep_time=500)
#define MRPT_LOG_DEBUG_STREAM(__CONTENTS)
#define ASSERTMSG_(f, __ERROR_MSG)
#define MRPT_LOG_ERROR_STREAM(__CONTENTS)
std::shared_ptr< CSphere > Ptr
Definition: CSphere.h:33
GLfloat GLfloat p
Definition: glext.h:6305
GLenum const GLfloat * params
Definition: glext.h:3534
void getEdgesStats(std::map< std::string, int > *edge_types_to_num) const
Internal auxiliary classes.
Definition: levmarq_impl.h:23
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section)
This method load the options from a ".ini"-like file or memory-stored string list.
bool fillNodePropsFromGroupParams(const mrpt::utils::TNodeID &nodeID, const std::map< mrpt::utils::TNodeID, node_props_t > &group_params, node_props_t *node_props)
Fill the TNodeProps instance using the parameters from the map.
const mrpt::utils::TNodeID & getDestination() const
Return the Destination node of this path.
Class acts as a container for storing pointers to mrpt::gui::CDisplayWindow3D, mrpt::graphslam::CWind...
bool approximatelyEqual(T1 a, T1 b, T2 epsilon)
Compare 2 floats and determine whether they are equal.
virtual int printf(const char *fmt,...) MRPT_printf_format_check(2
Writes a string to the stream in a textual form.
Definition: CStream.cpp:597
GRAPH_T::constraint_t constraint_t
Handy typedefs.
std::string getAsString(bool oneline=true) const
Return a string representation of the object at hand.
std::shared_ptr< CEllipsoid > Ptr
Definition: CEllipsoid.h:49
TSlidingWindow goodness_threshold_win
Keep track of ICP Goodness values for ICP between nearby nodes and adapt the Goodness threshold based...



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019