30 #define USE_INVERSE_POSES 32 #ifdef USE_INVERSE_POSES 33 #define INV_POSES_BOOL true 35 #define INV_POSES_BOOL false 61 static const unsigned int FrameDof = 6;
62 static const unsigned int PointDof = 3;
63 static const unsigned int ObsDim = 2;
67 using MyJacDataVec = std::vector<MyJacData>;
69 using Array_O = std::array<double, ObsDim>;
77 const bool use_robust_kernel =
81 const size_t max_iters =
83 const size_t num_fix_frames =
85 const size_t num_fix_points =
87 const double kernel_param =
90 const bool enable_profiler =
95 profiler.
enter(
"bundle_adj_full (complete run)");
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();
108 #ifdef USE_INVERSE_POSES 111 profiler.
enter(
"invert_poses");
112 for (
size_t i = 0; i < num_frames; i++) frame_poses[i].inverse();
113 profiler.
leave(
"invert_poses");
116 MyJacDataVec jac_data_vec(num_obs);
117 vector<Array_O> residual_vec(num_obs);
118 vector<double> kernel_1st_deriv(num_obs);
121 for (
size_t i = 0; i < num_obs; i++)
123 jac_data_vec[i].frame_id = observations[i].id_frame;
124 jac_data_vec[i].point_id = observations[i].id_feature;
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");
134 profiler.
enter(
"reprojectionResiduals");
136 observations, camera_params, frame_poses, landmark_points, residual_vec,
138 use_robust_kernel, kernel_param,
139 use_robust_kernel ? &kernel_1st_deriv :
nullptr);
140 profiler.
leave(
"reprojectionResiduals");
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;
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);
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");
172 double mu = initial_mu;
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));
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));
186 mu = tau * norm_max_A;
193 using SparseCholDecompPtr = std::unique_ptr<CSparseMatrix::CholeskyDecomp>;
195 SparseCholDecompPtr ptrCh;
197 for (
size_t iter = 0; iter < max_iters; iter++)
204 iter, res, max_iters, observations, frame_poses,
207 bool has_improved =
false;
210 profiler.
enter(
"COMPLETE_ITER");
214 I_muFrame.setDiagonal(FrameDof, mu);
215 I_muPoint.setDiagonal(PointDof, mu);
217 std::vector<Matrix_FxF> U_star(num_free_frames, I_muFrame);
218 std::vector<Matrix_PxP> V_inv(num_free_points);
220 for (
size_t i = 0; i < U_star.size(); ++i) U_star[i] += H_f[i];
222 for (
size_t i = 0; i < H_p.size(); ++i)
223 V_inv[i] = (H_p[i] + I_muPoint).inverse_LLt();
225 using WMap = std::map<pair<TCameraPoseID, TLandmarkID>, Matrix_FxP>;
229 vector<vector<WMap::iterator>> W_entries(
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)
237 const TFeatureID feat_id = it_obs->id_feature;
240 if (jac_iter->J_frame_valid && jac_iter->J_point_valid)
246 const pair<TCameraPoseID, TLandmarkID> id_pair =
247 make_pair(frame_id, feat_id);
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(
261 Y[id_pair] = tmp * V_inv[feat_id - num_fix_points];
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];
271 len_free_frames + len_free_points);
274 profiler.
enter(
"Schur.build.reduced.frames");
275 for (
size_t j = 0; j < num_free_frames; ++j)
277 &e[j * FrameDof], &eps_frame[j][0],
278 sizeof(e[0]) * FrameDof);
281 for (WMap::iterator Y_ij = Y.begin(); Y_ij != Y.end(); ++Y_ij)
285 Y_ij->first.second - num_fix_points;
287 Y_ij->first.first - num_fix_frames;
289 const vector<WMap::iterator>& iters =
292 for (
size_t itIdx = 0; itIdx < iters.size(); itIdx++)
295 const WMap::iterator& W_ik = iters[itIdx];
296 const TLandmarkID k = W_ik->first.first - num_fix_frames;
298 const auto YWt = Matrix_FxF(
299 Y_ij->second.asEigen() * W_ik->second.transpose());
302 const pair<TCameraPoseID, TLandmarkID> ids_jk =
303 pair<TCameraPoseID, TLandmarkID>(j, k);
305 auto it = YW_map.find(ids_jk);
306 if (it != YW_map.end())
309 YW_map[ids_jk] = -YWt;
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];
317 profiler.
leave(
"Schur.build.reduced.frames");
319 profiler.
enter(
"sS:ALL");
320 profiler.
enter(
"sS:fill");
322 VERBOSE_COUT <<
"Entries in YW_map:" << YW_map.size() << endl;
326 for (
auto it = YW_map.begin(); it != YW_map.end(); ++it)
328 const pair<TCameraPoseID, TLandmarkID>& ids = it->first;
329 const Matrix_FxF& YW = it->second;
331 ids.first * FrameDof, ids.second * FrameDof, YW);
333 profiler.
leave(
"sS:fill");
336 profiler.
enter(
"sS:compress");
338 profiler.
leave(
"sS:compress");
342 profiler.
enter(
"sS:chol");
346 ptrCh.get()->update(sS);
347 profiler.
leave(
"sS:chol");
349 profiler.
enter(
"sS:backsub");
351 ptrCh->backsub(e, bck_res);
353 &delta[0], &bck_res[0],
354 bck_res.
size() *
sizeof(bck_res[0]));
356 profiler.
leave(
"sS:backsub");
357 profiler.
leave(
"sS:ALL");
361 profiler.
leave(
"sS:ALL");
365 stop = (mu > 999999999.f);
369 profiler.
enter(
"PostSchur.landmarks");
379 for (
size_t i = 0; i < num_free_points; ++i)
381 Array_P tmp = eps_point[i];
383 for (
size_t j = 0; j < num_free_frames; ++j)
386 W_ij = W.find(make_pair(
392 const Array_F v(&delta[j * FrameDof]);
393 tmp -= Array_P(W_ij->second.transpose() * v.asEigen());
396 const auto Vi_tmp = Array_P(V_inv[i] * tmp);
399 &delta[len_free_frames + i * PointDof], &Vi_tmp[0],
400 sizeof(Vi_tmp[0]) * PointDof);
402 &g[len_free_frames + i * PointDof], &eps_point[i][0],
403 sizeof(eps_point[0][0]) * PointDof);
405 profiler.
leave(
"PostSchur.landmarks");
411 profiler.
enter(
"add_se3_deltas_to_frames");
413 frame_poses, delta, 0, len_free_frames, new_frame_poses,
415 profiler.
leave(
"add_se3_deltas_to_frames");
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");
423 vector<Array_O> new_residual_vec(num_obs);
424 vector<double> new_kernel_1st_deriv(num_obs);
426 profiler.
enter(
"reprojectionResiduals");
428 observations, camera_params, new_frame_poses,
429 new_landmark_points, new_residual_vec,
431 use_robust_kernel, kernel_param,
432 use_robust_kernel ? &new_kernel_1st_deriv :
nullptr);
433 profiler.
leave(
"reprojectionResiduals");
437 has_improved = (res_new < res);
444 <<
" avr.err(px):" << std::sqrt(res / num_obs)
445 <<
"->" << std::sqrt(res_new / num_obs) << endl;
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);
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");
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);
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");
477 mu = std::max(mu, 1e-100);
482 VERBOSE_COUT <<
"no update: res vs.res_new " << res <<
" vs. " 489 profiler.
leave(
"COMPLETE_ITER");
490 }
while (!has_improved && !stop);
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");
504 profiler.
leave(
"bundle_adj_full (complete run)");
A compile-time fixed-size numeric matrix container.
uint64_t TCameraPoseID
Unique IDs for camera frames (poses)
uint64_t TFeatureID
Definition of a feature ID.
uint64_t TLandmarkID
Unique IDs for landmarks.
Used in mrpt::math::CSparseMatrix.
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.
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 ASSERT_(f)
Defines an assertion mechanism.
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...
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:
Classes for computer vision, detectors, features, etc.
Parameters for the Brown-Conrady camera lens distortion model.
#define ASSERT_ABOVEEQ_(__A, __B)
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...
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)
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.
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 ¤t_frame_estimate, const mrpt::vision::TLandmarkLocationsVec ¤t_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".