Preconditioner.cpp
Go to the documentation of this file.
1 /*
2  * Preconditioner.cpp
3  *
4  * Created on: Jun 2, 2014
5  * Author: Yong-Dian Jian
6  * Author: Sungtae An
7  */
8 
11 #include <gtsam/linear/PCGSolver.h>
15 #include <boost/shared_ptr.hpp>
16 #include <boost/algorithm/string.hpp>
17 #include <boost/range/adaptor/map.hpp>
18 #include <iostream>
19 #include <vector>
20 
21 using namespace std;
22 
23 namespace gtsam {
24 
25 /*****************************************************************************/
27  print(cout);
28 }
29 
30 /***************************************************************************************/
31 void PreconditionerParameters::print(ostream &os) const {
32  os << "PreconditionerParameters" << endl
33  << "kernel: " << kernelTranslator(kernel_) << endl
34  << "verbosity: " << verbosityTranslator(verbosity_) << endl;
35 }
36 
37 /*****************************************************************************/
38  ostream& operator<<(ostream &os, const PreconditionerParameters &p) {
39  p.print(os);
40  return os;
41 }
42 
43 /***************************************************************************************/
44 PreconditionerParameters::Kernel PreconditionerParameters::kernelTranslator(const std::string &src) {
45  std::string s = src; boost::algorithm::to_upper(s);
46  if (s == "GTSAM") return PreconditionerParameters::GTSAM;
47  else if (s == "CHOLMOD") return PreconditionerParameters::CHOLMOD;
48  /* default is cholmod */
49  else return PreconditionerParameters::CHOLMOD;
50 }
51 
52 /***************************************************************************************/
53 PreconditionerParameters::Verbosity PreconditionerParameters::verbosityTranslator(const std::string &src) {
54  std::string s = src; boost::algorithm::to_upper(s);
55  if (s == "SILENT") return PreconditionerParameters::SILENT;
56  else if (s == "COMPLEXITY") return PreconditionerParameters::COMPLEXITY;
57  else if (s == "ERROR") return PreconditionerParameters::ERROR;
58  /* default is default */
59  else return PreconditionerParameters::SILENT;
60 }
61 
62 /***************************************************************************************/
63 std::string PreconditionerParameters::kernelTranslator(PreconditionerParameters::Kernel k) {
64  if ( k == GTSAM ) return "GTSAM";
65  if ( k == CHOLMOD ) return "CHOLMOD";
66  else return "UNKNOWN";
67 }
68 
69 /***************************************************************************************/
70 std::string PreconditionerParameters::verbosityTranslator(PreconditionerParameters::Verbosity verbosity) {
71  if (verbosity == SILENT) return "SILENT";
72  else if (verbosity == COMPLEXITY) return "COMPLEXITY";
73  else if (verbosity == ERROR) return "ERROR";
74  else return "UNKNOWN";
75 }
76 
77 /***************************************************************************************/
78 BlockJacobiPreconditioner::BlockJacobiPreconditioner()
79  : Base(), buffer_(0), bufferSize_(0), nnz_(0) {}
80 
81 /***************************************************************************************/
83 
84 /***************************************************************************************/
86 
87  const size_t n = dims_.size();
88  double *ptr = buffer_, *dst = x.data();
89 
90  std::copy(y.data(), y.data() + y.rows(), x.data());
91 
92  for ( size_t i = 0 ; i < n ; ++i ) {
93  const size_t d = dims_[i];
94  const size_t sz = d*d;
95 
96  const Eigen::Map<const Eigen::MatrixXd> R(ptr, d, d);
97  Eigen::Map<Eigen::VectorXd> b(dst, d, 1);
98  R.triangularView<Eigen::Lower>().solveInPlace(b);
99 
100  dst += d;
101  ptr += sz;
102  }
103 }
104 
105 /***************************************************************************************/
107  const size_t n = dims_.size();
108  double *ptr = buffer_, *dst = x.data();
109 
110  std::copy(y.data(), y.data() + y.rows(), x.data());
111 
112  for ( size_t i = 0 ; i < n ; ++i ) {
113  const size_t d = dims_[i];
114  const size_t sz = d*d;
115 
116  const Eigen::Map<const Eigen::MatrixXd> R(ptr, d, d);
117  Eigen::Map<Eigen::VectorXd> b(dst, d, 1);
118  R.transpose().triangularView<Eigen::Upper>().solveInPlace(b);
119 
120  dst += d;
121  ptr += sz;
122  }
123 }
124 
125 /***************************************************************************************/
127  const GaussianFactorGraph &gfg, const KeyInfo &keyInfo, const std::map<Key,Vector> &lambda)
128 {
129  // n is the number of keys
130  const size_t n = keyInfo.size();
131  // dims_ is a vector that contains the dimension of keys
132  dims_ = keyInfo.colSpec();
133 
134  /* prepare the buffer of block diagonals */
135  std::vector<Matrix> blocks; blocks.reserve(n);
136 
137  /* allocate memory for the factorization of block diagonals */
138  size_t nnz = 0;
139  for ( size_t i = 0 ; i < n ; ++i ) {
140  const size_t dim = dims_[i];
141  // blocks.push_back(Matrix::Zero(dim, dim));
142  // nnz += (((dim)*(dim+1)) >> 1); // d*(d+1) / 2 ;
143  nnz += dim*dim;
144  }
145 
146  /* getting the block diagonals over the factors */
147  std::map<Key, Matrix> hessianMap =gfg.hessianBlockDiagonal();
148  for (const Matrix& hessian: hessianMap | boost::adaptors::map_values)
149  blocks.push_back(hessian);
150 
151  /* if necessary, allocating the memory for cacheing the factorization results */
152  if ( nnz > bufferSize_ ) {
153  clean();
154  buffer_ = new double [nnz];
155  bufferSize_ = nnz;
156  }
157  nnz_ = nnz;
158 
159  /* factorizing the blocks respectively */
160  double *ptr = buffer_;
161  for ( size_t i = 0 ; i < n ; ++i ) {
162  /* use eigen to decompose Di */
163  /* It is same as L = chol(M,'lower') in MATLAB where M is full preconditioner */
164  const Matrix L = blocks[i].llt().matrixL();
165 
166  /* store the data in the buffer */
167  size_t sz = dims_[i]*dims_[i] ;
168  std::copy(L.data(), L.data() + sz, ptr);
169 
170  /* advance the pointer */
171  ptr += sz;
172  }
173 }
174 
175 /*****************************************************************************/
177  if ( buffer_ ) {
178  delete [] buffer_;
179  buffer_ = 0;
180  bufferSize_ = 0;
181  nnz_ = 0;
182  }
183 }
184 
185 /***************************************************************************************/
186 boost::shared_ptr<Preconditioner> createPreconditioner(
187  const boost::shared_ptr<PreconditionerParameters> params) {
188  using boost::dynamic_pointer_cast;
189  if (dynamic_pointer_cast<DummyPreconditionerParameters>(params)) {
190  return boost::make_shared<DummyPreconditioner>();
191  } else if (dynamic_pointer_cast<BlockJacobiPreconditionerParameters>(
192  params)) {
193  return boost::make_shared<BlockJacobiPreconditioner>();
194  } else if (auto subgraph =
195  dynamic_pointer_cast<SubgraphPreconditionerParameters>(
196  params)) {
197  return boost::make_shared<SubgraphPreconditioner>(*subgraph);
198  }
199 
200  throw invalid_argument(
201  "createPreconditioner: unexpected preconditioner parameter type");
202 }
203 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
virtual std::map< Key, Matrix > hessianBlockDiagonal() const
Scalar * y
void transposeSolve(const Vector &y, Vector &x) const override
implement x = L^{-T} y
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
int n
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Rot2 R(Rot2::fromAngle(0.1))
MatrixXd L
Definition: LLT_example.cpp:6
Definition: Half.h:150
Eigen::VectorXd Vector
Definition: Vector.h:38
boost::shared_ptr< Preconditioner > createPreconditioner(const boost::shared_ptr< PreconditionerParameters > params)
float * ptr
RealScalar s
Linear Factor Graph where all factors are Gaussians.
static SmartStereoProjectionParams params
const G & b
Definition: Group.h:83
void build(const GaussianFactorGraph &gfg, const KeyInfo &info, const std::map< Key, Vector > &lambda) override
build/factorize the preconditioner
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
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
std::vector< size_t > colSpec() const
Return a vector of dimensions ordered by ordering()
ofstream os("timeSchurFactors.csv")
float * p
ostream & operator<<(ostream &os, const PreconditionerParameters &p)
void solve(const Vector &y, Vector &x) const override
implement x = L^{-1} y
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


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