conversions.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/conversions.h"
00038 
00039 namespace pbl {
00040 
00041 void PDFtoMsg(const PDF& pdf, problib::PDF& msg) {
00042         msg.dimensions = pdf.dimensions();
00043         serialize(pdf, msg);
00044 
00045         if (pdf.type() == PDF::DISCRETE) {
00046                 msg.type = problib::PDF::DISCRETE;
00047         } else {
00048                 msg.type = msg.data[0];
00049         }
00050 }
00051 
00052 problib::PDF PDFtoMsg(const PDF& pdf) {
00053     problib::PDF msg;
00054     PDFtoMsg(pdf, msg);
00055     return msg;
00056 }
00057 
00058 PDF* msgToPDF(const problib::PDF& msg) {
00059         int i_data = 1;
00060         return deserialize(msg, msg.type, i_data);
00061 }
00062 
00063 Gaussian* msgToGaussian(const problib::PDF& msg) {
00064         int i_data = 1;
00065         if (msg.type == problib::PDF::GAUSSIAN) {
00066                 return deserialize_gaussian(msg, i_data);
00067         }
00068         return 0;
00069 }
00070 
00071 Mixture* msgToMixture(const problib::PDF& msg) {
00072         int i_data = 1;
00073         if (msg.type == problib::PDF::MIXTURE) {
00074                 return deserialize_mixture(msg, i_data);
00075         }
00076         return 0;
00077 }
00078 
00079 PMF* msgToPMF(const problib::PDF& msg) {
00080         if (msg.type == problib::PDF::DISCRETE) {
00081                 return deserialize_discrete(msg);
00082         }
00083         return 0;
00084 }
00085 
00086 const Mixture* PDFtoMixture(const PDF& pdf) {
00087         if (pdf.type() != PDF::MIXTURE) {
00088                 return 0;
00089         }
00090         return static_cast<const Mixture*>(&pdf);
00091 }
00092 
00093 const Gaussian* PDFtoGaussian(const PDF& pdf) {
00094         if (pdf.type() != PDF::GAUSSIAN) {
00095                 return 0;
00096         }
00097         const Gaussian* G = static_cast<const Gaussian*>(&pdf);
00098         return G;
00099 }
00100 
00101 const Uniform* PDFtoUniform(const PDF& pdf) {
00102         if (pdf.type() != PDF::UNIFORM) {
00103                 return 0;
00104         }
00105         const Uniform* U = static_cast<const Uniform*>(&pdf);
00106         return U;
00107 }
00108 
00109 const PMF* PDFtoPMF(const PDF& pdf) {
00110         if (pdf.type() != PDF::DISCRETE) {
00111                 return 0;
00112         }
00113         return static_cast<const PMF*>(&pdf);
00114 }
00115 
00116 const Hybrid* PDFtoHybrid(const PDF& pdf) {
00117     if (pdf.type() != PDF::HYBRID) {
00118         return 0;
00119     }
00120     return static_cast<const Hybrid*>(&pdf);
00121 }
00122 
00123 std::string typeToName(PDF::PDFType type) {
00124     if (type == PDF::GAUSSIAN) {
00125         return "gaussian";
00126     } else if (type == PDF::MIXTURE) {
00127         return "mixture";
00128     } else if (type == PDF::UNIFORM) {
00129         return "uniform";
00130     } else if (type == PDF::DISCRETE) {
00131         return "discrete";
00132     } else if (type == PDF::HYBRID) {
00133         return "hybrid";
00134     }
00135     return "unknown";
00136 }
00137 
00138 /* * * * * * * SERIALIZATION AND DESERIALIZATION * * * * * * */
00139 
00140 void serialize(const PDF& pdf, problib::PDF& msg) {
00141         if (pdf.type() == PDF::GAUSSIAN) {
00142                 const Gaussian* gauss = static_cast<const Gaussian*>(&pdf);
00143                 serialize_gaussian(*gauss, msg);
00144         } else if (pdf.type() == PDF::MIXTURE) {
00145                 const Mixture* mix = static_cast<const Mixture*>(&pdf);
00146                 serialize_mixture(*mix, msg);
00147         } else if (pdf.type() == PDF::UNIFORM) {
00148                 const Uniform* uniform = static_cast<const Uniform*>(&pdf);
00149                 serialize_uniform(*uniform, msg);
00150         } else if (pdf.type() == PDF::DISCRETE) {
00151                 const PMF* pmf = static_cast<const PMF*>(&pdf);
00152                 serialize_discrete(*pmf, msg);
00153     } else if (pdf.type() == PDF::HYBRID) {
00154         const Hybrid* hybrid = static_cast<const Hybrid*>(&pdf);
00155         serialize_hybrid(*hybrid, msg);
00156     }
00157 }
00158 
00159 PDF* deserialize(const problib::PDF& msg, int type, int& i_data) {
00160         if (type == problib::PDF::MIXTURE) {
00161                 return deserialize_mixture(msg, i_data);
00162         } else if (type == problib::PDF::GAUSSIAN) {
00163                 return deserialize_gaussian(msg, i_data);
00164         } else if (type == problib::PDF::UNIFORM) {
00165                 return deserialize_uniform(msg, i_data);
00166         } else if (type == problib::PDF::DISCRETE) {
00167                 return deserialize_discrete(msg);
00168         } else if (type == problib::PDF::EXACT) {
00169                 return deserialize_exact(msg);
00170     } else      if (type == problib::PDF::HYBRID) {
00171         return deserialize_hybrid(msg, i_data);
00172     }
00173         return 0;
00174 }
00175 
00176 void serialize_gaussian(const Gaussian& gauss, problib::PDF& msg) {
00177         int dimensions = gauss.dimensions();
00178         int new_data_size = dimensions + ((dimensions + 1) * dimensions / 2) + 1;
00179 
00180         msg.data.reserve(msg.data.size() + new_data_size);
00181 
00182         msg.type = problib::PDF::GAUSSIAN;
00183         msg.data.push_back(msg.type);
00184 
00185         const arma::vec& mu = gauss.getMean();
00186         for(int i = 0; i < dimensions; ++i) {
00187                 msg.data.push_back(mu(i));
00188         }
00189 
00190         const arma::mat& cov = gauss.getCovariance();
00191         for(int i = 0; i < dimensions; ++i) {
00192                 for(int j = i; j < dimensions; ++j) {
00193                         msg.data.push_back(cov(i, j));
00194                 }
00195         }
00196 }
00197 
00198 Gaussian* deserialize_gaussian(const problib::PDF& msg, int& i_data) {
00199         arma::vec mu(msg.dimensions);
00200         for(unsigned int i = 0; i < msg.dimensions; ++i) {
00201                 mu(i) = msg.data[i_data++];
00202         }
00203 
00204         arma::mat cov(msg.dimensions, msg.dimensions);
00205         for(unsigned int i = 0; i < msg.dimensions; ++i) {
00206                 for(unsigned int j = i; j < msg.dimensions; ++j) {
00207                         cov(i, j) = msg.data[i_data];
00208                         cov(j, i) = msg.data[i_data];
00209                         ++i_data;
00210                 }
00211         }
00212 
00213         return new Gaussian(mu, cov);
00214 }
00215 
00216 void serialize_mixture(const Mixture& mix, problib::PDF& msg) {
00217         // add type of pdf (mixture)
00218         msg.data.push_back(problib::PDF::MIXTURE);
00219 
00220         // add number of mixture components
00221         msg.data.push_back(mix.components());
00222 
00223         // add weights and components themselves
00224         for(int i = 0; i < mix.components(); ++i) {
00225                 msg.data.push_back(mix.getWeight(i));
00226                 const PDF& pdf = mix.getComponent(i);
00227                 serialize(pdf, msg);
00228         }
00229 }
00230 
00231 Mixture* deserialize_mixture(const problib::PDF& msg, int& i_data) {
00232         Mixture* mix = new Mixture();
00233 
00234         int num_components = (int)msg.data[i_data++];
00235 
00236         for(int c = 0; c < num_components; ++c) {
00237                 double w = msg.data[i_data++];
00238                 int type = (int)msg.data[i_data++];
00239 
00240                 PDF* component = deserialize(msg, type, i_data);
00241                 mix->addComponent(*component, w);
00242                 delete component;
00243         }
00244 
00245         mix->normalizeWeights();
00246 
00247         return mix;
00248 }
00249 
00250 void serialize_uniform(const Uniform& uniform, problib::PDF& msg) {
00251         msg.data.push_back(problib::PDF::UNIFORM);
00252         msg.data.push_back(uniform.getMaxDensity());
00253 }
00254 
00255 Uniform* deserialize_uniform(const problib::PDF& msg, int& i_data) {
00256         Uniform* uniform = new Uniform(msg.dimensions);
00257         uniform->setDensity(msg.data[i_data++]);
00258         return uniform;
00259 }
00260 
00261 void serialize_discrete(const PMF& pmf, problib::PDF& msg) {
00262         pmf.getValues(msg.values);
00263         pmf.getProbabilities(msg.probabilities);
00264         msg.domain_size = pmf.getDomainSize();
00265 }
00266 
00267 PMF* deserialize_discrete(const problib::PDF& msg) {
00268         PMF* pmf = new PMF(msg.domain_size);
00269         std::vector<double>::const_iterator it_p = msg.probabilities.begin();
00270         for(std::vector<std::string>::const_iterator it_v = msg.values.begin(); it_v != msg.values.end(); ++it_v) {
00271                 pmf->setProbability(*it_v, *it_p);
00272                 ++it_p;
00273         }
00274         pmf->setDomainSize(msg.domain_size);
00275         return pmf;
00276 }
00277 
00278 void serialize_hybrid(const Hybrid& hybrid, problib::PDF& msg) {
00279     // add type of pdf (hybrid)
00280     msg.data.push_back(problib::PDF::HYBRID);
00281 
00282     // add number of hybrid components
00283     msg.data.push_back(hybrid.getPDFS().size());
00284 
00285     // add components themselves
00286     const std::vector<PDF*> pdfs = hybrid.getPDFS();
00287     for(std::vector<PDF*>::const_iterator it = pdfs.begin(); it != pdfs.end(); ++it) {
00288         const PDF& pdf = **it;
00289 
00290         if (pdf.type() == PDF::DISCRETE) {
00291             bool already_contains_pmf = msg.domain_size != 0 || !msg.values.empty();
00292             assert_msg(!already_contains_pmf, "Can currently only decode at most one discrete pdf in hybrid pdf message.");
00293             msg.data.push_back(problib::PDF::DISCRETE);
00294         }
00295 
00296         serialize(pdf, msg);
00297     }
00298 }
00299 
00300 Hybrid* deserialize_hybrid(const problib::PDF& msg, int& i_data) {
00301     Hybrid* hybrid = new Hybrid();
00302 
00303     int num_components = (int)msg.data[i_data++];
00304 
00305     for(int c = 0; c < num_components; ++c) {
00306         int type = (int)msg.data[i_data++];
00307 
00308         PDF* pdf = deserialize(msg, type, i_data);
00309         hybrid->addPDF(*pdf, -1);
00310         delete pdf;
00311     }
00312 
00313     return hybrid;
00314 }
00315 
00316 PDF* deserialize_exact(const problib::PDF& msg) {
00317         if (!msg.exact_value_vec.empty()) {
00318                 // vector value, so we ASSUME continuous
00319                 unsigned int dim = msg.exact_value_vec.size();
00320                 arma::vec mu(dim);
00321                 for(unsigned int i = 0; i < dim; ++i) {
00322                         mu(i) = msg.exact_value_vec[i];
00323                 }
00324                 arma::mat cov = arma::zeros(dim, dim);
00325                 return new Gaussian(mu, cov);
00326         } else if (msg.exact_value_str != "") {
00327                 // string value, so discrete
00328                 PMF* pmf = new PMF();
00329                 pmf->setProbability(msg.exact_value_str, 1.0);
00330                 return pmf;
00331         }
00332         // no exact value found
00333         return 0;
00334 }
00335 
00336 }


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