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;
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");
148 arrF_zeros.assign(0);
150 arrP_zeros.assign(0);
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;
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.unit(FrameDof, mu);
215 I_muPoint.unit(PointDof, mu);
218 num_free_frames, I_muFrame);
221 for (
size_t i = 0; i < U_star.size(); ++i) U_star[i] += H_f[i];
223 for (
size_t i = 0; i < H_p.size(); ++i)
224 (H_p[i] + I_muPoint).inv_fast(V_inv[i]);
231 vector<vector<WMap::iterator>> W_entries(
236 observations.begin();
237 it_obs != observations.end(); ++it_obs)
239 const TFeatureID feat_id = it_obs->id_feature;
242 if (jac_iter->J_frame_valid && jac_iter->J_point_valid)
245 J_frame = jac_iter->J_frame;
247 J_point = jac_iter->J_point;
248 const pair<TCameraPoseID, TLandmarkID> id_pair =
249 make_pair(frame_id, feat_id);
252 tmp.multiply_AtB(J_frame, J_point);
256 const pair<WMap::iterator, bool>& retInsert =
257 W.insert(make_pair(id_pair, tmp));
258 ASSERT_(retInsert.second ==
true);
259 W_entries[feat_id].push_back(
263 Y[id_pair].multiply_AB(
264 tmp, V_inv[feat_id - num_fix_points]);
271 for (
size_t i = 0; i < H_f.size(); ++i)
272 YW_map[std::pair<TCameraPoseID, TLandmarkID>(i, i)] = U_star[i];
275 len_free_frames + len_free_points);
278 profiler.
enter(
"Schur.build.reduced.frames");
279 for (
size_t j = 0; j < num_free_frames; ++j)
281 &e[j * FrameDof], &eps_frame[j][0],
282 sizeof(e[0]) * FrameDof);
289 Y_ij->first.second - num_fix_points;
291 Y_ij->first.first - num_fix_frames;
293 const vector<WMap::iterator>& iters =
296 for (
size_t itIdx = 0; itIdx < iters.size(); itIdx++)
300 const TLandmarkID k = W_ik->first.first - num_fix_frames;
304 YWt.multiply_ABt(Y_ij->second, W_ik->second);
307 const pair<TCameraPoseID, TLandmarkID> ids_jk =
308 pair<TCameraPoseID, TLandmarkID>(j, k);
310 auto it = YW_map.find(ids_jk);
311 if (it != YW_map.end())
314 YW_map[ids_jk] = YWt * (-1.0);
318 Y_ij->second.multiply_Ab(eps_point[i],
r);
319 for (
size_t k = 0; k < FrameDof; k++)
320 e[j * FrameDof + k] -=
r[k];
322 profiler.
leave(
"Schur.build.reduced.frames");
324 profiler.
enter(
"sS:ALL");
325 profiler.
enter(
"sS:fill");
327 VERBOSE_COUT <<
"Entries in YW_map:" << YW_map.size() << endl;
331 for (
auto it = YW_map.begin(); it != YW_map.end(); ++it)
333 const pair<TCameraPoseID, TLandmarkID>&
ids = it->first;
334 const Matrix_FxF& YW = it->second;
336 ids.first * FrameDof,
ids.second * FrameDof, YW);
338 profiler.
leave(
"sS:fill");
341 profiler.
enter(
"sS:compress");
343 profiler.
leave(
"sS:compress");
347 profiler.
enter(
"sS:chol");
351 ptrCh.get()->update(sS);
352 profiler.
leave(
"sS:chol");
354 profiler.
enter(
"sS:backsub");
356 ptrCh->backsub(e, bck_res);
358 &delta[0], &bck_res[0],
359 bck_res.size() *
sizeof(bck_res[0]));
361 profiler.
leave(
"sS:backsub");
362 profiler.
leave(
"sS:ALL");
366 profiler.
leave(
"sS:ALL");
370 stop = (mu > 999999999.f);
374 profiler.
enter(
"PostSchur.landmarks");
384 for (
size_t i = 0; i < num_free_points; ++i)
389 for (
size_t j = 0; j < num_free_frames; ++j)
401 const Array_F
v(&delta[j * FrameDof]);
403 W_ij->second.multiply_Atb(
v,
r);
408 V_inv[i].multiply_Ab(tmp, Vi_tmp);
411 &delta[len_free_frames + i * PointDof], &Vi_tmp[0],
412 sizeof(Vi_tmp[0]) * PointDof);
414 &
g[len_free_frames + i * PointDof], &eps_point[i][0],
415 sizeof(eps_point[0][0]) * PointDof);
417 profiler.
leave(
"PostSchur.landmarks");
423 profiler.
enter(
"add_se3_deltas_to_frames");
425 frame_poses, delta, 0, len_free_frames, new_frame_poses,
427 profiler.
leave(
"add_se3_deltas_to_frames");
429 profiler.
enter(
"add_3d_deltas_to_points");
431 landmark_points, delta, len_free_frames, len_free_points,
432 new_landmark_points, num_fix_points);
433 profiler.
leave(
"add_3d_deltas_to_points");
435 vector<Array_O> new_residual_vec(num_obs);
436 vector<double> new_kernel_1st_deriv(num_obs);
438 profiler.
enter(
"reprojectionResiduals");
440 observations, camera_params, new_frame_poses,
441 new_landmark_points, new_residual_vec,
443 use_robust_kernel, kernel_param,
444 use_robust_kernel ? &new_kernel_1st_deriv :
nullptr);
445 profiler.
leave(
"reprojectionResiduals");
449 has_improved = (res_new <
res);
456 <<
" avr.err(px):" << std::sqrt(
res / num_obs)
457 <<
"->" << std::sqrt(res_new / num_obs) << endl;
460 frame_poses.swap(new_frame_poses);
461 landmark_points.swap(new_landmark_points);
462 residual_vec.swap(new_residual_vec);
463 kernel_1st_deriv.swap(new_kernel_1st_deriv);
467 profiler.
enter(
"compute_Jacobians");
468 ba_compute_Jacobians<INV_POSES_BOOL>(
469 frame_poses, landmark_points, camera_params, jac_data_vec,
470 num_fix_frames, num_fix_points);
471 profiler.
leave(
"compute_Jacobians");
474 H_f.assign(num_free_frames, Matrix_FxF());
475 H_p.assign(num_free_points, Matrix_PxP());
476 eps_frame.assign(num_free_frames, arrF_zeros);
477 eps_point.assign(num_free_points, arrP_zeros);
479 profiler.
enter(
"build_gradient_Hessians");
481 observations, residual_vec, jac_data_vec, H_f, eps_frame,
482 H_p, eps_point, num_fix_frames, num_fix_points,
483 use_robust_kernel ? &kernel_1st_deriv :
nullptr);
484 profiler.
leave(
"build_gradient_Hessians");
489 mu = std::max(mu, 1e-100);
501 profiler.
leave(
"COMPLETE_ITER");
502 }
while (!has_improved && !stop);
510 #ifdef USE_INVERSE_POSES 511 profiler.
enter(
"invert_poses");
512 for (
size_t i = 0; i < num_frames; i++) frame_poses[i].
inverse();
513 profiler.
leave(
"invert_poses");
516 profiler.
leave(
"bundle_adj_full (complete run)");
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...
CArrayNumeric is an array for numeric types supporting several mathematical operations (actually...
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.
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:
std::map< KEY, VALUE, std::less< KEY >, mrpt::aligned_allocator_cpp11< std::pair< const KEY, VALUE > >> aligned_std_map
std::vector< T, mrpt::aligned_allocator_cpp11< T > > aligned_std_vector
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...
A complete sequence of observations of features from different camera frames (poses).
#define ASSERT_(f)
Defines an assertion mechanism.
A numeric matrix of compile-time fixed size.
This base provides a set of functions for maths stuff.
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...
#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:
Eigen::Matrix< dataType, 4, 4 > inverse(Eigen::Matrix< dataType, 4, 4 > &pose)
Classes for computer vision, detectors, features, etc.
Structure to hold the parameters of a pinhole camera model.
double leave(const char *func_name)
End of a named section.
#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...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
GLdouble GLdouble GLdouble r
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X), among other stats.
void ba_build_gradient_Hessians(const TSequenceFeatureObservations &observations, const std::vector< std::array< double, 2 >> &residual_vec, const mrpt::aligned_std_vector< JacData< 6, 3, 2 >> &jac_data_vec, mrpt::aligned_std_vector< mrpt::math::CMatrixFixedNumeric< double, 6, 6 >> &U, mrpt::aligned_std_vector< CArrayDouble< 6 >> &eps_frame, mrpt::aligned_std_vector< mrpt::math::CMatrixFixedNumeric< double, 3, 3 >> &V, mrpt::aligned_std_vector< CArrayDouble< 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.
#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 ...
mrpt::aligned_std_vector< mrpt::poses::CPose3D > TFramePosesVec
A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs...
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.
const Scalar * const_iterator
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...
void enter(const char *func_name)
Start of a named section.
void memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) noexcept
An OS and compiler independent version of "memcpy".