2010-10-14 12:54:38 +08:00
|
|
|
/* ----------------------------------------------------------------------------
|
|
|
|
|
|
|
|
|
|
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
|
|
|
|
* Atlanta, Georgia 30332-0415
|
|
|
|
|
* All Rights Reserved
|
|
|
|
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
|
|
|
|
|
|
|
|
|
* See LICENSE for the license information
|
|
|
|
|
|
|
|
|
|
* -------------------------------------------------------------------------- */
|
|
|
|
|
|
2010-03-13 03:19:21 +08:00
|
|
|
#pragma once
|
|
|
|
|
|
2010-10-25 13:29:52 +08:00
|
|
|
|
2010-10-23 13:47:29 +08:00
|
|
|
#include <boost/shared_ptr.hpp>
|
|
|
|
|
#include <boost/make_shared.hpp>
|
|
|
|
|
|
2010-10-25 13:29:52 +08:00
|
|
|
#include <gtsam/linear/IterativeSolver.h>
|
2010-08-20 01:23:19 +08:00
|
|
|
#include <gtsam/linear/SubgraphPreconditioner.h>
|
2010-10-19 03:29:16 +08:00
|
|
|
#include <gtsam/nonlinear/Ordering.h>
|
2010-03-13 03:19:21 +08:00
|
|
|
|
|
|
|
|
namespace gtsam {
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* A nonlinear system solver using subgraph preconditioning conjugate gradient
|
|
|
|
|
* Concept NonLinearSolver<G,T,L> implements
|
|
|
|
|
* linearize: G * T -> L
|
2010-10-09 11:09:58 +08:00
|
|
|
* solve : L -> VectorValues
|
2010-03-13 03:19:21 +08:00
|
|
|
*/
|
2010-10-23 13:47:29 +08:00
|
|
|
template<class GRAPH, class LINEAR, class VALUES>
|
2010-10-25 13:29:52 +08:00
|
|
|
class SubgraphSolver : public IterativeSolver {
|
2010-03-13 03:19:21 +08:00
|
|
|
|
|
|
|
|
private:
|
2010-10-21 00:37:47 +08:00
|
|
|
typedef typename VALUES::Key Key;
|
|
|
|
|
typedef typename GRAPH::Pose Pose;
|
2010-10-23 13:47:29 +08:00
|
|
|
typedef typename GRAPH::Constraint Constraint;
|
|
|
|
|
|
|
|
|
|
typedef boost::shared_ptr<const SubgraphSolver> shared_ptr ;
|
|
|
|
|
typedef boost::shared_ptr<Ordering> shared_ordering ;
|
|
|
|
|
typedef boost::shared_ptr<GRAPH> shared_graph ;
|
|
|
|
|
typedef boost::shared_ptr<LINEAR> shared_linear ;
|
|
|
|
|
typedef boost::shared_ptr<VALUES> shared_values ;
|
|
|
|
|
typedef boost::shared_ptr<SubgraphPreconditioner> shared_preconditioner ;
|
|
|
|
|
typedef std::map<Index,Index> mapPairIndex ;
|
2010-03-13 03:19:21 +08:00
|
|
|
|
|
|
|
|
/* the ordering derived from the spanning tree */
|
2010-10-23 13:47:29 +08:00
|
|
|
shared_ordering ordering_;
|
2010-03-13 03:19:21 +08:00
|
|
|
|
2010-10-23 13:47:29 +08:00
|
|
|
/* the indice of two vertices in the gaussian factor graph */
|
|
|
|
|
mapPairIndex pairs_;
|
2010-03-13 03:19:21 +08:00
|
|
|
|
2010-10-23 13:47:29 +08:00
|
|
|
/* preconditioner */
|
|
|
|
|
shared_preconditioner pc_;
|
2010-03-13 03:19:21 +08:00
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
2010-10-23 13:47:29 +08:00
|
|
|
SubgraphSolver(const LINEAR &GFG) {
|
|
|
|
|
throw std::runtime_error("SubgraphSolver: gaussian factor graph initialization not supported");
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
SubgraphSolver(const SubgraphSolver& solver) :
|
2010-10-25 13:29:52 +08:00
|
|
|
IterativeSolver(solver), ordering_(solver.ordering_), pairs_(solver.pairs_), pc_(solver.pc_){}
|
2010-10-23 13:47:29 +08:00
|
|
|
|
|
|
|
|
SubgraphSolver(shared_ordering ordering,
|
|
|
|
|
mapPairIndex pairs,
|
2010-10-25 13:29:52 +08:00
|
|
|
shared_preconditioner pc,
|
|
|
|
|
sharedParameters parameters = boost::make_shared<Parameters>()) :
|
|
|
|
|
IterativeSolver(parameters), ordering_(ordering), pairs_(pairs), pc_(pc) {}
|
2010-10-23 13:47:29 +08:00
|
|
|
|
2010-10-25 13:29:52 +08:00
|
|
|
SubgraphSolver(const GRAPH& G, const VALUES& theta0):IterativeSolver(){
|
|
|
|
|
initialize(G,theta0);
|
2010-10-23 13:47:29 +08:00
|
|
|
}
|
|
|
|
|
|
2010-10-25 13:29:52 +08:00
|
|
|
shared_ptr update(const LINEAR &graph) const ;
|
|
|
|
|
VectorValues::shared_ptr optimize() const ;
|
2010-10-23 13:47:29 +08:00
|
|
|
shared_ordering ordering() const { return ordering_; }
|
|
|
|
|
|
2010-10-25 13:29:52 +08:00
|
|
|
|
2010-10-23 13:47:29 +08:00
|
|
|
protected:
|
|
|
|
|
|
2010-10-25 13:29:52 +08:00
|
|
|
void initialize(const GRAPH& G, const VALUES& theta0);
|
2010-10-19 03:29:16 +08:00
|
|
|
|
2010-10-25 13:29:52 +08:00
|
|
|
private:
|
2010-03-13 03:19:21 +08:00
|
|
|
|
2010-10-25 13:29:52 +08:00
|
|
|
SubgraphSolver():IterativeSolver(){}
|
|
|
|
|
};
|
2010-03-13 03:19:21 +08:00
|
|
|
|
|
|
|
|
} // nsamespace gtsam
|