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



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