#include <optimizer.h>
|
| Optimizer (const OptimizerParams ¶ms) |
|
virtual | ~Optimizer ()=default |
|
virtual bool | Optimize (const gtsam::NonlinearFactorGraph &factors, gtsam::Values &values)=0 |
|
virtual boost::optional< gtsam::Matrix > | Covariance (const gtsam::Key &key) const |
|
boost::optional< gtsam::Matrix > | Covariance (const gtsam::Key &key_a, const gtsam::Key &key_b) const |
|
boost::optional< const gtsam::Marginals & > | marginals () const |
|
virtual int | iterations () const =0 |
|
|
void | CalculateMarginals (const gtsam::NonlinearFactorGraph &factors, const gtsam::Values &values) |
|
◆ Optimizer()
◆ ~Optimizer()
virtual optimizers::Optimizer::~Optimizer |
( |
| ) |
|
|
virtualdefault |
◆ CalculateMarginals()
void optimizers::Optimizer::CalculateMarginals |
( |
const gtsam::NonlinearFactorGraph & |
factors, |
|
|
const gtsam::Values & |
values |
|
) |
| |
|
protected |
◆ Covariance() [1/2]
boost::optional< gtsam::Matrix > optimizers::Optimizer::Covariance |
( |
const gtsam::Key & |
key | ) |
const |
|
virtual |
◆ Covariance() [2/2]
boost::optional< gtsam::Matrix > optimizers::Optimizer::Covariance |
( |
const gtsam::Key & |
key_a, |
|
|
const gtsam::Key & |
key_b |
|
) |
| const |
◆ iterations()
virtual int optimizers::Optimizer::iterations |
( |
| ) |
const |
|
pure virtual |
◆ marginals()
boost::optional< const gtsam::Marginals & > optimizers::Optimizer::marginals |
( |
| ) |
const |
◆ Optimize()
virtual bool optimizers::Optimizer::Optimize |
( |
const gtsam::NonlinearFactorGraph & |
factors, |
|
|
gtsam::Values & |
values |
|
) |
| |
|
pure virtual |
◆ boost::serialization::access
friend class boost::serialization::access |
|
friend |
The documentation for this class was generated from the following files: