Uniform.cpp
Go to the documentation of this file.
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/Uniform.h"
00038 #include "problib/conversions.h"
00039 
00040 using namespace pbl;
00041 
00042 Uniform::Uniform(int dim) : PDF(dim, PDF::UNIFORM), uniform_probability_(0), size_is_set_(false) {
00043 }
00044 
00045 Uniform::Uniform(int dim, double density) : PDF(dim, PDF::UNIFORM), uniform_probability_(density), size_is_set_(false) {
00046 }
00047 
00048 Uniform::Uniform(pbl::Vector mean, pbl::Vector size) : PDF(mean.n_elem, PDF::UNIFORM), mean_(mean), size_(size), size_is_set_(true) {
00049     calculateUniformDensity();
00050 }
00051 
00052 Uniform::Uniform(const Uniform& orig) : PDF(orig), mean_(orig.mean_), size_(orig.size_),
00053     uniform_probability_(orig.uniform_probability_), size_is_set_(orig.size_is_set_) {
00054 }
00055 
00056 Uniform::~Uniform() {
00057 }
00058 
00059 Uniform& Uniform::operator=(const Uniform& other) {
00060     if (this != &other)  {
00061         mean_ = other.mean_;
00062         size_ = other.size_;
00063         size_is_set_ = other.size_is_set_;
00064         uniform_probability_ = other.uniform_probability_;
00065         dimensions_ = other.dimensions_;
00066     }
00067     return *this;
00068 }
00069 
00070 Uniform* Uniform::clone() const {
00071         return new Uniform(*this);
00072 }
00073 
00074 double Uniform::getLikelihood(const PDF& pdf) const {
00075         //assert_msg(false, "Uniform PDF: getLikelihood(PDF) is currently not implemented");
00076 
00077     assert(dimensions() == pdf.dimensions());
00078 
00079     if (size_is_set_) {
00080 
00081         arma::vec my_min = mean_ - size_ / 2;
00082         arma::vec my_max = mean_ + size_ / 2;
00083 
00084         if (pdf.type() == PDF::UNIFORM) {
00085             const Uniform* U = PDFtoUniform(pdf);
00086 
00087             arma::vec other_min = U->mean_ - U->size_ / 2;
00088             arma::vec other_max = U->mean_ + U->size_ / 2;
00089 
00090             double overlapping_volume = 1;
00091             for(int i = 0; i < dimensions(); ++i) {
00092                 double diff = std::min(my_max(i), other_max(i)) - std::max(my_min(i), other_min(i));
00093                 if (diff <= 0) {
00094                     return 0;
00095                 }
00096                 overlapping_volume *= diff;
00097             }
00098 
00099             return overlapping_volume * uniform_probability_ * U->uniform_probability_;
00100         } else if (pdf.type() == PDF::HYBRID) {
00101             return pdf.getLikelihood(*this);
00102         } else {
00103             arma::vec other_mean;
00104             if (!pdf.getExpectedValue(other_mean)) {
00105                 std::cout << pdf.toString() << std::endl;
00106                 assert_msg(false, "Uniform likelihood calculation: cannot determine expected value of pdf.");
00107                 return 0;
00108             }
00109 
00110             for(int i = 0; i < dimensions(); ++i) {
00111                 if (other_mean(i) < my_min(i) || other_mean(i) > my_max(i)) {
00112                     return 0;
00113                 }
00114             }
00115 
00116             return uniform_probability_;
00117         }
00118     }
00119 
00120     return uniform_probability_;
00121 }
00122 
00123 void Uniform::setDensity(const double& density) {
00124         uniform_probability_ = density;
00125     size_is_set_ = false;
00126 }
00127 
00128 double Uniform::getDensity(const arma::vec& vec) const {
00129         return uniform_probability_;
00130 }
00131 
00132 double Uniform::getMaxDensity() const {
00133         return uniform_probability_;
00134 }
00135 
00136 void Uniform::setMean(const pbl::Vector mean) {
00137     mean_ = mean;
00138 }
00139 
00140 void Uniform::setSize(const pbl::Vector size) {
00141     size_ = size;
00142     calculateUniformDensity();
00143 }
00144 
00145 void Uniform::calculateUniformDensity() {
00146     double volume = 1;
00147     for(unsigned int i = 0; i < size_.n_elem; ++i) {
00148         volume *= size_(i);
00149     }
00150     uniform_probability_ = 1.0 / volume;
00151     size_is_set_ = true;
00152 }
00153 
00154 std::string Uniform::toString(const std::string& indent) const {
00155         std::stringstream s;
00156     s << "U(" << uniform_probability_;
00157 
00158     if (size_is_set_) {
00159         s << ", mean = " << mean_ << ", size = " << size_;
00160     }
00161 
00162     s << ")";
00163 
00164         return s.str();
00165 }


problib
Author(s): Sjoerd van den Dries
autogenerated on Tue Jan 7 2014 11:42:42