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 
19 #include <gtsam/linear/Sampler.h>
23 
24 #ifdef __GNUC__
25 #pragma GCC diagnostic push
26 #pragma GCC diagnostic ignored "-Wunused-variable"
27 #endif
28 #ifdef __GNUC__
29 #pragma GCC diagnostic pop
30 #endif
31 
32 #include <functional>
33 #include <list>
34 #include <string>
35 #include <cmath>
36 
37 // In Wrappers we have no access to this so have a default ready
38 static std::mt19937_64 kRandomNumberGenerator(42);
39 
40 using namespace std;
41 
42 namespace gtsam {
43 
44  /* ************************************************************************* */
45  GaussianConditional::GaussianConditional(
46  Key key, const Vector& d, const Matrix& R, const SharedDiagonal& sigmas) :
47  BaseFactor(key, R, d, sigmas), BaseConditional(1) {}
48 
49  /* ************************************************************************ */
51  const Matrix& R, Key parent1,
52  const Matrix& S,
53  const SharedDiagonal& sigmas)
54  : BaseFactor(key, R, parent1, S, d, sigmas), BaseConditional(1) {}
55 
56  /* ************************************************************************ */
58  const Matrix& R, Key parent1,
59  const Matrix& S, Key parent2,
60  const Matrix& T,
61  const SharedDiagonal& sigmas)
62  : BaseFactor(key, R, parent1, S, parent2, T, d, sigmas),
63  BaseConditional(1) {}
64 
65  /* ************************************************************************ */
67  const Vector& mu,
68  double sigma) {
69  // |Rx - d| = |x - mu|/sigma
70  const Matrix R = Matrix::Identity(mu.size(), mu.size());
71  const Vector& d = mu;
72  return GaussianConditional(key, d, R,
74  }
75 
76  /* ************************************************************************ */
78  Key key, const Matrix& A, Key parent, const Vector& b, double sigma) {
79  // |Rx + Sy - d| = |x-(Ay + b)|/sigma
80  const Matrix R = Matrix::Identity(b.size(), b.size());
81  const Matrix S = -A;
82  const Vector& d = b;
83  return GaussianConditional(key, d, R, parent, S,
85  }
86 
87  /* ************************************************************************ */
89  Key key, const Matrix& A1, Key parent1, const Matrix& A2, Key parent2,
90  const Vector& b, double sigma) {
91  // |Rx + Sy + Tz - d| = |x-(A1 y + A2 z + b)|/sigma
92  const Matrix R = Matrix::Identity(b.size(), b.size());
93  const Matrix S = -A1;
94  const Matrix T = -A2;
95  const Vector& d = b;
96  return GaussianConditional(key, d, R, parent1, S, parent2, T,
98  }
99 
100  /* ************************************************************************ */
101  void GaussianConditional::print(const string &s, const KeyFormatter& formatter) const {
102  cout << s << " p(";
103  for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) {
104  cout << formatter(*it) << (nrFrontals() > 1 ? " " : "");
105  }
106 
107  if (nrParents()) {
108  cout << " |";
109  for (const_iterator it = beginParents(); it != endParents(); ++it) {
110  cout << " " << formatter(*it);
111  }
112  }
113  cout << ")" << endl;
114 
115  cout << formatMatrixIndented(" R = ", R()) << endl;
116  for (const_iterator it = beginParents() ; it != endParents() ; ++it) {
117  cout << formatMatrixIndented(" S[" + formatter(*it) + "] = ", getA(it)) << endl;
118  }
119  cout << formatMatrixIndented(" d = ", getb(), true) << "\n";
120  if (nrParents() == 0) {
121  const auto mean = solve({}); // solve for mean.
122  mean.print(" mean", formatter);
123  }
124  if (model_)
125  model_->print(" Noise model: ");
126  else
127  cout << " No noise model" << endl;
128  }
129 
130  /* ************************************************************************* */
131  bool GaussianConditional::equals(const GaussianFactor& f, double tol) const {
132  if (const GaussianConditional* c = dynamic_cast<const GaussianConditional*>(&f)) {
133  // check if the size of the parents_ map is the same
134  if (parents().size() != c->parents().size())
135  return false;
136 
137  // check if R_ and d_ are linear independent
138  for (DenseIndex i = 0; i < Ab_.rows(); i++) {
139  list<Vector> rows1, rows2;
140  rows1.push_back(Vector(R().row(i)));
141  rows2.push_back(Vector(c->R().row(i)));
142 
143  // check if the matrices are the same
144  // iterate over the parents_ map
145  for (const_iterator it = beginParents(); it != endParents(); ++it) {
146  const_iterator it2 = c->beginParents() + (it - beginParents());
147  if (*it != *(it2))
148  return false;
149  rows1.push_back(row(getA(it), i));
150  rows2.push_back(row(c->getA(it2), i));
151  }
152 
153  Vector row1 = concatVectors(rows1);
154  Vector row2 = concatVectors(rows2);
155  if (!linear_dependent(row1, row2, tol))
156  return false;
157  }
158 
159  // check if sigmas are equal
160  if ((model_ && !c->model_) || (!model_ && c->model_)
161  || (model_ && c->model_ && !model_->equals(*c->model_, tol)))
162  return false;
163 
164  return true;
165  } else {
166  return false;
167  }
168  }
169 
170  /* ************************************************************************* */
172  if (get_model()) {
173  Vector diag = R().diagonal();
174  get_model()->whitenInPlace(diag);
175  return diag.unaryExpr([](double x) { return log(x); }).sum();
176  } else {
177  return R().diagonal().unaryExpr([](double x) { return log(x); }).sum();
178  }
179  }
180 
181  /* ************************************************************************* */
182  // normalization constant = 1.0 / sqrt((2*pi)^n*det(Sigma))
183  // log = - 0.5 * n*log(2*pi) - 0.5 * log det(Sigma)
185  constexpr double log2pi = 1.8378770664093454835606594728112;
186  size_t n = d().size();
187  // log det(Sigma)) = - 2.0 * logDeterminant()
188  return - 0.5 * n * log2pi + logDeterminant();
189  }
190 
191  /* ************************************************************************* */
192  // density = k exp(-error(x))
193  // log = log(k) - error(x)
195  return logNormalizationConstant() - error(x);
196  }
197 
199  return logProbability(x.continuous());
200  }
201 
202  /* ************************************************************************* */
204  return exp(logProbability(x));
205  }
206 
208  return evaluate(x.continuous());
209  }
210 
211  /* ************************************************************************* */
213  // Concatenate all vector values that correspond to parent variables
214  const Vector xS = x.vector(KeyVector(beginParents(), endParents()));
215 
216  // Update right-hand-side
217  const Vector rhs = d() - S() * xS;
218 
219  // Solve matrix
220  const Vector solution = R().triangularView<Eigen::Upper>().solve(rhs);
221 
222  // Check for indeterminant solution
223  if (solution.hasNaN()) {
225  }
226 
227  // Insert solution into a VectorValues
229  DenseIndex vectorPosition = 0;
230  for (const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) {
231  result.emplace(*frontal, solution.segment(vectorPosition, getDim(frontal)));
232  vectorPosition += getDim(frontal);
233  }
234 
235  return result;
236  }
237 
238  /* ************************************************************************* */
240  const VectorValues& parents, const VectorValues& rhs) const {
241  // Concatenate all vector values that correspond to parent variables
242  Vector xS = parents.vector(KeyVector(beginParents(), endParents()));
243 
244  // Instead of updating getb(), update the right-hand-side from the given rhs
245  const Vector rhsR = rhs.vector(KeyVector(beginFrontals(), endFrontals()));
246  xS = rhsR - S() * xS;
247 
248  // Solve Matrix
249  Vector soln = R().triangularView<Eigen::Upper>().solve(xS);
250 
251  // Scale by sigmas
252  if (model_)
253  soln.array() *= model_->sigmas().array();
254 
255  // Insert solution into a VectorValues
257  DenseIndex vectorPosition = 0;
258  for (const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) {
259  result.emplace(*frontal, soln.segment(vectorPosition, getDim(frontal)));
260  vectorPosition += getDim(frontal);
261  }
262 
263  return result;
264  }
265 
266  /* ************************************************************************* */
268  Vector frontalVec = gy.vector(KeyVector(beginFrontals(), endFrontals()));
269  frontalVec = R().transpose().triangularView<Eigen::Lower>().solve(frontalVec);
270 
271  // Check for indeterminate solution
272  if (frontalVec.hasNaN()) throw IndeterminantLinearSystemException(this->keys().front());
273 
274  for (const_iterator it = beginParents(); it!= endParents(); it++)
275  gy[*it].noalias() += -1.0 * getA(it).transpose() * frontalVec;
276 
277  // Scale by sigmas
278  if (model_)
279  frontalVec.array() *= model_->sigmas().array();
280 
281  // Write frontal solution into a VectorValues
282  DenseIndex vectorPosition = 0;
283  for (const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) {
284  gy[*frontal] = frontalVec.segment(vectorPosition, getDim(frontal));
285  vectorPosition += getDim(frontal);
286  }
287  }
288 
289  /* ************************************************************************ */
291  const VectorValues& frontalValues) const {
292  // Error is |Rx - (d - Sy - Tz - ...)|^2
293  // so when we instantiate x (which has to be completely known) we beget:
294  // |Sy + Tz + ... - (d - Rx)|^2
295  // The noise model just transfers over!
296 
297  // Get frontalValues as vector
298  const Vector x =
299  frontalValues.vector(KeyVector(beginFrontals(), endFrontals()));
300 
301  // Copy the augmented Jacobian matrix:
302  auto newAb = Ab_;
303 
304  // Restrict view to parent blocks
305  newAb.firstBlock() += nrFrontals_;
306 
307  // Update right-hand-side (last column)
308  auto last = newAb.matrix().cols() - 1;
309  const auto RR = R().triangularView<Eigen::Upper>();
310  newAb.matrix().col(last) -= RR * x;
311 
312  // The keys now do not include the frontal keys:
313  KeyVector newKeys;
314  newKeys.reserve(nrParents());
315  for (auto&& key : parents()) newKeys.push_back(key);
316 
317  // Hopefully second newAb copy below is optimized out...
318  return std::make_shared<JacobianFactor>(newKeys, newAb, model_);
319  }
320 
321  /* **************************************************************************/
323  const Vector& frontal) const {
324  if (nrFrontals() != 1)
325  throw std::invalid_argument(
326  "GaussianConditional Single value likelihood can only be invoked on "
327  "single-variable conditional");
329  values.insert(keys_[0], frontal);
330  return likelihood(values);
331  }
332 
333  /* ************************************************************************ */
335  std::mt19937_64* rng) const {
336  if (nrFrontals() != 1) {
337  throw std::invalid_argument(
338  "GaussianConditional::sample can only be called on single variable "
339  "conditionals");
340  }
341 
342  VectorValues solution = solve(parentsValues);
343  Key key = firstFrontalKey();
344  // The vector of sigma values for sampling.
345  // If no model, initialize sigmas to 1, else to model sigmas
346  const Vector& sigmas = (!model_) ? Vector::Ones(rows()) : model_->sigmas();
347  solution[key] += Sampler::sampleDiagonal(sigmas, rng);
348  return solution;
349  }
350 
351  VectorValues GaussianConditional::sample(std::mt19937_64* rng) const {
352  if (nrParents() != 0)
353  throw std::invalid_argument(
354  "sample() can only be invoked on no-parent prior");
356  return sample(values);
357  }
358 
359  /* ************************************************************************ */
362  }
363 
365  return sample(given, &kRandomNumberGenerator);
366  }
367 
368  /* ************************************************************************ */
369 
370 } // namespace gtsam
const gtsam::Symbol key('X', 0)
VectorValues sample() const
Sample, use default rng.
std::string formatMatrixIndented(const std::string &label, const Matrix &matrix, bool makeVectorHorizontal)
Definition: Matrix.cpp:597
static Matrix A1
JacobianFactor::shared_ptr likelihood(const VectorValues &frontalValues) const
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
Definition: base/Matrix.h:221
static std::mt19937 kRandomNumberGenerator(42)
static std::mt19937_64 kRandomNumberGenerator(42)
double error(const VectorValues &c) const override
Matrix diag(const std::vector< Matrix > &Hs)
Definition: Matrix.cpp:206
void print(const std::string &="GaussianConditional", const KeyFormatter &formatter=DefaultKeyFormatter) const override
JacobianFactor ::const_iterator endFrontals() const
Definition: Conditional.h:182
size_t size() const
Definition: Factor.h:159
DenseIndex rows() const
Row size.
double mu
noiseModel::Diagonal::shared_ptr model_
static std::mt19937 rng
int n
VectorValues solve(const VectorValues &parents) const
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
Rot2 R(Rot2::fromAngle(0.1))
leaf::MyValues values
JacobianFactor ::const_iterator beginParents() const
Definition: Conditional.h:185
static Vector sampleDiagonal(const Vector &sigmas, std::mt19937_64 *rng)
sample with given random number generator
Definition: Sampler.cpp:36
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:87
Definition: BFloat16.h:88
iterator insert(const std::pair< Key, Vector > &key_value)
double evaluate(const VectorValues &x) const
const VectorValues & continuous() const
Return the multi-dimensional vector values.
Definition: HybridValues.h:89
const constBVector d() const
EIGEN_DEVICE_FUNC const LogReturnType log() const
static const symbolic::SymbolExpr< internal::symbolic_last_tag > last
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:108
Point3 mean(const CONTAINER &points)
mean
Definition: Point3.h:70
const KeyFormatter & formatter
JacobianFactor ::const_iterator beginFrontals() const
Definition: Conditional.h:179
std::pair< VectorValues::iterator, bool > emplace(Key j, Args &&... args)
Definition: VectorValues.h:185
bool linear_dependent(const Matrix &A, const Matrix &B, double tol)
Definition: Matrix.cpp:114
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
Factor Graph Values.
void solveTransposeInPlace(VectorValues &gy) const
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
JacobianFactor ::const_iterator endParents() const
Definition: Conditional.h:188
const constBVector getb() const
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
RealScalar s
DenseIndex getDim(const_iterator variable) const override
Conditional Gaussian Base class.
sampling from a NoiseModel
double logProbability(const VectorValues &x) const
std::shared_ptr< This > shared_ptr
shared_ptr to this class
static GaussianConditional FromMeanAndStddev(Key key, const Vector &mu, double sigma)
Construct from mean mu and standard deviation sigma.
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
const G & b
Definition: Group.h:86
Exceptions that may be thrown by linear solver components.
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:743
traits
Definition: chartTesting.h:28
double logDeterminant() const
Compute the log determinant of the R matrix.
constABlock getA() const
Key front() const
First key.
Definition: Factor.h:133
VectorValues solveOtherRHS(const VectorValues &parents, const VectorValues &rhs) const
Vector vector() const
VerticalBlockMatrix Ab_
const KeyVector & keys() const
Access the factor&#39;s involved variable keys.
Definition: Factor.h:142
static const double sigma
const DenseIndex & firstBlock() const
const G double tol
Definition: Group.h:86
KeyVector::const_iterator const_iterator
Const iterator over keys.
Definition: Factor.h:82
bool equals(const GaussianFactor &cg, double tol=1e-9) const override
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
double logNormalizationConstant() const override
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
Vector concatVectors(const std::list< Vector > &vs)
Definition: Vector.cpp:301
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
const SharedDiagonal & get_model() const
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:594


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:15