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 {
37 public:
39  typedef boost::shared_ptr<PCGSolverParameters> shared_ptr;
40 
42  }
43 
44  void print(std::ostream &os) const override;
45 
46  /* interface to preconditioner parameters */
47  inline const PreconditionerParameters& preconditioner() const {
48  return *preconditioner_;
49  }
50 
51  // needed for python wrapper
52  void print(const std::string &s) const;
53 
54  boost::shared_ptr<PreconditionerParameters> preconditioner_;
55 
56  void setPreconditionerParams(const boost::shared_ptr<PreconditionerParameters> preconditioner);
57 };
58 
62 class GTSAM_EXPORT PCGSolver: public IterativeSolver {
63 public:
65  typedef boost::shared_ptr<PCGSolver> shared_ptr;
66 
67 protected:
68 
70  boost::shared_ptr<Preconditioner> preconditioner_;
71 
72 public:
73  /* Interface to initialize a solver without a problem */
75  ~PCGSolver() override {
76  }
77 
79 
81  const KeyInfo &keyInfo, const std::map<Key, Vector> &lambda,
82  const VectorValues &initial) override;
83 
84 };
85 
89 class GTSAM_EXPORT GaussianFactorGraphSystem {
90 public:
91 
93  const Preconditioner &preconditioner, const KeyInfo &info,
94  const std::map<Key, Vector> &lambda);
95 
98  const KeyInfo &keyInfo_;
99  const std::map<Key, Vector> &lambda_;
100 
101  void residual(const Vector &x, Vector &r) const;
102  void multiply(const Vector &x, Vector& y) const;
103  void leftPrecondition(const Vector &x, Vector &y) const;
104  void rightPrecondition(const Vector &x, Vector &y) const;
105  inline void scal(const double alpha, Vector &x) const {
106  x *= alpha;
107  }
108  inline double dot(const Vector &x, const Vector &y) const {
109  return x.dot(y);
110  }
111  inline void axpy(const double alpha, const Vector &x, Vector &y) const {
112  y += alpha * x;
113  }
114 
115  void getb(Vector &b) const;
116 };
117 
120 
123  const std::map<Key, size_t> & dimensions);
124 
126 VectorValues buildVectorValues(const Vector &v, const KeyInfo &keyInfo);
127 
129 
130 }
131 
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Scalar * y
void scal(const double alpha, Vector &x) const
Definition: PCGSolver.h:105
static enum @843 ordering
boost::shared_ptr< PCGSolver > shared_ptr
Definition: PCGSolver.h:65
ArrayXcf v
Definition: Cwise_arg.cpp:1
const Preconditioner & preconditioner_
Definition: PCGSolver.h:97
boost::shared_ptr< PreconditionerParameters > preconditioner_
Definition: PCGSolver.h:54
~PCGSolver() override
Definition: PCGSolver.h:75
const PreconditionerParameters & preconditioner() const
Definition: PCGSolver.h:47
vector< size_t > dimensions(L.begin(), L.end())
const std::map< Key, Vector > & lambda_
Definition: PCGSolver.h:99
Implementation of Conjugate Gradient solver for a linear system.
double dot(const Vector &x, const Vector &y) const
Definition: PCGSolver.h:108
else if n * info
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
Eigen::VectorXd Vector
Definition: Vector.h:38
RealScalar alpha
RealScalar s
const G & b
Definition: Group.h:83
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
traits
Definition: chartTesting.h:28
ofstream os("timeSchurFactors.csv")
float * p
boost::shared_ptr< PCGSolverParameters > shared_ptr
Definition: PCGSolver.h:39
const GaussianFactorGraph & gfg_
Definition: PCGSolver.h:96
PCGSolverParameters parameters_
Definition: PCGSolver.h:69
ConjugateGradientParameters Base
Definition: PCGSolver.h:38
boost::shared_ptr< Preconditioner > preconditioner_
Definition: PCGSolver.h:70
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
IterativeSolver Base
Definition: PCGSolver.h:64
void axpy(const double alpha, const Vector &x, Vector &y) const
Definition: PCGSolver.h:111
GTSAM_EXPORT VectorValues optimize(const GaussianFactorGraph &gfg, boost::optional< const KeyInfo & >=boost::none, boost::optional< const std::map< Key, Vector > & > lambda=boost::none)
VectorValues buildVectorValues(const Vector &v, const Ordering &ordering, const map< Key, size_t > &dimensions)
Create VectorValues from a Vector.
Definition: PCGSolver.cpp:140


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:25