gtsam
4.0.0
gtsam
|
Public Member Functions | |
BatchFixedLagSmoother (double smootherLag=0.0, const LevenbergMarquardtParams ¶meters=LevenbergMarquardtParams(), bool enforceConsistency=true) | |
default constructor | |
virtual | ~BatchFixedLagSmoother () |
destructor | |
virtual void | print (const std::string &s="BatchFixedLagSmoother:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const |
Print the factor for debugging and testing (implementing Testable) | |
virtual bool | equals (const FixedLagSmoother &rhs, double tol=1e-9) const |
Check if two IncrementalFixedLagSmoother Objects are equal. | |
Result | update (const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const KeyTimestampMap ×tamps=KeyTimestampMap(), const FastVector< size_t > &factorsToRemove=FastVector< size_t >()) |
Add new factors, updating the solution and relinearizing as needed. More... | |
Values | calculateEstimate () const |
Compute an estimate from the incomplete linear delta computed during the last update. More... | |
template<class VALUE > | |
VALUE | calculateEstimate (Key key) const |
Compute an estimate for a single variable using its incomplete linear delta computed during the last update. More... | |
const LevenbergMarquardtParams & | params () const |
read the current set of optimizer parameters | |
LevenbergMarquardtParams & | params () |
update the current set of optimizer parameters | |
const NonlinearFactorGraph & | getFactors () const |
Access the current set of factors. | |
const Values & | getLinearizationPoint () const |
Access the current linearization point. | |
const Ordering & | getOrdering () const |
Access the current ordering. | |
const VectorValues & | getDelta () const |
Access the current set of deltas to the linearization point. | |
Matrix | marginalCovariance (Key key) const |
Calculate marginal covariance on given variable. | |
Static Public Member Functions | |
static GaussianFactorGraph | CalculateMarginalFactors (const GaussianFactorGraph &graph, const KeyVector &keys, const GaussianFactorGraph::Eliminate &eliminateFunction=EliminatePreferCholesky) |
Marginalize specific keys from a linear graph. More... | |
static NonlinearFactorGraph | CalculateMarginalFactors (const NonlinearFactorGraph &graph, const Values &theta, const KeyVector &keys, const GaussianFactorGraph::Eliminate &eliminateFunction=EliminatePreferCholesky) |
Marginalize specific keys from a nonlinear graph, wrap in LinearContainers. | |
Public Types | |
typedef boost::shared_ptr< BatchFixedLagSmoother > | shared_ptr |
Typedef for a shared pointer to an Incremental Fixed-Lag Smoother. | |
Protected Types | |
typedef std::map< Key, std::set< Key > > | FactorIndex |
A typedef defining an Key-Factor mapping. | |
Protected Member Functions | |
void | insertFactors (const NonlinearFactorGraph &newFactors) |
Augment the list of factors with a set of new factors. | |
void | removeFactors (const std::set< size_t > &deleteFactors) |
Remove factors from the list of factors by slot index. | |
void | eraseKeys (const KeyVector &keys) |
Erase any keys associated with timestamps before the provided time. | |
void | reorder (const KeyVector &marginalizeKeys=KeyVector()) |
Use colamd to update into an efficient ordering. | |
Result | optimize () |
Optimize the current graph using a modified version of L-M. | |
void | marginalize (const KeyVector &marginalizableKeys) |
Marginalize out selected variables. | |
Protected Attributes | |
LevenbergMarquardtParams | parameters_ |
The L-M optimization parameters. | |
bool | enforceConsistency_ |
A flag indicating if the optimizer should enforce probabilistic consistency by maintaining the linearization point of all variables involved in linearized/marginal factors at the edge of the smoothing window. More... | |
NonlinearFactorGraph | factors_ |
The nonlinear factors. | |
Values | theta_ |
The current linearization point. | |
Values | linearKeys_ |
The set of keys involved in current linear factors. More... | |
Ordering | ordering_ |
The current ordering. | |
VectorValues | delta_ |
The current set of linear deltas. | |
std::queue< size_t > | availableSlots_ |
The set of available factor graph slots. More... | |
FactorIndex | factorIndex_ |
A cross-reference structure to allow efficient factor lookups by key. | |
|
inlinevirtual |
Compute an estimate from the incomplete linear delta computed during the last update.
This delta is incomplete because it was not updated below wildfire_threshold. If only a single variable is needed, it is faster to call calculateEstimate(const KEY&).
Implements gtsam::FixedLagSmoother.
|
inline |
Compute an estimate for a single variable using its incomplete linear delta computed during the last update.
This is faster than calling the no-argument version of calculateEstimate, which operates on all variables.
key |
|
static |
Marginalize specific keys from a linear graph.
Does not check whether keys actually exist in graph. In that case will fail somewhere deep within elimination
|
virtual |
Add new factors, updating the solution and relinearizing as needed.
Implements gtsam::FixedLagSmoother.
|
protected |
The set of available factor graph slots.
These occur because we are constantly deleting factors, leaving holes.
|
protected |
A flag indicating if the optimizer should enforce probabilistic consistency by maintaining the linearization point of all variables involved in linearized/marginal factors at the edge of the smoothing window.
This idea is from ??? TODO: Look up paper reference
|
protected |
The set of keys involved in current linear factors.
These keys should not be relinearized.