PCGSolver.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
12 /*
13  * @file PCGSolver.h
14  * @brief Preconditioned Conjugate Gradient Solver for linear systems
15  * @date Jan 31, 2012
16  * @author Yong-Dian Jian
17  * @author Sungtae An
18  */
19 
20 #pragma once
21 
23 #include <string>
24 
25 namespace gtsam {
26 
27 class GaussianFactorGraph;
28 class KeyInfo;
29 class Preconditioner;
30 class VectorValues;
31 struct PreconditionerParameters;
32 
36 struct GTSAM_EXPORT PCGSolverParameters : public ConjugateGradientParameters {
38  typedef std::shared_ptr<PCGSolverParameters> shared_ptr;
39 
40  std::shared_ptr<PreconditionerParameters> preconditioner;
41 
43 
45  const std::shared_ptr<PreconditionerParameters> &preconditioner)
46  : preconditioner(preconditioner) {}
47 
48  void print(std::ostream &os) const override;
49  void print(const std::string &s) const;
50 };
51 
55 class GTSAM_EXPORT PCGSolver: public IterativeSolver {
56 public:
58  typedef std::shared_ptr<PCGSolver> shared_ptr;
59 
60 protected:
61 
63  std::shared_ptr<Preconditioner> preconditioner_;
64 
65 public:
66  /* Interface to initialize a solver without a problem */
68  ~PCGSolver() override {
69  }
70 
72 
74  const KeyInfo &keyInfo, const std::map<Key, Vector> &lambda,
75  const VectorValues &initial) override;
76 
77 };
78 
82 class GTSAM_EXPORT GaussianFactorGraphSystem {
86  std::map<Key, Vector> lambda_;
87 
88  public:
90  const Preconditioner &preconditioner,
91  const KeyInfo &info,
92  const std::map<Key, Vector> &lambda);
93 
94  void residual(const Vector &x, Vector &r) const;
95  void multiply(const Vector &x, Vector& y) const;
96  void leftPrecondition(const Vector &x, Vector &y) const;
97  void rightPrecondition(const Vector &x, Vector &y) const;
98  void scal(const double alpha, Vector &x) const;
99  double dot(const Vector &x, const Vector &y) const;
100  void axpy(const double alpha, const Vector &x, Vector &y) const;
101 
102  void getb(Vector &b) const;
103 };
104 
107 
110  const std::map<Key, size_t> & dimensions);
111 
113 VectorValues buildVectorValues(const Vector &v, const KeyInfo &keyInfo);
114 
116 
117 }
118 
VectorValues
gtsam::Preconditioner
Definition: Preconditioner.h:64
dimensions
const std::vector< size_t > dimensions
Definition: testVerticalBlockMatrix.cpp:27
gtsam::PCGSolver::~PCGSolver
~PCGSolver() override
Definition: PCGSolver.h:68
gtsam::GaussianFactorGraphSystem::keyInfo_
KeyInfo keyInfo_
Definition: PCGSolver.h:85
gtsam::PCGSolver::parameters_
PCGSolverParameters parameters_
Definition: PCGSolver.h:62
alpha
RealScalar alpha
Definition: level1_cplx_impl.h:147
s
RealScalar s
Definition: level1_cplx_impl.h:126
gtsam::PCGSolver::Base
IterativeSolver Base
Definition: PCGSolver.h:57
gtsam::optimize
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
Definition: triangulation.cpp:177
x
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Definition: gnuplot_common_settings.hh:12
os
ofstream os("timeSchurFactors.csv")
gtsam::IterativeSolver
Definition: IterativeSolver.h:87
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
scal
int EIGEN_BLAS_FUNC() scal(int *n, RealScalar *palpha, RealScalar *px, int *incx)
Definition: level1_impl.h:117
gtsam::KeyInfo
Definition: IterativeSolver.h:127
gtsam::PCGSolverParameters
Definition: PCGSolver.h:36
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
ConjugateGradientSolver.h
Implementation of Conjugate Gradient solver for a linear system.
gtsam::GaussianFactorGraphSystem::lambda_
std::map< Key, Vector > lambda_
Definition: PCGSolver.h:86
gtsam::PCGSolver::preconditioner_
std::shared_ptr< Preconditioner > preconditioner_
Definition: PCGSolver.h:63
gtsam::VectorValues
Definition: VectorValues.h:74
gtsam::PCGSolver
Definition: PCGSolver.h:55
gtsam::PCGSolverParameters::PCGSolverParameters
PCGSolverParameters()
Definition: PCGSolver.h:42
gtsam::PCGSolver::shared_ptr
std::shared_ptr< PCGSolver > shared_ptr
Definition: PCGSolver.h:58
gtsam::dot
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:195
info
else if n * info
Definition: 3rdparty/Eigen/lapack/cholesky.cpp:18
gtsam::GaussianFactorGraphSystem::gfg_
const GaussianFactorGraph & gfg_
Definition: PCGSolver.h:83
gtsam::PCGSolverParameters::shared_ptr
std::shared_ptr< PCGSolverParameters > shared_ptr
Definition: PCGSolver.h:38
lambda
static double lambda[]
Definition: jv.c:524
ordering
static enum @1096 ordering
gtsam::IterativeSolver::optimize
GTSAM_EXPORT VectorValues optimize(const GaussianFactorGraph &gfg, const KeyInfo *=nullptr, const std::map< Key, Vector > *lambda=nullptr)
Definition: IterativeSolver.cpp:92
gtsam::PCGSolverParameters::preconditioner
std::shared_ptr< PreconditionerParameters > preconditioner
Definition: PCGSolver.h:40
y
Scalar * y
Definition: level1_cplx_impl.h:124
gtsam::axpy
void axpy(double alpha, const Errors &x, Errors &y)
BLAS level 2 style AXPY, y := alpha*x + y
Definition: Errors.cpp:110
gtsam::b
const G & b
Definition: Group.h:79
gtsam
traits
Definition: SFMdata.h:40
gtsam::ConjugateGradientParameters
Definition: ConjugateGradientSolver.h:29
gtsam::GaussianFactorGraphSystem
Definition: PCGSolver.h:82
p
float * p
Definition: Tutorial_Map_using.cpp:9
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
initial
Definition: testScenarioRunner.cpp:148
gtsam::PCGSolverParameters::Base
ConjugateGradientParameters Base
Definition: PCGSolver.h:37
gtsam::buildVectorValues
VectorValues buildVectorValues(const Vector &v, const Ordering &ordering, const map< Key, size_t > &dimensions)
Create VectorValues from a Vector.
Definition: PCGSolver.cpp:145
gtsam::GaussianFactorGraphSystem::preconditioner_
const Preconditioner & preconditioner_
Definition: PCGSolver.h:84
gtsam::Ordering
Definition: inference/Ordering.h:33
gtsam::PCGSolverParameters::PCGSolverParameters
PCGSolverParameters(const std::shared_ptr< PreconditionerParameters > &preconditioner)
Definition: PCGSolver.h:44


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:03:33