Main MRPT website > C++ reference
MRPT logo
optimize_edges.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 #include <mrpt/math/ops_containers.h> // norm_inf()
13 
14 namespace mrpt { namespace srba {
15 
16 #ifndef SRBA_DETAILED_TIME_PROFILING
17 # define SRBA_DETAILED_TIME_PROFILING 0 // Enabling this has a measurable impact in performance, so use only for debugging.
18 #endif
19 
20 // Macros:
21 #if SRBA_DETAILED_TIME_PROFILING
22 # define DETAILED_PROFILING_ENTER(_STR) m_profiler.enter(_STR);
23 # define DETAILED_PROFILING_LEAVE(_STR) m_profiler.leave(_STR);
24 #else
25 # define DETAILED_PROFILING_ENTER(_STR)
26 # define DETAILED_PROFILING_LEAVE(_STR)
27 #endif
28 
29 namespace internal
30 {
31  /** Generic solver declaration */
32  template <bool USE_SCHUR, bool DENSE_CHOL,class RBA_ENGINE>
33  struct solver_engine;
34 
35  // Implemented in lev-marq_solvers.h
36 }
37 
38 
39 // ------------------------------------------
40 // optimize_edges
41 // (See header for docs)
42 // ------------------------------------------
43 template <class KF2KF_POSE_TYPE,class LM_TYPE,class OBS_TYPE,class RBA_OPTIONS>
45  const std::vector<size_t> & run_k2k_edges_in,
46  const std::vector<size_t> & run_feat_ids_in,
47  TOptimizeExtraOutputInfo & out_info,
48  const std::vector<size_t> & in_observation_indices_to_optimize
49  )
50 {
51  using namespace std;
52  // This method deals with many common tasks to any optimizer: update Jacobians, prepare Hessians, etc.
53  // The specific solver method details are implemented in "my_solver_t":
55 
56  m_profiler.enter("opt");
57 
58  // Problem dimensions:
59  const size_t POSE_DIMS = KF2KF_POSE_TYPE::REL_POSE_DIMS;
60  const size_t LM_DIMS = LM_TYPE::LM_DIMS;
61  const size_t OBS_DIMS = OBS_TYPE::OBS_DIMS;
62 
63 
64  // Filter out those unknowns which for sure do not have any observation,
65  // which can be checked by looking for empty columns in the sparse Jacobian.
66  // -------------------------------------------------------------------------------
67  DETAILED_PROFILING_ENTER("opt.filter_unknowns")
68 
69  std::vector<size_t> run_k2k_edges; run_k2k_edges.reserve(run_k2k_edges_in.size());
70  std::vector<size_t> run_feat_ids; run_feat_ids.reserve(run_feat_ids_in.size());
71 
72  for (size_t i=0;i<run_k2k_edges_in.size();i++)
73  {
74  const typename TSparseBlocksJacobians_dh_dAp::col_t & col_i = rba_state.lin_system.dh_dAp.getCol( run_k2k_edges_in[i] );
75  if (!col_i.empty()) run_k2k_edges.push_back( run_k2k_edges_in[i] );
76  else
77  {
78 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
79  const TKeyFrameID from = rba_state.k2k_edges[run_k2k_edges_in[i]]->from;
80  const TKeyFrameID to = rba_state.k2k_edges[run_k2k_edges_in[i]]->to;
81 #else
82  const TKeyFrameID from = rba_state.k2k_edges[run_k2k_edges_in[i]].from;
83  const TKeyFrameID to = rba_state.k2k_edges[run_k2k_edges_in[i]].to;
84 #endif
85  std::cerr << "[RbaEngine::optimize_edges] *Warning*: Skipping optimization of k2k edge #"<<run_k2k_edges_in[i] << " (" <<from <<"->"<<to <<") since no observation depends on it.\n";
86  }
87  }
88 
89  const mrpt::utils::map_as_vector<size_t,size_t> & dh_df_remap = rba_state.lin_system.dh_df.getColInverseRemappedIndices();
90  for (size_t i=0;i<run_feat_ids_in.size();i++)
91  {
92  const TLandmarkID feat_id = run_feat_ids_in[i];
93  ASSERT_(feat_id<rba_state.all_lms.size())
94 
95  const typename rba_problem_state_t::TLandmarkEntry &lm_e = rba_state.all_lms[feat_id];
96  ASSERTMSG_(lm_e.rfp!=NULL, "Trying to optimize an unknown feature ID")
97  ASSERTMSG_(!lm_e.has_known_pos,"Trying to optimize a feature with fixed (known) value")
98 
99  mrpt::utils::map_as_vector<size_t,size_t>::const_iterator it_remap = dh_df_remap.find(feat_id); // O(1) with map_as_vector
100  ASSERT_(it_remap != dh_df_remap.end())
101 
102  const typename TSparseBlocksJacobians_dh_df::col_t & col_i = rba_state.lin_system.dh_df.getCol( it_remap->second );
103 
104  if (!col_i.empty()) run_feat_ids.push_back( run_feat_ids_in[i] );
105  else { std::cerr << "[RbaEngine::optimize_edges] *Warning*: Skipping optimization of k2f edge #"<<run_feat_ids_in[i] << " since no observation depends on it.\n"; }
106  }
107 
108  DETAILED_PROFILING_LEAVE("opt.filter_unknowns")
109 
110  // Build list of unknowns, and their corresponding columns in the Sparse Jacobian:
111  // -------------------------------------------------------------------------------
112  const size_t nUnknowns_k2k = run_k2k_edges.size();
113  const size_t nUnknowns_k2f = run_feat_ids.size();
114 
115  const size_t idx_start_f = POSE_DIMS*nUnknowns_k2k; // In the vector of unknowns, the 0-based first index of the first feature variable (before that, all are SE(3) edges)
116  const size_t nUnknowns_scalars = POSE_DIMS*nUnknowns_k2k + LM_DIMS*nUnknowns_k2f;
117  ASSERT_(nUnknowns_scalars>=1)
118 
119  // k2k edges:
120  std::vector<typename TSparseBlocksJacobians_dh_dAp::col_t*> dh_dAp(nUnknowns_k2k);
121  std::vector<k2k_edge_t *> k2k_edge_unknowns(nUnknowns_k2k);
122  for (size_t i=0;i<nUnknowns_k2k;i++)
123  {
124  dh_dAp[i] = &rba_state.lin_system.dh_dAp.getCol( run_k2k_edges[i] );
125  k2k_edge_unknowns[i] =
126 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
127  rba_state.k2k_edges[run_k2k_edges[i]].pointer();
128 #else
129  & rba_state.k2k_edges[run_k2k_edges[i]];
130 #endif
131  }
132 
133  // k2f edges:
134  std::vector<typename TSparseBlocksJacobians_dh_df::col_t*> dh_df(nUnknowns_k2f);
135  std::vector<TRelativeLandmarkPos*> k2f_edge_unknowns(nUnknowns_k2f);
136  for (size_t i=0;i<nUnknowns_k2f;i++)
137  {
138  const TLandmarkID feat_id = run_feat_ids[i];
139  const typename rba_problem_state_t::TLandmarkEntry &lm_e = rba_state.all_lms[feat_id];
140 
141  mrpt::utils::map_as_vector<size_t,size_t>::const_iterator it_remap = dh_df_remap.find(feat_id); // O(1) with map_as_vector
142  ASSERT_(it_remap != dh_df_remap.end())
143 
144  dh_df[i] = &rba_state.lin_system.dh_df.getCol( it_remap->second );
145  k2f_edge_unknowns[i] = lm_e.rfp;
146  }
147 
148  // Unless stated otherwise, take into account ALL the observations involved in each
149  // unknown (i.e. don't discard any information).
150  // -------------------------------------------------------------------------------
151  DETAILED_PROFILING_ENTER("opt.build_obs_list")
152 
153  // Mapping betwwen obs. indices in the residuals vector & the global list of all the observations:
154  std::map<size_t,size_t> obs_global_idx2residual_idx;
155 
156  std::vector<TObsUsed> involved_obs; // + obs. data
157  if (in_observation_indices_to_optimize.empty())
158  {
159  // Observations for k2k edges Jacobians
160  for (size_t i=0;i<nUnknowns_k2k;i++)
161  {
162  // For each column, process each nonzero block:
163  typename TSparseBlocksJacobians_dh_dAp::col_t *col = dh_dAp[i];
164 
165  for (typename TSparseBlocksJacobians_dh_dAp::col_t::iterator it=col->begin();it!=col->end();++it)
166  {
167  const size_t global_obs_idx = it->first;
168  const size_t obs_idx = involved_obs.size();
169 
170  obs_global_idx2residual_idx[global_obs_idx] = obs_idx;
171 
172  involved_obs.push_back( TObsUsed (global_obs_idx,
173 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
174  &(*rba_state.all_observations[global_obs_idx])
175 #else
176  &rba_state.all_observations[global_obs_idx]
177 #endif
178  ) );
179  }
180  }
181  // Observations for k2f edges Jacobians
182  for (size_t i=0;i<nUnknowns_k2f;i++)
183  {
184  // For each column, process each nonzero block:
185  typename TSparseBlocksJacobians_dh_df::col_t *col = dh_df[i];
186 
187  for (typename TSparseBlocksJacobians_dh_df::col_t::iterator it=col->begin();it!=col->end();++it)
188  {
189  const size_t global_obs_idx = it->first;
190  // Only add if not already added before:
191  std::map<size_t,size_t>::const_iterator it_o = obs_global_idx2residual_idx.find(global_obs_idx);
192  /* TSizeFlag & sf = obs_global_idx2residual_idx[global_obs_idx];*/
193  if (it_o == obs_global_idx2residual_idx.end())
194  {
195  const size_t obs_idx = involved_obs.size();
196 
197  obs_global_idx2residual_idx[global_obs_idx] = obs_idx;
198 
199  involved_obs.push_back( TObsUsed( global_obs_idx,
200 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
201  &(*rba_state.all_observations[global_obs_idx])
202 #else
203  &rba_state.all_observations[global_obs_idx]
204 #endif
205  ) );
206  }
207  }
208  }
209  }
210  else
211  {
212  // use only those observations in "in_observation_indices_to_optimize":
213  const size_t nInObs = in_observation_indices_to_optimize.size();
214  for (size_t i=0;i<nInObs;i++)
215  {
216  const size_t global_obs_idx = in_observation_indices_to_optimize[i];
217  const size_t obs_idx = involved_obs.size();
218 
219  obs_global_idx2residual_idx[global_obs_idx] = obs_idx;
220 
221  involved_obs.push_back(TObsUsed(global_obs_idx,
222 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
223  &(*rba_state.all_observations[global_obs_idx])
224 #else
225  &rba_state.all_observations[global_obs_idx]
226 #endif
227  ) );
228  }
229  }
230 
231  DETAILED_PROFILING_LEAVE("opt.build_obs_list")
232 
233  const size_t nObs = involved_obs.size();
234 
235 
236  // Make a list of Keyframe IDs whose numeric spanning trees must be updated (so we only update them!)
237  // -------------------------------------------------------------------------------
238  DETAILED_PROFILING_ENTER("opt.prep_list_num_tree_roots")
239 
240  std::set<TKeyFrameID> kfs_num_spantrees_to_update;
241  prepare_Jacobians_required_tree_roots(kfs_num_spantrees_to_update, dh_dAp, dh_df);
242 
243  DETAILED_PROFILING_LEAVE("opt.prep_list_num_tree_roots")
244 
245  VERBOSE_LEVEL(2) << "[OPT] KF roots whose spantrees need numeric-updates: " << mrpt::system::sprintf_container("%u", kfs_num_spantrees_to_update) <<std::endl;
246 
247 
248  // Spanning tree: Update numerically only those entries which we really need:
249  // -------------------------------------------------------------------------------
250  DETAILED_PROFILING_ENTER("opt.update_spanning_tree_num")
251  const size_t count_span_tree_num_update = rba_state.spanning_tree.update_numeric(kfs_num_spantrees_to_update, false /* don't skip those marked as updated, so update all */);
252  DETAILED_PROFILING_LEAVE("opt.update_spanning_tree_num")
253 
254 
255  // Re-evaluate all Jacobians numerically:
256  // -------------------------------------------------------------------------------
257  std::vector<const pose_flag_t*> list_of_required_num_poses; // Filled-in by Jacobian evaluation upon first call.
258 
259 
260  DETAILED_PROFILING_ENTER("opt.reset_Jacobs_validity")
261  // Before evaluating Jacobians we must reset as "valid" all the involved observations.
262  // If needed, they'll be marked as invalid by the Jacobian evaluator if just one of the components
263  // for one observation leads to an error.
264  for (size_t i=0;i<nObs;i++)
265  rba_state.all_observations_Jacob_validity[ involved_obs[i].obs_idx ] = 1;
266 
267  DETAILED_PROFILING_LEAVE("opt.reset_Jacobs_validity")
268 
269 
270  DETAILED_PROFILING_ENTER("opt.recompute_all_Jacobians")
271  const size_t count_jacobians = recompute_all_Jacobians(dh_dAp, dh_df, &list_of_required_num_poses );
272  DETAILED_PROFILING_LEAVE("opt.recompute_all_Jacobians")
273 
274  // Mark all required spanning-tree numeric entries as outdated, so an exception will reveal us if
275  // next time Jacobians are required they haven't been updated as they should:
276  // -------------------------------------------------------------------------------
277  for (size_t i=0;i<list_of_required_num_poses.size();i++)
278  list_of_required_num_poses[i]->mark_outdated();
279 
280 #if 0 // Save a sparse block representation of the Jacobian.
281  {
282  static unsigned int dbg_idx = 0;
284  rba_state.lin_system.dh_dAp.getBinaryBlocksRepresentation(Jbin);
285  Jbin.saveToTextFile(mrpt::format("sparse_jacobs_blocks_%05u.txt",dbg_idx), mrpt::math::MATRIX_FORMAT_INT );
286  rba_state.lin_system.dh_dAp.saveToTextFileAsDense(mrpt::format("sparse_jacobs_%05u.txt",dbg_idx));
287  ++dbg_idx;
289  }
290 #endif
291 
292  // ----------------------------------------------------------------------
293  // Compute H = J^t * J , exploting the sparse, block representation of J:
294  //
295  // Don't add the LevMarq's "\lambda*I" here so "H" needs not to be
296  // modified between different LevMarq. trials with different lambda values.
297  // ----------------------------------------------------------------------
301 
302  // This symbolic constructions must be done only ONCE:
303  DETAILED_PROFILING_ENTER("opt.sparse_hessian_build_symbolic")
304  sparse_hessian_build_symbolic(
305  HAp,Hf,HApf,
306  dh_dAp,dh_df
307  );
308  DETAILED_PROFILING_LEAVE("opt.sparse_hessian_build_symbolic")
309 
310  // and then we only have to do a numeric evaluation upon changes:
311  size_t nInvalidJacobs = 0;
312  DETAILED_PROFILING_ENTER("opt.sparse_hessian_update_numeric")
313  nInvalidJacobs += sparse_hessian_update_numeric(HAp);
314  nInvalidJacobs += sparse_hessian_update_numeric(Hf);
315  nInvalidJacobs += sparse_hessian_update_numeric(HApf);
316  DETAILED_PROFILING_LEAVE("opt.sparse_hessian_update_numeric")
317 
318  if (nInvalidJacobs)
319  VERBOSE_LEVEL(1) << "[OPT] " << nInvalidJacobs << " Jacobian blocks ignored for 'invalid'.\n";
320 
321  VERBOSE_LEVEL(2) << "[OPT] Individual Jacobs: " << count_jacobians << " #k2k_edges=" << nUnknowns_k2k << " #k2f_edges=" << nUnknowns_k2f << " #obs=" << nObs << std::endl;
322  VERBOSE_LEVEL(2) << "[OPT] k2k_edges to optimize: " << mrpt::system::sprintf_container("% u",run_k2k_edges) << std::endl;
323  VERBOSE_LEVEL(2) << "[OPT] k2f_edges to optimize: " << mrpt::system::sprintf_container("% u",run_feat_ids) << std::endl;
324  // Extra verbose: display initial value of each optimized pose:
325  if (m_verbose_level>=2 && !run_k2k_edges.empty())
326  {
327  std::cout << "[OPT] k2k_edges to optimize, initial value(s):\n";
328  ASSERT_(k2k_edge_unknowns.size()==run_k2k_edges.size())
329  for (size_t i=0;i<run_k2k_edges.size();i++)
330  std::cout << " k2k_edge: " <<k2k_edge_unknowns[i]->from << "=>" << k2k_edge_unknowns[i]->to << ",inv_pose=" << k2k_edge_unknowns[i]->inv_pose << std::endl;
331  }
332 
333  // VERY IMPORTANT: For J^t*J to be invertible, we need a full rank Hessian:
334  // nObs*OBS_DIMS >= nUnknowns_k2k*POSE_DIMS+nUnknowns_k2f*LM_DIMS
335  //
336  ASSERT_ABOVEEQ_(OBS_DIMS*nObs,POSE_DIMS*nUnknowns_k2k+LM_DIMS*nUnknowns_k2f)
337 
338  // ----------------------------------------------------------------
339  // Iterative Levenberg Marquardt (LM) algorithm
340  // ----------------------------------------------------------------
341  // LevMar parameters:
342  double nu = 2;
343  const double max_gradient_to_stop = 1e-15; // Stop if the infinity norm of the gradient is smaller than this
344  double lambda = -1; // initial value. <0 = auto.
345 
346  // Automatic guess of "lambda" = tau * max(diag(Hessian)) (Hessian=H here)
347  if (lambda<0)
348  {
349  DETAILED_PROFILING_ENTER("opt.guess lambda")
350 
351  double Hess_diag_max = 0;
352  for (size_t i=0;i<nUnknowns_k2k;i++)
353  {
354  ASSERTDEB_(HAp.getCol(i).find(i)!=HAp.getCol(i).end())
355 
356  const double Hii_max = HAp.getCol(i)[i].num.diagonal().maxCoeff();
357  mrpt::utils::keep_max(Hess_diag_max, Hii_max);
358  }
359  for (size_t i=0;i<nUnknowns_k2f;i++)
360  {
361  ASSERTDEB_(Hf.getCol(i).find(i)!=Hf.getCol(i).end())
362 
363  const double Hii_max = Hf.getCol(i)[i].num.diagonal().maxCoeff();
364  mrpt::utils::keep_max(Hess_diag_max, Hii_max);
365  }
366 
367  const double tau = 1e-3;
368  lambda = tau * Hess_diag_max;
369 
370  DETAILED_PROFILING_LEAVE("opt.guess lambda")
371  }
372 
373  // Compute the reprojection errors:
374  // residuals = "h(x)-z" (a vector of 2-vectors).
375  // ---------------------------------------------------------------------------------
376  vector_residuals_t residuals(nObs);
377 
378  DETAILED_PROFILING_ENTER("opt.reprojection_residuals")
379  double total_proj_error = reprojection_residuals(
380  residuals, // Out
381  involved_obs // In
382  );
383  DETAILED_PROFILING_LEAVE("opt.reprojection_residuals")
384 
385  double RMSE = std::sqrt(total_proj_error/nObs);
386 
387  out_info.num_observations = nObs;
388  out_info.num_jacobians = count_jacobians;
389  out_info.num_kf2kf_edges_optimized = run_k2k_edges.size();
390  out_info.num_kf2lm_edges_optimized = run_feat_ids.size();
391  out_info.num_total_scalar_optimized = nUnknowns_scalars;
392  out_info.num_span_tree_numeric_updates = count_span_tree_num_update;
393  out_info.total_sqr_error_init = total_proj_error;
394 
395 
396  VERBOSE_LEVEL(1) << "[OPT] LM: Initial RMSE=" << RMSE << " #Jcbs=" << count_jacobians << " #k2k_edges=" << nUnknowns_k2k << " #k2f_edges=" << nUnknowns_k2f << " #obs=" << nObs << std::endl;
397 
398  if (parameters.srba.feedback_user_iteration)
399  (*parameters.srba.feedback_user_iteration)(0,total_proj_error,RMSE);
400 
401  // Compute the gradient: "grad = J^t * (h(x)-z)"
402  // ---------------------------------------------------------------------------------
403  Eigen::VectorXd minus_grad; // The negative of the gradient.
404 
405  DETAILED_PROFILING_ENTER("opt.compute_minus_gradient")
406  compute_minus_gradient(/* Out: */ minus_grad, /* In: */ dh_dAp, dh_df, residuals, obs_global_idx2residual_idx);
407  DETAILED_PROFILING_LEAVE("opt.compute_minus_gradient")
408 
409 
410  // Build symbolic structures for Schur complement:
411  // ---------------------------------------------------------------------------------
412  my_solver_t my_solver(
413  m_verbose_level, m_profiler,
414  HAp,Hf,HApf, // The different symbolic/numeric Hessian
415  minus_grad, // minus gradient of the Ap part
416  nUnknowns_k2k,
417  nUnknowns_k2f);
418  // Notice: At this point, the constructor of "my_solver_t" might have already built the Schur-complement
419  // of HAp-HApf into HAp: it's overwritten there (Only if RBA_OPTIONS::solver_t::USE_SCHUR=true).
420 
421  const double MAX_LAMBDA = this->parameters.srba.max_lambda;
422 
423  // These are defined here to avoid allocatin/deallocating memory with each iteration:
424 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
425  vector<stlplus::smart_ptr<k2k_edge_t> > old_k2k_edge_unknowns;
426  vector<stlplus::smart_ptr<pose_flag_t> > old_span_tree; // In the same order than "list_of_required_num_poses"
427  vector<stlplus::smart_ptr<TRelativeLandmarkPos> > old_k2f_edge_unknowns;
428 #else
429  vector<k2k_edge_t> old_k2k_edge_unknowns;
430  vector<pose_flag_t> old_span_tree; // In the same order than "list_of_required_num_poses"
431  vector<TRelativeLandmarkPos> old_k2f_edge_unknowns;
432 #endif
433 
434 #if SRBA_DETAILED_TIME_PROFILING
435  const std::string sLabelProfilerLM_iter = mrpt::format("opt.lm_iteration_k2k=%03u_k2f=%03u", static_cast<unsigned int>(nUnknowns_k2k), static_cast<unsigned int>(nUnknowns_k2f) );
436 #endif
437 
438  // LevMar iterations -------------------------------------
439  size_t iter; // Declared here so we can read the final # of iterations out of the "for" loop.
440  bool stop = false;
441  for (iter=0; iter<this->parameters.srba.max_iters && !stop; iter++)
442  {
443  DETAILED_PROFILING_ENTER(sLabelProfilerLM_iter.c_str())
444 
445  // Try with different rho's until a better solution is found:
446  double rho = 0;
447  if (lambda>=MAX_LAMBDA)
448  {
449  stop=true;
450  VERBOSE_LEVEL(2) << "[OPT] LM end criterion: lambda too large. " << lambda << ">=" <<MAX_LAMBDA<<endl;
451  }
452  if (RMSE < this->parameters.srba.max_error_per_obs_to_stop)
453  {
454  stop=true;
455  VERBOSE_LEVEL(2) << "[OPT] LM end criterion: error too small. " << RMSE << "<" <<this->parameters.srba.max_error_per_obs_to_stop<<endl;
456  }
457 
458  while(rho<=0 && !stop)
459  {
460  // -------------------------------------------------------------------------
461  // Build the matrix (Hessian+ \lambda I) and decompose it with Cholesky:
462  // -------------------------------------------------------------------------
463  if ( !my_solver.solve(lambda) )
464  {
465  // not positive definite so increase lambda and try again
466  lambda *= nu;
467  nu *= 2.;
468  stop = (lambda>MAX_LAMBDA);
469 
470  VERBOSE_LEVEL(2) << "[OPT] LM iter #"<< iter << " NotDefPos in Cholesky. Retrying with lambda=" << lambda << std::endl;
471  continue;
472  }
473 
474  // Make a copy of the old edge values, just in case we need to restore them back...
475  // ----------------------------------------------------------------------------------
476  DETAILED_PROFILING_ENTER("opt.make_backup_copy_edges")
477 
478  old_k2k_edge_unknowns.resize(nUnknowns_k2k);
479  for (size_t i=0;i<nUnknowns_k2k;i++)
480  {
481 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
482  old_k2k_edge_unknowns[i] = stlplus::smart_ptr<k2k_edge_t>( new k2k_edge_t(*k2k_edge_unknowns[i] ) );
483 #else
484  old_k2k_edge_unknowns[i] = *k2k_edge_unknowns[i];
485 #endif
486  }
487 
488  old_k2f_edge_unknowns.resize(nUnknowns_k2f);
489  for (size_t i=0;i<nUnknowns_k2f;i++)
490  {
491 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
492  old_k2f_edge_unknowns[i] = stlplus::smart_ptr<TRelativeLandmarkPos>(new TRelativeLandmarkPos(*k2f_edge_unknowns[i]));
493 #else
494  old_k2f_edge_unknowns[i] = *k2f_edge_unknowns[i];
495 #endif
496  }
497 
498  DETAILED_PROFILING_LEAVE("opt.make_backup_copy_edges")
499 
500  // Add SE(2/3) deltas to the k2k edges:
501  // ------------------------------------
502  DETAILED_PROFILING_ENTER("opt.add_se3_deltas_to_frames")
503  for (size_t i=0;i<nUnknowns_k2k;i++)
504  {
505  // edges_to_optimize:
506  const pose_t &old_pose = k2k_edge_unknowns[i]->inv_pose;
508 
509  // Use the Lie Algebra methods for the increment:
510  const mrpt::math::CArrayDouble<POSE_DIMS> incr( & my_solver.delta_eps[POSE_DIMS*i] );
512  se_traits_t::pseudo_exp(incr,incrPose); // incrPose = exp(incr) (Lie algebra pseudo-exponential map)
513 
514  //new_pose = old_pose [+] delta
515  // = exp(delta) (+) old_pose
516  new_pose.composeFrom(incrPose, old_pose);
517 
518  VERBOSE_LEVEL(3) << "[OPT] Update k2k_edge[" <<i<< "]: eps=" << incr.transpose() << "\n" << " such that: " << old_pose << " => " << new_pose << "\n";
519 
520  // Overwrite problem graph:
521  k2k_edge_unknowns[i]->inv_pose = new_pose;
522  }
523  DETAILED_PROFILING_LEAVE("opt.add_se3_deltas_to_frames")
524 
525 
526  // Add R^3 deltas to the k2f edges:
527  // ------------------------------------
528  DETAILED_PROFILING_ENTER("opt.add_deltas_to_feats")
529  for (size_t i=0;i<nUnknowns_k2f;i++)
530  {
531  const double *delta_feat = &my_solver.delta_eps[idx_start_f+LM_DIMS*i];
532  for (size_t k=0;k<LM_DIMS;k++)
533  k2f_edge_unknowns[i]->pos[k] += delta_feat[k];
534  }
535  DETAILED_PROFILING_LEAVE("opt.add_deltas_to_feats")
536 
537 
538  // Update the Spanning tree, making a back-up copy:
539  // ------------------------------------------------------
540 
541 
542  DETAILED_PROFILING_ENTER("opt.make_backup_copy_spntree_num")
543  // DON'T: old_span_tree = rba_state.spanning_tree.num; // This works but runs in O(n) with the size of the map!!
544  // Instead: copy just the required entries:
545  {
546  const size_t nReqNumPoses = list_of_required_num_poses.size();
547  if (old_span_tree.size()!=nReqNumPoses) old_span_tree.resize(nReqNumPoses);
548  for (size_t i=0;i<nReqNumPoses;i++)
549  {
550 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
551  old_span_tree[i] = stlplus::smart_ptr<pose_flag_t>(new pose_flag_t);
552  old_span_tree[i]->pose = list_of_required_num_poses[i]->pose;
553 #else
554  old_span_tree[i].pose = list_of_required_num_poses[i]->pose;
555 #endif
556  }
557  }
558  DETAILED_PROFILING_LEAVE("opt.make_backup_copy_spntree_num")
559 
560 
561  DETAILED_PROFILING_ENTER("opt.update_spanning_tree_num")
562  for (size_t i=0;i<list_of_required_num_poses.size();i++)
563  list_of_required_num_poses[i]->mark_outdated();
564 
565  rba_state.spanning_tree.update_numeric(kfs_num_spantrees_to_update, true /* Only those marked as outdated above */);
566  DETAILED_PROFILING_LEAVE("opt.update_spanning_tree_num")
567 
568  // Compute new reprojection errors:
569  // ----------------------------------
570  vector_residuals_t new_residuals;
571 
572  DETAILED_PROFILING_ENTER("opt.reprojection_residuals")
573  double new_total_proj_error = reprojection_residuals(
574  new_residuals, // Out
575  involved_obs // In
576  );
577  DETAILED_PROFILING_LEAVE("opt.reprojection_residuals")
578 
579  const double new_RMSE = std::sqrt(new_total_proj_error/nObs);
580 
581  const double error_reduction_ratio = total_proj_error>0 ? (total_proj_error - new_total_proj_error)/total_proj_error : 0;
582 
583  // is this better or worse?
584  // -----------------------------
585  rho = (total_proj_error - new_total_proj_error)/ (my_solver.delta_eps.array()*(lambda*my_solver.delta_eps + minus_grad).array() ).sum();
586 
587  if(rho>0)
588  {
589  // Good: Accept new values
590 
591  // Recalculate Jacobians?
592  bool do_relinearize = (error_reduction_ratio<0 || error_reduction_ratio> this->parameters.srba.min_error_reduction_ratio_to_relinearize );
593 
594  VERBOSE_LEVEL(2) << "[OPT] LM iter #"<< iter << " RMSE: " << RMSE << " -> " << new_RMSE << ", rho=" << rho << ", Err.reduc.ratio="<< error_reduction_ratio << " => Relinearize?:" << (do_relinearize ? "YES":"NO") << std::endl;
595  if (parameters.srba.feedback_user_iteration)
596  (*parameters.srba.feedback_user_iteration)(iter,new_total_proj_error,new_RMSE);
597 
598  // Switch variables to the temptative ones, which are now accepted:
599  // (swap where possible, since it's faster)
600  // ---------------------------------------------------------------------
601  residuals.swap( new_residuals );
602 
603  total_proj_error = new_total_proj_error;
604  RMSE = new_RMSE;
605 
606  if (do_relinearize)
607  {
608  DETAILED_PROFILING_ENTER("opt.reset_Jacobs_validity")
609  // Before evaluating Jacobians we must reset as "valid" all the involved observations.
610  // If needed, they'll be marked as invalid by the Jacobian evaluator if just one of the components
611  // for one observation leads to an error.
612  for (size_t i=0;i<nObs;i++)
613  rba_state.all_observations_Jacob_validity[ involved_obs[i].obs_idx ] = 1;
614 
615  DETAILED_PROFILING_LEAVE("opt.reset_Jacobs_validity")
616 
617  DETAILED_PROFILING_ENTER("opt.recompute_all_Jacobians")
618  recompute_all_Jacobians(dh_dAp, dh_df);
619  DETAILED_PROFILING_LEAVE("opt.recompute_all_Jacobians")
620 
621  // Recalculate Hessian:
622  DETAILED_PROFILING_ENTER("opt.sparse_hessian_update_numeric")
623  sparse_hessian_update_numeric(HAp);
624  sparse_hessian_update_numeric(Hf);
625  sparse_hessian_update_numeric(HApf);
626  DETAILED_PROFILING_LEAVE("opt.sparse_hessian_update_numeric")
627 
628  my_solver.realize_relinearized();
629  }
630 
631  // Update gradient:
632  DETAILED_PROFILING_ENTER("opt.compute_minus_gradient")
633  compute_minus_gradient(/* Out: */ minus_grad, /* In: */ dh_dAp, dh_df, residuals, obs_global_idx2residual_idx);
634  DETAILED_PROFILING_LEAVE("opt.compute_minus_gradient")
635 
636  const double norm_inf_min_grad = mrpt::math::norm_inf(minus_grad);
637  if (norm_inf_min_grad<=max_gradient_to_stop)
638  {
639  VERBOSE_LEVEL(2) << "[OPT] LM end criterion: norm_inf(minus_grad) below threshold: " << norm_inf_min_grad << " <= " <<max_gradient_to_stop<<endl;
640  stop = true;
641  }
642  if (RMSE<this->parameters.srba.max_error_per_obs_to_stop)
643  {
644  VERBOSE_LEVEL(2) << "[OPT] LM end criterion: RMSE below threshold: " << RMSE << " < " <<this->parameters.srba.max_error_per_obs_to_stop<<endl;
645  stop = true;
646  }
647  if (rho>this->parameters.srba.max_rho)
648  {
649  VERBOSE_LEVEL(2) << "[OPT] LM end criterion: rho above threshold: " << rho << " > " <<this->parameters.srba.max_rho<<endl;
650  stop = true;
651  }
652  // Reset other vars:
653  lambda *= 1.0/3.0; //std::max(1.0/3.0, 1-std::pow(2*rho-1,3.0) );
654  nu = 2.0;
655 
656  my_solver.realize_lambda_changed();
657  }
658  else
659  {
660  DETAILED_PROFILING_ENTER("opt.failedstep_restore_backup")
661 
662  // Restore old values and retry again with a different lambda:
663  //DON'T: rba_state.spanning_tree.num = old_span_tree; // NO! Don't do this, since existing pointers will break -> Copy elements one by one:
664  {
665  const size_t nReqNumPoses = list_of_required_num_poses.size();
666  for (size_t i=0;i<nReqNumPoses;i++)
667  {
668 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
669  const_cast<pose_flag_t*>(list_of_required_num_poses[i])->pose = old_span_tree[i]->pose;
670 #else
671  const_cast<pose_flag_t*>(list_of_required_num_poses[i])->pose = old_span_tree[i].pose;
672 #endif
673  }
674  }
675 
676  // Restore old edge values:
677  for (size_t i=0;i<nUnknowns_k2k;i++)
678  {
679  *k2k_edge_unknowns[i] =
680 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
681  *old_k2k_edge_unknowns[i];
682 #else
683  old_k2k_edge_unknowns[i];
684 #endif
685  }
686  for (size_t i=0;i<nUnknowns_k2f;i++)
687  {
688  *k2f_edge_unknowns[i] =
689 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
690  *old_k2f_edge_unknowns[i];
691 #else
692  old_k2f_edge_unknowns[i];
693 #endif
694  }
695 
696  DETAILED_PROFILING_LEAVE("opt.failedstep_restore_backup")
697 
698  VERBOSE_LEVEL(2) << "[OPT] LM iter #"<< iter << " no update,errs: " << sqrt(total_proj_error/nObs) << " < " << sqrt(new_total_proj_error/nObs) << " lambda=" << lambda <<endl;
699  lambda *= nu;
700  nu *= 2.0;
701  stop = (lambda>MAX_LAMBDA);
702 
703  my_solver.realize_lambda_changed();
704  }
705 
706  }; // end while rho
707 
708  DETAILED_PROFILING_LEAVE(sLabelProfilerLM_iter.c_str())
709 
710  } // end for LM "iter"
711 
712 #if 0
713  std::cout << "residuals" << std::endl;
714  for( size_t r = 0; r < residuals.size(); ++r )
715  {
716  std::cout << involved_obs[r].k2f->obs.obs.feat_id << ","
717  << residuals[r][0] << ","
718  << residuals[r][1] << ","
719  << residuals[r][2] << ","
720  << residuals[r][3];
721 
722  const double totalres = residuals[r][0]*residuals[r][0]+
723  residuals[r][1]*residuals[r][1]+
724  residuals[r][2]*residuals[r][2]+
725  residuals[r][3]*residuals[r][3];
726 
727  if( totalres > 20 )
728  std::cout << " <-- spurious( " << totalres << ")";
729 
730  std::cout << std::endl;
731  }
732  cout << "done" << std::endl;
733 #endif
734 
735  // Final output info:
736  out_info.total_sqr_error_final = total_proj_error;
737 
738  // Recover information on covariances?
739  // ----------------------------------------------
740  DETAILED_PROFILING_ENTER("opt.cov_recovery")
741  rba_state.unknown_lms_inf_matrices.clear();
742  switch (parameters.srba.cov_recovery)
743  {
744  case crpNone:
745  break;
746  case crpLandmarksApprox:
747  {
748  for (size_t i=0;i<nUnknowns_k2f;i++)
749  {
750  if (!my_solver.was_ith_feature_invertible(i))
751  continue;
752 
753  const typename hessian_traits_t::TSparseBlocksHessian_f::col_t & col_i = Hf.getCol(i);
754  ASSERT_(col_i.rbegin()->first==i) // Make sure the last block matrix is the diagonal term of the upper-triangular matrix.
755 
756  const typename hessian_traits_t::TSparseBlocksHessian_f::matrix_t & inf_mat_src = col_i.rbegin()->second.num;
757  typename hessian_traits_t::TSparseBlocksHessian_f::matrix_t & inf_mat_dst = rba_state.unknown_lms_inf_matrices[ run_feat_ids[i] ];
758  inf_mat_dst = inf_mat_src;
759  }
760  }
761  break;
762  default:
763  throw std::runtime_error("Unknown value found for 'parameters.srba.cov_recovery'");
764  }
765  DETAILED_PROFILING_LEAVE("opt.cov_recovery")
766 
767  if (parameters.srba.compute_condition_number)
768  {
769  DETAILED_PROFILING_ENTER("opt.condition_number")
770 
771  // Evaluate conditioning number of hessians:
772  mrpt::math::CMatrixDouble dense_HAp;
773  HAp.getAsDense(dense_HAp, true /* recover both triangular parts */);
774 
775  const Eigen::JacobiSVD<mrpt::math::CMatrixDouble::Base> H_svd = dense_HAp.jacobiSvd();
776  out_info.HAp_condition_number = H_svd.singularValues().maxCoeff()/H_svd.singularValues().minCoeff();
777 
778  DETAILED_PROFILING_LEAVE("opt.condition_number")
779  }
780 
781  // Fill in any other extra info from the solver:
782  DETAILED_PROFILING_ENTER("opt.get_extra_results")
783  my_solver.get_extra_results(out_info.extra_results);
784  DETAILED_PROFILING_LEAVE("opt.get_extra_results")
785 
786  // Extra verbose: display final value of each optimized pose:
787  if (m_verbose_level>=2 && !run_k2k_edges.empty())
788  {
789  std::cout << "[OPT] k2k_edges to optimize, final value(s):\n";
790  ASSERT_(k2k_edge_unknowns.size()==run_k2k_edges.size())
791  for (size_t i=0;i<run_k2k_edges.size();i++)
792  std::cout << " k2k_edge: " <<k2k_edge_unknowns[i]->from << "=>" << k2k_edge_unknowns[i]->to << ",inv_pose=" << k2k_edge_unknowns[i]->inv_pose << std::endl;
793  }
794 
795  // Save (quick swap) the list of unknowns to the output structure,
796  // now that these vectors are not needed anymore:
797  out_info.optimized_k2k_edge_indices.swap(run_k2k_edges);
798  out_info.optimized_landmark_indices.swap(run_feat_ids);
799 
800  m_profiler.leave("opt");
801  out_info.obs_rmse = RMSE;
802 
803  VERBOSE_LEVEL(1) << "[OPT] Final RMSE=" << RMSE << " #iters=" << iter << "\n";
804 }
805 
806 
807 } } // end namespaces
808 
size_t num_observations
Number of individual feature observations taken into account in the optimization. ...
Definition: RbaEngine.h:124
observation_traits_t::vector_residuals_t vector_residuals_t
Definition: RbaEngine.h:107
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
#define DETAILED_PROFILING_ENTER(_STR)
vec_t::const_iterator const_iterator
Definition: map_as_vector.h:56
uint64_t TLandmarkID
Numeric IDs for landmarks.
Definition: srba_types.h:32
iterator find(const size_t i)
Constant-time find, returning an iterator to the pair or to end() if not found (that is...
double total_sqr_error_final
Initial and final total squared error for all the observations.
Definition: RbaEngine.h:131
Scalar * iterator
Definition: eigen_plugins.h:23
This file implements several operations that operate element-wise on individual or pairs of container...
Don't recover any covariance information.
Definition: srba_types.h:178
STL namespace.
const Scalar * const_iterator
Definition: eigen_plugins.h:24
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
double HAp_condition_number
To be computed only if enabled in parameters.compute_condition_number.
Definition: RbaEngine.h:132
landmark_traits< LM_TYPE >::TLandmarkEntry TLandmarkEntry
Definition: srba_types.h:482
void BASE_IMPEXP pause(const std::string &msg=std::string("Press any key to continue...")) MRPT_NO_THROWS
Shows the message "Press any key to continue" (or other custom message) to the current standard outpu...
size_t num_jacobians
Number of Jacobian blocks which had been to be evaluated for each relinearization step...
Definition: RbaEngine.h:125
size_t num_total_scalar_optimized
The total number of dimensions (scalar values) in all the optimized unknowns.
Definition: RbaEngine.h:128
CONTAINER::Scalar sum(const CONTAINER &v)
Computes the sum of all the elements.
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
RBA_OPTIONS::solver_t::extra_results_t extra_results
Other solver-specific output information.
Definition: RbaEngine.h:138
landmark_traits_t::TRelativeLandmarkPos TRelativeLandmarkPos
One landmark position (relative to its base KF)
Definition: RbaEngine.h:98
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
#define DETAILED_PROFILING_LEAVE(_STR)
A templated column-indexed efficient storage of block-sparse Jacobian or Hessian matrices, together with other arbitrary information.
CONTAINER::Scalar norm_inf(const CONTAINER &v)
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
#define ASSERT_ABOVEEQ_(__A, __B)
Generic solver declaration.
#define VERBOSE_LEVEL(_LEVEL)
Definition: RbaEngine.h:25
All the information returned by the local area optimizer.
Definition: RbaEngine.h:117
#define ASSERT_(f)
A partial specialization of CArrayNumeric for double numbers.
Definition: CArrayNumeric.h:74
size_t num_kf2kf_edges_optimized
Number of solved unknowns of type "kf-to-kf edge".
Definition: RbaEngine.h:126
Approximate covariances of landmarks as the inverse of the hessian diagonal blocks.
Definition: srba_types.h:180
#define ASSERTMSG_(f, __ERROR_MSG)
size_t num_kf2lm_edges_optimized
Number of solved unknowns of type "kf-to-landmark".
Definition: RbaEngine.h:127
std::string sprintf_container(const char *fmt, const T &V)
Generates a string for a container in the format [A,B,C,...], and the fmt string for each vector elem...
Definition: string_utils.h:115
void keep_max(T &var, const K test_val)
If the second argument is above the first one, set the first argument to this higher value...
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 >())
void getAsDense(mrpt::math::CMatrixDouble &D, const bool force_symmetry=false, const bool is_col_compressed=true) const
Builds a dense representation of the matrix and saves to a text file.
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