#include <SubgraphSolver.h>
Public Types | |
typedef SubgraphSolverParameters | Parameters |
Public Types inherited from gtsam::IterativeSolver | |
typedef std::shared_ptr< IterativeSolver > | shared_ptr |
Protected Attributes | |
Parameters | parameters_ |
std::shared_ptr< SubgraphPreconditioner > | pc_ |
preconditioner object More... | |
Constructors | |
SubgraphSolver (const GaussianFactorGraph &A, const Parameters ¶meters, const Ordering &ordering) | |
SubgraphSolver (const GaussianFactorGraph &Ab1, const GaussianFactorGraph &Ab2, const Parameters ¶meters, const Ordering &ordering) | |
SubgraphSolver (const GaussianBayesNet &Rc1, const GaussianFactorGraph &Ab2, const Parameters ¶meters) | |
~SubgraphSolver () override | |
Destructor. More... | |
Implement interface | |
VectorValues | optimize () const |
Optimize from zero. More... | |
VectorValues | optimize (const GaussianFactorGraph &gfg, const KeyInfo &keyInfo, const std::map< Key, Vector > &lambda, const VectorValues &initial) override |
Interface that IterativeSolver subclasses have to implement. More... | |
std::pair< GaussianFactorGraph, GaussianFactorGraph > | splitGraph (const GaussianFactorGraph &gfg) |
Split graph using Kruskal algorithm, treating binary factors as edges. More... | |
Additional Inherited Members | |
Public Member Functions inherited from gtsam::IterativeSolver | |
IterativeSolver () | |
GTSAM_EXPORT VectorValues | optimize (const GaussianFactorGraph &gfg, const KeyInfo &keyInfo, const std::map< Key, Vector > &lambda) |
GTSAM_EXPORT VectorValues | optimize (const GaussianFactorGraph &gfg, const KeyInfo *=nullptr, const std::map< Key, Vector > *lambda=nullptr) |
virtual | ~IterativeSolver () |
This class implements the linear SPCG solver presented in Dellaert et al in IROS'10.
Given a linear least-squares problem . We split the problem into where denotes the "tree" part, and denotes the "constraint" part.
is factorized into , and we compute , and accordingly.
Then we solve a reparametrized problem , where , and
In the matrix form, it is equivalent to solving . We can solve it with the least-squares variation of the conjugate gradient method.
To use it in nonlinear optimization, please see the following example
LevenbergMarquardtParams parameters; parameters.linearSolverType = NonlinearOptimizerParams::CONJUGATE_GRADIENT; parameters.iterativeParams = std::make_shared<SubgraphSolverParameters>(); LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters); Values result = optimizer.optimize();
Definition at line 76 of file SubgraphSolver.h.
Definition at line 78 of file SubgraphSolver.h.
gtsam::SubgraphSolver::SubgraphSolver | ( | const GaussianFactorGraph & | A, |
const Parameters & | parameters, | ||
const Ordering & | ordering | ||
) |
Given a gaussian factor graph, split it into a spanning tree (A1) + others (A2) for SPCG Will throw exception if there are ternary factors or higher arity, as we use Kruskal's algorithm to split the graph, treating binary factors as edges.
Definition at line 34 of file SubgraphSolver.cpp.
gtsam::SubgraphSolver::SubgraphSolver | ( | const GaussianFactorGraph & | Ab1, |
const GaussianFactorGraph & | Ab2, | ||
const Parameters & | parameters, | ||
const Ordering & | ordering | ||
) |
The user specifies the subgraph part and the constraints part. May throw exception if A1 is underdetermined. An ordering is required to eliminate Ab1. We take Ab1 as a const reference, as it will be transformed into Rc1, but take Ab2 as a shared pointer as we need to keep it around.
Definition at line 60 of file SubgraphSolver.cpp.
gtsam::SubgraphSolver::SubgraphSolver | ( | const GaussianBayesNet & | Rc1, |
const GaussianFactorGraph & | Ab2, | ||
const Parameters & | parameters | ||
) |
The same as above, but we assume A1 was solved by caller. We take two shared pointers as we keep both around.
Definition at line 49 of file SubgraphSolver.cpp.
|
inlineoverride |
Destructor.
Definition at line 112 of file SubgraphSolver.h.
VectorValues gtsam::SubgraphSolver::optimize | ( | ) | const |
Optimize from zero.
Definition at line 68 of file SubgraphSolver.cpp.
|
overridevirtual |
Interface that IterativeSolver subclasses have to implement.
Implements gtsam::IterativeSolver.
Definition at line 74 of file SubgraphSolver.cpp.
pair< GaussianFactorGraph, GaussianFactorGraph > gtsam::SubgraphSolver::splitGraph | ( | const GaussianFactorGraph & | gfg | ) |
Split graph using Kruskal algorithm, treating binary factors as edges.
Definition at line 81 of file SubgraphSolver.cpp.
|
protected |
Definition at line 81 of file SubgraphSolver.h.
|
protected |
preconditioner object
Definition at line 82 of file SubgraphSolver.h.