25 #include "gtsam_unstable/dllexport.h" 39 typedef std::shared_ptr<IncrementalFixedLagSmoother>
shared_ptr;
52 void print(
const std::string&
s =
"IncrementalFixedLagSmoother:\n",
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);
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(
void print(const Matrix &A, const string &s, ostream &stream)
const gtsam::Symbol key('X', 0)
bool findUnusedFactorSlots
void PrintKeySet(const KeySet &keys, const string &s, const KeyFormatter &keyFormatter)
Utility function to print sets of keys with optional prefix.
std::map< Key, double > KeyTimestampMap
Typedef for a Key-Timestamp map/database.
static ISAM2Params DefaultISAM2Params()
const Values & getLinearizationPoint() const
std::shared_ptr< IncrementalFixedLagSmoother > shared_ptr
Typedef for a shared pointer to an Incremental Fixed-Lag Smoother.
const VectorValues & getDelta() const
IncrementalFixedLagSmoother(double smootherLag=0.0, const ISAM2Params ¶meters=DefaultISAM2Params())
const ISAM2 & getISAM2() const
Get the iSAM2 object which is used for the inference internally.
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
Values calculateEstimate() const override
static const SmartProjectionParams params
FastVector< FactorIndex > FactorIndices
Define collection types:
std::shared_ptr< This > shared_ptr
const NonlinearFactorGraph & getFactors() const
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
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.
static ConjugateGradientParameters parameters
std::shared_ptr< This > shared_ptr
shared_ptr to this class
std::vector< float > Values
~IncrementalFixedLagSmoother() override
Matrix marginalCovariance(Key key) const
Calculate marginal covariance on given variable.
const ISAM2Result & getISAM2Result() const
Get results of latest isam2 update.
VALUE calculateEstimate(Key key) const
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
std::uint64_t Key
Integer nonlinear key type.
const ISAM2Params & params() const