NonlinearConjugateGradientOptimizer.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
21 #include <gtsam/nonlinear/Values.h>
24 
25 #include <cmath>
26 
27 namespace gtsam {
28 
29 typedef internal::NonlinearOptimizerState State;
30 
38  const Values &values) {
39  // Linearize graph
40  GaussianFactorGraph::shared_ptr linear = nfg.linearize(values);
41  return linear->gradientAtZero();
42 }
43 
45  const NonlinearFactorGraph& graph, const Values& initialValues, const Parameters& params)
46  : Base(graph, std::unique_ptr<State>(new State(initialValues, graph.error(initialValues)))),
47  params_(params) {}
48 
49 double NonlinearConjugateGradientOptimizer::System::error(const State& state) const {
50  return graph_.error(state);
51 }
52 
54  const State &state) const {
55  return gradientInPlace(graph_, state);
56 }
57 
59  const State &current, const double alpha, const Gradient &g) const {
60  Gradient step = g;
61  step *= alpha;
62  return current.retract(step);
63 }
64 
66  Values newValues;
67  int dummy;
68  boost::tie(newValues, dummy) = nonlinearConjugateGradient<System, Values>(
69  System(graph_), state_->values, params_, true /* single iteration */);
70  state_.reset(new State(newValues, graph_.error(newValues), state_->iterations + 1));
71 
72  // NOTE(frank): We don't linearize this system, so we must return null here.
73  return nullptr;
74 }
75 
77  // Optimize until convergence
78  System system(graph_);
79  Values newValues;
80  int iterations;
81  boost::tie(newValues, iterations) =
82  nonlinearConjugateGradient(system, state_->values, params_, false);
83  state_.reset(new State(std::move(newValues), graph_.error(newValues), iterations));
84  return state_->values;
85 }
86 
87 } /* namespace gtsam */
88 
def step(data, isam, result, truth, currPoseIndex)
Definition: visual_isam.py:82
A non-templated config holding any types of Manifold-group elements.
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
boost::tuple< V, int > nonlinearConjugateGradient(const S &system, const V &initial, const NonlinearOptimizerParams &params, const bool singleIteration, const bool gradientDescent=false)
leaf::MyValues values
Definition: Half.h:150
Values retract(const VectorValues &delta) const
Definition: Values.cpp:109
NonlinearFactorGraph graph
void g(const string &key, int i)
Definition: testBTree.cpp:43
std::unique_ptr< internal::NonlinearOptimizerState > state_
PIMPL&#39;d state.
Factor Graph Values.
GaussianFactorGraph::shared_ptr iterate() override
RealScalar alpha
Linear Factor Graph where all factors are Gaussians.
static SmartStereoProjectionParams params
internal::DoglegState State
NonlinearConjugateGradientOptimizer(const NonlinearFactorGraph &graph, const Values &initialValues, const Parameters &params=Parameters())
Constructor.
traits
Definition: chartTesting.h:28
static VectorValues gradientInPlace(const NonlinearFactorGraph &nfg, const Values &values)
Return the gradient vector of a nonlinear factor graph.
NonlinearFactorGraph graph_
The graph with nonlinear factors.
Private class for NonlinearOptimizer state.
State advance(const State &current, const double alpha, const Gradient &g) const
static double error
Definition: testRot3.cpp:39
double error(const Values &values) const
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
Simple non-linear optimizer that solves using non-preconditioned CG.
size_t iterations() const
return number of iterations in current optimizer state


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:03