31 #define USE_INVERSE_POSES 33 #ifdef USE_INVERSE_POSES 34 #define INV_POSES_BOOL true 36 #define INV_POSES_BOOL false 62 static const unsigned int FrameDof = 6;
63 static const unsigned int PointDof = 3;
64 static const unsigned int ObsDim = 2;
70 typedef std::array<double, ObsDim> Array_O;
78 const bool use_robust_kernel =
82 const size_t max_iters =
84 const size_t num_fix_frames =
86 const size_t num_fix_points =
88 const double kernel_param =
91 const bool enable_profiler =
96 profiler.
enter(
"bundle_adj_full (complete run)");
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();
109 #ifdef USE_INVERSE_POSES 112 profiler.
enter(
"invert_poses");
113 for (
size_t i = 0; i < num_frames; i++) frame_poses[i].
inverse();
114 profiler.
leave(
"invert_poses");
117 MyJacDataVec jac_data_vec(num_obs);
118 vector<Array_O> residual_vec(num_obs);
119 vector<double> kernel_1st_deriv(num_obs);
122 for (
size_t i = 0; i < num_obs; i++)
124 jac_data_vec[i].frame_id = observations[i].id_frame;
125 jac_data_vec[i].point_id = observations[i].id_feature;
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");
135 profiler.
enter(
"reprojectionResiduals");
137 observations, camera_params, frame_poses, landmark_points, residual_vec,
139 use_robust_kernel, kernel_param,
140 use_robust_kernel ? &kernel_1st_deriv :
nullptr);
141 profiler.
leave(
"reprojectionResiduals");
149 arrF_zeros.assign(0);
151 arrP_zeros.assign(0);
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;
160 num_free_frames, arrF_zeros);
163 num_free_points, arrP_zeros);
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");
175 double mu = initial_mu;
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));
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));
189 mu = tau * norm_max_A;
196 typedef std::unique_ptr<CSparseMatrix::CholeskyDecomp> SparseCholDecompPtr;
198 SparseCholDecompPtr ptrCh;
200 for (
size_t iter = 0; iter < max_iters; iter++)
207 iter,
res, max_iters, observations, frame_poses,
210 bool has_improved =
false;
213 profiler.
enter(
"COMPLETE_ITER");
217 I_muFrame.unit(FrameDof, mu);
218 I_muPoint.unit(PointDof, mu);
221 num_free_frames, I_muFrame);
224 for (
size_t i = 0; i < U_star.size(); ++i) U_star[i] += H_f[i];
226 for (
size_t i = 0; i < H_p.size(); ++i)
227 (H_p[i] + I_muPoint).inv_fast(V_inv[i]);
230 Matrix_FxP>::map_t WMap;
234 vector<vector<WMap::iterator>> W_entries(
239 observations.begin();
240 it_obs != observations.end(); ++it_obs)
242 const TFeatureID feat_id = it_obs->id_feature;
245 if (jac_iter->J_frame_valid && jac_iter->J_point_valid)
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);
255 tmp.multiply_AtB(J_frame, J_point);
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(
266 Y[id_pair].multiply_AB(
267 tmp, V_inv[feat_id - num_fix_points]);
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];
278 len_free_frames + len_free_points);
281 profiler.
enter(
"Schur.build.reduced.frames");
282 for (
size_t j = 0; j < num_free_frames; ++j)
284 &e[j * FrameDof], &eps_frame[j][0],
285 sizeof(e[0]) * FrameDof);
292 Y_ij->first.second - num_fix_points;
294 Y_ij->first.first - num_fix_frames;
296 const vector<WMap::iterator>& iters =
299 for (
size_t itIdx = 0; itIdx < iters.size(); itIdx++)
303 const TLandmarkID k = W_ik->first.first - num_fix_frames;
307 YWt.multiply_ABt(Y_ij->second, W_ik->second);
310 const pair<TCameraPoseID, TLandmarkID> ids_jk =
311 pair<TCameraPoseID, TLandmarkID>(j, k);
316 if (it != YW_map.end())
319 YW_map[ids_jk] = YWt * (-1.0);
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];
327 profiler.
leave(
"Schur.build.reduced.frames");
329 profiler.
enter(
"sS:ALL");
330 profiler.
enter(
"sS:fill");
332 VERBOSE_COUT <<
"Entries in YW_map:" << YW_map.size() << endl;
339 it != YW_map.end(); ++it)
341 const pair<TCameraPoseID, TLandmarkID>&
ids = it->first;
342 const Matrix_FxF& YW = it->second;
344 ids.first * FrameDof,
ids.second * FrameDof, YW);
346 profiler.
leave(
"sS:fill");
349 profiler.
enter(
"sS:compress");
351 profiler.
leave(
"sS:compress");
355 profiler.
enter(
"sS:chol");
359 ptrCh.get()->update(sS);
360 profiler.
leave(
"sS:chol");
362 profiler.
enter(
"sS:backsub");
364 ptrCh->backsub(e, bck_res);
366 &delta[0], &bck_res[0],
367 bck_res.size() *
sizeof(bck_res[0]));
369 profiler.
leave(
"sS:backsub");
370 profiler.
leave(
"sS:ALL");
374 profiler.
leave(
"sS:ALL");
378 stop = (mu > 999999999.f);
382 profiler.
enter(
"PostSchur.landmarks");
392 for (
size_t i = 0; i < num_free_points; ++i)
397 for (
size_t j = 0; j < num_free_frames; ++j)
409 const Array_F
v(&delta[j * FrameDof]);
411 W_ij->second.multiply_Atb(
v,
r);
416 V_inv[i].multiply_Ab(tmp, Vi_tmp);
419 &delta[len_free_frames + i * PointDof], &Vi_tmp[0],
420 sizeof(Vi_tmp[0]) * PointDof);
422 &
g[len_free_frames + i * PointDof], &eps_point[i][0],
423 sizeof(eps_point[0][0]) * PointDof);
425 profiler.
leave(
"PostSchur.landmarks");
431 profiler.
enter(
"add_se3_deltas_to_frames");
433 frame_poses, delta, 0, len_free_frames, new_frame_poses,
435 profiler.
leave(
"add_se3_deltas_to_frames");
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");
443 vector<Array_O> new_residual_vec(num_obs);
444 vector<double> new_kernel_1st_deriv(num_obs);
446 profiler.
enter(
"reprojectionResiduals");
448 observations, camera_params, new_frame_poses,
449 new_landmark_points, new_residual_vec,
451 use_robust_kernel, kernel_param,
452 use_robust_kernel ? &new_kernel_1st_deriv :
nullptr);
453 profiler.
leave(
"reprojectionResiduals");
457 has_improved = (res_new <
res);
464 <<
" avr.err(px):" << std::sqrt(
res / num_obs)
465 <<
"->" << std::sqrt(res_new / num_obs) << endl;
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);
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");
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);
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");
497 mu = std::max(mu, 1e-100);
509 profiler.
leave(
"COMPLETE_ITER");
510 }
while (!has_improved && !stop);
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");
524 profiler.
leave(
"bundle_adj_full (complete run)");
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)
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...
Auxiliary class to hold the results of a Cholesky factorization of a sparse matrix.
A sparse matrix structure, wrapping T.
void compressFromTriplet()
ONLY for TRIPLET matrices: convert the matrix in a column-compressed form.
const Scalar * const_iterator
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:
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).
Used in mrpt::math::CSparseMatrix.
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.
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:
Eigen::Matrix< dataType, 4, 4 > inverse(Eigen::Matrix< dataType, 4, 4 > &pose)
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...
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...
uint64_t TCameraPoseID
Unique IDs for camera frames (poses)
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
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.
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...
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X), among other stats.
double leave(const char *func_name)
End of a named section.
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.
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...
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 ¤t_frame_estimate, const mrpt::vision::TLandmarkLocationsVec ¤t_landmark_estimate)> TBundleAdjustmentFeedbackFunctor
A functor type for BA methods.
void enter(const char *func_name)
Start of a named section.
std::vector< TYPE1, Eigen::aligned_allocator< TYPE1 > > vector_t
Structure to hold the parameters of a pinhole camera model.
void memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) noexcept
An OS and compiler independent version of "memcpy".