ISAM2Clique.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 
22 
23 #include <stack>
24 #include <utility>
25 #include <cassert>
26 
27 using namespace std;
28 
29 namespace gtsam {
30 
31 // Instantiate base class
32 template class BayesTreeCliqueBase<ISAM2Clique, GaussianFactorGraph>;
33 
34 /* ************************************************************************* */
35 void ISAM2Clique::setEliminationResult(
36  const FactorGraphType::EliminationResult& eliminationResult) {
37  conditional_ = eliminationResult.first;
38  cachedFactor_ = eliminationResult.second;
39  // Compute gradient contribution
40  gradientContribution_.resize(conditional_->cols() - 1);
41  // Rewrite -(R * P')'*d as -(d' * R * P')' for computational speed
42  // reasons
43  gradientContribution_ << -conditional_->R().transpose() *
44  conditional_->d(),
45  -conditional_->S().transpose() * conditional_->d();
46 }
47 
48 /* ************************************************************************* */
49 bool ISAM2Clique::equals(const This& other, double tol) const {
50  return Base::equals(other) &&
51  ((!cachedFactor_ && !other.cachedFactor_) ||
52  (cachedFactor_ && other.cachedFactor_ &&
53  cachedFactor_->equals(*other.cachedFactor_, tol)));
54 }
55 
56 /* ************************************************************************* */
57 void ISAM2Clique::print(const string& s, const KeyFormatter& formatter) const {
59  if (cachedFactor_)
60  cachedFactor_->print(s + "Cached: ", formatter);
61  else
62  cout << s << "Cached empty" << endl;
63  if (gradientContribution_.rows() != 0)
64  gtsam::print(gradientContribution_, "Gradient contribution: ");
65 }
66 
67 /* ************************************************************************* */
68 bool ISAM2Clique::isDirty(const KeySet& replaced, const KeySet& changed) const {
69  // if none of the variables in this clique (frontal and separator!) changed
70  // significantly, then by the running intersection property, none of the
71  // cliques in the children need to be processed
72 
73  // Are any clique variables part of the tree that has been redone?
74  bool dirty = replaced.exists(conditional_->frontals().front());
75 #if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS)
76  for (Key frontal : conditional_->frontals()) {
77  assert(dirty == replaced.exists(frontal));
78  }
79 #endif
80 
81  // If not, then has one of the separator variables changed significantly?
82  if (!dirty) {
83  for (Key parent : conditional_->parents()) {
84  if (changed.exists(parent)) {
85  dirty = true;
86  break;
87  }
88  }
89  }
90  return dirty;
91 }
92 
93 /* ************************************************************************* */
98 void ISAM2Clique::fastBackSubstitute(VectorValues* delta) const {
99 #ifdef USE_BROKEN_FAST_BACKSUBSTITUTE
100  // TODO(gareth): This code shares a lot of logic w/ linearAlgorithms-inst,
101  // potentially refactor
102 
103  // Create solution part pointers if necessary and possible - necessary if
104  // solnPointers_ is empty, and possible if either we're a root, or we have
105  // a parent with valid solnPointers_.
106  ISAM2Clique::shared_ptr parent = parent_.lock();
107  if (solnPointers_.empty() && (isRoot() || !parent->solnPointers_.empty())) {
108  for (Key frontal : conditional_->frontals())
109  solnPointers_.emplace(frontal, delta->find(frontal));
110  for (Key parentKey : conditional_->parents()) {
111  assert(parent->solnPointers_.exists(parentKey));
112  solnPointers_.emplace(parentKey, parent->solnPointers_.at(parentKey));
113  }
114  }
115 
116  // See if we can use solution part pointers - we can if they either
117  // already existed or were created above.
118  if (!solnPointers_.empty()) {
119  GaussianConditional& c = *conditional_;
120  // Solve matrix
121  Vector xS;
122  {
123  // Count dimensions of vector
124  DenseIndex dim = 0;
126  parentPointers.reserve(conditional_->nrParents());
127  for (Key parent : conditional_->parents()) {
128  parentPointers.push_back(solnPointers_.at(parent));
129  dim += parentPointers.back()->second.size();
130  }
131 
132  // Fill parent vector
133  xS.resize(dim);
134  DenseIndex vectorPos = 0;
135  for (const VectorValues::const_iterator& parentPointer : parentPointers) {
136  const Vector& parentVector = parentPointer->second;
137  xS.block(vectorPos, 0, parentVector.size(), 1) =
138  parentVector.block(0, 0, parentVector.size(), 1);
139  vectorPos += parentVector.size();
140  }
141  }
142 
143  // NOTE(gareth): We can no longer write: xS = b - S * xS
144  // This is because Eigen (as of 3.3) no longer evaluates S * xS into
145  // a temporary, and the operation trashes valus in xS.
146  // See: http://eigen.tuxfamily.org/index.php?title=3.3
147  const Vector rhs = c.getb() - c.S() * xS;
148  const Vector solution = c.R().triangularView<Eigen::Upper>().solve(rhs);
149 
150  // Check for indeterminant solution
151  if (solution.hasNaN())
152  throw IndeterminantLinearSystemException(c.keys().front());
153 
154  // Insert solution into a VectorValues
155  DenseIndex vectorPosition = 0;
156  for (GaussianConditional::const_iterator frontal = c.beginFrontals();
157  frontal != c.endFrontals(); ++frontal) {
158  solnPointers_.at(*frontal)->second =
159  solution.segment(vectorPosition, c.getDim(frontal));
160  vectorPosition += c.getDim(frontal);
161  }
162  } else {
163  // Just call plain solve because we couldn't use solution pointers.
164  delta->update(conditional_->solve(*delta));
165  }
166 #else
167  delta->update(conditional_->solve(*delta));
168 #endif
169 }
170 
171 /* ************************************************************************* */
172 bool ISAM2Clique::valuesChanged(const KeySet& replaced,
173  const Vector& originalValues,
174  const VectorValues& delta,
175  double threshold) const {
176  auto frontals = conditional_->frontals();
177  if (replaced.exists(frontals.front())) return true;
178  Vector diff = originalValues - delta.vector(frontals);
179  return diff.lpNorm<Eigen::Infinity>() >= threshold;
180 }
181 
182 /* ************************************************************************* */
184 void ISAM2Clique::markFrontalsAsChanged(KeySet* changed) const {
185  for (Key frontal : conditional_->frontals()) {
186  changed->insert(frontal);
187  }
188 }
189 
190 /* ************************************************************************* */
191 void ISAM2Clique::restoreFromOriginals(const Vector& originalValues,
192  VectorValues* delta) const {
193  size_t pos = 0;
194  for (Key frontal : conditional_->frontals()) {
195  auto v = delta->at(frontal);
196  v = originalValues.segment(pos, v.size());
197  pos += v.size();
198  }
199 }
200 
201 /* ************************************************************************* */
202 // Note: not being used right now in favor of non-recursive version below.
203 void ISAM2Clique::optimizeWildfire(const KeySet& replaced, double threshold,
204  KeySet* changed, VectorValues* delta,
205  size_t* count) const {
206  if (isDirty(replaced, *changed)) {
207  // Temporary copy of the original values, to check how much they change
208  auto originalValues = delta->vector(conditional_->frontals());
209 
210  // Back-substitute
211  fastBackSubstitute(delta);
212  count += conditional_->nrFrontals();
213 
214  if (valuesChanged(replaced, originalValues, *delta, threshold)) {
215  markFrontalsAsChanged(changed);
216  } else {
217  restoreFromOriginals(originalValues, delta);
218  }
219 
220  // Recurse to children
221  for (const auto& child : children) {
222  child->optimizeWildfire(replaced, threshold, changed, delta, count);
223  }
224  }
225 }
226 
227 size_t optimizeWildfire(const ISAM2Clique::shared_ptr& root, double threshold,
228  const KeySet& keys, VectorValues* delta) {
229  KeySet changed;
230  size_t count = 0;
231  // starting from the root, call optimize on each conditional
232  if (root) root->optimizeWildfire(keys, threshold, &changed, delta, &count);
233  return count;
234 }
235 
236 /* ************************************************************************* */
237 bool ISAM2Clique::optimizeWildfireNode(const KeySet& replaced, double threshold,
238  KeySet* changed, VectorValues* delta,
239  size_t* count) const {
240  // TODO(gareth): This code shares a lot of logic w/ linearAlgorithms-inst,
241  // potentially refactor
242  bool dirty = isDirty(replaced, *changed);
243  if (dirty) {
244  // Temporary copy of the original values, to check how much they change
245  auto originalValues = delta->vector(conditional_->frontals());
246 
247  // Back-substitute
248  fastBackSubstitute(delta);
249  *count += conditional_->nrFrontals();
250 
251  if (valuesChanged(replaced, originalValues, *delta, threshold)) {
252  markFrontalsAsChanged(changed);
253  } else {
254  restoreFromOriginals(originalValues, delta);
255  }
256  }
257 
258  return dirty;
259 }
260 
262  double threshold, const KeySet& keys,
263  VectorValues* delta) {
264  KeySet changed;
265  size_t count = 0;
266 
267  if (root) {
268  std::stack<ISAM2Clique::shared_ptr> travStack;
269  travStack.push(root);
270  ISAM2Clique::shared_ptr currentNode = root;
271  while (!travStack.empty()) {
272  currentNode = travStack.top();
273  travStack.pop();
274  bool dirty = currentNode->optimizeWildfireNode(keys, threshold, &changed,
275  delta, &count);
276  if (dirty) {
277  for (const auto& child : currentNode->children) {
278  travStack.push(child);
279  }
280  }
281  }
282  }
283 
284  return count;
285 }
286 
287 /* ************************************************************************* */
288 void ISAM2Clique::nnz_internal(size_t* result) const {
289  size_t dimR = conditional_->rows();
290  size_t dimSep = conditional_->S().cols();
291  *result += ((dimR + 1) * dimR) / 2 + dimSep * dimR;
292  // traverse the children
293  for (const auto& child : children) {
294  child->nnz_internal(result);
295  }
296 }
297 
298 /* ************************************************************************* */
299 size_t ISAM2Clique::calculate_nnz() const {
300  size_t result = 0;
301  nnz_internal(&result);
302  return result;
303 }
304 
305 /* ************************************************************************* */
306 void ISAM2Clique::findAll(const KeySet& markedMask, KeySet* keys) const {
307  static const bool debug = false;
308  // does the separator contain any of the variables?
309  bool found = false;
310  for (Key key : conditional_->parents()) {
311  if (markedMask.exists(key)) {
312  found = true;
313  break;
314  }
315  }
316  if (found) {
317  // then add this clique
318  keys->insert(conditional_->beginFrontals(), conditional_->endFrontals());
319  if (debug) print("Key(s) marked in clique ");
320  if (debug) cout << "so marking key " << conditional_->front() << endl;
321  }
322  for (const auto& child : children) {
323  child->findAll(markedMask, keys);
324  }
325 }
326 
327 /* ************************************************************************* */
328 void ISAM2Clique::addGradientAtZero(VectorValues* g) const {
329  // Loop through variables in each clique, adding contributions
330  DenseIndex position = 0;
331  for (auto it = conditional_->begin(); it != conditional_->end(); ++it) {
332  const DenseIndex dim = conditional_->getDim(it);
333  const Vector contribution = gradientContribution_.segment(position, dim);
334  auto [values_it, success] = g->tryInsert(*it, contribution);
335  if (!success) values_it->second += contribution;
336  position += dim;
337  }
338 
339  // Recursively add contributions from children
340  for (const auto& child : children) {
341  child->addGradientAtZero(g);
342  }
343 }
344 
345 /* ************************************************************************* */
346 } // namespace gtsam
ISAM2Clique.h
Specialized iSAM2 Clique.
Eigen::internal::print
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
Definition: NEON/PacketMath.h:3115
s
RealScalar s
Definition: level1_cplx_impl.h:126
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::FastSet::exists
bool exists(const VALUE &e) const
Definition: FastSet.h:98
gtsam::FastVector
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
Eigen::Upper
@ Upper
Definition: Constants.h:211
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
gtsam::FastSet< Key >
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::optimizeWildfire
size_t optimizeWildfire(const ISAM2Clique::shared_ptr &root, double threshold, const KeySet &keys, VectorValues *delta)
Definition: ISAM2Clique.cpp:227
gtsam::VectorValues::const_iterator
Values::const_iterator const_iterator
Const iterator over vector values.
Definition: VectorValues.h:85
gtsam::EliminateableFactorGraph< GaussianFactorGraph >::EliminationResult
std::pair< std::shared_ptr< ConditionalType >, std::shared_ptr< _FactorType > > EliminationResult
Definition: EliminateableFactorGraph.h:85
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
gtsam::optimizeWildfireNonRecursive
size_t optimizeWildfireNonRecursive(const ISAM2Clique::shared_ptr &root, double threshold, const KeySet &keys, VectorValues *delta)
Definition: ISAM2Clique.cpp:261
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
gtsam::VectorValues
Definition: VectorValues.h:74
gtsam::KeyFormatter
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
debug
static constexpr bool debug
Definition: testDiscreteBayesTree.cpp:31
gtsam::GaussianConditional
Definition: GaussianConditional.h:40
VectorValues.h
Factor Graph Values.
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
linearAlgorithms-inst.h
Templated algorithms that are used in multiple places in linear.
key
const gtsam::Symbol key('X', 0)
gtsam::ISAM2Clique::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: ISAM2Clique.h:41
gtsam::Factor::const_iterator
KeyVector::const_iterator const_iterator
Const iterator over keys.
Definition: Factor.h:83
gtsam
traits
Definition: SFMdata.h:40
gtsam::ISAM2Clique
Definition: ISAM2Clique.h:36
gtsam::DenseIndex
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:103
std
Definition: BFloat16.h:88
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::internal::position
Point3 position(const NavState &X, OptionalJacobian< 3, 9 > H)
Definition: navigation/expressions.h:25
gtsam::tol
const G double tol
Definition: Group.h:79
BayesTreeCliqueBase-inst.h
Base class for cliques of a BayesTree.
gtsam::IndeterminantLinearSystemException
Definition: linearExceptions.h:94
pos
Definition: example-NearestNeighbor.cpp:32
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
Eigen::Infinity
const int Infinity
Definition: Constants.h:36
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:46