30 #define USE_INVERSE_POSES 32 #ifdef USE_INVERSE_POSES 33 # define INV_POSES_BOOL true 35 # 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;
78 const bool use_robust_kernel = 0!=extra_params.
getWithDefaultVal(
"robust_kernel",1);
90 profiler.
enter(
"bundle_adj_full (complete run)");
93 const size_t num_points = landmark_points.size();
94 const size_t num_frames = frame_poses.size();
95 const size_t num_obs = observations.size();
104 #ifdef USE_INVERSE_POSES 106 profiler.
enter(
"invert_poses");
107 for (
size_t i=0;i<num_frames;i++)
109 profiler.
leave(
"invert_poses");
113 MyJacDataVec jac_data_vec(num_obs);
114 vector<Array_O> residual_vec(num_obs);
115 vector<double> kernel_1st_deriv(num_obs);
118 for (
size_t i=0; i<num_obs; i++)
120 jac_data_vec[i].frame_id = observations[i].id_frame;
121 jac_data_vec[i].point_id = observations[i].id_feature;
125 profiler.
enter(
"compute_Jacobians");
126 ba_compute_Jacobians<INV_POSES_BOOL>(frame_poses, landmark_points, camera_params, jac_data_vec, num_fix_frames, num_fix_points);
127 profiler.
leave(
"compute_Jacobians");
130 profiler.
enter(
"reprojectionResiduals");
132 observations, camera_params, frame_poses, landmark_points,
137 use_robust_kernel ? &kernel_1st_deriv : NULL );
138 profiler.
leave(
"reprojectionResiduals");
146 arrF_zeros.assign(0);
148 arrP_zeros.assign(0);
150 const size_t num_free_frames = num_frames-num_fix_frames;
151 const size_t num_free_points = num_points-num_fix_points;
152 const size_t len_free_frames = FrameDof * num_free_frames;
153 const size_t len_free_points = PointDof * num_free_points;
160 profiler.
enter(
"build_gradient_Hessians");
161 ba_build_gradient_Hessians(observations,residual_vec,jac_data_vec, H_f,eps_frame,H_p,eps_point, num_fix_frames, num_fix_points, use_robust_kernel ? &kernel_1st_deriv : NULL );
162 profiler.
leave(
"build_gradient_Hessians");
167 double mu = initial_mu;
172 double norm_max_A = 0;
173 for (
size_t j=0; j<num_free_frames; ++j)
174 for (
size_t dim=0; dim<FrameDof; dim++)
175 keep_max(norm_max_A, H_f[j](dim,dim) );
177 for (
size_t i=0; i<num_free_points; ++i)
178 for (
size_t dim=0; dim<PointDof; dim++)
179 keep_max(norm_max_A, H_p[i](dim,dim) );
189 typedef std::unique_ptr<CSparseMatrix::CholeskyDecomp> SparseCholDecompPtr;
191 typedef std::auto_ptr<CSparseMatrix::CholeskyDecomp> SparseCholDecompPtr;
193 SparseCholDecompPtr ptrCh;
195 for (
size_t iter=0; iter<max_iters; iter++)
201 (*user_feedback)(iter,
res, max_iters, observations, frame_poses, landmark_points );
203 bool has_improved =
false;
206 profiler.
enter(
"COMPLETE_ITER");
210 I_muFrame.unit(FrameDof,mu);
211 I_muPoint.unit(PointDof,mu);
216 for (
size_t i=0; i<U_star.size(); ++i)
219 for (
size_t i=0; i<H_p.size(); ++i)
220 (H_p[i]+I_muPoint).inv_fast( V_inv[i] );
227 vector<vector<WMap::iterator> > W_entries(num_points);
232 const TFeatureID feat_id = it_obs->id_feature;
235 if (jac_iter->J_frame_valid && jac_iter->J_point_valid)
239 const pair<TCameraPoseID,TLandmarkID> id_pair = make_pair(frame_id, feat_id);
242 tmp.multiply_AtB(J_frame, J_point);
246 const pair<WMap::iterator,bool> &retInsert = W.insert( make_pair(id_pair,tmp) );
247 ASSERT_(retInsert.second==
true)
248 W_entries[feat_id].push_back(retInsert.first);
251 Y[id_pair].multiply_AB(tmp, V_inv[feat_id-num_fix_points]);
257 for (
size_t i=0; i<H_f.size(); ++i)
258 YW_map[std::pair<TCameraPoseID,TLandmarkID>(i,i)] = U_star[i];
264 profiler.
enter(
"Schur.build.reduced.frames");
265 for (
size_t j=0; j<num_free_frames; ++j)
266 ::
memcpy( &e[j*FrameDof], &eps_frame[j][0],
sizeof(e[0])*FrameDof );
271 const size_t i = Y_ij->first.second - num_fix_points;
272 const size_t j = Y_ij->first.first - num_fix_frames;
274 const vector<WMap::iterator> &iters = W_entries[point_id];
276 for (
size_t itIdx=0; itIdx<iters.size(); itIdx++)
280 const TLandmarkID k = W_ik->first.first-num_fix_frames;
283 YWt.multiply_ABt( Y_ij->second, W_ik->second );
286 const pair<TCameraPoseID,TLandmarkID> ids_jk = pair<TCameraPoseID,TLandmarkID>(j,k);
292 YW_map[ids_jk] = YWt*(-1.0);
296 Y_ij->second.multiply_Ab( eps_point[i] ,
r);
297 for (
size_t k=0; k<FrameDof; k++)
298 e[j*FrameDof+k]-=
r[k];
300 profiler.
leave(
"Schur.build.reduced.frames");
303 profiler.
enter(
"sS:ALL");
304 profiler.
enter(
"sS:fill");
306 VERBOSE_COUT <<
"Entries in YW_map:" << YW_map.size() << endl;
312 const pair<TCameraPoseID,TLandmarkID> &
ids = it->first;
313 const Matrix_FxF & YW = it->second;
316 profiler.
leave(
"sS:fill");
319 profiler.
enter(
"sS:compress");
321 profiler.
leave(
"sS:compress");
325 profiler.
enter(
"sS:chol");
328 else ptrCh.get()->update(sS);
329 profiler.
leave(
"sS:chol");
331 profiler.
enter(
"sS:backsub");
333 ptrCh->backsub(e, bck_res);
334 ::memcpy(&delta[0],&bck_res[0],bck_res.size()*
sizeof(bck_res[0]));
335 profiler.
leave(
"sS:backsub");
336 profiler.
leave(
"sS:ALL");
340 profiler.
leave(
"sS:ALL");
344 stop = (mu>999999999.f);
348 profiler.
enter(
"PostSchur.landmarks");
351 ::memcpy(&
g[0],&e[0],len_free_frames*
sizeof(
g[0]));
353 for (
size_t i=0; i<num_free_points; ++i)
355 Array_P tmp = eps_point[i];
357 for (
size_t j=0; j<num_free_frames; ++j)
365 const Array_F
v( &delta[j*FrameDof] );
367 W_ij->second.multiply_Atb(
v,
r);
372 V_inv[i].multiply_Ab(tmp, Vi_tmp);
374 ::memcpy(&delta[len_free_frames + i*PointDof], &Vi_tmp[0],
sizeof(Vi_tmp[0])*PointDof );
375 ::memcpy(&
g[len_free_frames + i*PointDof], &eps_point[i][0],
sizeof(eps_point[0][0])*PointDof );
377 profiler.
leave(
"PostSchur.landmarks");
384 profiler.
enter(
"add_se3_deltas_to_frames");
387 delta, 0,len_free_frames,
388 new_frame_poses, num_fix_frames );
389 profiler.
leave(
"add_se3_deltas_to_frames");
391 profiler.
enter(
"add_3d_deltas_to_points");
394 delta, len_free_frames, len_free_points,
395 new_landmark_points, num_fix_points );
396 profiler.
leave(
"add_3d_deltas_to_points");
398 vector<Array_O> new_residual_vec(num_obs);
399 vector<double> new_kernel_1st_deriv(num_obs);
401 profiler.
enter(
"reprojectionResiduals");
403 observations, camera_params,
404 new_frame_poses, new_landmark_points,
409 use_robust_kernel ? &new_kernel_1st_deriv : NULL );
410 profiler.
leave(
"reprojectionResiduals");
414 has_improved = (res_new<
res);
420 VERBOSE_COUT <<
"new total sqr.err=" << res_new <<
" avr.err(px):"<< std::sqrt(
res/num_obs) <<
"->" << std::sqrt(res_new/num_obs) << endl;
423 frame_poses.swap(new_frame_poses);
424 landmark_points.swap(new_landmark_points);
425 residual_vec.swap( new_residual_vec );
426 kernel_1st_deriv.swap( new_kernel_1st_deriv );
430 profiler.
enter(
"compute_Jacobians");
431 ba_compute_Jacobians<INV_POSES_BOOL>(frame_poses, landmark_points, camera_params, jac_data_vec, num_fix_frames, num_fix_points);
432 profiler.
leave(
"compute_Jacobians");
436 H_f.assign(num_free_frames,Matrix_FxF() );
437 H_p.assign(num_free_points,Matrix_PxP() );
438 eps_frame.assign(num_free_frames, arrF_zeros);
439 eps_point.assign(num_free_points, arrP_zeros);
441 profiler.
enter(
"build_gradient_Hessians");
442 ba_build_gradient_Hessians(observations,residual_vec,jac_data_vec,H_f,eps_frame,H_p,eps_point, num_fix_frames, num_fix_points, use_robust_kernel ? &kernel_1st_deriv : NULL );
443 profiler.
leave(
"build_gradient_Hessians");
448 mu = std::max(mu, 1e-100);
463 profiler.
leave(
"COMPLETE_ITER");
465 while(!has_improved && !stop);
473 #ifdef USE_INVERSE_POSES 474 profiler.
enter(
"invert_poses");
475 for (
size_t i=0;i<num_frames;i++)
477 profiler.
leave(
"invert_poses");
480 profiler.
leave(
"bundle_adj_full (complete run)");
void BASE_IMPEXP memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) MRPT_NO_THROWS
An OS and compiler independent version of "memcpy".
double VISION_IMPEXP 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< mrpt::utils::CArray< 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=NULL)
Compute reprojection error vector (used from within Bundle Adjustment methods, but can be used in gen...
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 VISION_IMPEXP 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.
double VISION_IMPEXP 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=NULL)
Sparse Levenberg-Marquart solution to bundle adjustment - optimizes all the camera frames & the landm...
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 VISION_IMPEXP 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:
A STL container (as wrapper) for arrays of constant size defined at compile time. ...
Eigen::Matrix< dataType, 4, 4 > inverse(Eigen::Matrix< dataType, 4, 4 > &pose)
void(* TBundleAdjustmentFeedbackFunctor)(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)
A functor type for BA methods.
Classes for computer vision, detectors, features, etc.
uint64_t TFeatureID
Definition of a feature ID.
void ba_build_gradient_Hessians(const TSequenceFeatureObservations &observations, const std::vector< mrpt::utils::CArray< 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 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...
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 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.
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.