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


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:01:18