19 #ifndef OPTIMIZERS_ISAM2_OPTIMIZER_H_
20 #define OPTIMIZERS_ISAM2_OPTIMIZER_H_
25 #include <gtsam/nonlinear/NonlinearFactorGraph.h>
26 #include <gtsam/nonlinear/ISAM2.h>
27 #include <gtsam/nonlinear/ISAM2Params.h>
29 #include <boost/serialization/serialization.hpp>
44 bool Optimize(
const gtsam::NonlinearFactorGraph& factors, gtsam::Values& values)
final;
50 void SetOptimizationParams();
54 template <
class Archive>
55 void serialize(Archive& ar,
const unsigned int file_version) {
56 ar& BOOST_SERIALIZATION_NVP(params_);
57 ar& BOOST_SERIALIZATION_NVP(isam2_params_);
58 ar& BOOST_SERIALIZATION_NVP(isam2_);
59 ar& BOOST_SERIALIZATION_NVP(previous_factors_);
60 ar& BOOST_SERIALIZATION_NVP(previous_values_);
64 gtsam::ISAM2Params isam2_params_;
65 std::unique_ptr<gtsam::ISAM2> isam2_;
68 gtsam::NonlinearFactorGraph previous_factors_;
69 gtsam::Values previous_values_;
73 #endif // OPTIMIZERS_ISAM2_OPTIMIZER_H_