14 namespace mrpt {
namespace srba {
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.
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);
25 # define DETAILED_PROFILING_ENTER(_STR)
26 # define DETAILED_PROFILING_LEAVE(_STR)
32 template <
bool USE_SCHUR,
bool DENSE_CHOL,
class RBA_ENGINE>
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,
48 const std::vector<size_t> & in_observation_indices_to_optimize
56 m_profiler.enter(
"opt");
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;
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());
72 for (
size_t i=0;i<run_k2k_edges_in.size();i++)
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] );
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;
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;
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";
90 for (
size_t i=0;i<run_feat_ids_in.size();i++)
93 ASSERT_(feat_id<rba_state.all_lms.size())
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")
102 const typename TSparseBlocksJacobians_dh_df::col_t & col_i = rba_state.lin_system.dh_df.getCol( it_remap->second );
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"; }
112 const size_t nUnknowns_k2k = run_k2k_edges.size();
113 const size_t nUnknowns_k2f = run_feat_ids.size();
115 const size_t idx_start_f = POSE_DIMS*nUnknowns_k2k;
116 const size_t nUnknowns_scalars = POSE_DIMS*nUnknowns_k2k + LM_DIMS*nUnknowns_k2f;
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++)
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();
129 & rba_state.k2k_edges[run_k2k_edges[i]];
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++)
144 dh_df[i] = &rba_state.lin_system.dh_df.getCol( it_remap->second );
145 k2f_edge_unknowns[i] = lm_e.rfp;
154 std::map<size_t,size_t> obs_global_idx2residual_idx;
156 std::vector<TObsUsed> involved_obs;
157 if (in_observation_indices_to_optimize.empty())
160 for (
size_t i=0;i<nUnknowns_k2k;i++)
163 typename TSparseBlocksJacobians_dh_dAp::col_t *col = dh_dAp[i];
167 const size_t global_obs_idx = it->first;
168 const size_t obs_idx = involved_obs.size();
170 obs_global_idx2residual_idx[global_obs_idx] = obs_idx;
172 involved_obs.push_back(
TObsUsed (global_obs_idx,
173 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
174 &(*rba_state.all_observations[global_obs_idx])
176 &rba_state.all_observations[global_obs_idx]
182 for (
size_t i=0;i<nUnknowns_k2f;i++)
185 typename TSparseBlocksJacobians_dh_df::col_t *col = dh_df[i];
189 const size_t global_obs_idx = it->first;
193 if (it_o == obs_global_idx2residual_idx.end())
195 const size_t obs_idx = involved_obs.size();
197 obs_global_idx2residual_idx[global_obs_idx] = obs_idx;
199 involved_obs.push_back(
TObsUsed( global_obs_idx,
200 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
201 &(*rba_state.all_observations[global_obs_idx])
203 &rba_state.all_observations[global_obs_idx]
213 const size_t nInObs = in_observation_indices_to_optimize.size();
214 for (
size_t i=0;i<nInObs;i++)
216 const size_t global_obs_idx = in_observation_indices_to_optimize[i];
217 const size_t obs_idx = involved_obs.size();
219 obs_global_idx2residual_idx[global_obs_idx] = obs_idx;
221 involved_obs.push_back(
TObsUsed(global_obs_idx,
222 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
223 &(*rba_state.all_observations[global_obs_idx])
225 &rba_state.all_observations[global_obs_idx]
233 const size_t nObs = involved_obs.size();
240 std::set<TKeyFrameID> kfs_num_spantrees_to_update;
241 prepare_Jacobians_required_tree_roots(kfs_num_spantrees_to_update, dh_dAp, dh_df);
251 const size_t count_span_tree_num_update = rba_state.spanning_tree.update_numeric(kfs_num_spantrees_to_update,
false );
257 std::vector<const pose_flag_t*> list_of_required_num_poses;
264 for (
size_t i=0;i<nObs;i++)
265 rba_state.all_observations_Jacob_validity[ involved_obs[i].obs_idx ] = 1;
271 const size_t count_jacobians = recompute_all_Jacobians(dh_dAp, dh_df, &list_of_required_num_poses );
277 for (
size_t i=0;i<list_of_required_num_poses.size();i++)
278 list_of_required_num_poses[i]->mark_outdated();
280 #if 0 // Save a sparse block representation of the Jacobian.
282 static unsigned int dbg_idx = 0;
284 rba_state.lin_system.dh_dAp.getBinaryBlocksRepresentation(Jbin);
286 rba_state.lin_system.dh_dAp.saveToTextFileAsDense(
mrpt::format(
"sparse_jacobs_%05u.txt",dbg_idx));
304 sparse_hessian_build_symbolic(
311 size_t nInvalidJacobs = 0;
313 nInvalidJacobs += sparse_hessian_update_numeric(HAp);
314 nInvalidJacobs += sparse_hessian_update_numeric(Hf);
315 nInvalidJacobs += sparse_hessian_update_numeric(HApf);
319 VERBOSE_LEVEL(1) <<
"[OPT] " << nInvalidJacobs <<
" Jacobian blocks ignored for 'invalid'.\n";
321 VERBOSE_LEVEL(2) <<
"[OPT] Individual Jacobs: " << count_jacobians <<
" #k2k_edges=" << nUnknowns_k2k <<
" #k2f_edges=" << nUnknowns_k2f <<
" #obs=" << nObs << std::endl;
325 if (m_verbose_level>=2 && !run_k2k_edges.empty())
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;
336 ASSERT_ABOVEEQ_(OBS_DIMS*nObs,POSE_DIMS*nUnknowns_k2k+LM_DIMS*nUnknowns_k2f)
343 const double max_gradient_to_stop = 1e-15;
351 double Hess_diag_max = 0;
352 for (
size_t i=0;i<nUnknowns_k2k;i++)
356 const double Hii_max = HAp.
getCol(i)[i].num.diagonal().maxCoeff();
359 for (
size_t i=0;i<nUnknowns_k2f;i++)
363 const double Hii_max = Hf.
getCol(i)[i].num.diagonal().maxCoeff();
367 const double tau = 1e-3;
368 lambda = tau * Hess_diag_max;
379 double total_proj_error = reprojection_residuals(
385 double RMSE = std::sqrt(total_proj_error/nObs);
396 VERBOSE_LEVEL(1) <<
"[OPT] LM: Initial RMSE=" << RMSE <<
" #Jcbs=" << count_jacobians <<
" #k2k_edges=" << nUnknowns_k2k <<
" #k2f_edges=" << nUnknowns_k2f <<
" #obs=" << nObs << std::endl;
398 if (parameters.srba.feedback_user_iteration)
399 (*parameters.srba.feedback_user_iteration)(0,total_proj_error,RMSE);
403 Eigen::VectorXd minus_grad;
406 compute_minus_gradient( minus_grad, dh_dAp, dh_df, residuals, obs_global_idx2residual_idx);
412 my_solver_t my_solver(
413 m_verbose_level, m_profiler,
421 const double MAX_LAMBDA = this->parameters.srba.max_lambda;
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;
427 vector<stlplus::smart_ptr<TRelativeLandmarkPos> > old_k2f_edge_unknowns;
429 vector<k2k_edge_t> old_k2k_edge_unknowns;
430 vector<pose_flag_t> old_span_tree;
431 vector<TRelativeLandmarkPos> old_k2f_edge_unknowns;
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) );
441 for (iter=0; iter<this->parameters.srba.max_iters && !stop; iter++)
447 if (lambda>=MAX_LAMBDA)
450 VERBOSE_LEVEL(2) <<
"[OPT] LM end criterion: lambda too large. " << lambda <<
">=" <<MAX_LAMBDA<<endl;
452 if (RMSE < this->parameters.srba.max_error_per_obs_to_stop)
455 VERBOSE_LEVEL(2) <<
"[OPT] LM end criterion: error too small. " << RMSE <<
"<" <<this->parameters.srba.max_error_per_obs_to_stop<<endl;
458 while(rho<=0 && !stop)
463 if ( !my_solver.solve(lambda) )
468 stop = (lambda>MAX_LAMBDA);
470 VERBOSE_LEVEL(2) <<
"[OPT] LM iter #"<< iter <<
" NotDefPos in Cholesky. Retrying with lambda=" << lambda << std::endl;
478 old_k2k_edge_unknowns.resize(nUnknowns_k2k);
479 for (
size_t i=0;i<nUnknowns_k2k;i++)
481 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
484 old_k2k_edge_unknowns[i] = *k2k_edge_unknowns[i];
488 old_k2f_edge_unknowns.resize(nUnknowns_k2f);
489 for (
size_t i=0;i<nUnknowns_k2f;i++)
491 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
494 old_k2f_edge_unknowns[i] = *k2f_edge_unknowns[i];
503 for (
size_t i=0;i<nUnknowns_k2k;i++)
506 const pose_t &old_pose = k2k_edge_unknowns[i]->inv_pose;
512 se_traits_t::pseudo_exp(incr,incrPose);
516 new_pose.composeFrom(incrPose, old_pose);
518 VERBOSE_LEVEL(3) <<
"[OPT] Update k2k_edge[" <<i<<
"]: eps=" << incr.transpose() <<
"\n" <<
" such that: " << old_pose <<
" => " << new_pose <<
"\n";
521 k2k_edge_unknowns[i]->inv_pose = new_pose;
529 for (
size_t i=0;i<nUnknowns_k2f;i++)
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];
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++)
550 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
552 old_span_tree[i]->pose = list_of_required_num_poses[i]->pose;
554 old_span_tree[i].pose = list_of_required_num_poses[i]->pose;
562 for (
size_t i=0;i<list_of_required_num_poses.size();i++)
563 list_of_required_num_poses[i]->mark_outdated();
565 rba_state.spanning_tree.update_numeric(kfs_num_spantrees_to_update,
true );
573 double new_total_proj_error = reprojection_residuals(
579 const double new_RMSE = std::sqrt(new_total_proj_error/nObs);
581 const double error_reduction_ratio = total_proj_error>0 ? (total_proj_error - new_total_proj_error)/total_proj_error : 0;
585 rho = (total_proj_error - new_total_proj_error)/ (my_solver.delta_eps.array()*(lambda*my_solver.delta_eps + minus_grad).array() ).
sum();
592 bool do_relinearize = (error_reduction_ratio<0 || error_reduction_ratio> this->parameters.srba.min_error_reduction_ratio_to_relinearize );
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);
601 residuals.swap( new_residuals );
603 total_proj_error = new_total_proj_error;
612 for (
size_t i=0;i<nObs;i++)
613 rba_state.all_observations_Jacob_validity[ involved_obs[i].obs_idx ] = 1;
618 recompute_all_Jacobians(dh_dAp, dh_df);
623 sparse_hessian_update_numeric(HAp);
624 sparse_hessian_update_numeric(Hf);
625 sparse_hessian_update_numeric(HApf);
628 my_solver.realize_relinearized();
633 compute_minus_gradient( minus_grad, dh_dAp, dh_df, residuals, obs_global_idx2residual_idx);
637 if (norm_inf_min_grad<=max_gradient_to_stop)
639 VERBOSE_LEVEL(2) <<
"[OPT] LM end criterion: norm_inf(minus_grad) below threshold: " << norm_inf_min_grad <<
" <= " <<max_gradient_to_stop<<endl;
642 if (RMSE<this->parameters.srba.max_error_per_obs_to_stop)
644 VERBOSE_LEVEL(2) <<
"[OPT] LM end criterion: RMSE below threshold: " << RMSE <<
" < " <<this->parameters.srba.max_error_per_obs_to_stop<<endl;
647 if (rho>this->parameters.srba.max_rho)
649 VERBOSE_LEVEL(2) <<
"[OPT] LM end criterion: rho above threshold: " << rho <<
" > " <<this->parameters.srba.max_rho<<endl;
656 my_solver.realize_lambda_changed();
665 const size_t nReqNumPoses = list_of_required_num_poses.size();
666 for (
size_t i=0;i<nReqNumPoses;i++)
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;
671 const_cast<pose_flag_t*
>(list_of_required_num_poses[i])->pose = old_span_tree[i].pose;
677 for (
size_t i=0;i<nUnknowns_k2k;i++)
679 *k2k_edge_unknowns[i] =
680 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
681 *old_k2k_edge_unknowns[i];
683 old_k2k_edge_unknowns[i];
686 for (
size_t i=0;i<nUnknowns_k2f;i++)
688 *k2f_edge_unknowns[i] =
689 #ifdef SRBA_WORKAROUND_MSVC9_DEQUE_BUG
690 *old_k2f_edge_unknowns[i];
692 old_k2f_edge_unknowns[i];
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;
701 stop = (lambda>MAX_LAMBDA);
703 my_solver.realize_lambda_changed();
713 std::cout <<
"residuals" << std::endl;
714 for(
size_t r = 0; r < residuals.size(); ++r )
716 std::cout << involved_obs[r].k2f->obs.obs.feat_id <<
","
717 << residuals[r][0] <<
","
718 << residuals[r][1] <<
","
719 << residuals[r][2] <<
","
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];
728 std::cout <<
" <-- spurious( " << totalres <<
")";
730 std::cout << std::endl;
732 cout <<
"done" << std::endl;
741 rba_state.unknown_lms_inf_matrices.clear();
742 switch (parameters.srba.cov_recovery)
748 for (
size_t i=0;i<nUnknowns_k2f;i++)
750 if (!my_solver.was_ith_feature_invertible(i))
753 const typename hessian_traits_t::TSparseBlocksHessian_f::col_t & col_i = Hf.
getCol(i);
754 ASSERT_(col_i.rbegin()->first==i)
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;
763 throw std::runtime_error(
"Unknown value found for 'parameters.srba.cov_recovery'");
767 if (parameters.srba.compute_condition_number)
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();
787 if (m_verbose_level>=2 && !run_k2k_edges.empty())
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;
800 m_profiler.leave(
"opt");
803 VERBOSE_LEVEL(1) <<
"[OPT] Final RMSE=" << RMSE <<
" #iters=" << iter <<
"\n";
observation_traits_t::vector_residuals_t vector_residuals_t
#define DETAILED_PROFILING_ENTER(_STR)
vec_t::const_iterator const_iterator
uint64_t TLandmarkID
Numeric IDs for landmarks.
iterator find(const size_t i)
Constant-time find, returning an iterator to the pair or to end() if not found (that is...
This file implements several operations that operate element-wise on individual or pairs of container...
Don't recover any covariance information.
const Scalar * const_iterator
Each of the observations used during the optimization.
kf2kf_pose_traits_t::pose_flag_t pose_flag_t
KF2KF_POSE_TYPE::pose_t pose_t
The type of relative poses (e.g. mrpt::poses::CPose3D)
Keyframe-to-keyframe edge: an unknown of the problem.
landmark_traits< LM_TYPE >::TLandmarkEntry TLandmarkEntry
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...
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.
landmark_traits_t::TRelativeLandmarkPos TRelativeLandmarkPos
One landmark position (relative to its base KF)
#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)
col_t & getCol(const size_t idx)
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)
A partial specialization of CArrayNumeric for double numbers.
Approximate covariances of landmarks as the inverse of the hessian diagonal blocks.
#define ASSERTMSG_(f, __ERROR_MSG)
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...
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)