GaussianConditional.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 
21 
22 #include <boost/format.hpp>
23 #ifdef __GNUC__
24 #pragma GCC diagnostic push
25 #pragma GCC diagnostic ignored "-Wunused-variable"
26 #endif
27 #include <boost/lambda/lambda.hpp>
28 #include <boost/lambda/bind.hpp>
29 #ifdef __GNUC__
30 #pragma GCC diagnostic pop
31 #endif
32 
33 #include <functional>
34 #include <list>
35 #include <string>
36 
37 using namespace std;
38 
39 namespace gtsam {
40 
41  /* ************************************************************************* */
42  GaussianConditional::GaussianConditional(
43  Key key, const Vector& d, const Matrix& R, const SharedDiagonal& sigmas) :
44  BaseFactor(key, R, d, sigmas), BaseConditional(1) {}
45 
46  /* ************************************************************************* */
48  Key key, const Vector& d, const Matrix& R,
49  Key name1, const Matrix& S, const SharedDiagonal& sigmas) :
50  BaseFactor(key, R, name1, S, d, sigmas), BaseConditional(1) {}
51 
52  /* ************************************************************************* */
54  Key key, const Vector& d, const Matrix& R,
55  Key name1, const Matrix& S, Key name2, const Matrix& T, const SharedDiagonal& sigmas) :
56  BaseFactor(key, R, name1, S, name2, T, d, sigmas), BaseConditional(1) {}
57 
58  /* ************************************************************************* */
59  void GaussianConditional::print(const string &s, const KeyFormatter& formatter) const {
60  cout << s << " Conditional density ";
61  for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) {
62  cout << (boost::format("[%1%]")%(formatter(*it))).str() << " ";
63  }
64  cout << endl;
65  cout << formatMatrixIndented(" R = ", R()) << endl;
66  for (const_iterator it = beginParents() ; it != endParents() ; ++it) {
67  cout << formatMatrixIndented((boost::format(" S[%1%] = ")%(formatter(*it))).str(), getA(it))
68  << endl;
69  }
70  cout << formatMatrixIndented(" d = ", getb(), true) << "\n";
71  if (model_)
72  model_->print(" Noise model: ");
73  else
74  cout << " No noise model" << endl;
75  }
76 
77  /* ************************************************************************* */
78  bool GaussianConditional::equals(const GaussianFactor& f, double tol) const {
79  if (const GaussianConditional* c = dynamic_cast<const GaussianConditional*>(&f)) {
80  // check if the size of the parents_ map is the same
81  if (parents().size() != c->parents().size())
82  return false;
83 
84  // check if R_ and d_ are linear independent
85  for (DenseIndex i = 0; i < Ab_.rows(); i++) {
86  list<Vector> rows1, rows2;
87  rows1.push_back(Vector(R().row(i)));
88  rows2.push_back(Vector(c->R().row(i)));
89 
90  // check if the matrices are the same
91  // iterate over the parents_ map
92  for (const_iterator it = beginParents(); it != endParents(); ++it) {
93  const_iterator it2 = c->beginParents() + (it - beginParents());
94  if (*it != *(it2))
95  return false;
96  rows1.push_back(row(getA(it), i));
97  rows2.push_back(row(c->getA(it2), i));
98  }
99 
100  Vector row1 = concatVectors(rows1);
101  Vector row2 = concatVectors(rows2);
102  if (!linear_dependent(row1, row2, tol))
103  return false;
104  }
105 
106  // check if sigmas are equal
107  if ((model_ && !c->model_) || (!model_ && c->model_)
108  || (model_ && c->model_ && !model_->equals(*c->model_, tol)))
109  return false;
110 
111  return true;
112  } else {
113  return false;
114  }
115  }
116 
117  /* ************************************************************************* */
119  // Concatenate all vector values that correspond to parent variables
120  const Vector xS = x.vector(KeyVector(beginParents(), endParents()));
121 
122  // Update right-hand-side
123  const Vector rhs = d() - S() * xS;
124 
125  // Solve matrix
126  const Vector solution = R().triangularView<Eigen::Upper>().solve(rhs);
127 
128  // Check for indeterminant solution
129  if (solution.hasNaN()) {
131  }
132 
133  // Insert solution into a VectorValues
135  DenseIndex vectorPosition = 0;
136  for (const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) {
137  result.emplace(*frontal, solution.segment(vectorPosition, getDim(frontal)));
138  vectorPosition += getDim(frontal);
139  }
140 
141  return result;
142  }
143 
144  /* ************************************************************************* */
146  const VectorValues& parents, const VectorValues& rhs) const {
147  // Concatenate all vector values that correspond to parent variables
148  Vector xS = parents.vector(KeyVector(beginParents(), endParents()));
149 
150  // Instead of updating getb(), update the right-hand-side from the given rhs
151  const Vector rhsR = rhs.vector(KeyVector(beginFrontals(), endFrontals()));
152  xS = rhsR - S() * xS;
153 
154  // Solve Matrix
155  Vector soln = R().triangularView<Eigen::Upper>().solve(xS);
156 
157  // Scale by sigmas
158  if (model_)
159  soln.array() *= model_->sigmas().array();
160 
161  // Insert solution into a VectorValues
163  DenseIndex vectorPosition = 0;
164  for (const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) {
165  result.emplace(*frontal, soln.segment(vectorPosition, getDim(frontal)));
166  vectorPosition += getDim(frontal);
167  }
168 
169  return result;
170  }
171 
172  /* ************************************************************************* */
174  Vector frontalVec = gy.vector(KeyVector(beginFrontals(), endFrontals()));
175  frontalVec = R().transpose().triangularView<Eigen::Lower>().solve(frontalVec);
176 
177  // Check for indeterminant solution
178  if (frontalVec.hasNaN()) throw IndeterminantLinearSystemException(this->keys().front());
179 
180  for (const_iterator it = beginParents(); it!= endParents(); it++)
181  gy[*it].noalias() += -1.0 * getA(it).transpose() * frontalVec;
182 
183  // Scale by sigmas
184  if (model_)
185  frontalVec.array() *= model_->sigmas().array();
186 
187  // Write frontal solution into a VectorValues
188  DenseIndex vectorPosition = 0;
189  for (const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) {
190  gy[*frontal] = frontalVec.segment(vectorPosition, getDim(frontal));
191  vectorPosition += getDim(frontal);
192  }
193  }
194 
195  /* ************************************************************************* */
197  DenseIndex vectorPosition = 0;
198  for (const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) {
199  gy[*frontal].array() *= model_->sigmas().segment(vectorPosition, getDim(frontal)).array();
200  vectorPosition += getDim(frontal);
201  }
202  }
203 
204 } // namespace gtsam
VectorValues solveOtherRHS(const VectorValues &parents, const VectorValues &rhs) const
std::string formatMatrixIndented(const std::string &label, const Matrix &matrix, bool makeVectorHorizontal)
Definition: Matrix.cpp:598
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
Definition: base/Matrix.h:225
void solveTransposeInPlace(VectorValues &gy) const
JacobianFactor::const_iterator endParents() const
Definition: Conditional.h:114
constABlock getA() const
noiseModel::Diagonal::shared_ptr model_
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
Rot2 R(Rot2::fromAngle(0.1))
Definition: Half.h:150
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:67
const KeyFormatter & formatter
bool equals(const GaussianFactor &cg, double tol=1e-9) const override
Factor Graph Values.
JacobianFactor::const_iterator beginParents() const
Definition: Conditional.h:111
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
Key front() const
First key.
Definition: Factor.h:115
void print(const std::string &="GaussianConditional", const KeyFormatter &formatter=DefaultKeyFormatter) const override
const constBVector getb() const
JacobianFactor::const_iterator endFrontals() const
Definition: Conditional.h:108
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
RealScalar s
DenseIndex getDim(const_iterator variable) const override
Conditional Gaussian Base class.
const constBVector d() const
Exceptions that may be thrown by linear solver components.
void scaleFrontalsBySigma(VectorValues &gy) const
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
bool linear_dependent(const Matrix &A, const Matrix &B, double tol)
Definition: Matrix.cpp:116
JacobianFactor::const_iterator beginFrontals() const
Definition: Conditional.h:105
size_t size() const
Definition: Factor.h:135
const KeyVector & keys() const
Access the factor&#39;s involved variable keys.
Definition: Factor.h:124
VectorValues solve(const VectorValues &parents) const
VerticalBlockMatrix Ab_
const G double tol
Definition: Group.h:83
KeyVector::const_iterator const_iterator
Const iterator over keys.
Definition: Factor.h:67
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
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Vector concatVectors(const std::list< Vector > &vs)
Definition: Vector.cpp:302
Vector vector() const
DenseIndex rows() const
Row size.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:05