Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
sliding_window_levenberg_optimizer.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
4
6
14public:
16
18
26 std::shared_ptr<BaseOptimizer> clone() const override;
27
40 gtsam::Values optimize(gtsam::NonlinearFactorGraph& factor_graph, gtsam::Values& graph_values,
41 [[maybe_unused]] unsigned int pose_num,
42 [[maybe_unused]] unsigned int landmark_num) override;
43};
Base class for graph optimizers.
Sliding Window Levenberg-Marquardt optimizer for graph SLAM.
std::shared_ptr< BaseOptimizer > clone() const override
Clone the optimizer.
~SlidingWindowLevenbergOptimizer() override=default
gtsam::Values optimize(gtsam::NonlinearFactorGraph &factor_graph, gtsam::Values &graph_values, unsigned int pose_num, unsigned int landmark_num) override
Optimize the graph.
Parameters for the SLAM node.