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



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