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 }
gtsam::ISAM2Params
Definition: ISAM2Params.h:136
relicense.update
def update(text)
Definition: relicense.py:46
gtsam::ISAM2
Definition: ISAM2.h:45
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
gtsam::IncrementalFixedLagSmoother::getISAM2Result
const ISAM2Result & getISAM2Result() const
Get results of latest isam2 update.
Definition: IncrementalFixedLagSmoother.h:115
gtsam::IncrementalFixedLagSmoother::isam_
ISAM2 isam_
Definition: IncrementalFixedLagSmoother.h:131
gtsam::FastMap
Definition: FastMap.h:39
gtsam::IncrementalFixedLagSmoother::getDelta
const VectorValues & getDelta() const
Definition: IncrementalFixedLagSmoother.h:105
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
vanilla::params
static const SmartProjectionParams params
Definition: smartFactorScenarios.h:69
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
Eigen::internal::VALUE
@ VALUE
Definition: SpecialFunctionsImpl.h:729
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
gtsam::IncrementalFixedLagSmoother::isamResult_
ISAM2Result isamResult_
Definition: IncrementalFixedLagSmoother.h:134
gtsam::FixedLagSmoother
Definition: nonlinear/FixedLagSmoother.h:33
gtsam::IncrementalFixedLagSmoother::shared_ptr
std::shared_ptr< IncrementalFixedLagSmoother > shared_ptr
Typedef for a shared pointer to an Incremental Fixed-Lag Smoother.
Definition: IncrementalFixedLagSmoother.h:39
gtsam::IncrementalFixedLagSmoother
Definition: IncrementalFixedLagSmoother.h:34
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
parameters
static ConjugateGradientParameters parameters
Definition: testIterative.cpp:33
isam
NonlinearISAM isam(relinearizeInterval)
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::GaussianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42
gtsam::IncrementalFixedLagSmoother::getISAM2
const ISAM2 & getISAM2() const
Get the iSAM2 object which is used for the inference internally.
Definition: IncrementalFixedLagSmoother.h:118
gtsam::IncrementalFixedLagSmoother::calculateEstimate
VALUE calculateEstimate(Key key) const
Definition: IncrementalFixedLagSmoother.h:85
gtsam::equals
Definition: Testable.h:112
key
const gtsam::Symbol key('X', 0)
ISAM2.h
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
gtsam::ISAM2Clique::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: ISAM2Clique.h:41
gtsam::IncrementalFixedLagSmoother::getFactors
const NonlinearFactorGraph & getFactors() const
Definition: IncrementalFixedLagSmoother.h:95
FixedLagSmoother.h
Base class for a fixed-lag smoother. This mimics the basic interface to iSAM2.
Values
std::vector< float > Values
Definition: sparse_setter.cpp:45
gtsam
traits
Definition: chartTesting.h:28
gtsam::Values
Definition: Values.h:65
gtsam::IncrementalFixedLagSmoother::marginalCovariance
Matrix marginalCovariance(Key key) const
Calculate marginal covariance on given variable.
Definition: IncrementalFixedLagSmoother.h:110
gtsam::IncrementalFixedLagSmoother::getLinearizationPoint
const Values & getLinearizationPoint() const
Definition: IncrementalFixedLagSmoother.h:100
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::ISAM2Result
Definition: ISAM2Result.h:39
gtsam::IncrementalFixedLagSmoother::calculateEstimate
Values calculateEstimate() const override
Definition: IncrementalFixedLagSmoother.h:74
gtsam::IncrementalFixedLagSmoother::DefaultISAM2Params
static ISAM2Params DefaultISAM2Params()
Definition: IncrementalFixedLagSmoother.h:123
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::IncrementalFixedLagSmoother::params
const ISAM2Params & params() const
Definition: IncrementalFixedLagSmoother.h:90
gtsam::PrintKeySet
void PrintKeySet(const KeySet &keys, const string &s, const KeyFormatter &keyFormatter)
Utility function to print sets of keys with optional prefix.
Definition: Key.cpp:88
gtsam::IncrementalFixedLagSmoother::IncrementalFixedLagSmoother
IncrementalFixedLagSmoother(double smootherLag=0.0, const ISAM2Params &parameters=DefaultISAM2Params())
Definition: IncrementalFixedLagSmoother.h:42
gtsam::IncrementalFixedLagSmoother::~IncrementalFixedLagSmoother
~IncrementalFixedLagSmoother() override
Definition: IncrementalFixedLagSmoother.h:48
gtsam::Result
std::pair< std::shared_ptr< GaussianConditional >, GaussianMixtureFactor::sharedFactor > Result
Definition: HybridGaussianFactorGraph.cpp:280
gtsam::FactorIndices
FastVector< FactorIndex > FactorIndices
Define collection types:
Definition: Factor.h:36


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:01:01