Skip to content

Commit f42c9d8

Browse files
authored
Update initializer (Initialization with markers is now more stable) (#641)
- Add parameters about globalBA/g2o (verbose, gain_threshold) - Default value of Initializer::num_ba_iterations is changed (20 -> 100) - optimize_for_initialization automatically terminates optimization by gain_threshold - some minor fixes
1 parent a6e5d04 commit f42c9d8

File tree

8 files changed

+91
-38
lines changed

8 files changed

+91
-38
lines changed

src/stella_vslam/global_optimization_module.cc

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,8 @@ global_optimization_module::global_optimization_module(data::map_database* map_d
1919
loop_bundle_adjuster_(new module::loop_bundle_adjuster(
2020
map_db,
2121
util::yaml_optional_ref(yaml_node, "GlobalOptimizer")["num_iter"].as<unsigned int>(10),
22-
util::yaml_optional_ref(yaml_node, "GlobalOptimizer")["use_huber_kernel"].as<bool>(false))),
22+
util::yaml_optional_ref(yaml_node, "GlobalOptimizer")["use_huber_kernel"].as<bool>(false),
23+
util::yaml_optional_ref(yaml_node, "GlobalOptimizer")["verbose"].as<bool>(false))),
2324
map_db_(map_db),
2425
graph_optimizer_(new optimize::graph_optimizer(util::yaml_optional_ref(yaml_node, "GraphOptimizer"), fix_scale)),
2526
thr_neighbor_keyframes_(util::yaml_optional_ref(yaml_node, "GlobalOptimizer")["thr_neighbor_keyframes"].as<unsigned int>(15)) {

src/stella_vslam/module/initializer.cc

Lines changed: 9 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -24,10 +24,11 @@ initializer::initializer(data::map_database* map_db,
2424
min_num_triangulated_pts_(yaml_node["min_num_triangulated_pts"].as<unsigned int>(50)),
2525
parallax_deg_thr_(yaml_node["parallax_deg_threshold"].as<float>(1.0)),
2626
reproj_err_thr_(yaml_node["reprojection_error_threshold"].as<float>(4.0)),
27-
num_ba_iters_(yaml_node["num_ba_iterations"].as<unsigned int>(20)),
27+
num_ba_iters_(yaml_node["num_ba_iterations"].as<unsigned int>(100)),
2828
scaling_factor_(yaml_node["scaling_factor"].as<float>(1.0)),
2929
use_fixed_seed_(yaml_node["use_fixed_seed"].as<bool>(false)),
30-
required_keyframes_for_marker_initialization_(yaml_node["required_keyframes_for_marker_initialization"].as<unsigned int>(3)) {
30+
gain_threshold_(yaml_node["gain_threshold"].as<float>(1e-5)),
31+
verbose_(yaml_node["verbose"].as<bool>(false)) {
3132
spdlog::debug("CONSTRUCT: module::initializer");
3233
}
3334

@@ -271,17 +272,19 @@ bool initializer::create_map_for_monocular(data::bow_vocabulary* bow_vocab, data
271272
// Set the association to the new marker
272273
keyfrm->add_marker(marker);
273274
marker->observations_.emplace(keyfrm->id_, keyfrm);
274-
275-
marker_initializer::check_marker_initialization(*marker, required_keyframes_for_marker_initialization_);
276275
}
277276
};
278277
assign_marker_associations(init_keyfrm);
279278
assign_marker_associations(curr_keyfrm);
280279

281280
// global bundle adjustment
282-
const auto global_bundle_adjuster = optimize::global_bundle_adjuster(num_ba_iters_, true);
281+
const auto global_bundle_adjuster = optimize::global_bundle_adjuster(num_ba_iters_, true, verbose_);
283282
std::vector<std::shared_ptr<data::keyframe>> keyfrms{init_keyfrm, curr_keyfrm};
284-
global_bundle_adjuster.optimize_for_initialization(keyfrms, lms, markers);
283+
if (markers.size() > 0) {
284+
// Adjust map scale with reference to marker width.
285+
global_bundle_adjuster.optimize_for_initialization(keyfrms, lms, markers, gain_threshold_, true);
286+
}
287+
global_bundle_adjuster.optimize_for_initialization(keyfrms, lms, markers, gain_threshold_, false);
285288

286289
if (indefinite_scale) {
287290
// scale the map so that the median of depths is 1.0

src/stella_vslam/module/initializer.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -87,6 +87,10 @@ class initializer {
8787
const float scaling_factor_;
8888
//! Use fixed random seed for RANSAC if true
8989
const bool use_fixed_seed_;
90+
//! Gain threshold (for g2o)
91+
const float gain_threshold_;
92+
//! Verbosity (for g2o)
93+
const bool verbose_;
9094

9195
//-----------------------------------------
9296
// for monocular camera model

src/stella_vslam/module/loop_bundle_adjuster.cc

Lines changed: 12 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,12 @@ namespace module {
1515

1616
loop_bundle_adjuster::loop_bundle_adjuster(data::map_database* map_db,
1717
const unsigned int num_iter,
18-
const bool use_huber_kernel)
19-
: map_db_(map_db), num_iter_(num_iter), use_huber_kernel_(use_huber_kernel) {}
18+
const bool use_huber_kernel,
19+
const bool verbose)
20+
: map_db_(map_db),
21+
num_iter_(num_iter),
22+
use_huber_kernel_(use_huber_kernel),
23+
verbose_(verbose) {}
2024

2125
void loop_bundle_adjuster::set_mapping_module(mapping_module* mapper) {
2226
mapper_ = mapper;
@@ -47,7 +51,7 @@ void loop_bundle_adjuster::optimize(const std::shared_ptr<data::keyframe>& curr_
4751
eigen_alloc_unord_map<unsigned int, Vec3_t> lm_to_pos_w_after_global_BA;
4852
eigen_alloc_unord_map<unsigned int, Mat44_t> keyfrm_to_pose_cw_after_global_BA;
4953
eigen_alloc_unord_map<unsigned int, std::array<Vec3_t, 4>> marker_to_pos_w_after_global_BA;
50-
const auto global_BA = optimize::global_bundle_adjuster(num_iter_, use_huber_kernel_);
54+
const auto global_BA = optimize::global_bundle_adjuster(num_iter_, use_huber_kernel_, verbose_);
5155
bool ok = global_BA.optimize(curr_keyfrm->graph_node_->get_keyframes_from_root(),
5256
optimized_keyfrm_ids, optimized_landmark_ids,
5357
optimized_marker_ids,
@@ -185,13 +189,15 @@ void loop_bundle_adjuster::optimize(const std::shared_ptr<data::keyframe>& curr_
185189
}
186190

187191
for (const auto& mkr : markers) {
188-
if (!optimized_marker_ids.count(mkr->id_)) // not optimized
192+
if (!optimized_marker_ids.count(mkr->id_)) {
189193
continue;
194+
}
190195

191196
// Update all corners
192197
const std::array<Vec3_t, 4>& new_corners = marker_to_pos_w_after_global_BA.at(mkr->id_);
193-
for (size_t c = 0; c < 4; c++)
194-
mkr->corners_pos_w_[c] = new_corners[c];
198+
for (size_t corner_idx = 0; corner_idx < 4; corner_idx++) {
199+
mkr->corners_pos_w_[corner_idx] = new_corners[corner_idx];
200+
}
195201
}
196202

197203
mapper_->resume();

src/stella_vslam/module/loop_bundle_adjuster.h

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,8 @@ class loop_bundle_adjuster {
2121
*/
2222
explicit loop_bundle_adjuster(data::map_database* map_db,
2323
const unsigned int num_iter = 10,
24-
const bool use_huber_kernel = false);
24+
const bool use_huber_kernel = false,
25+
const bool verbose = false);
2526

2627
/**
2728
* Destructor
@@ -57,8 +58,10 @@ class loop_bundle_adjuster {
5758

5859
//! number of iteration for optimization
5960
const unsigned int num_iter_ = 10;
60-
61+
//! True if using Huber kernel (for g2o)
6162
const bool use_huber_kernel_ = false;
63+
//! Verbosity (for g2o)
64+
const bool verbose_ = false;
6265

6366
//-----------------------------------------
6467
// thread management

src/stella_vslam/optimize/global_bundle_adjuster.cc

Lines changed: 42 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,6 @@
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

195202
void 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

252279
bool 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)

src/stella_vslam/optimize/global_bundle_adjuster.h

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,12 @@ class global_bundle_adjuster {
1515
* Constructor
1616
* @param num_iter
1717
* @param use_huber_kernel
18+
* @param verbose
1819
*/
19-
explicit global_bundle_adjuster(const unsigned int num_iter = 10, const bool use_huber_kernel = true);
20+
explicit global_bundle_adjuster(
21+
unsigned int num_iter = 10,
22+
bool use_huber_kernel = true,
23+
bool verbose = false);
2024

2125
/**
2226
* Destructor
@@ -26,6 +30,8 @@ class global_bundle_adjuster {
2630
void optimize_for_initialization(const std::vector<std::shared_ptr<data::keyframe>>& keyfrms,
2731
const std::vector<std::shared_ptr<data::landmark>>& lms,
2832
const std::vector<std::shared_ptr<data::marker>>& markers,
33+
float gain_threshold,
34+
bool fix_markers,
2935
bool* const force_stop_flag = nullptr) const;
3036

3137
/**
@@ -50,9 +56,10 @@ class global_bundle_adjuster {
5056
private:
5157
//! number of iterations of optimization
5258
unsigned int num_iter_;
53-
5459
//! use Huber loss or not
5560
const bool use_huber_kernel_;
61+
//! Verbosity (for g2o)
62+
const bool verbose_ = false;
5663
};
5764

5865
} // namespace optimize

src/stella_vslam/optimize/local_bundle_adjuster_g2o.cc

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -411,19 +411,20 @@ void local_bundle_adjuster_g2o::optimize(data::map_database* map_db,
411411
// Also update the marker positions
412412
for (auto& id_mkr_pair : local_mkrs) {
413413
auto& mkr = id_mkr_pair.second;
414-
if (mkr->keep_fixed_)
414+
if (mkr->keep_fixed_) {
415415
continue;
416-
if (!mkr->initialized_before_)
416+
}
417+
if (!mkr->initialized_before_) {
417418
continue;
419+
}
418420
// It's possible that initialized_before_ got changed since it was
419421
// checked the last time, this actually tests if a vtx was made
420-
if (mkr_has_vtx.find(mkr->id_) == mkr_has_vtx.end())
422+
if (mkr_has_vtx.find(mkr->id_) == mkr_has_vtx.end()) {
421423
continue;
424+
}
422425

423-
for (size_t c = 0; c < 4; c++) {
424-
auto vtx = marker_vtx_container.get_vertex(mkr, c);
425-
auto new_pos = vtx->estimate();
426-
mkr->corners_pos_w_[c] = new_pos;
426+
for (size_t corner_idx = 0; corner_idx < 4; corner_idx++) {
427+
mkr->corners_pos_w_[corner_idx] = marker_vtx_container.get_vertex(mkr, corner_idx)->estimate();
427428
}
428429
}
429430
}

0 commit comments

Comments
 (0)