44#include " stella_vslam/data/map_database.h"
55#include " stella_vslam/marker_model/base.h"
66#include " stella_vslam/optimize/global_bundle_adjuster.h"
7- #include " stella_vslam/optimize/local_bundle_adjuster_g2o.h"
87#include " stella_vslam/optimize/terminate_action.h"
98#include " stella_vslam/optimize/internal/landmark_vertex_container.h"
109#include " stella_vslam/optimize/internal/marker_vertex_container.h"
@@ -35,6 +34,8 @@ void optimize_impl(g2o::SparseOptimizer& optimizer,
3534 std::unordered_set<unsigned int >& mkr_has_vtx,
3635 unsigned int num_iter,
3736 bool use_huber_kernel,
37+ bool fix_markers,
38+ bool verbose,
3839 bool * const force_stop_flag) {
3940 // 2. Construct an optimizer
4041
@@ -137,7 +138,7 @@ void optimize_impl(g2o::SparseOptimizer& optimizer,
137138
138139 // Only optimize if requested, and if enough keyframes were available to
139140 // initialize it correctly
140- if (!mkr->keep_fixed_ && !mkr->initialized_before_ )
141+ if (!fix_markers && ! mkr->keep_fixed_ && !mkr->initialized_before_ )
141142 continue ;
142143
143144 // Indicate that a vertex container will be available, this can be
@@ -146,7 +147,7 @@ void optimize_impl(g2o::SparseOptimizer& optimizer,
146147 mkr_has_vtx.insert (mkr->id_ );
147148
148149 // Convert the corners to the g2o vertex, then set it to the optimizer
149- auto corner_vertices = marker_vtx_container.create_vertices (mkr, mkr->keep_fixed_ );
150+ auto corner_vertices = marker_vtx_container.create_vertices (mkr, fix_markers || mkr->keep_fixed_ );
150151 for (unsigned int corner_idx = 0 ; corner_idx < corner_vertices.size (); ++corner_idx) {
151152 const auto corner_vtx = corner_vertices[corner_idx];
152153 optimizer.addVertex (corner_vtx);
@@ -168,7 +169,7 @@ void optimize_impl(g2o::SparseOptimizer& optimizer,
168169 const float x_right = -1.0 ;
169170 const float inv_sigma_sq = 1.0 ;
170171
171- const auto sqrt_chi_sq = (mkr->keep_fixed_ ) ? 0.0 : sqrt_chi_sq_2D;
172+ const auto sqrt_chi_sq = (fix_markers || mkr->keep_fixed_ ) ? 0.0 : sqrt_chi_sq_2D;
172173
173174 auto reproj_edge_wrap = reproj_edge_wrapper (keyfrm, keyfrm_vtx, nullptr , corner_vtx,
174175 0 , undist_pt.x , undist_pt.y , x_right,
@@ -182,19 +183,27 @@ void optimize_impl(g2o::SparseOptimizer& optimizer,
182183 // 5. Perform optimization
183184
184185 optimizer.initializeOptimization ();
186+ optimizer.setVerbose (verbose);
185187 optimizer.optimize (num_iter);
186188
187189 if (force_stop_flag && *force_stop_flag) {
188190 return ;
189191 }
190192}
191193
192- global_bundle_adjuster::global_bundle_adjuster (const unsigned int num_iter, const bool use_huber_kernel)
193- : num_iter_(num_iter), use_huber_kernel_(use_huber_kernel) {}
194+ global_bundle_adjuster::global_bundle_adjuster (
195+ const unsigned int num_iter,
196+ const bool use_huber_kernel,
197+ const bool verbose)
198+ : num_iter_(num_iter),
199+ use_huber_kernel_ (use_huber_kernel),
200+ verbose_(verbose) {}
194201
195202void global_bundle_adjuster::optimize_for_initialization (const std::vector<std::shared_ptr<data::keyframe>>& keyfrms,
196203 const std::vector<std::shared_ptr<data::landmark>>& lms,
197204 const std::vector<std::shared_ptr<data::marker>>& markers,
205+ float gain_threshold,
206+ bool fix_markers,
198207 bool * const force_stop_flag) const {
199208 std::vector<bool > is_optimized_lm (lms.size (), true );
200209
@@ -205,12 +214,15 @@ void global_bundle_adjuster::optimize_for_initialization(const std::vector<std::
205214 internal::landmark_vertex_container lm_vtx_container (vtx_id_offset, lms.size ());
206215 // Container of the landmark vertices
207216 internal::marker_vertex_container marker_vtx_container (vtx_id_offset, markers.size ());
208- std::unordered_set<unsigned int > mkr_has_vtx; // Not really used here, we're not updating markers in this function
217+ std::unordered_set<unsigned int > mkr_has_vtx;
209218
210219 g2o::SparseOptimizer optimizer;
220+ auto terminateAction = new terminate_action;
221+ terminateAction->setGainThreshold (gain_threshold);
222+ optimizer.addPostIterationAction (terminateAction);
211223
212224 optimize_impl (optimizer, keyfrms, lms, markers, is_optimized_lm, keyfrm_vtx_container, lm_vtx_container, marker_vtx_container,
213- mkr_has_vtx, num_iter_, use_huber_kernel_, force_stop_flag);
225+ mkr_has_vtx, num_iter_, use_huber_kernel_, fix_markers, verbose_, force_stop_flag);
214226
215227 if (force_stop_flag && *force_stop_flag) {
216228 return ;
@@ -247,6 +259,21 @@ void global_bundle_adjuster::optimize_for_initialization(const std::vector<std::
247259 lm->set_pos_in_world (pos_w);
248260 lm->update_mean_normal_and_obs_scale_variance ();
249261 }
262+
263+ for (auto & mkr : markers) {
264+ if (fix_markers || mkr->keep_fixed_ ) // No need to update
265+ continue ;
266+ if (!mkr->initialized_before_ )
267+ continue ;
268+ // It's possible that initialized_before_ got changed since it was
269+ // checked the last time, this actually tests if a vtx was made
270+ if (mkr_has_vtx.find (mkr->id_ ) == mkr_has_vtx.end ())
271+ continue ;
272+
273+ for (size_t corner_idx = 0 ; corner_idx < 4 ; corner_idx++) {
274+ mkr->corners_pos_w_ [corner_idx] = marker_vtx_container.get_vertex (mkr, corner_idx)->estimate ();
275+ }
276+ }
250277}
251278
252279bool global_bundle_adjuster::optimize (const std::vector<std::shared_ptr<data::keyframe>>& keyfrms,
@@ -309,7 +336,7 @@ bool global_bundle_adjuster::optimize(const std::vector<std::shared_ptr<data::ke
309336 optimizer.addPostIterationAction (terminateAction);
310337
311338 optimize_impl (optimizer, keyfrms, lms, markers, is_optimized_lm, keyfrm_vtx_container, lm_vtx_container, marker_vtx_container,
312- mkr_has_vtx, num_iter_, use_huber_kernel_, force_stop_flag);
339+ mkr_has_vtx, num_iter_, use_huber_kernel_, false , verbose_, force_stop_flag);
313340
314341 if (force_stop_flag && *force_stop_flag && !terminateAction->stopped_by_terminate_action_ ) {
315342 return false ;
@@ -362,15 +389,16 @@ bool global_bundle_adjuster::optimize(const std::vector<std::shared_ptr<data::ke
362389
363390 bool changed = false ;
364391 std::array<Vec3_t, 4 > new_pos_corners;
365- for (size_t c = 0 ; c < 4 ; c ++) {
366- auto orig_pos = mkr->corners_pos_w_ [c ];
367- auto vtx = marker_vtx_container.get_vertex (mkr, c );
392+ for (size_t corner_idx = 0 ; corner_idx < 4 ; corner_idx ++) {
393+ auto orig_pos = mkr->corners_pos_w_ [corner_idx ];
394+ auto vtx = marker_vtx_container.get_vertex (mkr, corner_idx );
368395 auto new_pos = vtx->estimate ();
369396
370- if (orig_pos != new_pos)
397+ if (orig_pos != new_pos) {
371398 changed = true ;
399+ }
372400
373- new_pos_corners[c ] = new_pos;
401+ new_pos_corners[corner_idx ] = new_pos;
374402 }
375403
376404 if (!changed)
0 commit comments