GaussianDensity.h
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 // \callgraph
20 #pragma once
21 
23 
24 namespace gtsam {
25 
33  class GTSAM_EXPORT GaussianDensity : public GaussianConditional {
34 
35  public:
36 
37  typedef boost::shared_ptr<GaussianDensity> shared_ptr;
38 
42  }
43 
45  GaussianDensity(const GaussianConditional& conditional) :
46  GaussianConditional(conditional) {
47  if(conditional.nrParents() != 0)
48  throw std::invalid_argument("GaussianDensity can only be created from a conditional with no parents");
49  }
50 
52  GaussianDensity(Key key, const Vector& d, const Matrix& R, const SharedDiagonal& noiseModel = SharedDiagonal()) :
53  GaussianConditional(key, d, R, noiseModel) {}
54 
56  static GaussianDensity FromMeanAndStddev(Key key, const Vector& mean, const double& sigma);
57 
59  void print(const std::string& = "GaussianDensity",
60  const KeyFormatter& formatter = DefaultKeyFormatter) const override;
61 
63  Vector mean() const;
64 
66  Matrix covariance() const;
67 
68  };
69  // GaussianDensity
70 
71 }// gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
static const double sigma
GaussianDensity(const GaussianConditional &conditional)
Copy constructor from GaussianConditional.
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Rot2 R(Rot2::fromAngle(0.1))
GaussianDensity(Key key, const Vector &d, const Matrix &R, const SharedDiagonal &noiseModel=SharedDiagonal())
constructor using d, R
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
Point3 mean(const CONTAINER &points)
mean
Definition: Point3.h:66
const KeyFormatter & formatter
Eigen::VectorXd Vector
Definition: Vector.h:38
GaussianDensity()
default constructor needed for serialization
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
size_t nrParents() const
Definition: Conditional.h:88
Conditional Gaussian Base class.
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
boost::shared_ptr< GaussianDensity > shared_ptr
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61


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