Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
normal_levenberg_optimizer.cpp
Go to the documentation of this file.
1
#include "
slam_solver/graph_slam_solver/optimizer/normal_levenberg_optimizer.hpp
"
2
3
NormalLevenbergOptimizer::NormalLevenbergOptimizer
(
const
SLAMParameters
& params)
4
:
BaseOptimizer
(params){};
5
6
std::shared_ptr<BaseOptimizer>
NormalLevenbergOptimizer::clone
()
const
{
7
return
std::make_shared<NormalLevenbergOptimizer>(*
this
);
8
}
9
10
gtsam::Values
NormalLevenbergOptimizer::optimize
(gtsam::NonlinearFactorGraph& factor_graph,
11
gtsam::Values& graph_values,
12
[[maybe_unused]]
unsigned
int
pose_num,
13
[[maybe_unused]]
unsigned
int
landmark_num) {
14
gtsam::LevenbergMarquardtOptimizer optimizer(factor_graph, graph_values);
15
return
optimizer.optimize();
16
}
BaseOptimizer
Base class for graph optimizers.
Definition
base_optimizer.hpp:13
NormalLevenbergOptimizer::clone
std::shared_ptr< BaseOptimizer > clone() const override
Clone the optimizer.
Definition
normal_levenberg_optimizer.cpp:6
NormalLevenbergOptimizer::optimize
gtsam::Values optimize(gtsam::NonlinearFactorGraph &factor_graph, gtsam::Values &graph_values, unsigned int pose_num, unsigned int landmark_num) override
Optimize the graph.
Definition
normal_levenberg_optimizer.cpp:10
NormalLevenbergOptimizer::NormalLevenbergOptimizer
NormalLevenbergOptimizer(const SLAMParameters ¶ms)
Definition
normal_levenberg_optimizer.cpp:3
normal_levenberg_optimizer.hpp
SLAMParameters
Parameters for the SLAM node.
Definition
general_config.hpp:12
src
slam
src
slam_solver
graph_slam_solver
optimizer
normal_levenberg_optimizer.cpp
Generated by
1.9.8