Public Types | Protected Attributes | List of all members
gtsam::SubgraphSolver Class Reference

#include <SubgraphSolver.h>

Inheritance diagram for gtsam::SubgraphSolver:
Inheritance graph
[legend]

Public Types

typedef SubgraphSolverParameters Parameters
 
- Public Types inherited from gtsam::IterativeSolver
typedef std::shared_ptr< IterativeSolvershared_ptr
 

Protected Attributes

Parameters parameters_
 
std::shared_ptr< SubgraphPreconditionerpc_
 preconditioner object More...
 

Constructors

 SubgraphSolver (const GaussianFactorGraph &A, const Parameters &parameters, const Ordering &ordering)
 
 SubgraphSolver (const GaussianFactorGraph &Ab1, const GaussianFactorGraph &Ab2, const Parameters &parameters, const Ordering &ordering)
 
 SubgraphSolver (const GaussianBayesNet &Rc1, const GaussianFactorGraph &Ab2, const Parameters &parameters)
 
 ~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, GaussianFactorGraphsplitGraph (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 *=nullptr, const std::map< Key, Vector > *lambda=nullptr)
 
GTSAM_EXPORT VectorValues optimize (const GaussianFactorGraph &gfg, const KeyInfo &keyInfo, const std::map< Key, Vector > &lambda)
 
virtual ~IterativeSolver ()
 

Detailed Description

This class implements the linear SPCG solver presented in Dellaert et al in IROS'10.

Given a linear least-squares problem $ f(x) = |A x - b|^2 $. We split the problem into $ f(x) = |A_t - b_t|^2 + |A_c - b_c|^2 $ where $ A_t $ denotes the "tree" part, and $ A_c $ denotes the "constraint" part.

$A_t $ is factorized into $ Q_t R_t $, and we compute $ c_t = Q_t^{-1} b_t $, and $ x_t = R_t^{-1} c_t $ accordingly.

Then we solve a reparametrized problem $ f(y) = |y|^2 + |A_c R_t^{-1} y -\bar{b_y}|^2 $, where $ y = R_t(x - x_t) $, and $ \bar{b_y} = (b_c - A_c x_t) $

In the matrix form, it is equivalent to solving $ [A_c R_t^{-1} ; I ] y = [\bar{b_y} ; 0] $. 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.

Member Typedef Documentation

◆ Parameters

Definition at line 78 of file SubgraphSolver.h.

Constructor & Destructor Documentation

◆ SubgraphSolver() [1/3]

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.

◆ SubgraphSolver() [2/3]

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.

◆ SubgraphSolver() [3/3]

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.

◆ ~SubgraphSolver()

gtsam::SubgraphSolver::~SubgraphSolver ( )
inlineoverride

Destructor.

Definition at line 112 of file SubgraphSolver.h.

Member Function Documentation

◆ optimize() [1/2]

VectorValues gtsam::SubgraphSolver::optimize ( ) const

Optimize from zero.

Definition at line 68 of file SubgraphSolver.cpp.

◆ optimize() [2/2]

VectorValues gtsam::SubgraphSolver::optimize ( const GaussianFactorGraph gfg,
const KeyInfo keyInfo,
const std::map< Key, Vector > &  lambda,
const VectorValues initial 
)
overridevirtual

Interface that IterativeSolver subclasses have to implement.

Implements gtsam::IterativeSolver.

Definition at line 74 of file SubgraphSolver.cpp.

◆ splitGraph()

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.

Member Data Documentation

◆ parameters_

Parameters gtsam::SubgraphSolver::parameters_
protected

Definition at line 81 of file SubgraphSolver.h.

◆ pc_

std::shared_ptr<SubgraphPreconditioner> gtsam::SubgraphSolver::pc_
protected

preconditioner object

Definition at line 82 of file SubgraphSolver.h.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:47:12