PCGSolver.cpp
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.cpp
14  * @brief Preconditioned Conjugate Gradient Solver for linear systems
15  * @date Feb 14, 2012
16  * @author Yong-Dian Jian
17  * @author Sungtae An
18  */
19 
20 #include <gtsam/linear/PCGSolver.h>
24 
25 #include <boost/algorithm/string.hpp>
26 
27 #include <algorithm>
28 #include <iostream>
29 #include <stdexcept>
30 
31 using namespace std;
32 
33 namespace gtsam {
34 
35 /*****************************************************************************/
36 void PCGSolverParameters::print(ostream &os) const {
37  Base::print(os);
38  os << "PCGSolverParameters:" << endl;
39  preconditioner_->print(os);
40 }
41 
42 /*****************************************************************************/
43 PCGSolver::PCGSolver(const PCGSolverParameters &p) {
44  parameters_ = p;
45  preconditioner_ = createPreconditioner(p.preconditioner_);
46 }
47 
48 void PCGSolverParameters::setPreconditionerParams(const boost::shared_ptr<PreconditionerParameters> preconditioner) {
49  preconditioner_ = preconditioner;
50 }
51 
52 void PCGSolverParameters::print(const std::string &s) const {
53  std::cout << s << std::endl;;
54  std::ostringstream os;
55  print(os);
56  std::cout << os.str() << std::endl;
57 }
58 
59 /*****************************************************************************/
61  const KeyInfo &keyInfo, const std::map<Key, Vector> &lambda,
62  const VectorValues &initial) {
63  /* build preconditioner */
64  preconditioner_->build(gfg, keyInfo, lambda);
65 
66  /* apply pcg */
67  GaussianFactorGraphSystem system(gfg, *preconditioner_, keyInfo, lambda);
68  Vector x0 = initial.vector(keyInfo.ordering());
69  const Vector sol = preconditionedConjugateGradient(system, x0, parameters_);
70 
71  return buildVectorValues(sol, keyInfo);
72 }
73 
74 /*****************************************************************************/
75 GaussianFactorGraphSystem::GaussianFactorGraphSystem(
76  const GaussianFactorGraph &gfg, const Preconditioner &preconditioner,
77  const KeyInfo &keyInfo, const std::map<Key, Vector> &lambda) :
78  gfg_(gfg), preconditioner_(preconditioner), keyInfo_(keyInfo), lambda_(
79  lambda) {
80 }
81 
82 /*****************************************************************************/
84  /* implement b-Ax, assume x and r are pre-allocated */
85 
86  /* reset r to b */
87  getb(r);
88 
89  /* substract A*x */
90  Vector Ax = Vector::Zero(r.rows(), 1);
91  multiply(x, Ax);
92  r -= Ax;
93 }
94 
95 /*****************************************************************************/
97  /* implement A^T*(A*x), assume x and AtAx are pre-allocated */
98 
99  // Build a VectorValues for Vector x
101 
102  // VectorValues form of A'Ax for multiplyHessianAdd
103  VectorValues vvAtAx = keyInfo_.x0(); // crucial for performance
104 
105  // vvAtAx += 1.0 * A'Ax for each factor
106  gfg_.multiplyHessianAdd(1.0, vvX, vvAtAx);
107 
108  // Make the result as Vector form
109  AtAx = vvAtAx.vector(keyInfo_.ordering());
110 }
111 
112 /*****************************************************************************/
114  /* compute rhs, assume b pre-allocated */
115 
116  // Get whitened r.h.s (A^T * b) from each factor in the form of VectorValues
118 
119  // Make the result as Vector form
120  b = -vvb.vector(keyInfo_.ordering());
121 }
122 
123 /**********************************************************************************/
125  Vector &y) const {
126  // For a preconditioner M = L*L^T
127  // Calculate y = L^{-1} x
128  preconditioner_.solve(x, y);
129 }
130 
131 /**********************************************************************************/
133  Vector &y) const {
134  // For a preconditioner M = L*L^T
135  // Calculate y = L^{-T} x
137 }
138 
139 /**********************************************************************************/
141  const map<Key, size_t> & dimensions) {
143 
144  DenseIndex offset = 0;
145  for (size_t i = 0; i < ordering.size(); ++i) {
146  const Key key = ordering[i];
147  map<Key, size_t>::const_iterator it = dimensions.find(key);
148  if (it == dimensions.end()) {
149  throw invalid_argument(
150  "buildVectorValues: inconsistent ordering and dimensions");
151  }
152  const size_t dim = it->second;
153  result.emplace(key, v.segment(offset, dim));
154  offset += dim;
155  }
156 
157  return result;
158 }
159 
160 /**********************************************************************************/
161 VectorValues buildVectorValues(const Vector &v, const KeyInfo &keyInfo) {
163  for ( const KeyInfo::value_type &item: keyInfo ) {
164  result.emplace(item.first, v.segment(item.second.start, item.second.dim));
165  }
166  return result;
167 }
168 
169 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Scalar * y
static enum @843 ordering
ArrayXcf v
Definition: Cwise_arg.cpp:1
const Preconditioner & preconditioner_
Definition: PCGSolver.h:97
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate offset
boost::shared_ptr< PreconditionerParameters > preconditioner_
Definition: PCGSolver.h:54
Definition: Half.h:150
const Ordering & ordering() const
Return the ordering.
void leftPrecondition(const Vector &x, Vector &y) const
Definition: PCGSolver.cpp:124
vector< size_t > dimensions(L.begin(), L.end())
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:67
VectorValues buildVectorValues(const Vector &v, const KeyInfo &keyInfo)
Create VectorValues from a Vector and a KeyInfo class.
Definition: PCGSolver.cpp:161
void residual(const Vector &x, Vector &r) const
Definition: PCGSolver.cpp:83
Factor Graph Values.
VectorValues x0() const
Return VectorValues with zeros, of correct dimension.
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
boost::shared_ptr< Preconditioner > createPreconditioner(const boost::shared_ptr< PreconditionerParameters > params)
V preconditionedConjugateGradient(const S &system, const V &initial, const ConjugateGradientParameters &parameters)
virtual void solve(const Vector &y, Vector &x) const =0
implement x = L^{-1} y
virtual void transposeSolve(const Vector &y, Vector &x) const =0
implement x = L^{-T} y
RealScalar s
Linear Factor Graph where all factors are Gaussians.
void multiply(const Vector &x, Vector &y) const
Definition: PCGSolver.cpp:96
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
static Symbol x0('x', 0)
const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2201
traits
Definition: chartTesting.h:28
void getb(Vector &b) const
Definition: PCGSolver.cpp:113
void multiplyHessianAdd(double alpha, const VectorValues &x, VectorValues &y) const
ofstream os("timeSchurFactors.csv")
float * p
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
Definition: timeSFMBAL.h:63
const GaussianFactorGraph & gfg_
Definition: PCGSolver.h:96
std::pair< VectorValues::iterator, bool > emplace(Key j, Args &&...args)
Definition: VectorValues.h:183
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
void rightPrecondition(const Vector &x, Vector &y) const
Definition: PCGSolver.cpp:132
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
VectorValues buildVectorValues(const Vector &v, const Ordering &ordering, const map< Key, size_t > &dimensions)
Create VectorValues from a Vector.
Definition: PCGSolver.cpp:140
Vector vector() const
virtual VectorValues gradientAtZero() const


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