3#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
25 std::shared_ptr<BaseOptimizer>
clone()
const override;
39 gtsam::Values
optimize(gtsam::NonlinearFactorGraph& factor_graph, gtsam::Values& graph_values,
40 [[maybe_unused]]
unsigned int pose_num,
41 [[maybe_unused]]
unsigned int landmark_num)
override;
Base class for graph optimizers.
Normal Levenberg-Marquardt optimizer for graph SLAM.
std::shared_ptr< BaseOptimizer > clone() const override
Clone the optimizer.
~NormalLevenbergOptimizer() 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.