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