Go to the documentation of this file.
25 #include "gtsam_unstable/dllexport.h"
39 typedef std::shared_ptr<IncrementalFixedLagSmoother>
shared_ptr;
52 void print(
const std::string&
s =
"IncrementalFixedLagSmoother:\n",
67 const KeyTimestampMap& timestamps = KeyTimestampMap(),
75 return isam_.calculateEstimate();
86 return isam_.calculateEstimate<
VALUE>(
key);
91 return isam_.params();
96 return isam_.getFactorsUnsafe();
101 return isam_.getLinearizationPoint();
106 return isam_.getDelta();
111 return isam_.marginalCovariance(
key);
125 params.findUnusedFactorSlots =
true;
137 void eraseKeysBefore(
double timestamp);
140 void createOrderingConstraints(
const KeyVector& marginalizableKeys,
145 static void PrintKeySet(
const std::set<Key>&
keys,
const std::string& label =
149 const std::string& label =
"Factor Graph:");
151 const std::string& label =
"Bayes Tree:");
152 static void PrintSymbolicTreeHelper(
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const ISAM2Result & getISAM2Result() const
Get results of latest isam2 update.
const VectorValues & getDelta() const
static const SmartProjectionParams params
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
void print(const Matrix &A, const string &s, ostream &stream)
std::shared_ptr< IncrementalFixedLagSmoother > shared_ptr
Typedef for a shared pointer to an Incremental Fixed-Lag Smoother.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
static ConjugateGradientParameters parameters
NonlinearISAM isam(relinearizeInterval)
std::shared_ptr< This > shared_ptr
shared_ptr to this class
const ISAM2 & getISAM2() const
Get the iSAM2 object which is used for the inference internally.
VALUE calculateEstimate(Key key) const
const gtsam::Symbol key('X', 0)
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
std::shared_ptr< This > shared_ptr
const NonlinearFactorGraph & getFactors() const
Base class for a fixed-lag smoother. This mimics the basic interface to iSAM2.
std::vector< float > Values
Matrix marginalCovariance(Key key) const
Calculate marginal covariance on given variable.
const Values & getLinearizationPoint() const
Values calculateEstimate() const override
static ISAM2Params DefaultISAM2Params()
NonlinearFactorGraph graph
std::uint64_t Key
Integer nonlinear key type.
const ISAM2Params & params() const
void PrintKeySet(const KeySet &keys, const string &s, const KeyFormatter &keyFormatter)
Utility function to print sets of keys with optional prefix.
IncrementalFixedLagSmoother(double smootherLag=0.0, const ISAM2Params ¶meters=DefaultISAM2Params())
~IncrementalFixedLagSmoother() override
FastVector< FactorIndex > FactorIndices
Define collection types:
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:27