MRPT  2.0.2
ba_full.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "vision-lgpl-precomp.h" // Precompiled headers
11 
16 #include <map>
17 
18 #include <memory> // unique_ptr
19 
20 #include "ba_internals.h"
21 
22 using namespace std;
23 using namespace mrpt;
24 using namespace mrpt::vision;
25 using namespace mrpt::img;
26 using namespace mrpt::math;
27 
28 // Define -> estimate the inverse of poses; Undefined -> estimate the camera
29 // poses (read the doc of mrpt::vision::bundle_adj_full)
30 #define USE_INVERSE_POSES
31 
32 #ifdef USE_INVERSE_POSES
33 #define INV_POSES_BOOL true
34 #else
35 #define INV_POSES_BOOL false
36 #endif
37 
38 /* ----------------------------------------------------------
39  bundle_adj_full
40 
41  See bundle_adjustment.h for docs.
42 
43  This implementation is almost entirely an adapted version from
44  RobotVision (at OpenSLAM.org) (C) by Hauke Strasdat (Imperial
45  College London), licensed under GNU LGPL.
46  See the related paper: H. Strasdat, J.M.M. Montiel,
47  A.J. Davison: "Scale Drift-Aware Large Scale Monocular SLAM",
48  RSS2010, http://www.roboticsproceedings.org/rss06/p10.html
49 
50  ---------------------------------------------------------- */
52  const TSequenceFeatureObservations& observations,
53  const TCamera& camera_params, TFramePosesVec& frame_poses,
54  TLandmarkLocationsVec& landmark_points,
55  const mrpt::system::TParametersDouble& extra_params,
56  const TBundleAdjustmentFeedbackFunctor user_feedback)
57 {
59 
60  // Generic BA problem dimension numbers:
61  static const unsigned int FrameDof = 6; // Poses: x y z yaw pitch roll
62  static const unsigned int PointDof = 3; // Landmarks: x y z
63  static const unsigned int ObsDim = 2; // Obs: x y (pixels)
64 
65  // Typedefs for this specific BA problem:
66  using MyJacData = JacData<FrameDof, PointDof, ObsDim>;
67  using MyJacDataVec = std::vector<MyJacData>;
68 
69  using Array_O = std::array<double, ObsDim>;
70  using Array_F = CVectorFixedDouble<FrameDof>;
71  using Array_P = CVectorFixedDouble<PointDof>;
75 
76  // Extra params:
77  const bool use_robust_kernel =
78  0 != extra_params.getWithDefaultVal("robust_kernel", 1);
79  const bool verbose = 0 != extra_params.getWithDefaultVal("verbose", 0);
80  const double initial_mu = extra_params.getWithDefaultVal("mu", -1);
81  const size_t max_iters =
82  extra_params.getWithDefaultVal("max_iterations", 50);
83  const size_t num_fix_frames =
84  extra_params.getWithDefaultVal("num_fix_frames", 1);
85  const size_t num_fix_points =
86  extra_params.getWithDefaultVal("num_fix_points", 0);
87  const double kernel_param =
88  extra_params.getWithDefaultVal("kernel_param", 3.0);
89 
90  const bool enable_profiler =
91  0 != extra_params.getWithDefaultVal("profiler", 0);
92 
93  mrpt::system::CTimeLogger profiler(enable_profiler);
94 
95  profiler.enter("bundle_adj_full (complete run)");
96 
97  // Input data sizes:
98  const size_t num_points = landmark_points.size();
99  const size_t num_frames = frame_poses.size();
100  const size_t num_obs = observations.size();
101 
102  ASSERT_ABOVE_(num_frames, 0);
103  ASSERT_ABOVE_(num_points, 0);
104  ASSERT_(num_fix_frames >= 1);
105  ASSERT_ABOVEEQ_(num_frames, num_fix_frames);
106  ASSERT_ABOVEEQ_(num_points, num_fix_points);
107 
108 #ifdef USE_INVERSE_POSES
109  // *Warning*: This implementation assumes inverse camera poses: inverse them
110  // at the entrance and at exit:
111  profiler.enter("invert_poses");
112  for (size_t i = 0; i < num_frames; i++) frame_poses[i].inverse();
113  profiler.leave("invert_poses");
114 #endif
115 
116  MyJacDataVec jac_data_vec(num_obs);
117  vector<Array_O> residual_vec(num_obs);
118  vector<double> kernel_1st_deriv(num_obs);
119 
120  // prepare structure of sparse Jacobians:
121  for (size_t i = 0; i < num_obs; i++)
122  {
123  jac_data_vec[i].frame_id = observations[i].id_frame;
124  jac_data_vec[i].point_id = observations[i].id_feature;
125  }
126 
127  // Compute sparse Jacobians:
128  profiler.enter("compute_Jacobians");
129  ba_compute_Jacobians<INV_POSES_BOOL>(
130  frame_poses, landmark_points, camera_params, jac_data_vec,
131  num_fix_frames, num_fix_points);
132  profiler.leave("compute_Jacobians");
133 
134  profiler.enter("reprojectionResiduals");
136  observations, camera_params, frame_poses, landmark_points, residual_vec,
137  INV_POSES_BOOL, // are poses inverse?
138  use_robust_kernel, kernel_param,
139  use_robust_kernel ? &kernel_1st_deriv : nullptr);
140  profiler.leave("reprojectionResiduals");
141 
143 
144  VERBOSE_COUT << "res: " << res << endl;
145 
146  // Auxiliary vars:
147  Array_F arrF_zeros;
148  arrF_zeros.fill(0);
149  Array_P arrP_zeros;
150  arrP_zeros.fill(0);
151 
152  const size_t num_free_frames = num_frames - num_fix_frames;
153  const size_t num_free_points = num_points - num_fix_points;
154  const size_t len_free_frames = FrameDof * num_free_frames;
155  const size_t len_free_points = PointDof * num_free_points;
156 
157  std::vector<Matrix_FxF> H_f(num_free_frames);
158  std::vector<Array_F> eps_frame(num_free_frames, arrF_zeros);
159  std::vector<Matrix_PxP> H_p(num_free_points);
160  std::vector<Array_P> eps_point(num_free_points, arrP_zeros);
161 
162  profiler.enter("build_gradient_Hessians");
164  observations, residual_vec, jac_data_vec, H_f, eps_frame, H_p,
165  eps_point, num_fix_frames, num_fix_points,
166  use_robust_kernel ? &kernel_1st_deriv : nullptr);
167  profiler.leave("build_gradient_Hessians");
168 
169  double nu = 2;
170  double eps = 1e-16; // 0.000000000000001;
171  bool stop = false;
172  double mu = initial_mu;
173 
174  // Automatic guess of "mu":
175  if (mu < 0)
176  {
177  double norm_max_A = 0;
178  for (size_t j = 0; j < num_free_frames; ++j)
179  for (size_t dim = 0; dim < FrameDof; dim++)
180  keep_max(norm_max_A, H_f[j](dim, dim));
181 
182  for (size_t i = 0; i < num_free_points; ++i)
183  for (size_t dim = 0; dim < PointDof; dim++)
184  keep_max(norm_max_A, H_p[i](dim, dim));
185  double tau = 1e-3;
186  mu = tau * norm_max_A;
187  }
188 
189  Matrix_FxF I_muFrame(UNINITIALIZED_MATRIX);
190  Matrix_PxP I_muPoint(UNINITIALIZED_MATRIX);
191 
192  // Cholesky object, as a pointer to reuse it between iterations:
193  using SparseCholDecompPtr = std::unique_ptr<CSparseMatrix::CholeskyDecomp>;
194 
195  SparseCholDecompPtr ptrCh;
196 
197  for (size_t iter = 0; iter < max_iters; iter++)
198  {
199  VERBOSE_COUT << "iteration: " << iter << endl;
200 
201  // provide feedback to the user:
202  if (user_feedback)
203  user_feedback(
204  iter, res, max_iters, observations, frame_poses,
205  landmark_points);
206 
207  bool has_improved = false;
208  do
209  {
210  profiler.enter("COMPLETE_ITER");
211 
212  VERBOSE_COUT << "mu: " << mu << endl;
213 
214  I_muFrame.setDiagonal(FrameDof, mu);
215  I_muPoint.setDiagonal(PointDof, mu);
216 
217  std::vector<Matrix_FxF> U_star(num_free_frames, I_muFrame);
218  std::vector<Matrix_PxP> V_inv(num_free_points);
219 
220  for (size_t i = 0; i < U_star.size(); ++i) U_star[i] += H_f[i];
221 
222  for (size_t i = 0; i < H_p.size(); ++i)
223  V_inv[i] = (H_p[i] + I_muPoint).inverse_LLt();
224 
225  using WMap = std::map<pair<TCameraPoseID, TLandmarkID>, Matrix_FxP>;
226  WMap W, Y;
227 
228  // For quick look-up of entries in W affecting a given point ID:
229  vector<vector<WMap::iterator>> W_entries(
230  num_points); // Index is "TLandmarkID"
231 
232  MyJacDataVec::const_iterator jac_iter = jac_data_vec.begin();
233  for (TSequenceFeatureObservations::const_iterator it_obs =
234  observations.begin();
235  it_obs != observations.end(); ++it_obs)
236  {
237  const TFeatureID feat_id = it_obs->id_feature;
238  const TCameraPoseID frame_id = it_obs->id_frame;
239 
240  if (jac_iter->J_frame_valid && jac_iter->J_point_valid)
241  {
243  jac_iter->J_frame;
245  jac_iter->J_point;
246  const pair<TCameraPoseID, TLandmarkID> id_pair =
247  make_pair(frame_id, feat_id);
248 
249  const auto tmp =
250  Matrix_FxP(J_frame.transpose() * J_point.asEigen());
251 
252  // W[ids] = J_f^T * J_p
253  // Was: W[id_pair] = tmp;
254  const pair<WMap::iterator, bool>& retInsert =
255  W.insert(make_pair(id_pair, tmp));
256  ASSERT_(retInsert.second == true);
257  W_entries[feat_id].push_back(
258  retInsert.first); // Keep the iterator
259 
260  // Y[ids] = W[ids] * H_p^{-1}
261  Y[id_pair] = tmp * V_inv[feat_id - num_fix_points];
262  }
263  ++jac_iter;
264  }
265 
266  std::map<pair<TCameraPoseID, TLandmarkID>, Matrix_FxF> YW_map;
267  for (size_t i = 0; i < H_f.size(); ++i)
268  YW_map[std::pair<TCameraPoseID, TLandmarkID>(i, i)] = U_star[i];
269 
270  CVectorDouble delta(
271  len_free_frames + len_free_points); // The optimal step
272  CVectorDouble e(len_free_frames);
273 
274  profiler.enter("Schur.build.reduced.frames");
275  for (size_t j = 0; j < num_free_frames; ++j)
276  ::memcpy(
277  &e[j * FrameDof], &eps_frame[j][0],
278  sizeof(e[0]) * FrameDof); // e.slice(j*FrameDof,FrameDof) =
279  // AT(eps_frame,j);
280 
281  for (WMap::iterator Y_ij = Y.begin(); Y_ij != Y.end(); ++Y_ij)
282  {
283  const TLandmarkID point_id = Y_ij->first.second;
284  const size_t i =
285  Y_ij->first.second - num_fix_points; // point index
286  const size_t j =
287  Y_ij->first.first - num_fix_frames; // frame index
288 
289  const vector<WMap::iterator>& iters =
290  W_entries[point_id]; //->second;
291 
292  for (size_t itIdx = 0; itIdx < iters.size(); itIdx++)
293  // for (size_t k=0; k<num_free_frames; ++k)
294  {
295  const WMap::iterator& W_ik = iters[itIdx];
296  const TLandmarkID k = W_ik->first.first - num_fix_frames;
297 
298  const auto YWt = Matrix_FxF(
299  Y_ij->second.asEigen() * W_ik->second.transpose());
300  // YWt*=-1.0; // The "-" sign is taken into account below:
301 
302  const pair<TCameraPoseID, TLandmarkID> ids_jk =
303  pair<TCameraPoseID, TLandmarkID>(j, k);
304 
305  auto it = YW_map.find(ids_jk);
306  if (it != YW_map.end())
307  it->second -= YWt; // += (-YWt);
308  else
309  YW_map[ids_jk] = -YWt;
310  }
311 
312  const auto r =
313  (Y_ij->second.asEigen() * eps_point[i].asEigen()).eval();
314  for (size_t k = 0; k < FrameDof; k++)
315  e[j * FrameDof + k] -= r[k];
316  }
317  profiler.leave("Schur.build.reduced.frames");
318 
319  profiler.enter("sS:ALL");
320  profiler.enter("sS:fill");
321 
322  VERBOSE_COUT << "Entries in YW_map:" << YW_map.size() << endl;
323 
324  CSparseMatrix sS(len_free_frames, len_free_frames);
325 
326  for (auto it = YW_map.begin(); it != YW_map.end(); ++it)
327  {
328  const pair<TCameraPoseID, TLandmarkID>& ids = it->first;
329  const Matrix_FxF& YW = it->second;
330  sS.insert_submatrix(
331  ids.first * FrameDof, ids.second * FrameDof, YW);
332  }
333  profiler.leave("sS:fill");
334 
335  // Compress the sparse matrix:
336  profiler.enter("sS:compress");
337  sS.compressFromTriplet();
338  profiler.leave("sS:compress");
339 
340  try
341  {
342  profiler.enter("sS:chol");
343  if (!ptrCh.get())
344  ptrCh.reset(new CSparseMatrix::CholeskyDecomp(sS));
345  else
346  ptrCh.get()->update(sS);
347  profiler.leave("sS:chol");
348 
349  profiler.enter("sS:backsub");
350  CVectorDouble bck_res;
351  ptrCh->backsub(e, bck_res); // Ax = b --> delta= x*
352  ::memcpy(
353  &delta[0], &bck_res[0],
354  bck_res.size() * sizeof(bck_res[0])); // delta.slice(0,...)
355  // = Ch.backsub(e);
356  profiler.leave("sS:backsub");
357  profiler.leave("sS:ALL");
358  }
359  catch (CExceptionNotDefPos&)
360  {
361  profiler.leave("sS:ALL");
362  // not positive definite so increase mu and try again
363  mu *= nu;
364  nu *= 2.;
365  stop = (mu > 999999999.f);
366  continue;
367  }
368 
369  profiler.enter("PostSchur.landmarks");
370 
371  CVectorDouble g(len_free_frames + len_free_points);
372  ::memcpy(
373  &g[0], &e[0],
374  len_free_frames *
375  sizeof(
376  g[0])); // g.slice(0,FrameDof*(num_frames-num_fix_frames))
377  // = e;
378 
379  for (size_t i = 0; i < num_free_points; ++i)
380  {
381  Array_P tmp = eps_point[i];
382 
383  for (size_t j = 0; j < num_free_frames; ++j)
384  {
385  WMap::iterator W_ij;
386  W_ij = W.find(make_pair(
387  TCameraPoseID(j + num_fix_frames),
388  TLandmarkID(i + num_fix_points)));
389 
390  if (W_ij != W.end())
391  {
392  const Array_F v(&delta[j * FrameDof]);
393  tmp -= Array_P(W_ij->second.transpose() * v.asEigen());
394  }
395  }
396  const auto Vi_tmp = Array_P(V_inv[i] * tmp);
397 
398  ::memcpy(
399  &delta[len_free_frames + i * PointDof], &Vi_tmp[0],
400  sizeof(Vi_tmp[0]) * PointDof);
401  ::memcpy(
402  &g[len_free_frames + i * PointDof], &eps_point[i][0],
403  sizeof(eps_point[0][0]) * PointDof);
404  }
405  profiler.leave("PostSchur.landmarks");
406 
407  // Vars for temptative new estimates:
408  TFramePosesVec new_frame_poses;
409  TLandmarkLocationsVec new_landmark_points;
410 
411  profiler.enter("add_se3_deltas_to_frames");
413  frame_poses, delta, 0, len_free_frames, new_frame_poses,
414  num_fix_frames);
415  profiler.leave("add_se3_deltas_to_frames");
416 
417  profiler.enter("add_3d_deltas_to_points");
419  landmark_points, delta, len_free_frames, len_free_points,
420  new_landmark_points, num_fix_points);
421  profiler.leave("add_3d_deltas_to_points");
422 
423  vector<Array_O> new_residual_vec(num_obs);
424  vector<double> new_kernel_1st_deriv(num_obs);
425 
426  profiler.enter("reprojectionResiduals");
427  double res_new = mrpt::vision::reprojectionResiduals(
428  observations, camera_params, new_frame_poses,
429  new_landmark_points, new_residual_vec,
430  INV_POSES_BOOL, // are poses inverse?
431  use_robust_kernel, kernel_param,
432  use_robust_kernel ? &new_kernel_1st_deriv : nullptr);
433  profiler.leave("reprojectionResiduals");
434 
435  MRPT_CHECK_NORMAL_NUMBER(res_new);
436 
437  has_improved = (res_new < res);
438 
439  if (has_improved)
440  {
441  // rho = (res-)/ (delta.array()*(mu*delta + g).array() ).sum();
442  // Good: Accept new values
443  VERBOSE_COUT << "new total sqr.err=" << res_new
444  << " avr.err(px):" << std::sqrt(res / num_obs)
445  << "->" << std::sqrt(res_new / num_obs) << endl;
446 
447  // swap is faster than "="
448  frame_poses.swap(new_frame_poses);
449  landmark_points.swap(new_landmark_points);
450  residual_vec.swap(new_residual_vec);
451  kernel_1st_deriv.swap(new_kernel_1st_deriv);
452 
453  res = res_new;
454 
455  profiler.enter("compute_Jacobians");
456  ba_compute_Jacobians<INV_POSES_BOOL>(
457  frame_poses, landmark_points, camera_params, jac_data_vec,
458  num_fix_frames, num_fix_points);
459  profiler.leave("compute_Jacobians");
460 
461  // Reset to zeros:
462  H_f.assign(num_free_frames, Matrix_FxF());
463  H_p.assign(num_free_points, Matrix_PxP());
464  eps_frame.assign(num_free_frames, arrF_zeros);
465  eps_point.assign(num_free_points, arrP_zeros);
466 
467  profiler.enter("build_gradient_Hessians");
469  observations, residual_vec, jac_data_vec, H_f, eps_frame,
470  H_p, eps_point, num_fix_frames, num_fix_points,
471  use_robust_kernel ? &kernel_1st_deriv : nullptr);
472  profiler.leave("build_gradient_Hessians");
473 
474  stop = norm_inf(g) <= eps;
475  // mu *= max(1.0/3.0, 1-std::pow(2*rho-1,3.0) );
476  mu *= 0.1;
477  mu = std::max(mu, 1e-100);
478  nu = 2.0;
479  }
480  else
481  {
482  VERBOSE_COUT << "no update: res vs.res_new " << res << " vs. "
483  << res_new << endl;
484  mu *= nu;
485  nu *= 2.0;
486  stop = (mu > 1e9);
487  }
488 
489  profiler.leave("COMPLETE_ITER");
490  } while (!has_improved && !stop);
491 
492  if (stop) break;
493 
494  } // end for each "iter"
495 
496 // *Warning*: This implementation assumes inverse camera poses: inverse them at
497 // the entrance and at exit:
498 #ifdef USE_INVERSE_POSES
499  profiler.enter("invert_poses");
500  for (size_t i = 0; i < num_frames; i++) frame_poses[i].inverse();
501  profiler.leave("invert_poses");
502 #endif
503 
504  profiler.leave("bundle_adj_full (complete run)");
505 
506  return res;
507  MRPT_END
508 }
A compile-time fixed-size numeric matrix container.
Definition: CMatrixFixed.h:33
uint64_t TCameraPoseID
Unique IDs for camera frames (poses)
#define MRPT_START
Definition: exceptions.h:241
uint64_t TFeatureID
Definition of a feature ID.
uint64_t TLandmarkID
Unique IDs for landmarks.
Used in mrpt::math::CSparseMatrix.
Definition: CSparseMatrix.h:37
This file implements several operations that operate element-wise on individual or pairs of container...
size_type size() const
Get a 2-vector with [NROWS NCOLS] (as in MATLAB command size(x))
Auxiliary class to hold the results of a Cholesky factorization of a sparse matrix.
A sparse matrix structure, wrapping T.
Definition: CSparseMatrix.h:98
STL namespace.
void compressFromTriplet()
ONLY for TRIPLET matrices: convert the matrix in a column-compressed form.
void add_se3_deltas_to_frames(const mrpt::vision::TFramePosesVec &frame_poses, const mrpt::math::CVectorDouble &delta, const size_t delta_first_idx, const size_t delta_num_vals, mrpt::vision::TFramePosesVec &new_frame_poses, const size_t num_fix_frames)
For each pose in the vector frame_poses, adds a "delta" increment to the manifold, with the "delta" given in the se(3) Lie algebra:
A complete sequence of observations of features from different camera frames (poses).
#define VERBOSE_COUT
Definition: ba_internals.h:44
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:120
std::vector< mrpt::poses::CPose3D > TFramePosesVec
A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs...
This base provides a set of functions for maths stuff.
#define MRPT_CHECK_NORMAL_NUMBER(v)
Throws an exception if the number is NaN, IND, or +/-INF, or return the same number otherwise...
Definition: exceptions.h:125
void add_3d_deltas_to_points(const mrpt::vision::TLandmarkLocationsVec &landmark_points, const mrpt::math::CVectorDouble &delta, const size_t delta_first_idx, const size_t delta_num_vals, mrpt::vision::TLandmarkLocationsVec &new_landmark_points, const size_t num_fix_points)
For each pose in the vector frame_poses, adds a "delta" increment to the manifold, with the "delta" given in the se(3) Lie algebra:
Definition: ba_common.cpp:366
const double eps
#define INV_POSES_BOOL
Definition: ba_full.cpp:33
Classes for computer vision, detectors, features, etc.
Definition: CDifodo.h:17
Parameters for the Brown-Conrady camera lens distortion model.
Definition: TCamera.h:26
#define ASSERT_ABOVEEQ_(__A, __B)
Definition: exceptions.h:167
double reprojectionResiduals(const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::img::TCamera &camera_params, const mrpt::vision::TFramePosesVec &frame_poses, const mrpt::vision::TLandmarkLocationsVec &landmark_points, std::vector< std::array< double, 2 >> &out_residuals, const bool frame_poses_are_inverse, const bool use_robust_kernel=true, const double kernel_param=3.0, std::vector< double > *out_kernel_1st_deriv=nullptr)
Compute reprojection error vector (used from within Bundle Adjustment methods, but can be used in gen...
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...
CONTAINER::Scalar norm_inf(const CONTAINER &v)
void enter(const std::string_view &func_name) noexcept
Start of a named section.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
RET getWithDefaultVal(const std::string &s, const RET &defaultVal) const
A const version of the [] operator and with a default value in case the parameter is not set (for usa...
Definition: TParameters.h:90
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X), among other stats.
#define ASSERT_ABOVE_(__A, __B)
Definition: exceptions.h:155
#define MRPT_END
Definition: exceptions.h:245
void insert_submatrix(const size_t row, const size_t col, const MATRIX &M)
ONLY for TRIPLET matrices: insert a given matrix (in any of the MRPT formats) at a given location of ...
void ba_build_gradient_Hessians(const TSequenceFeatureObservations &observations, const std::vector< std::array< double, 2 >> &residual_vec, const std::vector< JacData< 6, 3, 2 >> &jac_data_vec, std::vector< mrpt::math::CMatrixFixed< double, 6, 6 >> &U, std::vector< CVectorFixedDouble< 6 >> &eps_frame, std::vector< mrpt::math::CMatrixFixed< double, 3, 3 >> &V, std::vector< CVectorFixedDouble< 3 >> &eps_point, const size_t num_fix_frames, const size_t num_fix_points, const vector< double > *kernel_1st_deriv)
Construct the BA linear system.
EIGEN_MAP asEigen()
Get as an Eigen-compatible Eigen::Map object.
Definition: CMatrixFixed.h:251
double leave(const std::string_view &func_name) noexcept
End of a named section.
double bundle_adj_full(const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::img::TCamera &camera_params, mrpt::vision::TFramePosesVec &frame_poses, mrpt::vision::TLandmarkLocationsVec &landmark_points, const mrpt::system::TParametersDouble &extra_params=mrpt::system::TParametersDouble(), const mrpt::vision::TBundleAdjustmentFeedbackFunctor user_feedback=mrpt::vision::TBundleAdjustmentFeedbackFunctor())
Sparse Levenberg-Marquart solution to bundle adjustment - optimizes all the camera frames & the landm...
std::function< void(const size_t cur_iter, const double cur_total_sq_error, const size_t max_iters, const mrpt::vision::TSequenceFeatureObservations &input_observations, const mrpt::vision::TFramePosesVec &current_frame_estimate, const mrpt::vision::TLandmarkLocationsVec &current_landmark_estimate)> TBundleAdjustmentFeedbackFunctor
A functor type for BA methods.
std::vector< mrpt::math::TPoint3D > TLandmarkLocationsVec
A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs.
void memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) noexcept
An OS and compiler independent version of "memcpy".



Page generated by Doxygen 1.8.14 for MRPT 2.0.2 Git: 9b4fd2465 Mon May 4 16:59:08 2020 +0200 at lun may 4 17:26:07 CEST 2020