Gaussian.h
Go to the documentation of this file.
1 /************************************************************************
2  * Copyright (C) 2012 Eindhoven University of Technology (TU/e). *
3  * All rights reserved. *
4  ************************************************************************
5  * Redistribution and use in source and binary forms, with or without *
6  * modification, are permitted provided that the following conditions *
7  * are met: *
8  * *
9  * 1. Redistributions of source code must retain the above *
10  * copyright notice, this list of conditions and the following *
11  * disclaimer. *
12  * *
13  * 2. Redistributions in binary form must reproduce the above *
14  * copyright notice, this list of conditions and the following *
15  * disclaimer in the documentation and/or other materials *
16  * provided with the distribution. *
17  * *
18  * THIS SOFTWARE IS PROVIDED BY TU/e "AS IS" AND ANY EXPRESS OR *
19  * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED *
20  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE *
21  * ARE DISCLAIMED. IN NO EVENT SHALL TU/e OR CONTRIBUTORS BE LIABLE *
22  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR *
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT *
24  * OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; *
25  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF *
26  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
27  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE *
28  * USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH *
29  * DAMAGE. *
30  * *
31  * The views and conclusions contained in the software and *
32  * documentation are those of the authors and should not be *
33  * interpreted as representing official policies, either expressed or *
34  * implied, of TU/e. *
35  ************************************************************************/
36 
37 #ifndef PROBLIB_GAUSSIAN_H_
38 #define PROBLIB_GAUSSIAN_H_
39 
40 #include "PDF.h"
41 
42 namespace pbl {
43 
51 class Gaussian: public PDF {
52 
53 public:
54 
60  Gaussian(int dim);
61 
68  Gaussian(const arma::vec& mean, const arma::mat& cov);
69 
73  Gaussian(const Gaussian& orig);
74 
78  virtual ~Gaussian();
79 
85  Gaussian& operator=(const Gaussian& other);
86 
92  Gaussian* clone() const;
93 
94  double getLikelihood(const PDF& pdf) const;
95 
102  double getDensity(const arma::vec& v, double max_mah_dist = 0) const;
103 
104  double getDensity(const Gaussian& npdf, double max_mah_dist = 0) const;
105 
111  double getMaxDensity() const;
112 
119  bool getExpectedValue(arma::vec& v) const;
120 
125  void setMean(const arma::vec& mu);
126 
131  void setCovariance(const arma::mat& cov);
132 
137  const arma::vec& getMean() const;
138 
143  const arma::mat& getCovariance() const;
144 
150  std::string toString(const std::string& indent = "") const;
151 
152 protected:
153 
154  struct GaussianStruct {
155 
157 
159 
160  int n_ptrs_;
161 
162  GaussianStruct(const arma::vec& mu, const arma::mat& cov) : mu_(mu) , cov_(cov), n_ptrs_(1) { }
163 
164  GaussianStruct(const GaussianStruct& orig) : mu_(orig.mu_), cov_(orig.cov_), n_ptrs_(1) { }
165  };
166 
168 
169  void cloneStruct();
170 
171  double getDensity(const arma::vec& v1, const arma::vec& v2, const arma::mat& S, double max_mah_dist = 0) const;
172 
173 #define CHECK_INITIALIZED assert_msg(ptr_, "Gaussian was not yet initialized.")
174 
175 };
176 
177 }
178 
179 #endif /* NORMALPDF_H_ */
bool getExpectedValue(arma::vec &v) const
Returns the expected value E[x] of the Gaussian, which corresponds to its mean.
Definition: Gaussian.cpp:122
virtual ~Gaussian()
Destructor.
Definition: Gaussian.cpp:54
This class represents a multi-variate Gaussian (Normal) distribution.
Definition: Gaussian.h:51
arma_inline const Op< T1, op_mean > mean(const Base< typename T1::elem_type, T1 > &X, const uword dim=0)
Gaussian & operator=(const Gaussian &other)
Assignment operator. The operation is cheap since it only copies a pointer. A deep clone will only be...
Definition: Gaussian.cpp:64
Mat< double > mat
double getMaxDensity() const
Calculates the maximum density of the Gaussian, i.e., the density at the mean.
Definition: Gaussian.cpp:117
const arma::mat & getCovariance() const
Returns the covariance matrix of the Gaussian.
Definition: Gaussian.cpp:186
void setMean(const arma::vec &mu)
Sets the mean of the Gaussian.
Definition: Gaussian.cpp:161
const arma::vec & getMean() const
Returns the mean of the Gaussian.
Definition: Gaussian.cpp:181
GaussianStruct * ptr_
Definition: Gaussian.h:167
GaussianStruct(const GaussianStruct &orig)
Definition: Gaussian.h:164
double getLikelihood(const PDF &pdf) const
Definition: Gaussian.cpp:91
Gaussian(int dim)
Constructs a (multi-variate) Gaussian with specific dimensionality but leaves mean and covariance uns...
Definition: Gaussian.cpp:42
void cloneStruct()
Definition: Gaussian.cpp:84
const Op< T1, op_cov > cov(const Base< typename T1::elem_type, T1 > &X, const uword norm_type=0)
GaussianStruct(const arma::vec &mu, const arma::mat &cov)
Definition: Gaussian.h:162
double getDensity(const arma::vec &v, double max_mah_dist=0) const
Calculates the density of the Gaussian at point v.
Definition: Gaussian.cpp:106
Definition: PDF.h:47
Col< double > vec
Gaussian * clone() const
Creates a clone of the object. The clone method is cheap since it only copies a pointer. A deep clone will only be created if the original object is modified.
Definition: Gaussian.cpp:80
void setCovariance(const arma::mat &cov)
Sets the covariance of the Gaussian.
Definition: Gaussian.cpp:171
std::string toString(const std::string &indent="") const
Represents the Gaussian as a string for easier console output.
Definition: Gaussian.cpp:191


problib
Author(s): Sjoerd van den Dries, Jos Elfring
autogenerated on Fri Apr 16 2021 02:32:19