Skip to content

Commit 7b78cc9

Browse files
authored
Add Options for GlobalOptimizer (#621)
* Add Options for GlobalOptimizer - num_iter - use_huber_kernel * Update clang-format-lint-action
1 parent 4be17ea commit 7b78cc9

File tree

4 files changed

+15
-6
lines changed

4 files changed

+15
-6
lines changed

.github/workflows/main.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ jobs:
2626
shell: bash
2727
steps:
2828
- uses: actions/checkout@v3
29-
- uses: DoozyX/clang-format-lint-action@v0.12
29+
- uses: DoozyX/clang-format-lint-action@v0.18.1
3030
with:
3131
source: "."
3232
exclude: "./3rd"

src/stella_vslam/global_optimization_module.cc

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,10 @@ global_optimization_module::global_optimization_module(data::map_database* map_d
1616
data::bow_vocabulary* bow_vocab, const YAML::Node& yaml_node,
1717
const bool fix_scale)
1818
: loop_detector_(new module::loop_detector(bow_db, bow_vocab, util::yaml_optional_ref(yaml_node, "LoopDetector"), fix_scale)),
19-
loop_bundle_adjuster_(new module::loop_bundle_adjuster(map_db)),
19+
loop_bundle_adjuster_(new module::loop_bundle_adjuster(
20+
map_db,
21+
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))),
2023
map_db_(map_db),
2124
graph_optimizer_(new optimize::graph_optimizer(util::yaml_optional_ref(yaml_node, "GraphOptimizer"), fix_scale)),
2225
thr_neighbor_keyframes_(util::yaml_optional_ref(yaml_node, "GlobalOptimizer")["thr_neighbor_keyframes"].as<unsigned int>(15)) {

src/stella_vslam/module/loop_bundle_adjuster.cc

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,10 @@
1212
namespace stella_vslam {
1313
namespace module {
1414

15-
loop_bundle_adjuster::loop_bundle_adjuster(data::map_database* map_db, const unsigned int num_iter)
16-
: map_db_(map_db), num_iter_(num_iter) {}
15+
loop_bundle_adjuster::loop_bundle_adjuster(data::map_database* map_db,
16+
const unsigned int num_iter,
17+
const bool use_huber_kernel)
18+
: map_db_(map_db), num_iter_(num_iter), use_huber_kernel_(use_huber_kernel) {}
1719

1820
void loop_bundle_adjuster::set_mapping_module(mapping_module* mapper) {
1921
mapper_ = mapper;
@@ -42,7 +44,7 @@ void loop_bundle_adjuster::optimize(const std::shared_ptr<data::keyframe>& curr_
4244
std::unordered_set<unsigned int> optimized_landmark_ids;
4345
eigen_alloc_unord_map<unsigned int, Vec3_t> lm_to_pos_w_after_global_BA;
4446
eigen_alloc_unord_map<unsigned int, Mat44_t> keyfrm_to_pose_cw_after_global_BA;
45-
const auto global_BA = optimize::global_bundle_adjuster(num_iter_, false);
47+
const auto global_BA = optimize::global_bundle_adjuster(num_iter_, use_huber_kernel_);
4648
bool ok = global_BA.optimize(curr_keyfrm->graph_node_->get_keyframes_from_root(),
4749
optimized_keyfrm_ids, optimized_landmark_ids,
4850
lm_to_pos_w_after_global_BA,

src/stella_vslam/module/loop_bundle_adjuster.h

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,9 @@ class loop_bundle_adjuster {
1919
/**
2020
* Constructor
2121
*/
22-
explicit loop_bundle_adjuster(data::map_database* map_db, const unsigned int num_iter = 10);
22+
explicit loop_bundle_adjuster(data::map_database* map_db,
23+
const unsigned int num_iter = 10,
24+
const bool use_huber_kernel = false);
2325

2426
/**
2527
* Destructor
@@ -56,6 +58,8 @@ class loop_bundle_adjuster {
5658
//! number of iteration for optimization
5759
const unsigned int num_iter_ = 10;
5860

61+
const bool use_huber_kernel_ = false;
62+
5963
//-----------------------------------------
6064
// thread management
6165

0 commit comments

Comments
 (0)