Go to the documentation of this file.00001 
00029 #pragma once
00030 
00031 #include <Eigen/Dense>
00032 
00033 #include "Properties.h"
00034 #include "OptimizationInterface.h"
00035 #include "SparseSystem.h"
00036 #include "Cholesky.h"
00037 #include "Node.h"
00038 
00039 namespace isam {
00040 
00041 class Optimizer {
00042 
00043 private:
00044 
00049   OptimizationInterface& function_system;
00050 
00055   Cholesky* _cholesky;
00056 
00060   Eigen::VectorXd gradient;
00061 
00065   double Delta;
00066 
00071   Eigen::VectorXd last_accepted_hdl;
00072 
00077   double current_SSE_at_linpoint;
00078 
00079 
00080   void update_trust_radius(double rho, double hdl_norm);
00081 
00088   Eigen::VectorXd compute_dog_leg(double alpha, const Eigen::VectorXd& h_sd,
00089       const Eigen::VectorXd& h_gn, double delta,
00090       double& gain_ratio_denominator);
00091 
00092   bool powells_dog_leg_update(double epsilon1, double epsilon3,
00093       SparseSystem& jacobian, Eigen::VectorXd& f_x, Eigen::VectorXd& gradient);
00094 
00105   void permute_vector(const Eigen::VectorXd& v, Eigen::VectorXd& p,
00106       const int* permutation);
00107 
00120   Eigen::VectorXd compute_gauss_newton_step(const SparseSystem& jacobian,
00121       SparseSystem* R = NULL, double lambda = 0.);
00122 
00123   void gauss_newton(const Properties& prop, int* num_iterations = NULL);
00124 
00131   void levenberg_marquardt(const Properties& prop, int* num_iterations = NULL);
00132 
00148   void powells_dog_leg(int* num_iterations = NULL, double delta0 = 1.0,
00149       int max_iterations = 0, double epsilon1 = 1e-4, double epsilon2 = 1e-4,
00150       double epsilon3 = 1e-4);
00151 
00152 public:
00153 
00154   Optimizer(OptimizationInterface& fs)
00155       : function_system(fs), Delta(1.0) {
00156     
00157     _cholesky = Cholesky::Create();
00158   }
00159 
00163   void batch_optimize(const Properties& prop, int* num_iterations);
00164 
00169   void augment_sparse_linear_system(SparseSystem& W, const Properties& prop);
00170 
00211   void relinearize(const Properties& prop);
00212 
00216   void update_estimate(const Properties& prop);
00217 
00218   ~Optimizer() {
00219     delete _cholesky;
00220   }
00221 
00222 };
00223 
00224 }