38 typedef boost::shared_ptr<IncrementalFixedLagSmoother>
shared_ptr;
51 void print(
const std::string&
s =
"IncrementalFixedLagSmoother:\n",
74 return isam_.calculateEstimate();
85 return isam_.calculateEstimate<VALUE>(
key);
90 return isam_.params();
95 return isam_.getFactorsUnsafe();
100 return isam_.getLinearizationPoint();
105 return isam_.getDelta();
110 return isam_.marginalCovariance(key);
133 void eraseKeysBefore(
double timestamp);
136 void createOrderingConstraints(
const KeyVector& marginalizableKeys,
141 static void PrintKeySet(
const std::set<Key>&
keys,
const std::string& label =
145 const std::string& label =
"Factor Graph:");
147 const std::string& label =
"Bayes Tree:");
148 static void PrintSymbolicTreeHelper(
void print(const Matrix &A, const string &s, ostream &stream)
bool findUnusedFactorSlots
boost::shared_ptr< IncrementalFixedLagSmoother > shared_ptr
Typedef for a shared pointer to an Incremental Fixed-Lag Smoother.
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()
boost::shared_ptr< This > shared_ptr
Base class for a fixed-lag smoother. This mimics the basic interface to iSAM2.
FastVector< FactorIndex > FactorIndices
Define collection types:
IncrementalFixedLagSmoother(double smootherLag=0.0, const ISAM2Params ¶meters=DefaultISAM2Params())
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
Values calculateEstimate() const override
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
const ISAM2Result & getISAM2Result() const
Get results of latest isam2 update.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
NonlinearISAM isam(relinearizeInterval)
static SmartStereoProjectionParams params
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
static ConjugateGradientParameters parameters
std::vector< float > Values
~IncrementalFixedLagSmoother() override
const NonlinearFactorGraph & getFactors() const
VALUE calculateEstimate(Key key) const
const ISAM2Params & params() const
const Values & getLinearizationPoint() const
const VectorValues & getDelta() const
Matrix marginalCovariance(Key key) const
Calculate marginal covariance on given variable.
std::uint64_t Key
Integer nonlinear key type.