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.
2
5
6std::shared_ptr<BaseOptimizer> NormalLevenbergOptimizer::clone() const {
7 return std::make_shared<NormalLevenbergOptimizer>(*this);
8}
9
10gtsam::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}
Base class for graph optimizers.
std::shared_ptr< BaseOptimizer > clone() const override
Clone the optimizer.
gtsam::Values optimize(gtsam::NonlinearFactorGraph &factor_graph, gtsam::Values &graph_values, unsigned int pose_num, unsigned int landmark_num) override
Optimize the graph.
NormalLevenbergOptimizer(const SLAMParameters &params)
Parameters for the SLAM node.