Main MRPT website > C++ reference for MRPT 1.9.9
CLoopCloserERD.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-2018, 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_H
11 #define CLOOPCLOSERERD_H
12 
13 #include <mrpt/math/CMatrix.h>
16 #include <mrpt/img/TColor.h>
19 #include <mrpt/obs/CSensoryFrame.h>
21 #include <mrpt/slam/CICP.h>
22 
29 
30 #include <map>
31 #include <vector>
32 #include <string>
33 #include <set>
34 #include <utility>
35 
36 namespace mrpt
37 {
38 namespace graphslam
39 {
40 namespace deciders
41 {
42 /**\brief Edge Registration Decider scheme specialized in Loop Closing.
43  *
44  * ## Description
45  *
46  * Current decider is implemented based on the following papers:
47  *
48  * - [1] <a
49  *
50 href="http://ieeexplore.ieee.org/xpl/login.jsp?tp=&arnumber=1641810&url=http%3A%2F%2Fieeexplore.ieee.org%2Fxpls%2Fabs_all.jsp%3Farnumber%3D1641810">Consistent
51  * Observation Grouping for Generating Metric-Topological Maps that Improves
52  * Robot Localization</a> - J. Blanco, J. Gonzalez, J. Antonio Fernandez
53  * Madrigal, 2006
54  * - [2] <a
55 href="https://april.eecs.umich.edu/pdfs/olson2009ras.pdf">Recognizing
56  * places using spectrally clustered local matches</a> - E. Olson, 2009
57  *
58  * ### Specifications
59  *
60  * - Map type: 2D
61  * - MRPT rawlog format: #1, #2
62  * - Graph Type: CPosePDFGaussianInf
63  * - Observations: CObservation2DRangeScan
64  * - Edge Registration Strategy: ICP Scan-matching between nearby nodes
65  * - Loop Registration Strategy: Pair-wise Consistency of ICP Edges
66  *
67  * ### Loop Closing Strategy
68  *
69  * The Loop closure registration strategy is described below:
70  *
71  * - We split the graph under-construction into groups of nodes. The groups are
72  * formatted based on the observations gathered in each node position. The
73  * actual split between the groups is decided by the minimum normalized Cut
74  * (minNcut) as described in [1].
75  * - Having assembled the groups of nodes, we find the groups that might
76  * contain loop closure edges (these groups contain successive nodes with
77 large
78  * difference in their IDs). These groups are then split into two subgroups
79  * A, B, with the former containing the lower NodeIDs and the latter the
80  * higher. To minimize computational cost as well as the possibility of wrong
81  * loop closure registration, we search for loop closures only between the
82  * <a>last</a> nodes of group B and the <a>first</a> nodes of group A. Based
83 on [2] the
84  * potential loop closure edges are not evaluated individually but rather in
85  * sets. Refer to [2] for insight on the algorithm and to
86  * evaluatePartitionsForLC method for the actual implementation. See below
87  * for images of potential Loop closure edges.
88  *
89  * <div>
90  * <div>
91  * <img src="graphslam-engine_loop_closing_full.png">
92  * <caption align="bottom">
93  * Loop closing schematic. blue nodes belong to group A and have lower
94  * NodeIDs, while red nodes belong to group B and have higher NodeIDs.
95  * Nodes of both groups A and B belong to the same partition based on their
96  * corresponding 2DRangeScan observations.
97  * </caption>
98  * </div>
99  * <div>
100  * <img src="graphslam-engine_loop_closing_consistency_element.png">
101  * <caption align="bottom">
102  * Rigid body transformation of hypotheses and two corresponding
103  * dijkstra links
104  * </caption>
105  * </div>
106  * </div>
107  *
108  * \note
109  * Olson uses the following formula for evaluating the pairwise
110  * consistency between two hypotheses i,j:
111  * <br><center> \f$ A_{i,j} = e^{T \Sigma_T^{-1} T^T} \f$ </center>
112  *
113  * \note
114  * Where:
115  * - T is the rigid body transformation using the two hypotheses and the two
116  * Dijkstra Links connecting the nodes that form the hypotheses
117  * - \f$ \Sigma_T \f$ is the covariance matrix of the aforementioned rigid
118  * body transformation
119  *
120  * \note
121  * However this formula is <a>inconsistent with the rest of the paper
122  * explanations and mathematical formulas </a>:
123  * - The author states that:
124  * \verbatim
125 "This quantity is proportional to the probability density that the rigid-body
126 transformation is the identity matrix (i.e., T = [0 0 0])"
127 \endverbatim
128  * This is \a inconsistent with the given formula. Suppose that a
129  * wrong loop closure is included in the \f$ A_{i,j} \f$, therefore the
130  * pairwise-consistency element should have a low value. For this to hold
131  * true the exponent of the consistency element shoud be small and
132  * neglecting the covariance matrix of rigid-body transformation (e.g. unit
133  * covariance matrix), \f$ T T^T \f$ should be small.
134  * When a wrong loop closure is evaluated the aforementioned quantity
135  * increases since the hypotheses do not form a correct loop. Therefore the
136  * worse the rigid-body transformation the higher the exponent term,
137  * therefore the higher the consistency element
138  * - Author uses the information matrix \f$ \Sigma_T^{-1} \f$ in the
139 exponential.
140  * However in the optimal case (high certainty of two correct loop closure
141  * hypotheses) information matrix and rigid body transformation vector T
142  * have opposite effects in the exponent term:
143  * - \f$ \text{Correct loop closure} \Rightarrow T \rightarrow [0, 0, 0]
144  * \Rightarrow \text{exponent} \downarrow \f$
145  * - \f$ \text{Correct loop closure} \Rightarrow
146  * \text{diagonal\_terms}(\Sigma_T^{-1}) \uparrow \Rightarrow \text{exponent}
147  * \uparrow \f$
148  *
149  * \note
150  * Based on the previous comments the following formula is used in the decider:
151  * <br><center> \f$ A_{i,j} = e^{-T \Sigma_T T^T} \f$ </center>
152  *
153  * ### .ini Configuration Parameters
154  *
155  * \htmlinclude graphslam-engine_config_params_preamble.txt
156  *
157  * - \b class_verbosity
158  * + \a Section : EdgeRegistrationDeciderParameters
159  * + \a Default value : 1 (mrpt::system::LVL_INFO)
160  * + \a Required : FALSE
161  *
162  * - \b use_scan_matching
163  * + \a Section : EdgeRegistrationDeciderParameters
164  * + \a Default value : TRUE
165  * + \a Required : FALSE
166  * + \a Description :Indicates whether the decider uses scan matching
167  * between the current and previous laser scans to correct the robot
168  * trajectory.
169  *
170  * - \b visualize_laser_scans
171  * + \a Section : VisualizationParameters
172  * + \a Default value : 10
173  * + \a Required : FALSE
174  *
175  * - \b LC_min_nodeid_diff
176  * + \a Section : GeneralConfiguration
177  * + \a Default value : 30
178  * + \a Required : FALSE
179  * + \a Description : Minimum NodeID difference for an edge to be considered
180  * a loop closure.
181  *
182  * - \b LC_min_remote_nodes
183  * + \a Section : EdgeRegistrationDeciderParameters
184  * + \a Default value : 3
185  * + \a Required : FALSE
186  * + \a Description : Number of remote nodes that must exist in order for
187  * the Loop Closure procedure to commence
188  *
189  * - \b LC_eigenvalues_ratio_thresh
190  * + \a Section : EdgeRegistrationDeciderParameters
191  * + \a Default value : 2
192  * + \a Required : FALSE
193  * + \a Description : Minimum ratio of the two dominant eigenvalues for a
194  * loop closing hypotheses set to be considered valid
195  *
196  * - \b LC_check_curr_partition_only
197  * + \a Section : EdgeRegistrationDeciderParameters
198  * + \a Default value : TRUE
199  * + \a Required : FALSE
200  * + \a Description : Boolean flag indicating whether to check for loop
201  * closures only in the current node's partition
202  *
203  * - \b visualize_map_partitions
204  * + \a Section : VisualizationParameters
205  * + \a Default value : TRUE
206  * + \a Required : FALSE
207  *
208  * \note Class contains an instance of the
209  * mrpt::slam::CIncrementalMapPartitioner class and it parses the configuration
210  * parameters of the latter from the "EdgeRegistrationDeciderParameters"
211  * section. Refer to mrpt::slam::CIncrementalMapPartitioner documentation for
212  * its list of configuration parameters
213  *
214  * \sa mrpt::slam::CIncrementalMapPartitioner
215  * \ingroup mrpt_graphslam_grp
216  */
217 template <class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
220 {
221  public:
222  /**\brief Edge Registration Decider */
224 
225  /**\brief Handy typedefs */
226  /**\{*/
227  /**\brief type of graph constraints */
228  using constraint_t = typename GRAPH_T::constraint_t;
229  /**\brief type of underlying poses (2D/3D). */
230  using pose_t = typename GRAPH_T::constraint_t::type_value;
231  using global_pose_t = typename GRAPH_T::global_pose_t;
232  using decider_t = CLoopCloserERD<GRAPH_T>; /**< self type */
235  /**\brief Typedef for referring to a list of partitions */
236  using partitions_t = std::vector<std::vector<uint32_t>>;
240  using hypots_t = std::vector<hypot_t>;
241  using hypotsp_t = std::vector<hypot_t*>;
242  using hypotsp_to_consist_t =
243  std::map<std::pair<hypot_t*, hypot_t*>, double>;
245  using paths_t = std::vector<path_t>;
247  /**\}*/
248 
249  // Public methods
250  //////////////////////////////////////////////////////////////
251  CLoopCloserERD();
252  virtual ~CLoopCloserERD();
253 
254  virtual bool updateState(
256  mrpt::obs::CSensoryFrame::Ptr observations,
257  mrpt::obs::CObservation::Ptr observation);
258 
261  const std::map<std::string, bool>& events_occurred);
262  void getEdgesStats(std::map<std::string, int>* edge_types_to_num) const;
263 
264  void initializeVisuals();
265  void updateVisuals();
266  void loadParams(const std::string& source_fname);
267  void printParams() const;
268 
269  void getDescriptiveReport(std::string* report_str) const;
270  void getCurrentPartitions(partitions_t& partitions_out) const;
271  const partitions_t& getCurrentPartitions() const;
272  /**\brief Return the minimum number of nodes that should exist in the graph
273  * prior to running Dijkstra
274  */
276  {
278  }
279  void setDijkstraExecutionThresh(size_t new_thresh)
280  {
281  m_dijkstra_node_count_thresh = new_thresh;
282  }
283 
284  /**\name Helper structs */
285  /**\{ */
286 
287  /**
288  * \brief Struct for passing additional parameters to the getICPEdge call
289  *
290  * Handy for overriding the search to the \a GRAPH_T::nodes map or the
291  * search for the node's LaserScan
292  */
294  {
296 
297  node_props_t from_params; /**< Ad. params for the from_node */
298  node_props_t to_params; /**< Ad. params for the to_node */
299  pose_t init_estim; /**< Initial ICP estimation */
300 
301  void getAsString(std::string* str) const
302  {
303  using namespace std;
304  using namespace mrpt;
305  str->clear();
306  *str +=
307  format("from_params: %s", from_params.getAsString().c_str());
308  *str += format("to_params: %s", to_params.getAsString().c_str());
309  *str += format("init_estim: %s\n", init_estim.asString().c_str());
310  }
312  {
313  std::string str;
314  this->getAsString(&str);
315  return str;
316  }
317  friend std::ostream& operator<<(std::ostream& o, const self_t& params)
318  {
319  o << params.getAsString() << endl;
320  return o;
321  }
322  };
323  /**\brief Struct for passing additional parameters to the
324  * generateHypotsPool call
325  */
327  {
328  using group_t = std::map<mrpt::graphs::TNodeID, node_props_t>;
329 
330  /**\brief Ad. params for groupA */
332  /**\brief Ad. params for groupB */
334  };
335  /**\} */
336 
337  /**\brief Generate the hypothesis pool for all the inter-group constraints
338  * between two groups of nodes.
339  *
340  * \param[in] groupA First group to be tested
341  * \param[in] groupB Second group to be tested
342  * \param[out] generated_hypots Pool of generated hypothesis. Hypotheses
343  * are generated in the heap, so the caller is responsible of afterwards
344  * calling \a delete.
345  */
346  void generateHypotsPool(
347  const std::vector<uint32_t>& groupA,
348  const std::vector<uint32_t>& groupB, hypotsp_t* generated_hypots,
349  const TGenerateHypotsPoolAdParams* ad_params = NULL);
350  /**\brief Compute the pair-wise consistencies Matrix.
351  *
352  * \param[in] groupA First group to be used
353  * \param[in] groupB Second group to be used
354  * \param[in] hypots_pool Pool of hypothesis that has been generated
355  * between the two groups
356  * \pram[out] consist_matrix Pointer to Pair-wise consistencies matrix that
357  * is to be filled
358 
359  * \param[in] groupA_opt_paths Pointer to vector of optimal paths that can
360  * be used instead of making queries to the m_node_optimal_paths class
361  * vector. See corresponding argument in generatePWConsistencyElement
362  * method
363  * \param[in] groupB_opt_paths
364  *
365  * \sa generatePWConsistencyElement
366  * \sa evalPWConsistenciesMatrix
367  */
369  const std::vector<uint32_t>& groupA,
370  const std::vector<uint32_t>& groupB, const hypotsp_t& hypots_pool,
371  mrpt::math::CMatrixDouble* consist_matrix,
372  const paths_t* groupA_opt_paths = NULL,
373  const paths_t* groupB_opt_paths = NULL);
374  /**\brief Evalute the consistencies matrix, fill the valid hypotheses
375  *
376  * Call to this method should be made right after generating the
377  * consistencies matrix using the generatePWConsistenciesMatrix method
378  *
379  * \sa generatePWConsistenciesMatrix
380  */
382  const mrpt::math::CMatrixDouble& consist_matrix,
383  const hypotsp_t& hypots_pool, hypotsp_t* valid_hypots);
384  // Public variables
385  // ////////////////////////////
386  protected:
387  // protected functions
388  //////////////////////////////////////////////////////////////
389 
390  /**\brief Fill the TNodeProps instance using the parameters from the map
391  *
392  * \param[in] nodeID ID of node corresponding to the TNodeProps struct that
393  * is to be filled
394  * \param[in] group_params Map of TNodeID to corresponding TNodeProps
395  * instance.
396  * \param[out] node_props Pointer to the TNodeProps struct to be filled.
397  *
398  *
399  * \return True if operation was successful, false otherwise.
400  */
402  const mrpt::graphs::TNodeID& nodeID,
403  const std::map<mrpt::graphs::TNodeID, node_props_t>& group_params,
404  node_props_t* node_props);
405  /**\brief Fill the pose and LaserScan for the given nodeID.
406  * Pose and LaserScan are either fetched from the TNodeProps struct if it
407  * contains valid data, otherwise from the corresponding class vars
408  *
409  * \return True if operation was successful and pose, scan contain valid
410  * data.
411  */
412  bool getPropsOfNodeID(
413  const mrpt::graphs::TNodeID& nodeID, global_pose_t* pose,
415  const node_props_t* node_props = NULL) const;
416 
417  /**\brief Struct for storing together the parameters needed for ICP
418  * matching, laser scans visualization etc.
419  */
421  {
422  public:
423  TLaserParams();
424  ~TLaserParams();
425 
426  void loadFromConfigFile(
428  const std::string& section);
429  void dumpToTextStream(std::ostream& out) const;
431  /**\brief How many nodes back to check ICP against?
432  */
434 
435  /** see Constructor for initialization */
438  // keystroke to be used by the user to toggle the LaserScans from
439  // the CDisplayWindow
441 
442  /**\brief Indicate whethet to use scan-matching at all during
443  * graphSLAM [on by default].
444  *
445  * \warning It is strongly recomended that the user does not set this
446  * to false (via the .ini file). graphSLAM may diverge significantly if
447  * no scan-matching is not used.
448  */
451  /**\brief Keep track of the mahalanobis distance between the initial
452  * pose
453  * difference and the suggested new edge for the pairs of checked
454  * nodes.
455  */
457  /**\brief Keep track of ICP Goodness values for ICP between nearby
458  * nodes and adapt the Goodness threshold based on the median of the
459  * recorded Goodness values.
460  */
462  };
463 
464  /**\brief Struct for storing together the loop-closing related parameters.
465  */
467  {
468  public:
471 
472  void loadFromConfigFile(
474  const std::string& section);
475  void dumpToTextStream(std::ostream& out) const;
476  /**\brief flag indicating whether to check only the partition of the
477  * last
478  * registered node for potential loop closures
479  */
481  /**\brief nodeID difference for detecting potential loop closure in a
482  * partition.
483  *
484  * If this difference is surpassed then the partition should be
485  * investigated for loop closures using Olson's strategy.
486  */
488  /**\brief Eigenvalues ratio for accepting/rejecting a hypothesis set.
489  *
490  * By default this is set to 2.
491  */
493  /**\brief how many remote nodes (large nodID difference should there be
494  * before I consider the potential loop closure.
495  */
497  /**\brief Full partition of map only afer X new nodes have been
498  * registered
499  */
503 
506 
507  // map partitioning - visualization window parameters
508  const double balloon_elevation;
509  const double balloon_radius;
513 
515  };
518 
519  /**brief Compare the suggested ICP edge against the initial node
520  * difference.
521  *
522  * If this difference is significantly larger than the rest of of the
523  * recorded mahalanobis distances, reject the suggested ICP edge.
524  *
525  * \return True if suggested ICP edge is accepted
526  * \note Method updates the Mahalanobis Distance TSlidingWindow which
527  * keep track of the recorded mahalanobis distance values.
528  * \sa getICPEdge
529  */
531  const mrpt::graphs::TNodeID& from, const mrpt::graphs::TNodeID& to,
532  const constraint_t& rel_edge);
533  /**\brief Wrapper around the registerNewEdge method which accepts a
534  * THypothesis object instead.
535  */
536  void registerHypothesis(const hypot_t& h);
537  void registerNewEdge(
538  const mrpt::graphs::TNodeID& from, const mrpt::graphs::TNodeID& to,
539  const constraint_t& rel_edge);
540  /**\brief Fetch a list of nodes with regards prior to the given nodeID for
541  * which to try and add scan matching edges
542  *
543  * \sa addScanMatchingEdges
544  */
545  virtual void fetchNodeIDsForScanMatching(
546  const mrpt::graphs::TNodeID& curr_nodeID,
547  std::set<mrpt::graphs::TNodeID>* nodes_set);
548  /**\brief Addd ICP constraints from X previous nodeIDs up to the given
549  * nodeID.
550  *
551  * X is set by the user in the .ini configuration file (see
552  * TLaserParams::prev_nodes_for_ICP)
553  *
554  * \sa fetchNodeIDsForScanMatching
555  */
556  virtual void addScanMatchingEdges(const mrpt::graphs::TNodeID& curr_nodeID);
559  /**\brief togle the LaserScans visualization on and off
560  */
563  std::string viz_flag, int sleep_time = 500 /* ms */);
564  /**\brief Split the currently registered graph nodes into partitions. */
565  void updateMapPartitions(
566  bool full_update = false, bool is_first_time_node_reg = false);
567  /**\brief Initialize the visualization of the map partition objects. */
569  /**\brief Update the map partitions visualization. */
571  /**\brief Toggle the map partitions visualization objects.
572  *
573  * To be called upon relevant keystroke press by the user (see \b
574  * TLoopClosureParams::keystroke_map_partitions)
575  */
579  /**\brief Compute the Centroid of a group of a vector of node positions.
580  *
581  * \param[in] nodes_list List of node IDs whose positions are taken into
582  * account
583  * \param[out] centroid_coords Contains the Centroid coordinates as a pair
584  * [x,y]
585  *
586  * \note Method is used during the visualization of the map partitions.
587  */
589  const std::vector<uint32_t>& nodes_list,
590  std::pair<double, double>* centroid_coords) const;
591  /**\brief Check the registered so far partitions for potential loop
592  * closures.
593  *
594  * Practically checks whether there exist nodes in a single partition whose
595  * distance surpasses the minimum loop closure nodeID distance. The latter
596  * is read from a .ini external file, thus specified by the user (see \b
597  * TLoopClosureParams.LC_min_nodeid_diff.
598  *
599  * \sa evaluatePartitionsForLC
600  */
601  void checkPartitionsForLC(partitions_t* partitions_for_LC);
602  /**\brief Evaluate the given partitions for loop closures.
603  *
604  * Call this method when you have identified potential loop closures - e.g.
605  * far away nodes in the same partitions - and you want to evaluate the
606  * potential hypotheses in the group. Comprises the main function that
607  * tests potential loop closures in <b>partitions of nodes</b>
608  *
609  * \sa checkPartitionsForLC
610  */
611  void evaluatePartitionsForLC(const partitions_t& partitions);
612 
614  const mrpt::math::CMatrixDouble& consist_matrix,
616  bool use_power_method = false);
617  /**\brief Return the pair-wise consistency between the observations of the
618  * given nodes.
619  *
620  * For the tranformation matrix of the loop use the following edges
621  * - a1=>a2 (Dijkstra Link)
622  * - a2=>b1 (hypothesis - ICP edge)
623  * - b1=>b2 (Dijkstra Link)
624  * - b2=>a1 (hypothesis - ICP edge)
625  *
626  * Given the transformation vector \f$ (x,y,\phi)\f$ of the above
627  * composition (e.g. T) the
628  * pairwise consistency element would then be:
629  * <br><center> \f$ A_{i,j} = e^{-T \Sigma_T T^T} \f$ </center>
630  *
631  * \param[in] hypots Hypothesis corresponding to the potential inter-group
632  * constraints
633  * \param[in] opt_paths Vector of optimal paths that can be used instead of
634  * making queries to the m_node_optimal_paths class vector. See
635  * corresponding argument in generatePWConsistenciesMatrix method
636  * - 1st element \rightarrow a1->a2 path
637  * - 2nd element \rightarrow b1->b2 path
638  *
639  * \return Pairwise consistency eleement of the composition of
640  * transformations
641  *
642  * \sa generatePWConsistenciesMatrix
643  */
647  const hypotsp_t& hypots, const paths_t* opt_paths = NULL);
648  /**\brief Given a vector of THypothesis objects, find the one that
649  * has the given start and end nodes.
650  *
651  * \note If multiple hypothesis between the same start and end node exist,
652  * only the first one is returned.
653  *
654  * \param[in] vec_hypots Vector of hypothesis to check
655  * \param[in] from Starting Node for hypothesis
656  * \param[in] to Ending Node for hypothesis
657  * \param[in] throw_exc If true and hypothesis is not found, <b>throw a
658  * HypothesisNotFoundException</b>
659  *
660  * \return Pointer to the found hypothesis if that is found, otherwise NULL.
661  *
662  */
663  static hypot_t* findHypotByEnds(
664  const hypotsp_t& vec_hypots, const mrpt::graphs::TNodeID& from,
665  const mrpt::graphs::TNodeID& to, bool throw_exc = true);
666  /**\brief Given a vector of TUncertaintyPath objects, find the one that has
667  * the given source and destination nodeIDs.
668  *
669  * \note If multiple paths between the same start and end node exist,
670  * only the first one is returned.
671  *
672  * \return NULL if a path with the given source and destination NodeIDs is
673  * not found, otherwise a pointer to the matching TUncertaintyPath.
674  *
675  * \exception std::runtime_error if path was not found and throw_exc is set
676  * to true
677  */
678  static const path_t* findPathByEnds(
679  const paths_t& vec_paths, const mrpt::graphs::TNodeID& src,
680  const mrpt::graphs::TNodeID& dst, bool throw_exc = true);
681  /**\brief Given a vector of THypothesis objects, find the one that
682  * has the given ID.
683  *
684  * \note If multiple hypothesis with the same ID exist, only the first one
685  * is returned.
686  *
687  * \param[in] vec_hypots Vector of hypothesis to check
688  * \param[in] id, ID of the hypothesis to be returned
689  * \param[in] throw_exc If true and hypothesis is not found, <b>throw a
690  * HypothesisNotFoundException</b>
691  *
692  * \return Pointer to the hypothesis with the given ID if that is found,
693  * otherwies NULL.
694  */
695  static hypot_t* findHypotByID(
696  const hypotsp_t& vec_hypots, const size_t& id, bool throw_exc = true);
697  /**\brief Get the ICP Edge between the provided nodes.
698  *
699  * Handy for not having to manually fetch the laser scans, as the method
700  * takes care of this.
701  *
702  * \param[out] icp_info Struct that will be filled with the results of the
703  * ICP operation
704  *
705  * \param[in] ad_params Pointer to additional parameters in the getICPEdge
706  * call
707  *
708  * \return True if operation was successful, false otherwise (e.g. if the
709  * either of the nodes' CObservation2DRangeScan object does not contain
710  * valid data.
711  */
712  virtual bool getICPEdge(
713  const mrpt::graphs::TNodeID& from, const mrpt::graphs::TNodeID& to,
714  constraint_t* rel_edge, mrpt::slam::CICP::TReturnInfo* icp_info = NULL,
715  const TGetICPEdgeAdParams* ad_params = NULL);
716  /**\brief compute the minimum uncertainty of each node position with
717  * regards to the graph root.
718  *
719  * \param[in] starting_node Node from which I start the Dijkstra projection
720  * algorithm
721  * \param[in] ending_node Specify the nodeID whose uncertainty wrt the
722  * starting_node, we are interested in computing. If given, method
723  * execution ends when this path is computed.
724  */
726  mrpt::graphs::TNodeID starting_node = 0,
727  mrpt::graphs::TNodeID ending_node = INVALID_NODEID);
728  /**\brief Given two nodeIDs compute and return the path connecting them.
729  *
730  * Method takes care of multiple edges, as well as edges with 0 covariance
731  * matrices
732  */
734  const mrpt::graphs::TNodeID from, const mrpt::graphs::TNodeID to,
735  path_t* path) const;
736  /**\brief Find the minimum uncertainty path from te given pool of
737  * TUncertaintyPath instances.
738  *
739  * Removes (and returns) the found path from the pool.
740  *
741  * \return Minimum uncertainty path from the pool provided
742  */
744  std::set<path_t*>* pool_of_paths) const;
745  /**\brief Append the paths starting from the current node.
746  *
747  * \param[in] pool_of_paths Paths that are currently registered
748  * \param[in] curr_path Path that I am currently traversing. This path is
749  * already removed from \a pool_of_paths
750  * \param[in] neighbors std::set of neighboring nodes to the last node of
751  * the current path
752  */
753  void addToPaths(
754  std::set<path_t*>* pool_of_paths, const path_t& curr_path,
755  const std::set<mrpt::graphs::TNodeID>& neibors) const;
756  /**\brief Query for the optimal path of a nodeID.
757  *
758  * Method handles calls to out-of-bounds nodes as well as nodes whose paths
759  * have not yet been computed.
760  *
761  * \param[in] node nodeID for which hte path is going to be returned
762  *
763  * \return Optimal path corresponding to the given nodeID or nullptr if the
764  * former is not found.
765  */
767  const mrpt::graphs::TNodeID node) const;
768  /**\brief Split an existing partition to Groups
769  *
770  * Have two groups A, B.
771  * - Group A consists of the lower nodeIDs. They correspond to the start
772  * of the course
773  * - Group B consists of the higher (more recent) nodeIDs. They
774  * correspond to the end of the course find where to split the current
775  * partition
776  *
777  * \note Method is used in single-robot graphSLAM for spliting a
778  * partition of nodes to lower and higher node IDs
779  *
780  * \param[in] partition Partition to be split.
781  * \param[out] groupA First group of nodes.
782  * \param[out] groupB Second group of nodes.
783  * \param[in] max_nodes_in_group Max number of nodes that are to exist in
784  * each group (Use -1 to disable this threshold).
785  */
787  std::vector<uint32_t>& partition, std::vector<uint32_t>* groupA,
788  std::vector<uint32_t>* groupB, int max_nodes_in_group = 5);
789  /**\brief Assign the last recorded 2D Laser scan
790  *
791  * \note Compact way of assigning the last recorded laser scan for both
792  * MRPT rawlog formats.
793  *
794  * Method takes into account the start of graphSLAM proc. when two nodes
795  * are added at the graph at the same time (root + node for 1st constraint)
796  */
798 
799  // protected variables
800  //////////////////////////////////////////////////////////////
801  /**\brief Instance responsible for partitioning the map */
803 
808 
809  /**\brief Keep track of the registered edge types.
810  *
811  * Handy for displaying them in the Visualization window.
812  */
813  std::map<std::string, int> m_edge_types_to_nums;
814  /**\brief Keep the last laser scan for visualization purposes */
816  /**\name Partition vectors */
817  /**\{ */
818  /**\brief Previous partitions vector */
820  /**\brief Current partitions vector */
822  /**\} */
823  /**\brief Indicate whether the partitions have been updated recently */
825  /**\brief Keep track of the evaluated partitions so they are not checked
826  * again if nothing changed in them.
827  */
828  std::map<int, std::vector<uint32_t>> m_partitionID_to_prev_nodes_list;
829  /**\brief Map that stores the lowest uncertainty path towards a node.
830  * Starting node depends on the starting node as used in the
831  * execDijkstraProjection method
832  */
833  typename std::map<mrpt::graphs::TNodeID, path_t*> m_node_optimal_paths;
834  /**\brief Keep track of the first recorded laser scan so that it can be
835  * assigned to the root node when the NRD adds the first *two* nodes to the
836  * graph.
837  */
839  /**\brief Track the first node registration occurance
840  *
841  * Handy so that we can assign a measurement to the root node as well.
842  */
844  /**\brief Node Count lower bound before executing dijkstra
845  */
847  /**\brief Factor used for accepting an ICP Constraint as valid.
848  */
850  /**\brief Factor used for accepting an ICP Constraint in the loop closure
851  * proc.
852  */
854 };
855 } // namespace deciders
856 } // namespace graphslam
857 } // namespace mrpt
858 
859 #include "CLoopCloserERD_impl.h"
860 #endif /* end of include guard: CLOOPCLOSERERD_H */
mrpt::obs::CObservation::Ptr
std::shared_ptr< CObservation > Ptr
Definition: CObservation.h:45
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::balloon_curr_color
const mrpt::img::TColor balloon_curr_color
Definition: CLoopCloserERD.h:511
mrpt::obs::gnss::a1
double a1
Definition: gnss_messages_novatel.h:454
mrpt::graphslam::deciders::CLoopCloserERD::m_offset_y_curr_node_covariance
double m_offset_y_curr_node_covariance
Definition: CLoopCloserERD.h:806
mrpt::graphslam::deciders::CLoopCloserERD::setLastLaserScan2D
void setLastLaserScan2D(mrpt::obs::CObservation2DRangeScan::Ptr scan)
Assign the last recorded 2D Laser scan.
mrpt::graphslam::deciders::CLoopCloserERD::splitPartitionToGroups
void splitPartitionToGroups(std::vector< uint32_t > &partition, std::vector< uint32_t > *groupA, std::vector< uint32_t > *groupB, int max_nodes_in_group=5)
Split an existing partition to Groups.
Definition: CLoopCloserERD_impl.h:683
mrpt::graphslam::deciders::CLoopCloserERD::evalPWConsistenciesMatrix
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.
Definition: CLoopCloserERD_impl.h:609
const_iterator
const Scalar * const_iterator
Definition: eigen_plugins.h:27
mrpt::graphslam::deciders::CLoopCloserERD::updateMapPartitionsVisualization
void updateMapPartitionsVisualization()
Update the map partitions visualization.
Definition: CLoopCloserERD_impl.h:1843
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::text_index_map_partitions
int text_index_map_partitions
Definition: CLoopCloserERD.h:505
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::full_partition_per_nodes
int full_partition_per_nodes
Full partition of map only afer X new nodes have been registered.
Definition: CLoopCloserERD.h:500
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::has_read_config
bool has_read_config
Definition: CLoopCloserERD.h:514
mrpt::obs::CSensoryFrame::Ptr
std::shared_ptr< CSensoryFrame > Ptr
Definition: CSensoryFrame.h:56
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::keystroke_map_partitions
std::string keystroke_map_partitions
Definition: CLoopCloserERD.h:502
mrpt::graphslam::deciders::CLoopCloserERD::m_consec_icp_constraint_factor
double m_consec_icp_constraint_factor
Factor used for accepting an ICP Constraint as valid.
Definition: CLoopCloserERD.h:849
mrpt::graphslam::deciders::CLoopCloserERD::TGenerateHypotsPoolAdParams
Struct for passing additional parameters to the generateHypotsPool call.
Definition: CLoopCloserERD.h:326
src
GLuint src
Definition: glext.h:7278
mrpt::graphslam::deciders::CLoopCloserERD::m_node_optimal_paths
std::map< mrpt::graphs::TNodeID, path_t * > m_node_optimal_paths
Map that stores the lowest uncertainty path towards a node.
Definition: CLoopCloserERD.h:833
mrpt::math::dynamic_vector
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction.
Definition: eigen_frwds.h:44
mrpt::graphslam::deciders::CLoopCloserERD::execDijkstraProjection
void execDijkstraProjection(mrpt::graphs::TNodeID starting_node=0, mrpt::graphs::TNodeID ending_node=INVALID_NODEID)
compute the minimum uncertainty of each node position with regards to the graph root.
Definition: CLoopCloserERD_impl.h:1340
mrpt::graphslam::deciders::CLoopCloserERD::m_last_laser_scan2D
mrpt::obs::CObservation2DRangeScan::Ptr m_last_laser_scan2D
Keep the last laser scan for visualization purposes.
Definition: CLoopCloserERD.h:815
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::offset_y_map_partitions
double offset_y_map_partitions
Definition: CLoopCloserERD.h:504
mrpt::graphslam::deciders::CLoopCloserERD::addScanMatchingEdges
virtual void addScanMatchingEdges(const mrpt::graphs::TNodeID &curr_nodeID)
Addd ICP constraints from X previous nodeIDs up to the given nodeID.
Definition: CLoopCloserERD_impl.h:191
mrpt::graphslam::deciders::CLoopCloserERD::edges_iterator
typename GRAPH_T::edges_map_t::iterator edges_iterator
Definition: CLoopCloserERD.h:238
mrpt::graphslam::deciders::CLoopCloserERD::TLaserParams::laser_scans_color
const mrpt::img::TColor laser_scans_color
see Constructor for initialization
Definition: CLoopCloserERD.h:436
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::LC_eigenvalues_ratio_thresh
double LC_eigenvalues_ratio_thresh
Eigenvalues ratio for accepting/rejecting a hypothesis set.
Definition: CLoopCloserERD.h:492
mrpt::graphs::TNodeID
uint64_t TNodeID
A generic numeric type for unique IDs of nodes or entities.
Definition: TNodeID.h:17
mrpt::graphslam::deciders::CLoopCloserERD::initMapPartitionsVisualization
void initMapPartitionsVisualization()
Initialize the visualization of the map partition objects.
Definition: CLoopCloserERD_impl.h:1819
mrpt::graphslam::deciders::CLoopCloserERD::TLaserParams
Struct for storing together the parameters needed for ICP matching, laser scans visualization etc.
Definition: CLoopCloserERD.h:420
THypothesis.h
CMatrix.h
mrpt::graphslam::deciders::CLoopCloserERD::updateCurrCovarianceVisualization
void updateCurrCovarianceVisualization()
Definition: CLoopCloserERD_impl.h:2307
mrpt::graphslam::deciders::CLoopCloserERD::getEdgesStats
void getEdgesStats(std::map< std::string, int > *edge_types_to_num) const
Definition: CLoopCloserERD_impl.h:2212
mrpt::graphs::detail::THypothesis
An edge hypothesis between two nodeIDs.
Definition: THypothesis.h:37
CICP.h
mrpt::graphslam::deciders::CLoopCloserERD::TLaserParams::prev_nodes_for_ICP
int prev_nodes_for_ICP
How many nodes back to check ICP against?
Definition: CLoopCloserERD.h:433
mrpt::graphslam::deciders::CLoopCloserERD::m_laser_params
TLaserParams m_laser_params
Definition: CLoopCloserERD.h:516
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::balloon_elevation
const double balloon_elevation
Definition: CLoopCloserERD.h:508
CRangeScanEdgeRegistrationDecider.h
mrpt::graphslam::deciders::CLoopCloserERD::updateLaserScansVisualization
void updateLaserScansVisualization()
Definition: CLoopCloserERD_impl.h:2144
mrpt::graphslam::detail::TNodeProps::getAsString
void getAsString(std::string *str) const
Definition: TNodeProps.h:34
mrpt
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Definition: CKalmanFilterCapable.h:30
mrpt::graphslam::deciders::CLoopCloserERD::paths_t
std::vector< path_t > paths_t
Definition: CLoopCloserERD.h:245
mrpt::graphslam::deciders::CLoopCloserERD::m_is_first_time_node_reg
bool m_is_first_time_node_reg
Track the first node registration occurance.
Definition: CLoopCloserERD.h:843
mrpt::graphslam::deciders::CLoopCloserERD::CLoopCloserERD
CLoopCloserERD()
Definition: CLoopCloserERD_impl.h:27
mrpt::graphslam::deciders::CLoopCloserERD::mahalanobisDistanceOdometryToICPEdge
bool mahalanobisDistanceOdometryToICPEdge(const mrpt::graphs::TNodeID &from, const mrpt::graphs::TNodeID &to, const constraint_t &rel_edge)
brief Compare the suggested ICP edge against the initial node difference.
Definition: CLoopCloserERD_impl.h:1688
mrpt::graphslam::deciders::CLoopCloserERD::registerNewEdge
void registerNewEdge(const mrpt::graphs::TNodeID &from, const mrpt::graphs::TNodeID &to, const constraint_t &rel_edge)
Definition: CLoopCloserERD_impl.h:1743
mrpt::graphslam::deciders::CLoopCloserERD::fillNodePropsFromGroupParams
bool fillNodePropsFromGroupParams(const mrpt::graphs::TNodeID &nodeID, const std::map< mrpt::graphs::TNodeID, node_props_t > &group_params, node_props_t *node_props)
Fill the TNodeProps instance using the parameters from the map.
Definition: CLoopCloserERD_impl.h:326
CActionCollection.h
mrpt::graphslam::CWindowManager
Class acts as a container for storing pointers to mrpt::gui::CDisplayWindow3D, mrpt::graphslam::CWind...
Definition: CWindowManager.h:30
mrpt::graphslam::deciders::CLoopCloserERD::TLaserParams::goodness_threshold_win
TSlidingWindow goodness_threshold_win
Keep track of ICP Goodness values for ICP between nearby nodes and adapt the Goodness threshold based...
Definition: CLoopCloserERD.h:461
mrpt::graphslam::deciders::CLoopCloserERD::registerHypothesis
void registerHypothesis(const hypot_t &h)
Wrapper around the registerNewEdge method which accepts a THypothesis object instead.
Definition: CLoopCloserERD_impl.h:1735
mrpt::graphslam::deciders::CLoopCloserERD::TLaserParams::mahal_distance_ICP_odom_win
TSlidingWindow mahal_distance_ICP_odom_win
Keep track of the mahalanobis distance between the initial pose difference and the suggested new edge...
Definition: CLoopCloserERD.h:456
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::visualize_map_partitions
bool visualize_map_partitions
Definition: CLoopCloserERD.h:501
mrpt::graphslam::deciders::CLoopCloserERD::m_edge_types_to_nums
std::map< std::string, int > m_edge_types_to_nums
Keep track of the registered edge types.
Definition: CLoopCloserERD.h:813
mrpt::graphslam::deciders::CLoopCloserERD::findPathByEnds
static const path_t * findPathByEnds(const paths_t &vec_paths, const mrpt::graphs::TNodeID &src, const mrpt::graphs::TNodeID &dst, bool throw_exc=true)
Given a vector of TUncertaintyPath objects, find the one that has the given source and destination no...
Definition: CLoopCloserERD_impl.h:1251
mrpt::slam::CICP::TReturnInfo
The ICP algorithm return information.
Definition: CICP.h:192
dst
GLuint dst
Definition: glext.h:7135
source
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
CLoopCloserERD_impl.h
mrpt::graphslam::deciders::CLoopCloserERD::TGetICPEdgeAdParams::from_params
node_props_t from_params
Ad.
Definition: CLoopCloserERD.h:297
mrpt::math::CMatrixTemplateNumeric< double >
mrpt::graphslam::deciders::CLoopCloserERD::getICPEdge
virtual bool getICPEdge(const mrpt::graphs::TNodeID &from, const mrpt::graphs::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.
Definition: CLoopCloserERD_impl.h:254
mrpt::graphslam::deciders::CLoopCloserERD::m_visualize_curr_node_covariance
bool m_visualize_curr_node_covariance
Definition: CLoopCloserERD.h:804
mrpt::graphslam::deciders::CLoopCloserERD::hypotsp_to_consist_t
std::map< std::pair< hypot_t *, hypot_t * >, double > hypotsp_to_consist_t
Definition: CLoopCloserERD.h:243
mrpt::graphslam::deciders::CLoopCloserERD::getPropsOfNodeID
bool getPropsOfNodeID(const mrpt::graphs::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.
Definition: CLoopCloserERD_impl.h:359
mrpt::graphslam::deciders::CLoopCloserERD::m_lc_icp_constraint_factor
double m_lc_icp_constraint_factor
Factor used for accepting an ICP Constraint in the loop closure proc.
Definition: CLoopCloserERD.h:853
mrpt::graphslam::deciders::CLoopCloserERD::m_curr_node_covariance_color
const mrpt::img::TColor m_curr_node_covariance_color
Definition: CLoopCloserERD.h:805
mrpt::graphslam::deciders::CLoopCloserERD::m_dijkstra_node_count_thresh
size_t m_dijkstra_node_count_thresh
Node Count lower bound before executing dijkstra.
Definition: CLoopCloserERD.h:846
CConfigFileBase.h
mrpt::graphslam::deciders::CLoopCloserERD::TGenerateHypotsPoolAdParams::group_t
std::map< mrpt::graphs::TNodeID, node_props_t > group_t
Definition: CLoopCloserERD.h:328
mrpt::graphslam::deciders::CLoopCloserERD::TLaserParams::use_scan_matching
bool use_scan_matching
Indicate whethet to use scan-matching at all during graphSLAM [on by default].
Definition: CLoopCloserERD.h:449
mrpt::graphslam::deciders::CLoopCloserERD::printParams
void printParams() const
Definition: CLoopCloserERD_impl.h:2395
mrpt::graphslam::deciders::CLoopCloserERD::TGetICPEdgeAdParams::init_estim
pose_t init_estim
Initial ICP estimation.
Definition: CLoopCloserERD.h:299
mrpt::graphslam::deciders::CLoopCloserERD::updateVisuals
void updateVisuals()
Definition: CLoopCloserERD_impl.h:2249
mrpt::graphslam::deciders::CLoopCloserERD::checkPartitionsForLC
void checkPartitionsForLC(partitions_t *partitions_for_LC)
Check the registered so far partitions for potential loop closures.
Definition: CLoopCloserERD_impl.h:427
mrpt::graphslam::deciders::CLoopCloserERD::~CLoopCloserERD
virtual ~CLoopCloserERD()
Definition: CLoopCloserERD_impl.h:41
mrpt::obs::gnss::a2
double a2
Definition: gnss_messages_novatel.h:454
mrpt::graphslam::deciders::CLoopCloserERD::m_text_index_curr_node_covariance
int m_text_index_curr_node_covariance
Definition: CLoopCloserERD.h:807
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::balloon_std_color
const mrpt::img::TColor balloon_std_color
Definition: CLoopCloserERD.h:510
mrpt::graphslam::deciders::CLoopCloserERD::notifyOfWindowEvents
void notifyOfWindowEvents(const std::map< std::string, bool > &events_occurred)
Definition: CLoopCloserERD_impl.h:1798
TSlidingWindow.h
mrpt::graphslam::deciders::CLoopCloserERD::hypot_t
typename mrpt::graphs::detail::THypothesis< GRAPH_T > hypot_t
Definition: CLoopCloserERD.h:239
mrpt::config::CConfigFileBase
This class allows loading and storing values and vectors of different types from a configuration text...
Definition: config/CConfigFileBase.h:44
mrpt::format
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:16
mrpt::graphslam::deciders::CLoopCloserERD::dumpVisibilityErrorMsg
void dumpVisibilityErrorMsg(std::string viz_flag, int sleep_time=500)
Definition: CLoopCloserERD_impl.h:2349
mrpt::graphslam::deciders::CLoopCloserERD::getMinUncertaintyPath
void getMinUncertaintyPath(const mrpt::graphs::TNodeID from, const mrpt::graphs::TNodeID to, path_t *path) const
Given two nodeIDs compute and return the path connecting them.
Definition: CLoopCloserERD_impl.h:1548
mrpt::graphslam::deciders::CLoopCloserERD::m_last_partitions
partitions_t m_last_partitions
Previous partitions vector.
Definition: CLoopCloserERD.h:819
mrpt::graphslam::deciders::CLoopCloserERD::updateState
virtual bool updateState(mrpt::obs::CActionCollection::Ptr action, mrpt::obs::CSensoryFrame::Ptr observations, mrpt::obs::CObservation::Ptr observation)
Definition: CLoopCloserERD_impl.h:58
mrpt::graphslam::deciders::CLoopCloserERD::setDijkstraExecutionThresh
void setDijkstraExecutionThresh(size_t new_thresh)
Definition: CLoopCloserERD.h:279
mrpt::obs::gnss::b2
double b2
Definition: gnss_messages_novatel.h:454
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::balloon_radius
const double balloon_radius
Definition: CLoopCloserERD.h:509
mrpt::img::TColor
A RGB color - 8bit.
Definition: TColor.h:22
mrpt::config::CLoadableOptions
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
Definition: config/CLoadableOptions.h:28
TUncertaintyPath.h
mrpt::graphslam::deciders::CLoopCloserERD::loadParams
void loadParams(const std::string &source_fname)
Definition: CLoopCloserERD_impl.h:2366
mrpt::graphslam::deciders::CLoopCloserERD::hypotsp_t
std::vector< hypot_t * > hypotsp_t
Definition: CLoopCloserERD.h:241
mrpt::graphslam::deciders::CLoopCloserERD::m_partitions_full_update
bool m_partitions_full_update
Indicate whether the partitions have been updated recently.
Definition: CLoopCloserERD.h:824
mrpt::graphslam::deciders::CLoopCloserERD::TGetICPEdgeAdParams::getAsString
void getAsString(std::string *str) const
Definition: CLoopCloserERD.h:301
mrpt::graphslam::deciders::CLoopCloserERD::initLaserScansVisualization
void initLaserScansVisualization()
Definition: CLoopCloserERD_impl.h:2112
mrpt::graphslam::deciders::CLoopCloserERD::constraint_t
typename GRAPH_T::constraint_t constraint_t
Handy typedefs.
Definition: CLoopCloserERD.h:228
mrpt::graphslam::deciders::CRangeScanEdgeRegistrationDecider::range_ops_t
mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T > range_ops_t
Typedef for accessing methods of the RangeScanRegistrationDecider_t parent class.
Definition: CRangeScanEdgeRegistrationDecider.h:44
mrpt::graphslam::deciders::CLoopCloserERD::getCurrentPartitions
const partitions_t & getCurrentPartitions() const
Definition: CLoopCloserERD_impl.h:2460
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams
Struct for storing together the loop-closing related parameters.
Definition: CLoopCloserERD.h:466
mrpt::slam::CICP
Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a ...
Definition: CICP.h:67
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::LC_min_nodeid_diff
size_t LC_min_nodeid_diff
nodeID difference for detecting potential loop closure in a partition.
Definition: CLoopCloserERD.h:487
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::LC_min_remote_nodes
int LC_min_remote_nodes
how many remote nodes (large nodID difference should there be before I consider the potential loop cl...
Definition: CLoopCloserERD.h:496
mrpt::graphslam::deciders::CRangeScanEdgeRegistrationDecider::nodes_to_scans2D_t
std::map< mrpt::graphs::TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > nodes_to_scans2D_t
Definition: CRangeScanEdgeRegistrationDecider.h:46
mrpt::graphslam::deciders::CLoopCloserERD::TGenerateHypotsPoolAdParams::groupB_params
group_t groupB_params
Ad.
Definition: CLoopCloserERD.h:333
mrpt::graphslam::deciders::CLoopCloserERD::partitions_t
std::vector< std::vector< uint32_t > > partitions_t
Typedef for referring to a list of partitions.
Definition: CLoopCloserERD.h:236
mrpt::obs::CObservation2DRangeScan::Ptr
std::shared_ptr< CObservation2DRangeScan > Ptr
Definition: CObservation2DRangeScan.h:58
mrpt::graphslam::deciders::CLoopCloserERD::setWindowManagerPtr
void setWindowManagerPtr(mrpt::graphslam::CWindowManager *win_manager)
Definition: CLoopCloserERD_impl.h:1774
CSensoryFrame.h
mrpt::graphslam::deciders::CLoopCloserERD::global_pose_t
typename GRAPH_T::global_pose_t global_pose_t
Definition: CLoopCloserERD.h:231
mrpt::graphslam::deciders::CLoopCloserERD::nodes_to_scans2D_t
typename parent_t::nodes_to_scans2D_t nodes_to_scans2D_t
Definition: CLoopCloserERD.h:234
mrpt::graphslam::deciders::CLoopCloserERD::m_partitioner
mrpt::slam::CIncrementalMapPartitioner m_partitioner
Instance responsible for partitioning the map.
Definition: CLoopCloserERD.h:802
mrpt::graphslam::deciders::CLoopCloserERD::generateHypotsPool
void generateHypotsPool(const std::vector< uint32_t > &groupA, const std::vector< uint32_t > &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.
Definition: CLoopCloserERD_impl.h:749
mrpt::graphslam::deciders::CLoopCloserERD::updateMapPartitions
void updateMapPartitions(bool full_update=false, bool is_first_time_node_reg=false)
Split the currently registered graph nodes into partitions.
Definition: CLoopCloserERD_impl.h:2466
mrpt::graphslam::deciders::CLoopCloserERD::evaluatePartitionsForLC
void evaluatePartitionsForLC(const partitions_t &partitions)
Evaluate the given partitions for loop closures.
Definition: CLoopCloserERD_impl.h:541
mrpt::graphslam::deciders::CLoopCloserERD::toggleMapPartitionsVisualization
void toggleMapPartitionsVisualization()
Toggle the map partitions visualization objects.
Definition: CLoopCloserERD_impl.h:2056
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::LC_check_curr_partition_only
bool LC_check_curr_partition_only
flag indicating whether to check only the partition of the last registered node for potential loop cl...
Definition: CLoopCloserERD.h:480
mrpt::graphslam::deciders::CLoopCloserERD::getDijkstraExecutionThresh
size_t getDijkstraExecutionThresh() const
Return the minimum number of nodes that should exist in the graph prior to running Dijkstra.
Definition: CLoopCloserERD.h:275
mrpt::graphslam::deciders::CLoopCloserERD::computeDominantEigenVector
bool computeDominantEigenVector(const mrpt::math::CMatrixDouble &consist_matrix, mrpt::math::dynamic_vector< double > *eigvec, bool use_power_method=false)
Definition: CLoopCloserERD_impl.h:902
mrpt::graphslam::deciders::CLoopCloserERD::findHypotByEnds
static hypot_t * findHypotByEnds(const hypotsp_t &vec_hypots, const mrpt::graphs::TNodeID &from, const mrpt::graphs::TNodeID &to, bool throw_exc=true)
Given a vector of THypothesis objects, find the one that has the given start and end nodes.
Definition: CLoopCloserERD_impl.h:1283
mrpt::slam::CIncrementalMapPartitioner
Finds partitions in metric maps based on N-cut graph partition theory.
Definition: CIncrementalMapPartitioner.h:60
CLoadableOptions.h
mrpt::graphslam::deciders::CLoopCloserERD::hypots_t
std::vector< hypot_t > hypots_t
Definition: CLoopCloserERD.h:240
TNodeProps.h
mrpt::graphslam::deciders::CRangeScanEdgeRegistrationDecider
Edge Registration Decider Interface from which RangeScanner-based ERDs can inherit from.
Definition: CRangeScanEdgeRegistrationDecider.h:34
mrpt::graphslam::TSlidingWindow
Class to monitor the evolution of a statistical quantity.
Definition: TSlidingWindow.h:45
mrpt::graphslam::deciders::CLoopCloserERD::TLoopClosureParams::connecting_lines_color
const mrpt::img::TColor connecting_lines_color
Definition: CLoopCloserERD.h:512
mrpt::graphslam::deciders::CLoopCloserERD::TLaserParams::has_read_config
bool has_read_config
Definition: CLoopCloserERD.h:450
mrpt::graphslam::deciders::CLoopCloserERD::fetchNodeIDsForScanMatching
virtual void fetchNodeIDsForScanMatching(const mrpt::graphs::TNodeID &curr_nodeID, std::set< mrpt::graphs::TNodeID > *nodes_set)
Fetch a list of nodes with regards prior to the given nodeID for which to try and add scan matching e...
Definition: CLoopCloserERD_impl.h:170
mrpt::graphslam::deciders::CLoopCloserERD::toggleLaserScansVisualization
void toggleLaserScansVisualization()
togle the LaserScans visualization on and off
Definition: CLoopCloserERD_impl.h:2184
mrpt::graphslam::deciders::CLoopCloserERD::TLaserParams::icp
mrpt::slam::CICP icp
Definition: CLoopCloserERD.h:430
CIncrementalMapPartitioner.h
mrpt::graphslam::deciders::CLoopCloserERD::initializeVisuals
void initializeVisuals()
Definition: CLoopCloserERD_impl.h:2221
mrpt::graphslam::deciders::CLoopCloserERD::addToPaths
void addToPaths(std::set< path_t * > *pool_of_paths, const path_t &curr_path, const std::set< mrpt::graphs::TNodeID > &neibors) const
Append the paths starting from the current node.
Definition: CLoopCloserERD_impl.h:1491
string
GLsizei const GLchar ** string
Definition: glext.h:4101
mrpt::graphslam::deciders::CLoopCloserERD::TGetICPEdgeAdParams::getAsString
std::string getAsString() const
Definition: CLoopCloserERD.h:311
mrpt::graphslam::deciders::CLoopCloserERD::popMinUncertaintyPath
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.
Definition: CLoopCloserERD_impl.h:1658
mrpt::graphslam::deciders::CLoopCloserERD::getDescriptiveReport
void getDescriptiveReport(std::string *report_str) const
Definition: CLoopCloserERD_impl.h:2419
mrpt::graphslam::deciders::CLoopCloserERD::generatePWConsistencyElement
double generatePWConsistencyElement(const mrpt::graphs::TNodeID &a1, const mrpt::graphs::TNodeID &a2, const mrpt::graphs::TNodeID &b1, const mrpt::graphs::TNodeID &b2, const hypotsp_t &hypots, const paths_t *opt_paths=NULL)
Return the pair-wise consistency between the observations of the given nodes.
Definition: CLoopCloserERD_impl.h:1128
mrpt::graphslam::deciders::CLoopCloserERD
Edge Registration Decider scheme specialized in Loop Closing.
Definition: CLoopCloserERD.h:218
mrpt::graphslam::deciders::CLoopCloserERD::range_ops_t
typename parent_t::range_ops_t range_ops_t
Definition: CLoopCloserERD.h:233
mrpt::graphslam::deciders::CLoopCloserERD::TLaserParams::keystroke_laser_scans
std::string keystroke_laser_scans
Definition: CLoopCloserERD.h:440
iterator
Scalar * iterator
Definition: eigen_plugins.h:26
INVALID_NODEID
#define INVALID_NODEID
Definition: TNodeID.h:20
CHypothesisNotFoundException.h
mrpt::graphslam::deciders::CLoopCloserERD::initCurrCovarianceVisualization
void initCurrCovarianceVisualization()
Definition: CLoopCloserERD_impl.h:2274
mrpt::graphslam::deciders::CLoopCloserERD::m_curr_partitions
partitions_t m_curr_partitions
Current partitions vector.
Definition: CLoopCloserERD.h:821
mrpt::graphslam::deciders::CLoopCloserERD::TGetICPEdgeAdParams::to_params
node_props_t to_params
Ad.
Definition: CLoopCloserERD.h:298
mrpt::obs::CActionCollection::Ptr
std::shared_ptr< CActionCollection > Ptr
Definition: CActionCollection.h:30
mrpt::graphslam::deciders
Definition: CEmptyERD.h:21
mrpt::graphslam::deciders::CLoopCloserERD::TLaserParams::visualize_laser_scans
bool visualize_laser_scans
Definition: CLoopCloserERD.h:437
mrpt::obs::gnss::b1
double b1
Definition: gnss_messages_novatel.h:454
mrpt::graphslam::deciders::CLoopCloserERD::m_lc_params
TLoopClosureParams m_lc_params
Definition: CLoopCloserERD.h:517
mrpt::graphslam::deciders::CLoopCloserERD::TGetICPEdgeAdParams::operator<<
friend std::ostream & operator<<(std::ostream &o, const self_t &params)
Definition: CLoopCloserERD.h:317
mrpt::graphslam::TUncertaintyPath
Holds the data of an information path.
Definition: TUncertaintyPath.h:31
mrpt::graphslam::deciders::CLoopCloserERD::m_first_laser_scan
mrpt::obs::CObservation2DRangeScan::Ptr m_first_laser_scan
Keep track of the first recorded laser scan so that it can be assigned to the root node when the NRD ...
Definition: CLoopCloserERD.h:838
mrpt::graphslam::deciders::CLoopCloserERD::pose_t
typename GRAPH_T::constraint_t::type_value pose_t
type of underlying poses (2D/3D).
Definition: CLoopCloserERD.h:230
TColor.h
mrpt::graphslam::deciders::CLoopCloserERD::TGetICPEdgeAdParams
Struct for passing additional parameters to the getICPEdge call.
Definition: CLoopCloserERD.h:293
CObservation2DRangeScan.h
mrpt::graphslam::detail::TNodeProps
Definition: TNodeProps.h:22
params
GLenum const GLfloat * params
Definition: glext.h:3534
mrpt::graphslam::deciders::CLoopCloserERD::edges_citerator
typename GRAPH_T::edges_map_t::const_iterator edges_citerator
Definition: CLoopCloserERD.h:237
mrpt::graphslam::deciders::CLoopCloserERD::TGenerateHypotsPoolAdParams::groupA_params
group_t groupA_params
Ad.
Definition: CLoopCloserERD.h:331
mrpt::graphslam::deciders::CLoopCloserERD::computeCentroidOfNodesVector
void computeCentroidOfNodesVector(const std::vector< uint32_t > &nodes_list, std::pair< double, double > *centroid_coords) const
Compute the Centroid of a group of a vector of node positions.
Definition: CLoopCloserERD_impl.h:2084
mrpt::graphslam::deciders::CLoopCloserERD::m_partitionID_to_prev_nodes_list
std::map< int, std::vector< uint32_t > > m_partitionID_to_prev_nodes_list
Keep track of the evaluated partitions so they are not checked again if nothing changed in them.
Definition: CLoopCloserERD.h:828
mrpt::graphslam::deciders::CLoopCloserERD::findHypotByID
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.
Definition: CLoopCloserERD_impl.h:1314
mrpt::graphslam::deciders::CLoopCloserERD::queryOptimalPath
mrpt::graphslam::TUncertaintyPath< GRAPH_T > * queryOptimalPath(const mrpt::graphs::TNodeID node) const
Query for the optimal path of a nodeID.
Definition: CLoopCloserERD_impl.h:1530
mrpt::graphslam::deciders::CLoopCloserERD::generatePWConsistenciesMatrix
void generatePWConsistenciesMatrix(const std::vector< uint32_t > &groupA, const std::vector< uint32_t > &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.
Definition: CLoopCloserERD_impl.h:977



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST