Go to the documentation of this file.
41 vector<std::pair<size_t, size_t> > cache;
48 cache.emplace_back(entry.
start, entry.
dim);
55 for (
const auto &
p : cache) {
56 result.segment(index,
p.second) = src.segment(
p.first,
p.second);
69 const size_t keyDim = entry.
dim;
70 dst.segment(entry.
start, keyDim) = src.segment(index, keyDim);
81 for (
const auto &
factor : gfg)
83 auto jf = std::dynamic_pointer_cast<JacobianFactor>(
factor);
85 jf = std::make_shared<JacobianFactor>(*
factor);
100 b2bar_(-Ab2_.gaussianErrors(xbar)), parameters_(
p) {
114 return 0.5 * (
dot(
e,
e) +
dot(e2,e2));
133 e.splice(
e.end(), e2);
141 Errors::iterator ei =
e.begin();
142 for(
const auto& key_value:
y) {
143 *ei = key_value.second;
156 Errors::const_iterator it =
e.begin();
158 for(
auto& key_value:
y) {
159 key_value.second = *it;
171 Errors::const_iterator it =
e.begin();
172 for(
auto& key_value:
y) {
174 key_value.second +=
alpha * ei;
177 transposeMultiplyAdd2(
alpha, it,
e.end(),
y);
183 Errors::const_iterator it, Errors::const_iterator
end,
VectorValues&
y)
const {
188 while (it !=
end) e2.push_back(*(it++));
203 assert(
x.
size() ==
y.size());
209 const KeyVector parentKeys(cg->beginParents(), cg->endParents());
210 const KeyVector frontalKeys(cg->beginFrontals(), cg->endFrontals());
216 rhsFrontal - cg->S() * xParent);
226 assert(
x.
size() ==
y.size());
227 std::copy(
y.data(),
y.data() +
y.rows(),
x.data());
230 for (
const auto &cg :
Rc1_) {
231 const KeyVector frontalKeys(cg->beginFrontals(), cg->endFrontals());
238 if (solFrontal.hasNaN())
245 for (
auto it = cg->beginParents(); it != cg->endParents(); it++) {
248 rhsParent -=
Matrix(cg->getA(it)).transpose() * solFrontal;
258 auto subgraph = builder(gfg);
266 Rc1_ = *gfg_subgraph.eliminateSequential();
GaussianFactorGraph buildFactorSubgraph(const GaussianFactorGraph &gfg, const Subgraph &subgraph, const bool clone)
Errors operator*(const VectorValues &y) const
Linear Factor Graph where all factors are Gaussians.
typedef and functions to augment Eigen's VectorXd
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Typedefs for easier changing of types.
VectorValues operator^(const Errors &e) const
SubgraphPreconditioner(const SubgraphPreconditionerParameters &p=SubgraphPreconditionerParameters())
virtual void print(const std::string &s="FactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const
Print out graph to std::cout, with optional key formatter.
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
double error(const VectorValues &y) const
Errors b2bar_
A2*xbar - b2.
Chordal Bayes Net, the result of eliminating a factor graph.
static void setSubvector(const Vector &src, const KeyInfo &keyInfo, const KeyVector &keys, Vector &dst)
static Vector getSubvector(const Vector &src, const KeyInfo &keyInfo, const KeyVector &keys)
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
DecisionTreeFactor factor(D &C &B &A, "0.0 0.0 0.0 0.60658897 0.61241912 0.61241969 0.61247685 0.61247742 0.0 " "0.0 0.0 0.99995287 1.0 1.0 1.0 1.0")
VectorValues x(const VectorValues &y) const
void transposeMultiplyAdd(double alpha, const Errors &e, VectorValues &y) const
VectorValues gradient(const VectorValues &y) const
void print(const std::string &s="SubgraphPreconditioner") const
void transposeSolve(const Vector &y, Vector &x) const override
implement x = R^{-T} y
Errors createErrors(const VectorValues &V)
Break V into pieces according to its start indices.
void multiplyInPlace(const VectorValues &y, Errors &e) const
double dot(const V1 &a, const V2 &b)
static VectorValues Zero(const VectorValues &other)
VectorValues backSubstituteTranspose(const VectorValues &gx) const
A matrix or vector expression mapping an existing array of data.
SubgraphBuilderParameters builderParams
Errors gaussianErrors(const VectorValues &x) const
const gtsam::Symbol key('X', 0)
void transposeMultiplyAdd2(double alpha, Errors::const_iterator begin, Errors::const_iterator end, VectorValues &y) const
void solve(const Vector &y, Vector &x) const override
implement x = R^{-1} y
static GaussianFactorGraph convertToJacobianFactors(const GaussianFactorGraph &gfg)
void transposeMultiplyAdd(double alpha, const Errors &e, VectorValues &x) const
std::reverse_iterator< Iterator > make_reverse_iterator(Iterator i)
const_iterator end() const
VectorValues backSubstitute(const VectorValues &gx) const
Array< int, Dynamic, 1 > v
void build(const GaussianFactorGraph &gfg, const KeyInfo &info, const std::map< Key, Vector > &lambda) override
build/factorize the preconditioner
const_iterator begin() const
SubgraphPreconditionerParameters parameters_
static const EIGEN_DEPRECATED end_t end
void multiplyInPlace(const VectorValues &x, Errors &e) const
** In-place version e <- A*x that overwrites e. */
std::uint64_t Key
Integer nonlinear key type.
VectorValues xbar_
A1 \ b1.
VectorValues zero() const
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:14:04