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) :
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.empty() ? "" : 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  cout << " logNormalizationConstant: " << -negLogConstant() << endl;
125  if (model_)
126  model_->print(" Noise model: ");
127  else
128  cout << " No noise model" << endl;
129  }
130 
131  /* ************************************************************************* */
132  bool GaussianConditional::equals(const GaussianFactor& f, double tol) const {
133  if (const GaussianConditional* c = dynamic_cast<const GaussianConditional*>(&f)) {
134  // check if the size of the parents_ map is the same
135  if (parents().size() != c->parents().size())
136  return false;
137 
138  // check if R_ and d_ are linear independent
139  for (DenseIndex i = 0; i < Ab_.rows(); i++) {
140  list<Vector> rows1, rows2;
141  rows1.push_back(Vector(R().row(i)));
142  rows2.push_back(Vector(c->R().row(i)));
143 
144  // check if the matrices are the same
145  // iterate over the parents_ map
146  for (const_iterator it = beginParents(); it != endParents(); ++it) {
147  const_iterator it2 = c->beginParents() + (it - beginParents());
148  if (*it != *(it2))
149  return false;
150  rows1.push_back(row(getA(it), i));
151  rows2.push_back(row(c->getA(it2), i));
152  }
153 
154  Vector row1 = concatVectors(rows1);
155  Vector row2 = concatVectors(rows2);
156  if (!linear_dependent(row1, row2, tol))
157  return false;
158  }
159 
160  // check if sigmas are equal
161  if ((model_ && !c->model_) || (!model_ && c->model_)
162  || (model_ && c->model_ && !model_->equals(*c->model_, tol)))
163  return false;
164 
165  return true;
166  } else {
167  return false;
168  }
169  }
170 
171  /* ************************************************************************* */
173  if (get_model()) {
174  Vector diag = R().diagonal();
175  get_model()->whitenInPlace(diag);
176  return diag.unaryExpr([](double x) { return log(x); }).sum();
177  } else {
178  return R().diagonal().unaryExpr([](double x) { return log(x); }).sum();
179  }
180  }
181 
182  /* ************************************************************************* */
183  // normalization constant = 1.0 / sqrt((2*pi)^n*det(Sigma))
184  // neg-log = 0.5 * n*log(2*pi) + 0.5 * log det(Sigma)
186  constexpr double log2pi = 1.8378770664093454835606594728112;
187  size_t n = d().size();
188  // Sigma = (R'R)^{-1}, det(Sigma) = det((R'R)^{-1}) = det(R'R)^{-1}
189  // log det(Sigma) = -log(det(R'R)) = -2*log(det(R))
190  // Hence, log det(Sigma)) = -2.0 * logDeterminant()
191  // which gives neg-log = 0.5*n*log(2*pi) + 0.5*(-2.0 * logDeterminant())
192  // = 0.5*n*log(2*pi) - (0.5*2.0 * logDeterminant())
193  // = 0.5*n*log(2*pi) - logDeterminant()
194  return 0.5 * n * log2pi - logDeterminant();
195  }
196 
197  /* ************************************************************************* */
198  // density = k exp(-error(x))
199  // log = log(k) - error(x)
201  return -(negLogConstant() + error(x));
202  }
203 
205  return logProbability(x.continuous());
206  }
207 
208  /* ************************************************************************* */
210  return exp(logProbability(x));
211  }
212 
214  return evaluate(x.continuous());
215  }
216 
217  /* ************************************************************************* */
219  // Concatenate all vector values that correspond to parent variables
220  const Vector xS = x.vector(KeyVector(beginParents(), endParents()));
221 
222  // Update right-hand-side
223  const Vector rhs = d() - S() * xS;
224 
225  // Solve matrix
226  const Vector solution = R().triangularView<Eigen::Upper>().solve(rhs);
227 
228  // Check for indeterminant solution
229  if (solution.hasNaN()) {
231  }
232 
233  // Insert solution into a VectorValues
235  DenseIndex vectorPosition = 0;
236  for (const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) {
237  result.emplace(*frontal, solution.segment(vectorPosition, getDim(frontal)));
238  vectorPosition += getDim(frontal);
239  }
240 
241  return result;
242  }
243 
244  /* ************************************************************************* */
246  const VectorValues& parents, const VectorValues& rhs) const {
247  // Concatenate all vector values that correspond to parent variables
248  Vector xS = parents.vector(KeyVector(beginParents(), endParents()));
249 
250  // Instead of updating getb(), update the right-hand-side from the given rhs
251  const Vector rhsR = rhs.vector(KeyVector(beginFrontals(), endFrontals()));
252  xS = rhsR - S() * xS;
253 
254  // Solve Matrix
255  Vector soln = R().triangularView<Eigen::Upper>().solve(xS);
256 
257  // Scale by sigmas
258  if (model_)
259  soln.array() *= model_->sigmas().array();
260 
261  // Insert solution into a VectorValues
263  DenseIndex vectorPosition = 0;
264  for (const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) {
265  result.emplace(*frontal, soln.segment(vectorPosition, getDim(frontal)));
266  vectorPosition += getDim(frontal);
267  }
268 
269  return result;
270  }
271 
272  /* ************************************************************************* */
274  Vector frontalVec = gy.vector(KeyVector(beginFrontals(), endFrontals()));
275  frontalVec = R().transpose().triangularView<Eigen::Lower>().solve(frontalVec);
276 
277  // Check for indeterminate solution
278  if (frontalVec.hasNaN()) throw IndeterminantLinearSystemException(this->keys().front());
279 
280  for (const_iterator it = beginParents(); it!= endParents(); it++)
281  gy[*it].noalias() += -1.0 * getA(it).transpose() * frontalVec;
282 
283  // Scale by sigmas
284  if (model_)
285  frontalVec.array() *= model_->sigmas().array();
286 
287  // Write frontal solution into a VectorValues
288  DenseIndex vectorPosition = 0;
289  for (const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) {
290  gy[*frontal] = frontalVec.segment(vectorPosition, getDim(frontal));
291  vectorPosition += getDim(frontal);
292  }
293  }
294 
295  /* ************************************************************************ */
297  const VectorValues& frontalValues) const {
298  // Error is |Rx - (d - Sy - Tz - ...)|^2
299  // so when we instantiate x (which has to be completely known) we beget:
300  // |Sy + Tz + ... - (d - Rx)|^2
301  // The noise model just transfers over!
302 
303  // Get frontalValues as vector
304  const Vector x =
305  frontalValues.vector(KeyVector(beginFrontals(), endFrontals()));
306 
307  // Copy the augmented Jacobian matrix:
308  auto newAb = Ab_;
309 
310  // Restrict view to parent blocks
311  newAb.firstBlock() += nrFrontals_;
312 
313  // Update right-hand-side (last column)
314  auto last = newAb.matrix().cols() - 1;
315  const auto RR = R().triangularView<Eigen::Upper>();
316  newAb.matrix().col(last) -= RR * x;
317 
318  // The keys now do not include the frontal keys:
319  KeyVector newKeys;
320  newKeys.reserve(nrParents());
321  for (auto&& key : parents()) newKeys.push_back(key);
322 
323  // Hopefully second newAb copy below is optimized out...
324  return std::make_shared<JacobianFactor>(newKeys, newAb, model_);
325  }
326 
327  /* **************************************************************************/
329  const Vector& frontal) const {
330  if (nrFrontals() != 1)
331  throw std::invalid_argument(
332  "GaussianConditional Single value likelihood can only be invoked on "
333  "single-variable conditional");
335  values.insert(keys_[0], frontal);
336  return likelihood(values);
337  }
338 
339  /* ************************************************************************ */
341  std::mt19937_64* rng) const {
342  if (nrFrontals() != 1) {
343  throw std::invalid_argument(
344  "GaussianConditional::sample can only be called on single variable "
345  "conditionals");
346  }
347 
348  VectorValues solution = solve(parentsValues);
349  Key key = firstFrontalKey();
350  // The vector of sigma values for sampling.
351  // If no model, initialize sigmas to 1, else to model sigmas
352  const Vector& sigmas = (!model_) ? Vector::Ones(rows()) : model_->sigmas();
353  solution[key] += Sampler::sampleDiagonal(sigmas, rng);
354  return solution;
355  }
356 
357  VectorValues GaussianConditional::sample(std::mt19937_64* rng) const {
358  if (nrParents() != 0)
359  throw std::invalid_argument(
360  "sample() can only be invoked on no-parent prior");
362  return sample(values);
363  }
364 
365  /* ************************************************************************ */
368  }
369 
371  return sample(given, &kRandomNumberGenerator);
372  }
373 
374  /* ************************************************************************ */
375 
376 } // 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:225
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:292
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:273
gtsam::diag
Matrix diag(const std::vector< Matrix > &Hs)
Definition: Matrix.cpp:207
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:245
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:284
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:209
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::concatVectors
Vector concatVectors(const std::list< Vector > &vs)
Definition: Vector.cpp:302
gtsam::JacobianFactor::getb
const constBVector getb() const
Definition: JacobianFactor.h:298
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:184
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:222
gtsam::JacobianFactor::getDim
DenseIndex getDim(const_iterator variable) const override
Definition: JacobianFactor.h:277
gtsam::VectorValues
Definition: VectorValues.h:74
gtsam::row
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
Definition: base/Matrix.h:221
gtsam::GaussianConditional::negLogConstant
double negLogConstant() const override
Return the negative log of the normalization constant.
Definition: GaussianConditional.cpp:185
gtsam::Conditional< JacobianFactor, GaussianConditional >::endFrontals
JacobianFactor ::const_iterator endFrontals() const
Definition: Conditional.h:183
gtsam::kRandomNumberGenerator
static std::mt19937 kRandomNumberGenerator(42)
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:101
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:132
gtsam::GaussianConditional::d
const constBVector d() const
Definition: GaussianConditional.h:231
gtsam::GaussianConditional::GaussianConditional
GaussianConditional()
Definition: GaussianConditional.h:54
gtsam::GaussianConditional::logProbability
double logProbability(const VectorValues &x) const
Definition: GaussianConditional.cpp:200
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
kRandomNumberGenerator
static std::mt19937_64 kRandomNumberGenerator(42)
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: SFMdata.h:40
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
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:296
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:172
gtsam::VerticalBlockMatrix::rows
DenseIndex rows() const
Row size.
Definition: VerticalBlockMatrix.h:117
gtsam::JacobianFactor::error
double error(const VectorValues &c) const override
Definition: JacobianFactor.cpp:487
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:625
gtsam::IndeterminantLinearSystemException
Definition: linearExceptions.h:94
Sampler.h
sampling from a NoiseModel
gtsam::JacobianFactor::getA
constABlock getA() const
Definition: JacobianFactor.h:304
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:245
HybridValues.h
gtsam::GaussianConditional::solve
VectorValues solve(const VectorValues &parents) const
Definition: GaussianConditional.cpp:218
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:66
S
DiscreteKey S(1, 2)
gtsam::formatMatrixIndented
std::string formatMatrixIndented(const std::string &label, const Matrix &matrix, bool makeVectorHorizontal)
Definition: Matrix.cpp:598
gtsam::GaussianConditional::sample
VectorValues sample() const
Sample, use default rng.
Definition: GaussianConditional.cpp:366
gtsam::VectorValues::vector
Vector vector() const
Definition: VectorValues.cpp:175


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:34