IncrementalFixedLagSmoother.h
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 // \callgraph
21 #pragma once
22 
24 #include <gtsam/nonlinear/ISAM2.h>
25 #include "gtsam_unstable/dllexport.h"
26 
27 namespace gtsam {
28 
34 class GTSAM_UNSTABLE_EXPORT IncrementalFixedLagSmoother: public FixedLagSmoother {
35 
36 public:
37 
39  typedef std::shared_ptr<IncrementalFixedLagSmoother> shared_ptr;
40 
42  IncrementalFixedLagSmoother(double smootherLag = 0.0,
43  const ISAM2Params& parameters = DefaultISAM2Params()) :
44  FixedLagSmoother(smootherLag), isam_(parameters) {
45  }
46 
49  }
50 
52  void print(const std::string& s = "IncrementalFixedLagSmoother:\n",
53  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override;
54 
56  bool equals(const FixedLagSmoother& rhs, double tol = 1e-9) const override;
57 
66  const Values& newTheta = Values(), //
67  const KeyTimestampMap& timestamps = KeyTimestampMap(),
68  const FactorIndices& factorsToRemove = FactorIndices()) override;
69 
74  Values calculateEstimate() const override {
75  return isam_.calculateEstimate();
76  }
77 
84  template<class VALUE>
86  return isam_.calculateEstimate<VALUE>(key);
87  }
88 
90  const ISAM2Params& params() const {
91  return isam_.params();
92  }
93 
96  return isam_.getFactorsUnsafe();
97  }
98 
100  const Values& getLinearizationPoint() const {
101  return isam_.getLinearizationPoint();
102  }
103 
105  const VectorValues& getDelta() const {
106  return isam_.getDelta();
107  }
108 
111  return isam_.marginalCovariance(key);
112  }
113 
115  const ISAM2Result& getISAM2Result() const{ return isamResult_; }
116 
118  const ISAM2& getISAM2() const { return isam_; }
119 
120 protected:
121 
125  params.findUnusedFactorSlots = true;
126  return params;
127  }
128 
132 
135 
137  void eraseKeysBefore(double timestamp);
138 
140  void createOrderingConstraints(const KeyVector& marginalizableKeys,
141  std::optional<FastMap<Key, int> >& constrainedKeys) const;
142 
143 private:
145  static void PrintKeySet(const std::set<Key>& keys, const std::string& label =
146  "Keys:");
147  static void PrintSymbolicFactor(const GaussianFactor::shared_ptr& factor);
148  static void PrintSymbolicGraph(const GaussianFactorGraph& graph,
149  const std::string& label = "Factor Graph:");
150  static void PrintSymbolicTree(const gtsam::ISAM2& isam,
151  const std::string& label = "Bayes Tree:");
152  static void PrintSymbolicTreeHelper(
153  const gtsam::ISAM2Clique::shared_ptr& clique, const std::string indent =
154  "");
155 
156 };
157 // IncrementalFixedLagSmoother
158 
159 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
const gtsam::Symbol key('X', 0)
void PrintKeySet(const KeySet &keys, const string &s, const KeyFormatter &keyFormatter)
Utility function to print sets of keys with optional prefix.
Definition: Key.cpp:85
std::map< Key, double > KeyTimestampMap
Typedef for a Key-Timestamp map/database.
def update(text)
Definition: relicense.py:46
std::shared_ptr< IncrementalFixedLagSmoother > shared_ptr
Typedef for a shared pointer to an Incremental Fixed-Lag Smoother.
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
IncrementalFixedLagSmoother(double smootherLag=0.0, const ISAM2Params &parameters=DefaultISAM2Params())
const ISAM2 & getISAM2() const
Get the iSAM2 object which is used for the inference internally.
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
static const SmartProjectionParams params
FastVector< FactorIndex > FactorIndices
Define collection types:
Definition: Factor.h:36
std::shared_ptr< This > shared_ptr
Definition: ISAM2Clique.h:41
const NonlinearFactorGraph & getFactors() const
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
NonlinearISAM isam(relinearizeInterval)
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
static ConjugateGradientParameters parameters
std::shared_ptr< This > shared_ptr
shared_ptr to this class
traits
Definition: chartTesting.h:28
std::vector< float > Values
Matrix marginalCovariance(Key key) const
Calculate marginal covariance on given variable.
const ISAM2Result & getISAM2Result() const
Get results of latest isam2 update.
const G double tol
Definition: Group.h:86
const KeyVector keys
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:22