$search
00001 /************************************************************************ 00002 * Copyright (C) 2012 Eindhoven University of Technology (TU/e). * 00003 * All rights reserved. * 00004 ************************************************************************ 00005 * Redistribution and use in source and binary forms, with or without * 00006 * modification, are permitted provided that the following conditions * 00007 * are met: * 00008 * * 00009 * 1. Redistributions of source code must retain the above * 00010 * copyright notice, this list of conditions and the following * 00011 * disclaimer. * 00012 * * 00013 * 2. Redistributions in binary form must reproduce the above * 00014 * copyright notice, this list of conditions and the following * 00015 * disclaimer in the documentation and/or other materials * 00016 * provided with the distribution. * 00017 * * 00018 * THIS SOFTWARE IS PROVIDED BY TU/e "AS IS" AND ANY EXPRESS OR * 00019 * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * 00020 * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * 00021 * ARE DISCLAIMED. IN NO EVENT SHALL TU/e OR CONTRIBUTORS BE LIABLE * 00022 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * 00023 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT * 00024 * OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; * 00025 * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF * 00026 * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * 00027 * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE * 00028 * USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH * 00029 * DAMAGE. * 00030 * * 00031 * The views and conclusions contained in the software and * 00032 * documentation are those of the authors and should not be * 00033 * interpreted as representing official policies, either expressed or * 00034 * implied, of TU/e. * 00035 ************************************************************************/ 00036 00037 #include "problib/pdfs/Gaussian.h" 00038 #include "problib/pdfs/Uniform.h" 00039 00040 using namespace pbl; 00041 00042 Gaussian::Gaussian(int dim) : PDF(dim, PDF::GAUSSIAN), ptr_(0) { 00043 } 00044 00045 Gaussian::Gaussian(const arma::vec& mu, const arma::mat& cov) : PDF(mu.n_elem, PDF::GAUSSIAN), ptr_(new GaussianStruct(mu, cov)) { 00046 } 00047 00048 Gaussian::Gaussian(const Gaussian& orig) : PDF(orig.ptr_->mu_.n_elem, PDF::GAUSSIAN), ptr_(orig.ptr_) { 00049 if (ptr_) { 00050 ++ptr_->n_ptrs_; 00051 } 00052 } 00053 00054 Gaussian::~Gaussian() { 00055 if (ptr_) { 00056 --ptr_->n_ptrs_; 00057 00058 if (ptr_->n_ptrs_ == 0) { 00059 delete ptr_; 00060 } 00061 } 00062 } 00063 00064 Gaussian& Gaussian::operator=(const Gaussian& other) { 00065 if (this != &other) { 00066 if (ptr_) { 00067 --ptr_->n_ptrs_; 00068 if (ptr_->n_ptrs_ == 0) { 00069 delete ptr_; 00070 } 00071 } 00072 ptr_ = other.ptr_; 00073 ++ptr_->n_ptrs_; 00074 00075 dimensions_ = other.dimensions_; 00076 } 00077 return *this; 00078 } 00079 00080 Gaussian* Gaussian::clone() const { 00081 return new Gaussian(*this); 00082 } 00083 00084 void Gaussian::cloneStruct() { 00085 if (ptr_->n_ptrs_ > 1) { 00086 --ptr_->n_ptrs_; 00087 ptr_ = new GaussianStruct(*ptr_); 00088 } 00089 } 00090 00091 double Gaussian::getLikelihood(const PDF& pdf) const { 00092 CHECK_INITIALIZED 00093 00094 if (pdf.type() == PDF::GAUSSIAN) { 00095 const Gaussian* G = static_cast<const pbl::Gaussian*>(&pdf); 00096 return getDensity(*G); 00097 } else if (pdf.type() == PDF::UNIFORM) { 00098 const Uniform* U = static_cast<const pbl::Uniform*>(&pdf); 00099 return U->getLikelihood(*this); 00100 } 00101 00102 assert_msg(false, "Gaussian: Likelihood can only be calculated with another Gaussian or Uniform pdf."); 00103 return 0; 00104 } 00105 00106 double Gaussian::getDensity(const arma::vec& v, double max_mah_dist) const { 00107 CHECK_INITIALIZED 00108 return getDensity(v, ptr_->mu_, ptr_->cov_, max_mah_dist); 00109 } 00110 00111 double Gaussian::getDensity(const Gaussian& G, double max_mah_dist) const { 00112 CHECK_INITIALIZED 00113 arma::mat S = G.getCovariance() + ptr_->cov_; 00114 return getDensity(ptr_->mu_, G.getMean(), S); 00115 } 00116 00117 double Gaussian::getMaxDensity() const { 00118 CHECK_INITIALIZED 00119 return getDensity(ptr_->mu_, ptr_->mu_, ptr_->cov_); 00120 } 00121 00122 bool Gaussian::getExpectedValue(arma::vec& v) const { 00123 CHECK_INITIALIZED 00124 v = ptr_->mu_; 00125 return true; 00126 } 00127 00128 double Gaussian::getDensity(const arma::vec& v1, const arma::vec& v2, const arma::mat& S, double max_mah_dist) const { 00129 // check dimensions 00130 assert(v1.n_elem == v2.n_elem && v1.n_elem == S.n_rows); 00131 00132 double det = arma::det(S); 00133 00134 // covariance should have non-zero determinant 00135 assert(det != 0); 00136 00137 // calculate difference between v1 and v2 00138 arma::vec diff = v2 - v1; 00139 00140 // calculate squared mahalanobis distance 00141 double mahalanobis_dist_sq = arma::dot(arma::inv(S) * diff, diff); 00142 00143 // mahalanobis distance should always be 0 or positive 00144 assert(mahalanobis_dist_sq >= 0); 00145 00146 // threshold to 0 if maximum mahalanobis distance is exceeded 00147 if (max_mah_dist > 0 && mahalanobis_dist_sq > (max_mah_dist * max_mah_dist)) { 00148 return 0; 00149 } 00150 00151 double pi2_pow = 1; 00152 for(unsigned int d = 0; d < S.n_rows; ++d) { 00153 pi2_pow *= 2 * M_PI; 00154 } 00155 00156 // calculate density 00157 double pos_sqrt_pow = 1 / sqrt(pi2_pow * det); 00158 return exp(-0.5 * mahalanobis_dist_sq) * pos_sqrt_pow; 00159 } 00160 00161 void Gaussian::setMean(const arma::vec& mu) { 00162 if (ptr_) { 00163 cloneStruct(); 00164 } else { 00165 ptr_ = new GaussianStruct(mu, arma::zeros(mu.n_elem, mu.n_elem)); 00166 } 00167 00168 ptr_->mu_ = mu; 00169 } 00170 00171 void Gaussian::setCovariance(const arma::mat& cov) { 00172 if (ptr_) { 00173 cloneStruct(); 00174 } else { 00175 ptr_ = new GaussianStruct(arma::zeros(cov.n_cols), cov); 00176 } 00177 00178 ptr_->cov_ = cov; 00179 } 00180 00181 const arma::vec& Gaussian::getMean() const { 00182 CHECK_INITIALIZED 00183 return ptr_->mu_; 00184 } 00185 00186 const arma::mat& Gaussian::getCovariance() const { 00187 CHECK_INITIALIZED 00188 return ptr_->cov_; 00189 } 00190 00191 std::string Gaussian::toString(const std::string& indent) const { 00192 if (!ptr_) { 00193 return "N(-)"; 00194 } 00195 00196 std::stringstream s; 00197 00198 s << "N( ["; 00199 for(int i = 0; i < dimensions_; ++i) { 00200 s << " " << ptr_->mu_(i); 00201 } 00202 00203 s << "], ["; 00204 for(int i = 0; i < dimensions_; ++i) { 00205 for(int j = 0; j < dimensions_; ++j) { 00206 s << " " << ptr_->cov_(i, j); 00207 } 00208 s << ";"; 00209 } 00210 s << "] )"; 00211 00212 return s.str(); 00213 }