19 #ifndef OPTIMIZERS_NONLINEAR_OPTIMIZER_H_ 
   20 #define OPTIMIZERS_NONLINEAR_OPTIMIZER_H_ 
   25 #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h> 
   26 #include <gtsam/nonlinear/NonlinearFactorGraph.h> 
   28 #include <boost/serialization/serialization.hpp> 
   41   bool Optimize(
const gtsam::NonlinearFactorGraph& factors, gtsam::Values& values) 
final;
 
   47   void SetOptimizationParams();
 
   51   void SetOrdering(
const gtsam::NonlinearFactorGraph& factors, 
const gtsam::KeyVector& old_keys);
 
   55   template <
class Archive>
 
   56   void serialize(Archive& ar, 
const unsigned int file_version) {
 
   57     ar& BOOST_SERIALIZATION_NVP(params_);
 
   58     ar& BOOST_SERIALIZATION_NVP(levenberg_marquardt_params_);
 
   62   gtsam::LevenbergMarquardtParams levenberg_marquardt_params_;
 
   67 #endif  // OPTIMIZERS_NONLINEAR_OPTIMIZER_H_