Main MRPT website > C++ reference
MRPT logo
RbaEngine.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-2015, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 
10 #pragma once
11 
12 /** \file RbaEngine.h
13  * \brief This file exposes the public API and data types of libmrpt-srba (it requires also including srba/models/{*.h} to have a complete SLAM/RBA system)
14  */
15 
16 #include <mrpt/utils/CTimeLogger.h>
20 
21 #include "srba_types.h"
22 #include "srba_options.h"
24 
25 #define VERBOSE_LEVEL(_LEVEL) if (m_verbose_level>=_LEVEL) std::cout
26 
27 namespace mrpt
28 {
29 /** An heavily template-based implementation of Relative Bundle Adjustment (RBA) - See \ref mrpt_srba_grp */
30 namespace srba
31 {
32  /** The set of default settings for RbaEngine */
34  {
35  typedef options::sensor_pose_on_robot_none sensor_pose_on_robot_t; //!< The sensor pose coincides with the robot pose
36  typedef options::observation_noise_identity obs_noise_matrix_t; //!< The sensor noise matrix is the same for all observations and equal to \sigma * I(identity)
37  typedef options::solver_LM_schur_dense_cholesky solver_t; //!< Solver algorithm (Default: Lev-Marq, with Schur, with dense Cholesky)
38  };
39 
40  /** The main class for the mrpt-srba: it defines a Relative Bundle-Adjustment (RBA) problem with (optionally, partially known) landmarks,
41  * the methods to update it with new observations and to optimize the relative poses with least squares optimizers.
42  *
43  * The unknowns to be solved are:
44  * - Relative poses among keyframes.
45  * - Relative positions of landmarks wrt to their base frame (or no landmarks for graph-SLAM-like problems)
46  *
47  * The set of known data used to run the optimization comprises:
48  * - Sequence of all observations.
49  * - Optional sensor parameters (e.g. camera calibration)
50  * - Optionally, the relative positions of a subset of landmarks wrt to their base frame (these are the "fixed" or "known" landmarks).
51  *
52  * See http://www.mrpt.org/srba and the <a href="srba-guide.pdf" >library guide</a> for a list of possible template arguments, code examples, etc.
53  *
54  * \tparam KF2KF_POSE_TYPE The parameterization of keyframe-to-keyframe relative poses (edges, problem unknowns).
55  * \tparam LM_TYPE The parameterization of relative positions of landmarks relative poses (edges).
56  * \tparam OBS_TYPE The type of observations.
57  * \tparam RBA_OPTIONS A struct with nested typedefs which can be used to tune and customize the behavior of this class.
58  */
59  template <class KF2KF_POSE_TYPE,class LM_TYPE,class OBS_TYPE, class RBA_OPTIONS = RBA_OPTIONS_DEFAULT>
60  class RbaEngine
61  {
62  public:
63  /** @name Templatized typedef's
64  @{ */
66 
67  typedef KF2KF_POSE_TYPE kf2kf_pose_type;
68  typedef LM_TYPE lm_type;
69  typedef OBS_TYPE obs_type;
70  typedef RBA_OPTIONS rba_options_type;
71 
72  static const size_t REL_POSE_DIMS = KF2KF_POSE_TYPE::REL_POSE_DIMS;
73  static const size_t LM_DIMS = LM_TYPE::LM_DIMS;
74  static const size_t OBS_DIMS = OBS_TYPE::OBS_DIMS;
75 
76  typedef typename KF2KF_POSE_TYPE::se_traits_t se_traits_t; //!< The SE(2) or SE(3) traits struct (for Lie algebra log/exp maps, etc.)
77 
84 
85  typedef sensor_model<LM_TYPE,OBS_TYPE> sensor_model_t; //!< The sensor model for the specified combination of LM parameterization + observation type.
86 
87  typedef typename KF2KF_POSE_TYPE::pose_t pose_t; //!< The type of relative poses (e.g. mrpt::poses::CPose3D)
89 
92  typedef typename rba_problem_state_t::k2k_edges_deque_t k2k_edges_deque_t; //!< A list (deque) of KF-to-KF edges (unknown relative poses).
93 
94  typedef typename kf2kf_pose_traits_t::pose_flag_t pose_flag_t;
97  typedef typename landmark_traits_t::TRelativeLandmarkPosMap TRelativeLandmarkPosMap; //!< An index of feature IDs and their relative locations
98  typedef typename landmark_traits_t::TRelativeLandmarkPos TRelativeLandmarkPos; //!< One landmark position (relative to its base KF)
102 
108 
111  /** @} */
112 
113  /** Default constructor */
114  RbaEngine();
115 
116  /** All the information returned by the local area optimizer \sa define_new_keyframe() */
118  {
120  {
121  clear();
122  }
123 
124  size_t num_observations; //!< Number of individual feature observations taken into account in the optimization
125  size_t num_jacobians; //!< Number of Jacobian blocks which had been to be evaluated for each relinearization step.
126  size_t num_kf2kf_edges_optimized; //!< Number of solved unknowns of type "kf-to-kf edge".
127  size_t num_kf2lm_edges_optimized; //!< Number of solved unknowns of type "kf-to-landmark".
128  size_t num_total_scalar_optimized; //!< The total number of dimensions (scalar values) in all the optimized unknowns.
129  size_t num_span_tree_numeric_updates; //!< Number of poses updated in the spanning tree numeric-update stage.
130  double obs_rmse; //!< RMSE for each observation after optimization
131  double total_sqr_error_init, total_sqr_error_final; //!< Initial and final total squared error for all the observations
132  double HAp_condition_number; //!< To be computed only if enabled in parameters.compute_condition_number
133 
134  std::vector<size_t> optimized_k2k_edge_indices; //!< The 0-based indices of all kf-to-kf edges which were considered in the optimization
135  std::vector<size_t> optimized_landmark_indices; //!< The 0-based indices of all landmarks whose relative positions were considered as unknowns in the optimization
136 
137  /** Other solver-specific output information */
138  typename RBA_OPTIONS::solver_t::extra_results_t extra_results;
139 
140  void clear()
141  {
142  num_observations = 0;
143  num_jacobians = 0;
144  num_kf2kf_edges_optimized = 0;
145  num_kf2lm_edges_optimized = 0;
146  num_total_scalar_optimized = 0;
147  num_span_tree_numeric_updates=0;
148  total_sqr_error_init=0.;
149  total_sqr_error_final=0.;
150  HAp_condition_number=0.;
151  optimized_k2k_edge_indices.clear();
152  optimized_landmark_indices.clear();
153  extra_results.clear();
154  }
155  };
156 
157  /** Information returned by RbaEngine::define_new_keyframe() */
159  {
160  TKeyFrameID kf_id; //!< The ID of the newly created KF.
161  std::vector<TNewEdgeInfo> created_edge_ids; //!< The newly created edges (minimum: 1 edge)
162  TOptimizeExtraOutputInfo optimize_results; //!< Results from the least-squares optimization
163  TOptimizeExtraOutputInfo optimize_results_stg1; //!< Results from the least-squares optimization
164 
165  void clear()
166  {
167  kf_id = static_cast<TKeyFrameID>(-1);
168  created_edge_ids.clear();
169  optimize_results.clear();
170  }
171  };
172 
173  /** @name Main API methods
174  @{ */
175 
176  /** The most common entry point for SRBA: append a new keyframe (KF) to the map, automatically creates the required edges
177  * and optimize the local area around this new KF.
178  *
179  * \param[in] obs All the landmark observations gathered from this new KF (with data association already solved).
180  * \param[out] out_new_kf_info Returned information about the newly created KF.
181  * \param[in] run_local_optimization If set to true (default), the local map around the new KF will be optimized (i.e. optimize_local_area() will be called automatically).
182  */
183  void define_new_keyframe(
184  const typename traits_t::new_kf_observations_t & obs,
185  TNewKeyFrameInfo & out_new_kf_info,
186  const bool run_local_optimization = true
187  );
188 
189  /** Parameters for optimize_local_area() */
191  {
194  TKeyFrameID max_visitable_kf_id; //!< While exploring around the root KF, stop the BFS when KF_ID>=this number (default:infinity)
195  size_t dont_optimize_landmarks_seen_less_than_n_times; //!< Set to 1 to try to optimize all landmarks even if they're just observed once, which may makes sense depending on the sensor type (default: 2)
196 
198  optimize_k2k_edges(true),
199  optimize_landmarks(true),
200  max_visitable_kf_id( static_cast<TKeyFrameID>(-1) ),
201  dont_optimize_landmarks_seen_less_than_n_times( 2 )
202  {}
203  };
204 
205  /** Runs least-squares optimization for all the unknowns within a given topological distance to a given KeyFrame.
206  *
207  * \param[in] observation_indices_to_optimize Indices wrt \a rba_state.all_observations. An empty vector means use ALL the observations involving the selected unknowns.
208  * \note Extra options are available in \a parameters
209  * \sa define_new_keyframe, add_observation, optimize_edges
210  */
211  void optimize_local_area(
212  const TKeyFrameID root_id,
213  const unsigned int win_size,
214  TOptimizeExtraOutputInfo & out_info,
215  const TOptimizeLocalAreaParams &params = TOptimizeLocalAreaParams(),
216  const std::vector<size_t> & observation_indices_to_optimize = std::vector<size_t>()
217  );
218 
219 
220  struct TOpenGLRepresentationOptions : public LM_TYPE::render_mode_t::TOpenGLRepresentationOptionsExtra
221  {
223  span_tree_max_depth(static_cast<size_t>(-1)),
224  draw_unknown_feats(true),
228  {
229  }
230 
231  size_t span_tree_max_depth; //!< Maximum spanning tree depth for reconstructing relative poses (default=-1 : infinity)
232  bool draw_unknown_feats; //!< Draw features with non-fixed rel.pos as well?
236  };
237 
238  /** Build an opengl representation of the current state of this RBA problem
239  * One of different representations can be generated: those opengl objects passed as NULL smart pointers will not be generated.
240  * \param[out] out_scene If not a NULL smart pointer, at return will hold a 3D view of the current KF, neighbor KFs and landmarks.
241  * \param[out] out_root_tree If not a NULL smart pointer, at return will hold a schematic 2D view of the current KF and its spanning tree.
242  */
244  const srba::TKeyFrameID root_keyframe,
245  const TOpenGLRepresentationOptions &options,
246  mrpt::opengl::CSetOfObjectsPtr out_scene,
247  mrpt::opengl::CSetOfObjectsPtr out_root_tree = mrpt::opengl::CSetOfObjectsPtr()
248  ) const;
249 
250  /** Exports all the keyframes (and optionally all landmarks) as a directed graph in DOT (graphviz) format.
251  * \return false on any error writing to target file */
252  bool save_graph_as_dot(
253  const std::string &targetFileName,
254  const bool all_landmarks = false
255  ) const;
256 
257  /** Evaluates the quality of the overall map/landmark estimations, by computing the sum of the squared
258  * error contributions for all observations. For this, this method may have to compute *very long* shortest paths
259  * between distant keyframes if no loop-closure edges exist in order to evaluate the best approximation of relative
260  * coordinates between observing KFs and features' reference KFs.
261  *
262  * The worst-case time consumed by this method is O(M*log(N) + N^2 + N E), N=# of KFs, E=# of edges, M=# of observations.
263  */
264  double eval_overall_squared_error() const;
265 
267  {
268  TKeyFrameID root_kf_id; //!< The KF to use as a root for the spanning tree to init global poses (default=0)
269 
270  ExportGraphSLAM_Params() : root_kf_id(0) {}
271  };
272  /** Build a graph-slam problem suitable for recovering the (consistent) global pose (vs. relative ones as are handled in SRBA) of each keyframe.
273  * \note This version of the method doesn't account for the covariances of relative pose estimations in RBA.
274  * \sa mrpt::graphslam (for methods capable of optimizing the output graph of pose constraints)
275  * \param[out] global_graph Previous contents will be erased. The output global graph will be returned here, initialized with poses from a Dijkstra/Spanning-tree from the first KF.
276  * \tparam POSE_GRAPH Must be an instance of mrpt::graphs::CNetworkOfPoses<>, e.g. CNetworkOfPoses2D (for 2D poses) or CNetworkOfPoses3D (for 3D).
277  * \note This method is NOT O(1)
278  */
279  template <class POSE_GRAPH>
280  void get_global_graphslam_problem(POSE_GRAPH &global_graph, const ExportGraphSLAM_Params &params = ExportGraphSLAM_Params() ) const;
281 
282 
283  /** @} */ // End of main API methods
284 
285 
286  /** @name Extra API methods (for debugging, etc.)
287  @{ */
288 
289  /** Reset the entire problem to an empty state (automatically called at construction) */
290  void clear();
291 
292  /** Users normally won't need to call this directly. Use define_new_keyframe() instead.
293  * This method appends an empty new keyframe to the data structures
294  * \return The ID of the new KF.
295  * \note Runs in O(1)
296  */
298 
299  /** Users normally won't need to call this directly. Use define_new_keyframe() instead.
300  * This method calls:
301  * 1) alloc_kf2kf_edge() for creating the data structures
302  * 2) spanning_tree.update_symbolic_new_node() for updating the spanning trees.
303  *
304  * \note obs is passed just for fixing missing spanning trees when using the policy of pure linear graph.
305  */
306  size_t create_kf2kf_edge(
307  const TKeyFrameID new_kf_id,
308  const TPairKeyFrameID & new_edge,
309  const typename traits_t::new_kf_observations_t & obs,
310  const pose_t &init_inv_pose_val = pose_t() );
311 
312 
313  /** Creates a numeric spanning tree between a given root keyframe and the entire graph, returning it into a user-supplied data structure
314  * Note that this method does NOT use the depth-limited spanning trees which are built incrementally with the graph. So, it takes an extra cost to
315  * call this method. For the other trees, see get_rba_state()
316  * \param[in] root_id The root keyframe
317  * \param[out] span_tree The output with all found relative poses. Its previous contents are cleared.
318  * \param[in] max_depth Defaults to std::numeric_limits<size_t>::max() for infinity depth, can be set to a maximum desired depth from the root.
319  * \param[in] aux_ws Auxiliary working space: Set to an uninitialized vector<bool> (it'll automatically initialized) if you want to call this method simultaneously from several threads. Otherwise, setting to NULL will automatically use one working space, reusable between succesive calls.
320  * \sa find_path_bfs
321  */
323  const TKeyFrameID root_id,
324  frameid2pose_map_t & span_tree,
325  const size_t max_depth = std::numeric_limits<size_t>::max(),
326  std::vector<bool> * aux_ws = NULL
327  ) const;
328 
329  /** An unconstrained breadth-first search (BFS) for the shortest path between two keyframes.
330  * Note that this method does NOT use the depth-limited spanning trees which are built incrementally with the graph. So, it takes the extra cost of
331  * really running a BFS algorithm. For the other precomputed trees, see get_rba_state()
332  * Edge direction is ignored during the search, i.e. as if we had an undirected graph of Keyframes.
333  * If both source and target KF coincide, an empty path is returned.
334  * \return true if a path was found.
335  * \note Worst-case computational complexity is that of a BFS over the entire graph: O(V+E), V=number of nodes, E=number of edges.
336  * \sa create_complete_spanning_tree
337  */
339  const TKeyFrameID src_kf,
340  const TKeyFrameID trg_kf,
341  std::vector<TKeyFrameID> & found_path) const
342  {
343  return rba_state.find_path_bfs(src_kf,trg_kf,&found_path);
344  }
345 
346  /** Visits all k2k & k2f edges following a BFS starting at a given starting node and up to a given maximum depth.
347  * Only k2k edges are considered for BFS paths.
348  */
349  template <
350  class KF_VISITOR,
351  class FEAT_VISITOR,
352  class K2K_EDGE_VISITOR,
353  class K2F_EDGE_VISITOR
354  >
355  void bfs_visitor(
356  const TKeyFrameID root_id,
357  const topo_dist_t max_distance,
358  const bool rely_on_prebuilt_spanning_trees,
359  KF_VISITOR & kf_visitor,
360  FEAT_VISITOR & feat_visitor,
361  K2K_EDGE_VISITOR & k2k_edge_visitor,
362  K2F_EDGE_VISITOR & k2f_edge_visitor ) const;
363 
364  /** @} */ // End of Extra API methods
365 
366 
367  /** @name Public data fields
368  @{ */
369 
370  /** Different parameters for the SRBA methods */
372  {
373  TSRBAParameters();
374 
375  /** See docs of mrpt::utils::CLoadableOptions */
376  virtual void loadFromConfigFile(const mrpt::utils::CConfigFileBase & source,const std::string & section);
377  /** See docs of mrpt::utils::CLoadableOptions */
378  virtual void saveToConfigFile(mrpt::utils::CConfigFileBase &out,const std::string & section) const;
379 
380 
381  /** Parameters for determine_kf2kf_edges_to_create(); custom user-defined policies can be also defined (see tutorials) */
383 
384  /** Maximum depth for maintained spanning trees. */
386 
387  /** The maximum topological distance of keyframes to be optimized around the most recent keyframe. */
389 
390  size_t submap_size;
391  size_t min_obs_to_loop_closure; //!< Default:6, reduce to 1 for relative graph-slam
392  // -------------------------------------------------------
393 
394  // Parameters for optimize_*()
395  // -------------------------------------
396  bool optimize_new_edges_alone; //!< (Default:true) Before running a whole "local area" optimization, try to optimize new edges one by one to have a better starting point.
399  double kernel_param;
400  size_t max_iters;
401  double max_error_per_obs_to_stop; //!< default: 1e-9
402  double max_rho; //!< default: 1.0
403  double max_lambda; //!< default: 1e20
405  bool numeric_jacobians; //!< (Default:false) Use a numeric approximation of the Jacobians (very slow!) instead of analytical ones.
406  void (*feedback_user_iteration)(unsigned int iter, const double total_sq_err, const double mean_sqroot_error);
407  bool compute_condition_number; //!< Compute and return to the user the Hessian condition number of k2k edges (default=false)
408 
409  TCovarianceRecoveryPolicy cov_recovery; //!< Recover covariance? What method to use? (Default: crpLandmarksApprox)
410  // -------------------------------------
411 
412  };
413 
414  /** The unique struct which hold all the parameters from the different SRBA modules (sensors, optional features, optimizers,...) */
416  {
417  /** Different parameters for the SRBA methods \sa sensor_params */
419 
420  /** Sensor-specific parameters (sensor calibration, etc.) \sa parameters */
421  typename OBS_TYPE::TObservationParams sensor;
422 
423  /** Parameters related to the relative pose of sensors wrt the robot (if applicable) */
424  typename RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t sensor_pose;
425 
426  /** Parameters related to the sensor noise covariance matrix */
427  typename RBA_OPTIONS::obs_noise_matrix_t::parameters_t obs_noise;
428  };
429 
431 
432  /** @} */ // End of data fields
433 
434 
435  /** Enable or disables time profiling of all operations (default=enabled), which will be reported upon destruction */
436  void inline enable_time_profiler(bool enable=true) { m_profiler.enable(enable); }
437 
438  const k2k_edges_deque_t & get_k2k_edges() const { return rba_state.k2k_edges; }
439 
440  const TRelativeLandmarkPosMap & get_known_feats() const { return rba_state.known_lms; }
441  const TRelativeLandmarkPosMap & get_unknown_feats() const { return rba_state.unknown_lms; }
442 
443  const rba_problem_state_t & get_rba_state() const { return rba_state; }
444  rba_problem_state_t & get_rba_state() { return rba_state; }
445 
446  /** Access to the time profiler */
448 
449  /** Changes the verbosity level: 0=None (only critical msgs), 1=verbose, 2=so verbose you'll have to say "Stop!" */
450  inline void setVerbosityLevel(int level) { m_verbose_level = level; }
451 
452  /** Rebuild the Hessian symbolic information from the given Jacobians.
453  * \param[out] H Output hessian (must be empty at input)
454  */
455  template <class HESS_Ap, class HESS_f,class HESS_Apf, class JACOB_COLUMN_dh_dAp,class JACOB_COLUMN_dh_df>
456  static void sparse_hessian_build_symbolic(
457  HESS_Ap & HAp,
458  HESS_f & Hf,
459  HESS_Apf & HApf,
460  const std::vector<JACOB_COLUMN_dh_dAp*> & dh_dAp,
461  const std::vector<JACOB_COLUMN_dh_df*> & dh_df);
462 
463  /** Rebuild the Hessian symbolic information from the internal pointers to blocks of Jacobians.
464  * Only the upper triangle is filled-in (all what is needed for Cholesky) for square Hessians, in whole for rectangular ones (it depends on the symbolic decomposition, done elsewhere).
465  * \tparam SPARSEBLOCKHESSIAN can be: TSparseBlocksHessian_6x6, TSparseBlocksHessian_3x3 or TSparseBlocksHessian_6x3
466  * \return The number of Jacobian multiplications skipped due to its observation being marked as "invalid"
467  */
468  template <class SPARSEBLOCKHESSIAN>
469  size_t sparse_hessian_update_numeric( SPARSEBLOCKHESSIAN & H ) const;
470 
471 
472  protected:
473  int m_verbose_level; //!< 0: None (only critical msgs), 1: verbose, 2:even more verbose, 3: even more
474 
475  typedef std::multimap<size_t,TKeyFrameID,std::greater<size_t> > base_sorted_lst_t;
476 
477  /** @name (Protected) Sub-algorithms
478  @{ */
479 
480  /** Make a list of base KFs of my new observations, ordered in descending order by # of shared observations: */
482  const typename traits_t::new_kf_observations_t & obs,
483  base_sorted_lst_t & obs_for_each_base_sorted,
484  std::map<TKeyFrameID,size_t> *out_obs_for_each_base =NULL ) const;
485 
486  /** This method will call edge_creation_policy(), which has predefined algorithms but could be re-defined by the user in a derived class */
488  const TKeyFrameID new_kf_id,
489  const typename traits_t::new_kf_observations_t & obs,
490  std::vector<TNewEdgeInfo> &new_k2k_edge_ids );
491 
492  /** Implements the edge-creation policy, by default depending on "parameters.edge_creation_policy" if the user doesn't re-implement this virtual method.
493  * See tutorials for examples of how to implement custom policies. */
494  virtual void edge_creation_policy(
495  const TKeyFrameID new_kf_id,
496  const typename traits_t::new_kf_observations_t & obs,
497  std::vector<TNewEdgeInfo> &new_k2k_edge_ids );
498 
499  /**
500  * \param observation_indices_to_optimize Indices wrt \a rba_state.all_observations. An empty vector means use ALL the observations involving the selected unknowns.
501  * \sa optimize_local_area
502  */
503  void optimize_edges(
504  const std::vector<size_t> & run_k2k_edges,
505  const std::vector<size_t> & run_feat_ids_in,
506  TOptimizeExtraOutputInfo & out_info,
507  const std::vector<size_t> & observation_indices_to_optimize = std::vector<size_t>()
508  );
509 
510  /** @} */
511 
512  /** Aux visitor struct, used in optimize_local_area() */
514  {
515  VisitorOptimizeLocalArea(const rba_problem_state_t & rba_state_, const TOptimizeLocalAreaParams &params_) :
516  rba_state(rba_state_),
517  params(params_)
518  { }
519 
520  const rba_problem_state_t & rba_state;
522 
524  std::map<TLandmarkID,size_t> lm_times_seen;
525 
526  /* Implementation of FEAT_VISITOR */
527  inline bool visit_filter_feat(const TLandmarkID lm_ID,const topo_dist_t cur_dist)
528  {
529  MRPT_UNUSED_PARAM(lm_ID); MRPT_UNUSED_PARAM(cur_dist);
530  return false; // Don't need to visit landmark nodes.
531  }
532 
533  inline void visit_feat(const TLandmarkID lm_ID,const topo_dist_t cur_dist)
534  {
535  MRPT_UNUSED_PARAM(lm_ID); MRPT_UNUSED_PARAM(cur_dist);
536  // Nothing to do
537  }
538 
539  /* Implementation of KF_VISITOR */
540  inline bool visit_filter_kf(const TKeyFrameID kf_ID,const topo_dist_t cur_dist)
541  {
542  MRPT_UNUSED_PARAM(cur_dist);
543  return (kf_ID<=params.max_visitable_kf_id);
544  }
545 
546  inline void visit_kf(const TKeyFrameID kf_ID,const topo_dist_t cur_dist)
547  {
548  MRPT_UNUSED_PARAM(kf_ID); MRPT_UNUSED_PARAM(cur_dist);
549  // Nothing to do.
550  }
551 
552  /* Implementation of K2K_EDGE_VISITOR */
553  inline bool visit_filter_k2k(const TKeyFrameID current_kf, const TKeyFrameID next_kf,
554  const k2k_edge_t* edge, const topo_dist_t cur_dist)
555  {
556  MRPT_UNUSED_PARAM(current_kf); MRPT_UNUSED_PARAM(next_kf);
557  MRPT_UNUSED_PARAM(edge); MRPT_UNUSED_PARAM(cur_dist);
558  return true; // Visit all k2k edges
559  }
560 
561  inline void visit_k2k(const TKeyFrameID current_kf, const TKeyFrameID next_kf,
562  const k2k_edge_t* edge, const topo_dist_t cur_dist)
563  {
564  MRPT_UNUSED_PARAM(current_kf); MRPT_UNUSED_PARAM(next_kf);
565  MRPT_UNUSED_PARAM(cur_dist);
566  if (params.optimize_k2k_edges)
567  k2k_edges_to_optimize.push_back(edge->id);
568  }
569 
570  /* Implementation of K2F_EDGE_VISITOR */
571  inline bool visit_filter_k2f(const TKeyFrameID current_kf, const k2f_edge_t* edge,
572  const topo_dist_t cur_dist)
573  {
574  MRPT_UNUSED_PARAM(current_kf); MRPT_UNUSED_PARAM(edge); MRPT_UNUSED_PARAM(cur_dist);
575  return params.optimize_landmarks; // Yes: visit all feature nodes if we're asked to
576  }
577  inline void visit_k2f(const TKeyFrameID current_kf, const k2f_edge_t* edge, const topo_dist_t cur_dist)
578  {
579  MRPT_UNUSED_PARAM(current_kf); MRPT_UNUSED_PARAM(cur_dist);
580  if (!edge->feat_has_known_rel_pos)
581  {
582  const TLandmarkID lm_ID = edge->obs.obs.feat_id;
583  // Use an "==" so we only add the LM_ID to the list ONCE, just when it passes the threshold
584  if (++lm_times_seen[lm_ID] == params.dont_optimize_landmarks_seen_less_than_n_times)
585  lm_IDs_to_optimize.push_back(lm_ID);
586  }
587  }
588  };
589 
590  private:
591  rba_problem_state_t rba_state; //!< All the beef is here.
592 
593  mutable std::vector<bool> m_complete_st_ws; //!< Temporary working space used in \a create_complete_spanning_tree()
594 
595  /** Profiler for all SRBA operations
596  * Enabled by default, can be disabled with \a enable_time_profiler(false)
597  */
599 
600  /** Creates a new known/unknown position landmark (upon first LM observation ), and expands Jacobians with new observation
601  * \param[in] new_obs The basic data on the observed landmark: landmark ID, keyframe from which it's observed and parameters ("z" vector) of the observation itself (e.g. pixel coordinates).
602  * \param[in] fixed_relative_position If not NULL, this is the first observation of a landmark with a fixed, known position. Each such feature can be created only once, next observations MUST have this field set to NULL as with normal ("unfixed") landmarks.
603  * \param[in] unknown_relative_position_init_val Can be set to not-NULL only upon the first observation of a landmark with an unknown relative position. The feature will be created with this initial value for its relative position wrt the KF (further optimization will refine that value).
604  *
605  * \return The 0-based index of the new observation
606  *
607  * \note Both \a fixed_relative_position and \a unknown_relative_position_init_val CAN'T be set to !=NULL at once.
608  *
609  * \note If new edges had been introduced before this observation, make sure the symbolic spanning trees are up-to-date!
610  *
611  * \note Runs in O(P+log C), with:
612  * - C=typical amount of KFs which all see the same landmark,
613  * - P=typical number of kf2kf edges between observing and the base KF of the observed landmark.
614  */
615  size_t add_observation(
616  const TKeyFrameID observing_kf_id,
617  const typename observation_traits_t::observation_t & new_obs,
618  const array_landmark_t * fixed_relative_position = NULL,
619  const array_landmark_t * unknown_relative_position_init_val = NULL
620  );
621 
622  /** Prepare the list of all required KF roots whose spanning trees need numeric updates with each optimization iteration */
624  std::set<TKeyFrameID> & kfs_num_spantrees_to_update,
625  const std::vector<typename TSparseBlocksJacobians_dh_dAp::col_t*> &lst_JacobCols_dAp,
626  const std::vector<typename TSparseBlocksJacobians_dh_df::col_t*> &lst_JacobCols_df );
627 
628 
629  /** Re-evaluate all Jacobians numerically using their symbolic info. Return overall number of block Jacobians */
631  std::vector<typename TSparseBlocksJacobians_dh_dAp::col_t*> &lst_JacobCols_dAp,
632  std::vector<typename TSparseBlocksJacobians_dh_df::col_t*> &lst_JacobCols_df,
633  std::vector<const pose_flag_t*> * out_list_of_required_num_poses = NULL );
634 
635  public:
636 
637  /** Private aux structure for BFS searches. */
639  {
640  TBFSEntryEdges() : dist( std::numeric_limits<topo_dist_t>::max() ), edge(NULL)
641  {}
642 
645  const k2k_edge_t* edge;
646  };
647 
648 
649  /** ====================================================================
650  j,i lm_id,base_id
651  \partial h \partial h
652  l obs_frame_id
653  dh_dp = ------------------ = ---------------------------------
654  d+1 cur_id
655  \partial p \partial p
656  d stp.next_node
657 
658  See tech report:
659  "A tutorial on SE(3) transformation parameterizations and
660  on-manifold optimization", Jose-Luis Blanco, 2010.
661  ==================================================================== */
663  typename TSparseBlocksJacobians_dh_dAp::TEntry &jacob,
664  const k2f_edge_t & observation,
665  const k2k_edges_deque_t &k2k_edges,
666  std::vector<const pose_flag_t*> *out_list_of_required_num_poses) const;
667 
668  /** ====================================================================
669  j,i lm_id,base_id
670  \partial h \partial h
671  l obs_frame_id
672  dh_df = ------------------ = ---------------------------------
673 
674  \partial f \partial f
675 
676  Note: f=relative position of landmark with respect to its base kf
677  ==================================================================== */
679  typename TSparseBlocksJacobians_dh_df::TEntry &jacob,
680  const k2f_edge_t & observation,
681  std::vector<const pose_flag_t*> *out_list_of_required_num_poses) const;
682 
683  void gl_aux_draw_node(mrpt::opengl::CSetOfObjects &soo, const std::string &label, const float x, const float y) const;
684 
685  const pose_t aux_null_pose; //!< A fixed SE(3) pose at the origin (used when we need a pointer or a reference to a "null transformation").
686 
688  {
690  const size_t _k2k_edge_id,
691  const pose_t * _pose_d1_wrt_obs,
692  const pose_t & _pose_base_wrt_d1,
693  const array_landmark_t & _xji_i,
694  const bool _is_inverse_dir,
695  const k2k_edges_deque_t &_k2k_edges,
696  const typename OBS_TYPE::TObservationParams & _sensor_params,
697  const typename RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t & _sensor_pose
698  ) :
699  k2k_edge_id(_k2k_edge_id),
700  pose_d1_wrt_obs(_pose_d1_wrt_obs),
701  pose_base_wrt_d1(_pose_base_wrt_d1),
702  xji_i(_xji_i),
703  is_inverse_dir(_is_inverse_dir),
704  k2k_edges(_k2k_edges),
705  sensor_params(_sensor_params),
706  sensor_pose(_sensor_pose)
707  {
708  }
709 
710  const size_t k2k_edge_id;
711  const pose_t * pose_d1_wrt_obs;
712  const pose_t & pose_base_wrt_d1;
713  const array_landmark_t & xji_i;
714  const bool is_inverse_dir;
715  const k2k_edges_deque_t &k2k_edges;
716  const typename OBS_TYPE::TObservationParams & sensor_params;
717  const typename RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t & sensor_pose;
718  };
719 
721  {
723  const pose_t * _pose_base_wrt_obs,
724  const array_landmark_t & _xji_i,
725  const typename OBS_TYPE::TObservationParams & _sensor_params,
726  const typename RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t & _sensor_pose
727  ) :
728  pose_base_wrt_obs(_pose_base_wrt_obs),
729  xji_i(_xji_i),
730  sensor_params(_sensor_params),
731  sensor_pose(_sensor_pose)
732  {
733  }
734 
735  const pose_t * pose_base_wrt_obs;
736  const array_landmark_t & xji_i;
737  const typename OBS_TYPE::TObservationParams & sensor_params;
738  const typename RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t & sensor_pose;
739  };
740 
741  /** Auxiliary method for numeric Jacobian: numerically evaluates the new observation "y" for a small increment "x" in a relative KF-to-KF pose */
742  static void numeric_dh_dAp(const array_pose_t &x, const TNumeric_dh_dAp_params& params, array_obs_t &y);
743  /** Auxiliary method for numeric Jacobian: numerically evaluates the new observation "y" for a small increment "x" in a landmark position */
744  static void numeric_dh_df(const array_landmark_t &x, const TNumeric_dh_df_params& params, array_obs_t &y);
745 
746  static inline void add_edge_ij_to_list_needed_roots(std::set<TKeyFrameID> & lst, const TKeyFrameID i, const TKeyFrameID j)
747  {
748  lst.insert(i);
749  lst.insert(j);
750  }
751 
753  Eigen::VectorXd & minus_grad,
754  const std::vector<typename TSparseBlocksJacobians_dh_dAp::col_t*> & sparse_jacobs_Ap,
755  const std::vector<typename TSparseBlocksJacobians_dh_df::col_t*> & sparse_jacobs_f,
756  const vector_residuals_t & residuals,
757  const std::map<size_t,size_t> &obs_global_idx2residual_idx
758  ) const;
759 
760  /** Each of the observations used during the optimization */
761  struct TObsUsed
762  {
763  TObsUsed(const size_t obs_idx_, k2f_edge_t * const k2f_) : obs_idx(obs_idx_),k2f(k2f_)
764  { }
765 
766  size_t obs_idx; //!< Global index in all_observations
767  k2f_edge_t* k2f; //!< Obs data
768 
769  private:
770  // Don't use this constructor
771  TObsUsed() : obs_idx(0), k2f(NULL) {}
772  }; // end of TObsUsed
773 
774 
775  inline double reprojection_residuals(
776  vector_residuals_t & residuals, // Out:
777  const std::vector<TObsUsed> & observations // In:
778  ) const;
779 
780  /** pseudo-huber cost function */
781  static inline double huber_kernel(double delta, const double kernel_param)
782  {
783  return std::abs(2*mrpt::utils::square(kernel_param)*(std::sqrt(1+mrpt::utils::square(delta/kernel_param))-1));
784  }
785 
786  }; // end of class "RbaEngine"
787 
788 
789 } // end of namespace "srba"
790 } // end of namespace "mrpt"
791 
792 // -----------------------------------------------------------------
793 // Include all template implementation files
794 // -----------------------------------------------------------------
795 #include "impl/add-observations.h"
796 #include "impl/alloc_keyframe.h"
797 #include "impl/alloc_kf2kf_edge.h"
798 #include "impl/create_kf2kf_edge.h"
800 #include "impl/jacobians.h"
801 #include "impl/rba_problem_common.h"
802 #include "impl/schur.h"
805 
809 #include "impl/spantree_misc.h"
810 
811 #include "impl/jacobians.h"
812 
813 #include "impl/export_opengl.h"
814 #include "impl/export_dot.h"
816 
817 #include "impl/eval_overall_error.h"
818 
821 
824 #include "impl/optimize_edges.h"
825 #include "impl/lev-marq_solvers.h"
826 
827 #include "impl/bfs_visitor.h"
829 // -----------------------------------------------------------------
830 // ^^ End of implementation files ^^
831 // -----------------------------------------------------------------
832 
833 // Undefine temporary macro for verbose output
834 #undef VERBOSE_LEVEL
835 
RBA_OPTIONS::obs_noise_matrix_t::parameters_t obs_noise
Parameters related to the sensor noise covariance matrix.
Definition: RbaEngine.h:427
size_t num_observations
Number of individual feature observations taken into account in the optimization. ...
Definition: RbaEngine.h:124
The main class for the mrpt-srba: it defines a Relative Bundle-Adjustment (RBA) problem with (optiona...
Definition: RbaEngine.h:60
static const size_t REL_POSE_DIMS
Definition: RbaEngine.h:72
size_t sparse_hessian_update_numeric(SPARSEBLOCKHESSIAN &H) const
Rebuild the Hessian symbolic information from the internal pointers to blocks of Jacobians.
TAllParameters parameters
Definition: RbaEngine.h:430
bool optimize_new_edges_alone
(Default:true) Before running a whole "local area" optimization, try to optimize new edges one by one...
Definition: RbaEngine.h:396
void compute_jacobian_dh_dp(typename TSparseBlocksJacobians_dh_dAp::TEntry &jacob, const k2f_edge_t &observation, const k2k_edges_deque_t &k2k_edges, std::vector< const pose_flag_t * > *out_list_of_required_num_poses) const
==================================================================== j,i lm_id,base_id h h l obs_fr...
A STL-like container which looks and behaves (almost exactly) like a std::map<> but is implemented as...
Definition: map_as_vector.h:46
obs_traits_t::observation_t obs
Observation data.
Definition: srba_types.h:433
const rba_problem_state_t & rba_state
Definition: RbaEngine.h:520
RBA_OPTIONS rba_options_type
Definition: RbaEngine.h:70
KF2KF_POSE_TYPE kf2kf_pose_type
Definition: RbaEngine.h:67
virtual void edge_creation_policy(const TKeyFrameID new_kf_id, const typename traits_t::new_kf_observations_t &obs, std::vector< TNewEdgeInfo > &new_k2k_edge_ids)
Implements the edge-creation policy, by default depending on "parameters.edge_creation_policy" if the...
jacobian_traits< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE > jacobian_traits_t
Definition: RbaEngine.h:79
TObsUsed(const size_t obs_idx_, k2f_edge_t *const k2f_)
Definition: RbaEngine.h:763
TKeyFrameID max_visitable_kf_id
While exploring around the root KF, stop the BFS when KF_ID>=this number (default:infinity) ...
Definition: RbaEngine.h:194
observation_traits_t::vector_residuals_t vector_residuals_t
Definition: RbaEngine.h:107
const rba_problem_state_t & get_rba_state() const
Definition: RbaEngine.h:443
size_t num_span_tree_numeric_updates
Number of poses updated in the spanning tree numeric-update stage.
Definition: RbaEngine.h:129
double obs_rmse
RMSE for each observation after optimization.
Definition: RbaEngine.h:130
A set of object, which are referenced to the coordinates framework established in this object...
Definition: CSetOfObjects.h:32
options::solver_LM_schur_dense_cholesky solver_t
Solver algorithm (Default: Lev-Marq, with Schur, with dense Cholesky)
Definition: RbaEngine.h:37
double max_error_per_obs_to_stop
default: 1e-9
Definition: RbaEngine.h:401
T square(const T x)
Inline function for the square of a number.
TKeyFrameID kf_id
The ID of the newly created KF.
Definition: RbaEngine.h:160
TNumeric_dh_df_params(const pose_t *_pose_base_wrt_obs, const array_landmark_t &_xji_i, const typename OBS_TYPE::TObservationParams &_sensor_params, const typename RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t &_sensor_pose)
Definition: RbaEngine.h:722
bool compute_condition_number
Compute and return to the user the Hessian condition number of k2k edges (default=false) ...
Definition: RbaEngine.h:407
bool visit_filter_k2k(const TKeyFrameID current_kf, const TKeyFrameID next_kf, const k2k_edge_t *edge, const topo_dist_t cur_dist)
Definition: RbaEngine.h:553
uint64_t TLandmarkID
Numeric IDs for landmarks.
Definition: srba_types.h:32
const RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t & sensor_pose
Definition: RbaEngine.h:717
topo_dist_t max_tree_depth
Maximum depth for maintained spanning trees.
Definition: RbaEngine.h:385
TEdgeCreationPolicy
For usage in RbaEngine.parameters.
Definition: srba_types.h:164
hessian_traits< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE > hessian_traits_t
Definition: RbaEngine.h:80
RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t sensor_pose
Parameters related to the relative pose of sensors wrt the robot (if applicable)
Definition: RbaEngine.h:424
double total_sqr_error_final
Initial and final total squared error for all the observations.
Definition: RbaEngine.h:131
Different parameters for the SRBA methods.
Definition: RbaEngine.h:371
Usage: A possible type for RBA_OPTIONS::solver_t.
rba_problem_state_t::k2k_edges_deque_t k2k_edges_deque_t
A list (deque) of KF-to-KF edges (unknown relative poses).
Definition: RbaEngine.h:92
mrpt::utils::CTimeLogger m_profiler
Profiler for all SRBA operations Enabled by default, can be disabled with enable_time_profiler(false)...
Definition: RbaEngine.h:598
size_t obs_idx
Global index in all_observations.
Definition: RbaEngine.h:766
double reprojection_residuals(vector_residuals_t &residuals, const std::vector< TObsUsed > &observations) const
reprojection_residuals
const k2k_edges_deque_t & get_k2k_edges() const
Definition: RbaEngine.h:438
TOptimizeExtraOutputInfo optimize_results_stg1
Results from the least-squares optimization.
Definition: RbaEngine.h:163
size_t recompute_all_Jacobians(std::vector< typename TSparseBlocksJacobians_dh_dAp::col_t * > &lst_JacobCols_dAp, std::vector< typename TSparseBlocksJacobians_dh_df::col_t * > &lst_JacobCols_df, std::vector< const pose_flag_t * > *out_list_of_required_num_poses=NULL)
Re-evaluate all Jacobians numerically using their symbolic info.
size_t id
0-based index of this edge, in the std::list "k2k_edges".
Definition: srba_types.h:88
STL namespace.
TSRBAParameters srba
Different parameters for the SRBA methods.
Definition: RbaEngine.h:418
observation_traits< OBS_TYPE > observation_traits_t
Definition: RbaEngine.h:83
Each of the observations used during the optimization.
Definition: RbaEngine.h:761
std::vector< size_t > optimized_k2k_edge_indices
The 0-based indices of all kf-to-kf edges which were considered in the optimization.
Definition: RbaEngine.h:134
kf2kf_pose_traits_t::pose_flag_t pose_flag_t
Definition: RbaEngine.h:94
KF2KF_POSE_TYPE::pose_t pose_t
The type of relative poses (e.g. mrpt::poses::CPose3D)
Definition: RbaEngine.h:87
Keyframe-to-keyframe edge: an unknown of the problem.
Definition: srba_types.h:82
TCovarianceRecoveryPolicy cov_recovery
Recover covariance? What method to use? (Default: crpLandmarksApprox)
Definition: RbaEngine.h:409
double min_error_reduction_ratio_to_relinearize
default 0.01
Definition: RbaEngine.h:404
double HAp_condition_number
To be computed only if enabled in parameters.compute_condition_number.
Definition: RbaEngine.h:132
uint64_t topo_dist_t
Unsigned integral type for topological distances in a graph/tree.
Definition: srba_types.h:33
std::map< TLandmarkID, size_t > lm_times_seen
Definition: RbaEngine.h:524
std::deque< new_kf_observation_t > new_kf_observations_t
A set of all the observations made from a new KF, as provided by the user.
Definition: srba_types.h:422
Usage: A possible type for RBA_OPTIONS::obs_noise_matrix_t.
TKeyFrameID alloc_keyframe()
Users normally won't need to call this directly.
bool visit_filter_k2f(const TKeyFrameID current_kf, const k2f_edge_t *edge, const topo_dist_t cur_dist)
Definition: RbaEngine.h:571
kf2kf_pose_traits_t::TRelativePosesForEachTarget TRelativePosesForEachTarget
Definition: RbaEngine.h:96
static void numeric_dh_df(const array_landmark_t &x, const TNumeric_dh_df_params &params, array_obs_t &y)
Auxiliary method for numeric Jacobian: numerically evaluates the new observation "y" for a small incr...
TNumeric_dh_dAp_params(const size_t _k2k_edge_id, const pose_t *_pose_d1_wrt_obs, const pose_t &_pose_base_wrt_d1, const array_landmark_t &_xji_i, const bool _is_inverse_dir, const k2k_edges_deque_t &_k2k_edges, const typename OBS_TYPE::TObservationParams &_sensor_params, const typename RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t &_sensor_pose)
Definition: RbaEngine.h:689
void enable(bool enabled=true)
Definition: CTimeLogger.h:71
This class allows loading and storing values and vectors of different types from a configuration text...
static const size_t LM_DIMS
Definition: RbaEngine.h:73
kf2kf_pose_traits_t::array_pose_t array_pose_t
Definition: RbaEngine.h:103
static void sparse_hessian_build_symbolic(HESS_Ap &HAp, HESS_f &Hf, HESS_Apf &HApf, const std::vector< JACOB_COLUMN_dh_dAp * > &dh_dAp, const std::vector< JACOB_COLUMN_dh_df * > &dh_df)
Rebuild the Hessian symbolic information from the given Jacobians.
void define_new_keyframe(const typename traits_t::new_kf_observations_t &obs, TNewKeyFrameInfo &out_new_kf_info, const bool run_local_optimization=true)
The most common entry point for SRBA: append a new keyframe (KF) to the map, automatically creates th...
const OBS_TYPE::TObservationParams & sensor_params
Definition: RbaEngine.h:737
observation_traits_t::residual_t residual_t
Definition: RbaEngine.h:106
size_t num_jacobians
Number of Jacobian blocks which had been to be evaluated for each relinearization step...
Definition: RbaEngine.h:125
traits_t::keyframe_info keyframe_info
Definition: RbaEngine.h:99
TCovarianceRecoveryPolicy
Covariances recovery from Hessian matrix policy, for usage in RbaEngine.parameters.
Definition: srba_types.h:176
void optimize_local_area(const TKeyFrameID root_id, const unsigned int win_size, TOptimizeExtraOutputInfo &out_info, const TOptimizeLocalAreaParams &params=TOptimizeLocalAreaParams(), const std::vector< size_t > &observation_indices_to_optimize=std::vector< size_t >())
Runs least-squares optimization for all the unknowns within a given topological distance to a given K...
TKeyFrameID prev
Definition: RbaEngine.h:643
Generic declaration, of which specializations are defined for each combination of LM+OBS type...
Definition: srba_types.h:44
void compute_minus_gradient(Eigen::VectorXd &minus_grad, const std::vector< typename TSparseBlocksJacobians_dh_dAp::col_t * > &sparse_jacobs_Ap, const std::vector< typename TSparseBlocksJacobians_dh_df::col_t * > &sparse_jacobs_f, const vector_residuals_t &residuals, const std::map< size_t, size_t > &obs_global_idx2residual_idx) const
Useful data structures that depend of a combination of "OBSERVATION_TYPE"+"LANDMARK_PARAMETERIZATION_...
Definition: srba_types.h:362
rba_joint_parameterization_traits_t< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE > traits_t
Definition: RbaEngine.h:78
Parameters for optimize_local_area()
Definition: RbaEngine.h:190
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
size_t num_total_scalar_optimized
The total number of dimensions (scalar values) in all the optimized unknowns.
Definition: RbaEngine.h:128
KF2KF_POSE_TYPE::se_traits_t se_traits_t
The SE(2) or SE(3) traits struct (for Lie algebra log/exp maps, etc.)
Definition: RbaEngine.h:76
std::map< TLandmarkID, TRelativeLandmarkPos > TRelativeLandmarkPosMap
An index of feature IDs and their relative locations.
Definition: srba_types.h:124
Private aux structure for BFS searches.
Definition: RbaEngine.h:638
rba_problem_state_t & get_rba_state()
Definition: RbaEngine.h:444
landmark_traits_t::array_landmark_t array_landmark_t
Definition: RbaEngine.h:104
k2k_edges_deque_t k2k_edges
(unknowns) All keyframe-to-keyframe edges
Definition: srba_types.h:636
void get_global_graphslam_problem(POSE_GRAPH &global_graph, const ExportGraphSLAM_Params &params=ExportGraphSLAM_Params()) const
Build a graph-slam problem suitable for recovering the (consistent) global pose (vs.
TOptimizeExtraOutputInfo optimize_results
Results from the least-squares optimization.
Definition: RbaEngine.h:162
void(* feedback_user_iteration)(unsigned int iter, const double total_sq_err, const double mean_sqroot_error)
Definition: RbaEngine.h:406
const TRelativeLandmarkPosMap & get_known_feats() const
Definition: RbaEngine.h:440
static const size_t OBS_DIMS
Definition: RbaEngine.h:74
TRBA_Problem_state< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE, RBA_OPTIONS > rba_problem_state_t
Definition: RbaEngine.h:88
topo_dist_t dist
Definition: RbaEngine.h:644
void enable_time_profiler(bool enable=true)
Enable or disables time profiling of all operations (default=enabled), which will be reported upon de...
Definition: RbaEngine.h:436
const k2k_edge_t * edge
Definition: RbaEngine.h:645
RBA_OPTIONS::solver_t::extra_results_t extra_results
Other solver-specific output information.
Definition: RbaEngine.h:138
RbaEngine()
Default constructor.
void visit_k2f(const TKeyFrameID current_kf, const k2f_edge_t *edge, const topo_dist_t cur_dist)
Definition: RbaEngine.h:577
landmark_traits_t::TRelativeLandmarkPos TRelativeLandmarkPos
One landmark position (relative to its base KF)
Definition: RbaEngine.h:98
T abs(T x)
Definition: nanoflann.hpp:237
std::vector< size_t > optimized_landmark_indices
The 0-based indices of all landmarks whose relative positions were considered as unknowns in the opti...
Definition: RbaEngine.h:135
bool save_graph_as_dot(const std::string &targetFileName, const bool all_landmarks=false) const
Exports all the keyframes (and optionally all landmarks) as a directed graph in DOT (graphviz) format...
Definition: export_dot.h:16
TKeyFrameID root_kf_id
The KF to use as a root for the spanning tree to init global poses (default=0)
Definition: RbaEngine.h:268
void make_ordered_list_base_kfs(const typename traits_t::new_kf_observations_t &obs, base_sorted_lst_t &obs_for_each_base_sorted, std::map< TKeyFrameID, size_t > *out_obs_for_each_base=NULL) const
Make a list of base KFs of my new observations, ordered in descending order by # of shared observatio...
static void numeric_dh_dAp(const array_pose_t &x, const TNumeric_dh_dAp_params &params, array_obs_t &y)
Auxiliary method for numeric Jacobian: numerically evaluates the new observation "y" for a small incr...
virtual void saveToConfigFile(mrpt::utils::CConfigFileBase &out, const std::string &section) const
See docs of mrpt::utils::CLoadableOptions.
VisitorOptimizeLocalArea(const rba_problem_state_t &rba_state_, const TOptimizeLocalAreaParams &params_)
Definition: RbaEngine.h:515
mrpt::aligned_containers< k2k_edge_t >::deque_t k2k_edges_deque_t
Definition: srba_types.h:493
jacobian_traits< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE >::TSparseBlocksJacobians_dh_df TSparseBlocksJacobians_dh_df
Definition: RbaEngine.h:110
All the important data of a RBA problem at any given instant of time Operations on this structure are...
Definition: srba_types.h:474
size_t span_tree_max_depth
Maximum spanning tree depth for reconstructing relative poses (default=-1 : infinity) ...
Definition: RbaEngine.h:231
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
traits_t::new_kf_observations_t new_kf_observations_t
Definition: RbaEngine.h:101
size_t min_obs_to_loop_closure
Default:6, reduce to 1 for relative graph-slam.
Definition: RbaEngine.h:391
void compute_jacobian_dh_df(typename TSparseBlocksJacobians_dh_df::TEntry &jacob, const k2f_edge_t &observation, std::vector< const pose_flag_t * > *out_list_of_required_num_poses) const
==================================================================== j,i lm_id,base_id h h l obs_fr...
bool draw_unknown_feats
Draw features with non-fixed rel.pos as well?
Definition: RbaEngine.h:232
void visit_k2k(const TKeyFrameID current_kf, const TKeyFrameID next_kf, const k2k_edge_t *edge, const topo_dist_t cur_dist)
Definition: RbaEngine.h:561
mrpt::utils::CTimeLogger & get_time_profiler()
Access to the time profiler.
Definition: RbaEngine.h:447
topo_dist_t max_optimize_depth
The maximum topological distance of keyframes to be optimized around the most recent keyframe...
Definition: RbaEngine.h:388
void visit_kf(const TKeyFrameID kf_ID, const topo_dist_t cur_dist)
Definition: RbaEngine.h:546
TBFSEntryEdges()
Definition: RbaEngine.h:640
bool visit_filter_kf(const TKeyFrameID kf_ID, const topo_dist_t cur_dist)
Definition: RbaEngine.h:540
landmark_traits< LM_TYPE > landmark_traits_t
Definition: RbaEngine.h:82
kf2kf_pose_traits_t::frameid2pose_map_t frameid2pose_map_t
Definition: RbaEngine.h:95
const TRelativeLandmarkPosMap & get_unknown_feats() const
Definition: RbaEngine.h:441
std::pair< TKeyFrameID, TKeyFrameID > TPairKeyFrameID
Used to represent the IDs of a directed edge (first –> second)
Definition: srba_types.h:34
bool visit_filter_feat(const TLandmarkID lm_ID, const topo_dist_t cur_dist)
Definition: RbaEngine.h:527
TEdgeCreationPolicy edge_creation_policy
Parameters for determine_kf2kf_edges_to_create(); custom user-defined policies can be also defined (s...
Definition: RbaEngine.h:382
Aux visitor struct, used in optimize_local_area()
Definition: RbaEngine.h:513
options::sensor_pose_on_robot_none sensor_pose_on_robot_t
The sensor pose coincides with the robot pose.
Definition: RbaEngine.h:35
void create_complete_spanning_tree(const TKeyFrameID root_id, frameid2pose_map_t &span_tree, const size_t max_depth=std::numeric_limits< size_t >::max(), std::vector< bool > *aux_ws=NULL) const
Creates a numeric spanning tree between a given root keyframe and the entire graph, returning it into a user-supplied data structure Note that this method does NOT use the depth-limited spanning trees which are built incrementally with the graph.
jacobian_traits< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE >::TSparseBlocksJacobians_dh_dAp TSparseBlocksJacobians_dh_dAp
Definition: RbaEngine.h:109
bool find_path_bfs(const TKeyFrameID from, const TKeyFrameID to, std::vector< TKeyFrameID > *out_path_IDs, typename kf2kf_pose_traits< KF2KF_POSE_TYPE >::k2k_edge_vector_t *out_path_edges=NULL) const
Auxiliary, brute force (BFS) method for finding the shortest path between any two Keyframes...
virtual void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section)
See docs of mrpt::utils::CLoadableOptions.
const TOptimizeLocalAreaParams & params
Definition: RbaEngine.h:521
void build_opengl_representation(const srba::TKeyFrameID root_keyframe, const TOpenGLRepresentationOptions &options, mrpt::opengl::CSetOfObjectsPtr out_scene, mrpt::opengl::CSetOfObjectsPtr out_root_tree=mrpt::opengl::CSetOfObjectsPtr()) const
Build an opengl representation of the current state of this RBA problem One of different representati...
Definition: export_opengl.h:24
size_t create_kf2kf_edge(const TKeyFrameID new_kf_id, const TPairKeyFrameID &new_edge, const typename traits_t::new_kf_observations_t &obs, const pose_t &init_inv_pose_val=pose_t())
Users normally won't need to call this directly.
const RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t & sensor_pose
Definition: RbaEngine.h:738
std::vector< TNewEdgeInfo > created_edge_ids
The newly created edges (minimum: 1 edge)
Definition: RbaEngine.h:161
All the information returned by the local area optimizer.
Definition: RbaEngine.h:117
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X), among other stats.
Definition: CTimeLogger.h:35
A partial specialization of CArrayNumeric for double numbers.
Definition: CArrayNumeric.h:74
void setVerbosityLevel(int level)
Changes the verbosity level: 0=None (only critical msgs), 1=verbose, 2=so verbose you'll have to say ...
Definition: RbaEngine.h:450
OBS_TYPE::TObservationParams sensor
Sensor-specific parameters (sensor calibration, etc.)
Definition: RbaEngine.h:421
size_t num_kf2kf_edges_optimized
Number of solved unknowns of type "kf-to-kf edge".
Definition: RbaEngine.h:126
void prepare_Jacobians_required_tree_roots(std::set< TKeyFrameID > &kfs_num_spantrees_to_update, const std::vector< typename TSparseBlocksJacobians_dh_dAp::col_t * > &lst_JacobCols_dAp, const std::vector< typename TSparseBlocksJacobians_dh_df::col_t * > &lst_JacobCols_df)
Prepare the list of all required KF roots whose spanning trees need numeric updates with each optimiz...
const pose_t aux_null_pose
A fixed SE(3) pose at the origin (used when we need a pointer or a reference to a "null transformatio...
Definition: RbaEngine.h:685
TRelativeLandmarkPosMap unknown_lms
(unknown values) Landmarks with an unknown fixed 3D position relative to their base frame_id ...
Definition: srba_types.h:637
std::multimap< size_t, TKeyFrameID, std::greater< size_t > > base_sorted_lst_t
Definition: RbaEngine.h:475
Information per key-frame needed for RBA.
Definition: srba_types.h:453
sensor_model< LM_TYPE, OBS_TYPE > sensor_model_t
The sensor model for the specified combination of LM parameterization + observation type...
Definition: RbaEngine.h:85
landmark_traits_t::TRelativeLandmarkPosMap TRelativeLandmarkPosMap
An index of feature IDs and their relative locations.
Definition: RbaEngine.h:97
mrpt::aligned_containers< residual_t >::vector_t vector_residuals_t
Definition: srba_types.h:145
const OBS_TYPE::TObservationParams & sensor_params
Definition: RbaEngine.h:716
size_t dont_optimize_landmarks_seen_less_than_n_times
Set to 1 to try to optimize all landmarks even if they're just observed once, which may makes sense d...
Definition: RbaEngine.h:195
static void add_edge_ij_to_list_needed_roots(std::set< TKeyFrameID > &lst, const TKeyFrameID i, const TKeyFrameID j)
Definition: RbaEngine.h:746
observation_traits_t::array_obs_t array_obs_t
Definition: RbaEngine.h:105
void bfs_visitor(const TKeyFrameID root_id, const topo_dist_t max_distance, const bool rely_on_prebuilt_spanning_trees, KF_VISITOR &kf_visitor, FEAT_VISITOR &feat_visitor, K2K_EDGE_VISITOR &k2k_edge_visitor, K2F_EDGE_VISITOR &k2f_edge_visitor) const
Visits all k2k & k2f edges following a BFS starting at a given starting node and up to a given maximu...
Definition: bfs_visitor.h:21
rba_problem_state_t::k2k_edge_t k2k_edge_t
Definition: RbaEngine.h:91
The set of default settings for RbaEngine.
Definition: RbaEngine.h:33
int m_verbose_level
0: None (only critical msgs), 1: verbose, 2:even more verbose, 3: even more
Definition: RbaEngine.h:473
Keyframe-to-feature edge: observation data stored for each keyframe.
Definition: srba_types.h:442
TRelativeLandmarkPosMap known_lms
(known values) Landmarks with a known, fixed 3D position relative to their base frame_id ...
Definition: srba_types.h:639
double eval_overall_squared_error() const
Evaluates the quality of the overall map/landmark estimations, by computing the sum of the squared er...
void gl_aux_draw_node(mrpt::opengl::CSetOfObjects &soo, const std::string &label, const float x, const float y) const
The unique struct which hold all the parameters from the different SRBA modules (sensors, optional features, optimizers,...)
Definition: RbaEngine.h:415
size_t add_observation(const TKeyFrameID observing_kf_id, const typename observation_traits_t::observation_t &new_obs, const array_landmark_t *fixed_relative_position=NULL, const array_landmark_t *unknown_relative_position_init_val=NULL)
Creates a new known/unknown position landmark (upon first LM observation ), and expands Jacobians wit...
options::observation_noise_identity obs_noise_matrix_t
The sensor noise matrix is the same for all observations and equal to * I(identity) ...
Definition: RbaEngine.h:36
std::vector< bool > m_complete_st_ws
Temporary working space used in create_complete_spanning_tree()
Definition: RbaEngine.h:593
Usage: A possible type for RBA_OPTIONS::sensor_pose_on_robot_t.
size_t num_kf2lm_edges_optimized
Number of solved unknowns of type "kf-to-landmark".
Definition: RbaEngine.h:127
bool find_path_bfs(const TKeyFrameID src_kf, const TKeyFrameID trg_kf, std::vector< TKeyFrameID > &found_path) const
An unconstrained breadth-first search (BFS) for the shortest path between two keyframes.
Definition: RbaEngine.h:338
void clear()
Reset the entire problem to an empty state (automatically called at construction) ...
Information returned by RbaEngine::define_new_keyframe()
Definition: RbaEngine.h:158
bool feat_has_known_rel_pos
whether it's a known or unknown relative position feature
Definition: srba_types.h:445
void determine_kf2kf_edges_to_create(const TKeyFrameID new_kf_id, const typename traits_t::new_kf_observations_t &obs, std::vector< TNewEdgeInfo > &new_k2k_edge_ids)
This method will call edge_creation_policy(), which has predefined algorithms but could be re-defined...
kf2kf_pose_traits< KF2KF_POSE_TYPE > kf2kf_pose_traits_t
Definition: RbaEngine.h:81
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
void optimize_edges(const std::vector< size_t > &run_k2k_edges, const std::vector< size_t > &run_feat_ids_in, TOptimizeExtraOutputInfo &out_info, const std::vector< size_t > &observation_indices_to_optimize=std::vector< size_t >())
mrpt::aligned_containers< TKeyFrameID, pose_flag_t >::map_t frameid2pose_map_t
"numeric" values of spanning tree poses:
Definition: srba_types.h:71
bool numeric_jacobians
(Default:false) Use a numeric approximation of the Jacobians (very slow!) instead of analytical ones...
Definition: RbaEngine.h:405
rba_problem_state_t rba_state
All the beef is here.
Definition: RbaEngine.h:591
RbaEngine< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE, RBA_OPTIONS > rba_engine_t
Definition: RbaEngine.h:65
traits_t::new_kf_observation_t new_kf_observation_t
Definition: RbaEngine.h:100
k2f_edge_t * k2f
Obs data.
Definition: RbaEngine.h:767
void visit_feat(const TLandmarkID lm_ID, const topo_dist_t cur_dist)
Definition: RbaEngine.h:533
rba_problem_state_t::k2f_edge_t k2f_edge_t
Definition: RbaEngine.h:90
static double huber_kernel(double delta, const double kernel_param)
pseudo-huber cost function
Definition: RbaEngine.h:781
uint64_t TKeyFrameID
Numeric IDs for key-frames (KFs)
Definition: srba_types.h:31



Page generated by Doxygen 1.8.9.1 for MRPT 1.3.0 SVN: at Sun Sep 13 03:55:12 UTC 2015