15 #include <boost/shared_ptr.hpp> 16 #include <boost/algorithm/string.hpp> 17 #include <boost/range/adaptor/map.hpp> 32 os <<
"PreconditionerParameters" << endl
33 <<
"kernel: " << kernelTranslator(kernel_) << endl
34 <<
"verbosity: " << verbosityTranslator(verbosity_) << endl;
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;
49 else return PreconditionerParameters::CHOLMOD;
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;
59 else return PreconditionerParameters::SILENT;
64 if ( k == GTSAM )
return "GTSAM";
65 if ( k == CHOLMOD )
return "CHOLMOD";
66 else return "UNKNOWN";
71 if (verbosity == SILENT)
return "SILENT";
72 else if (verbosity == COMPLEXITY)
return "COMPLEXITY";
73 else if (verbosity == ERROR)
return "ERROR";
74 else return "UNKNOWN";
78 BlockJacobiPreconditioner::BlockJacobiPreconditioner()
79 :
Base(), buffer_(0), bufferSize_(0), nnz_(0) {}
87 const size_t n =
dims_.size();
90 std::copy(y.data(), y.data() + y.rows(), x.data());
92 for (
size_t i = 0 ;
i <
n ; ++
i ) {
94 const size_t sz = d*
d;
107 const size_t n =
dims_.size();
110 std::copy(y.data(), y.data() + y.rows(), x.data());
112 for (
size_t i = 0 ;
i <
n ; ++
i ) {
114 const size_t sz = d*
d;
118 R.transpose().triangularView<
Eigen::Upper>().solveInPlace(b);
130 const size_t n = keyInfo.size();
135 std::vector<Matrix> blocks; blocks.reserve(n);
139 for (
size_t i = 0 ;
i <
n ; ++
i ) {
148 for (
const Matrix& hessian: hessianMap | boost::adaptors::map_values)
149 blocks.push_back(hessian);
161 for (
size_t i = 0 ;
i <
n ; ++
i ) {
164 const Matrix L = blocks[
i].llt().matrixL();
168 std::copy(L.data(), L.data() + sz,
ptr);
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>(
193 return boost::make_shared<BlockJacobiPreconditioner>();
194 }
else if (
auto subgraph =
195 dynamic_pointer_cast<SubgraphPreconditionerParameters>(
197 return boost::make_shared<SubgraphPreconditioner>(*subgraph);
200 throw invalid_argument(
201 "createPreconditioner: unexpected preconditioner parameter type");
void print(const Matrix &A, const string &s, ostream &stream)
virtual std::map< Key, Matrix > hessianBlockDiagonal() const
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.
Rot2 R(Rot2::fromAngle(0.1))
~BlockJacobiPreconditioner() override
std::vector< size_t > dims_
boost::shared_ptr< Preconditioner > createPreconditioner(const boost::shared_ptr< PreconditionerParameters > params)
Linear Factor Graph where all factors are Gaussians.
static SmartStereoProjectionParams params
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())
std::vector< size_t > colSpec() const
Return a vector of dimensions ordered by ordering()
ofstream os("timeSchurFactors.csv")
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