3#include <gtsam/nonlinear/NonlinearFactorGraph.h>
4#include <gtsam/nonlinear/Values.h>
21 if (
this == &other)
return *
this;
34 virtual std::shared_ptr<BaseOptimizer>
clone()
const = 0;
50 virtual gtsam::Values
optimize(gtsam::NonlinearFactorGraph& factor_graph,
51 gtsam::Values& graph_values,
52 [[maybe_unused]]
unsigned int pose_num,
53 [[maybe_unused]]
unsigned int landmark_num) = 0;
Base class for graph optimizers.
BaseOptimizer & operator=(const BaseOptimizer &other)
virtual ~BaseOptimizer()=default
BaseOptimizer(const BaseOptimizer &other)
BaseOptimizer(const SLAMParameters ¶ms)
const SLAMParameters & _params_
virtual std::shared_ptr< BaseOptimizer > clone() const =0
Clone the optimizer.
virtual gtsam::Values optimize(gtsam::NonlinearFactorGraph &factor_graph, gtsam::Values &graph_values, unsigned int pose_num, unsigned int landmark_num)=0
Optimize the graph.
Parameters for the SLAM node.