GaussianDensity.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 
20 #include <string>
21 
22 using std::cout;
23 using std::endl;
24 using std::string;
25 
26 namespace gtsam {
27 
28 /* ************************************************************************* */
30  double sigma) {
31  return GaussianDensity(key, mean, Matrix::Identity(mean.size(), mean.size()),
33 }
34 
35 /* ************************************************************************* */
36 void GaussianDensity::print(const string& s,
37  const KeyFormatter& formatter) const {
38  cout << s << ": density on ";
39  for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) {
40  cout << "[" << formatter(*it) << "] ";
41  }
42  cout << endl;
43  gtsam::print(mean(), "mean: ");
44  gtsam::print(covariance(), "covariance: ");
45  if (model_) model_->print("Noise model: ");
46 }
47 
48 /* ************************************************************************* */
50  VectorValues soln = this->solve(VectorValues());
51  return soln[firstFrontalKey()];
52 }
53 
54 /* ************************************************************************* */
55 Matrix GaussianDensity::covariance() const { return information().inverse(); }
56 
57 } // namespace gtsam
s
RealScalar s
Definition: level1_cplx_impl.h:126
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
sampling::sigma
static const double sigma
Definition: testGaussianBayesNet.cpp:169
gtsam::JacobianFactor::model_
noiseModel::Diagonal::shared_ptr model_
Definition: JacobianFactor.h:107
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
gtsam::VectorValues
Definition: VectorValues.h:74
gtsam::JacobianFactor::information
Matrix information() const override
Definition: JacobianFactor.cpp:505
gtsam::Conditional< JacobianFactor, GaussianConditional >::endFrontals
JacobianFactor ::const_iterator endFrontals() const
Definition: Conditional.h:182
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
GaussianDensity.h
A Gaussian Density.
gtsam::Conditional< JacobianFactor, GaussianConditional >::beginFrontals
JacobianFactor ::const_iterator beginFrontals() const
Definition: Conditional.h:179
gtsam::GaussianDensity
Definition: GaussianDensity.h:32
gtsam::GaussianDensity::covariance
Matrix covariance() const
Covariance matrix .
Definition: GaussianDensity.cpp:55
key
const gtsam::Symbol key('X', 0)
gtsam::Conditional< JacobianFactor, GaussianConditional >::firstFrontalKey
Key firstFrontalKey() const
Definition: Conditional.h:135
gtsam::Factor::const_iterator
KeyVector::const_iterator const_iterator
Const iterator over keys.
Definition: Factor.h:82
gtsam::GaussianDensity::print
void print(const std::string &="GaussianDensity", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print
Definition: GaussianDensity.cpp:36
gtsam
traits
Definition: chartTesting.h:28
gtsam::mean
Point3 mean(const CONTAINER &points)
mean
Definition: Point3.h:70
gtsam::GaussianDensity::mean
Vector mean() const
Mean .
Definition: GaussianDensity.cpp:49
gtsam::noiseModel::Isotropic::Sigma
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:594
gtsam::GaussianDensity::GaussianDensity
GaussianDensity()
default constructor needed for serialization
Definition: GaussianDensity.h:39
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::GaussianConditional::solve
VectorValues solve(const VectorValues &parents) const
Definition: GaussianConditional.cpp:212
gtsam::GaussianDensity::FromMeanAndStddev
static GaussianDensity FromMeanAndStddev(Key key, const Vector &mean, double sigma)
Construct using a mean and standard deviation.
Definition: GaussianDensity.cpp:29


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:00:53