ISAM2-impl.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 
20 #include <gtsam/base/debug.h>
21 #include <gtsam/config.h> // for GTSAM_USE_TBB
22 #include <gtsam/inference/Symbol.h> // for selective linearization thresholds
24 
25 #include <boost/range/adaptors.hpp>
26 #include <functional>
27 #include <limits>
28 #include <string>
29 
30 using namespace std;
31 
32 namespace gtsam {
33 
34 /* ************************************************************************* */
35 namespace internal {
36 inline static void optimizeInPlace(const ISAM2::sharedClique& clique,
38  // parents are assumed to already be solved and available in result
39  result->update(clique->conditional()->solve(*result));
40 
41  // starting from the root, call optimize on each conditional
42  for (const ISAM2::sharedClique& child : clique->children)
43  optimizeInPlace(child, result);
44 }
45 } // namespace internal
46 
47 /* ************************************************************************* */
48 size_t DeltaImpl::UpdateGaussNewtonDelta(const ISAM2::Roots& roots,
49  const KeySet& replacedKeys,
50  double wildfireThreshold,
52  size_t lastBacksubVariableCount;
53 
54  if (wildfireThreshold <= 0.0) {
55  // Threshold is zero or less, so do a full recalculation
56  for (const ISAM2::sharedClique& root : roots)
58  lastBacksubVariableCount = delta->size();
59 
60  } else {
61  // Optimize with wildfire
62  lastBacksubVariableCount = 0;
63  for (const ISAM2::sharedClique& root : roots)
64  lastBacksubVariableCount += optimizeWildfireNonRecursive(
65  root, wildfireThreshold, replacedKeys, delta); // modifies delta
66 
67 #if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS)
68  for (VectorValues::const_iterator key_delta = delta->begin();
69  key_delta != delta->end(); ++key_delta) {
70  assert((*delta)[key_delta->first].allFinite());
71  }
72 #endif
73  }
74 
75  return lastBacksubVariableCount;
76 }
77 
78 /* ************************************************************************* */
79 namespace internal {
80 void updateRgProd(const ISAM2::sharedClique& clique, const KeySet& replacedKeys,
81  const VectorValues& grad, VectorValues* RgProd,
82  size_t* varsUpdated) {
83  // Check if any frontal or separator keys were recalculated, if so, we need
84  // update deltas and recurse to children, but if not, we do not need to
85  // recurse further because of the running separator property.
86  bool anyReplaced = false;
87  for (Key j : *clique->conditional()) {
88  if (replacedKeys.exists(j)) {
89  anyReplaced = true;
90  break;
91  }
92  }
93 
94  if (anyReplaced) {
95  // Update the current variable
96  // Get VectorValues slice corresponding to current variables
97  Vector gR =
98  grad.vector(KeyVector(clique->conditional()->beginFrontals(),
99  clique->conditional()->endFrontals()));
100  Vector gS =
101  grad.vector(KeyVector(clique->conditional()->beginParents(),
102  clique->conditional()->endParents()));
103 
104  // Compute R*g and S*g for this clique
105  Vector RSgProd = clique->conditional()->R() * gR +
106  clique->conditional()->S() * gS;
107 
108  // Write into RgProd vector
109  DenseIndex vectorPosition = 0;
110  for (Key frontal : clique->conditional()->frontals()) {
111  Vector& RgProdValue = (*RgProd)[frontal];
112  RgProdValue = RSgProd.segment(vectorPosition, RgProdValue.size());
113  vectorPosition += RgProdValue.size();
114  }
115 
116  // Now solve the part of the Newton's method point for this clique
117  // (back-substitution)
118  // (*clique)->solveInPlace(deltaNewton);
119 
120  *varsUpdated += clique->conditional()->nrFrontals();
121 
122  // Recurse to children
123  for (const ISAM2::sharedClique& child : clique->children) {
124  updateRgProd(child, replacedKeys, grad, RgProd, varsUpdated);
125  }
126  }
127 }
128 } // namespace internal
129 
130 /* ************************************************************************* */
131 size_t DeltaImpl::UpdateRgProd(const ISAM2::Roots& roots,
132  const KeySet& replacedKeys,
133  const VectorValues& gradAtZero,
134  VectorValues* RgProd) {
135  // Update variables
136  size_t varsUpdated = 0;
137  for (const ISAM2::sharedClique& root : roots) {
138  internal::updateRgProd(root, replacedKeys, gradAtZero, RgProd,
139  &varsUpdated);
140  }
141 
142  return varsUpdated;
143 }
144 
145 /* ************************************************************************* */
146 VectorValues DeltaImpl::ComputeGradientSearch(const VectorValues& gradAtZero,
147  const VectorValues& RgProd) {
148  // Compute gradient squared-magnitude
149  const double gradientSqNorm = gradAtZero.dot(gradAtZero);
150 
151  // Compute minimizing step size
152  double RgNormSq = RgProd.vector().squaredNorm();
153  double step = -gradientSqNorm / RgNormSq;
154 
155  // Compute steepest descent point
156  return step * gradAtZero;
157 }
158 
159 } // namespace gtsam
def step(data, isam, result, truth, currPoseIndex)
Definition: visual_isam.py:82
Global debugging flags.
size_t size() const
Definition: VectorValues.h:125
Definition: Half.h:150
iterator end()
Iterator over variables.
Definition: VectorValues.h:228
void update(const VectorValues &values)
const mpreal root(const mpreal &x, unsigned long int k, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2194
bool exists(const VALUE &e) const
Definition: FastSet.h:98
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:67
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
size_t optimizeWildfireNonRecursive(const ISAM2Clique::shared_ptr &root, double threshold, const KeySet &keys, VectorValues *delta)
void updateRgProd(const ISAM2::sharedClique &clique, const KeySet &replacedKeys, const VectorValues &grad, VectorValues *RgProd, size_t *varsUpdated)
Definition: ISAM2-impl.cpp:80
static void optimizeInPlace(const ISAM2::sharedClique &clique, VectorValues *result)
Definition: ISAM2-impl.cpp:36
Base::sharedClique sharedClique
Shared pointer to a clique.
Definition: ISAM2.h:103
Values::const_iterator const_iterator
Const iterator over vector values.
Definition: VectorValues.h:82
double dot(const VectorValues &v) const
traits
Definition: chartTesting.h:28
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
FastVector< sharedClique > Roots
Definition: BayesTree.h:93
iterator begin()
Iterator over variables.
Definition: VectorValues.h:226
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j
Vector vector() const


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:18