conversions.cpp
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 #include "problib/conversions.h"
38 
39 namespace pbl {
40 
41 void PDFtoMsg(const PDF& pdf, problib::PDF& msg) {
42  msg.dimensions = pdf.dimensions();
43  serialize(pdf, msg);
44 
45  if (pdf.type() == PDF::DISCRETE) {
46  msg.type = problib::PDF::DISCRETE;
47  } else {
48  msg.type = msg.data[0];
49  }
50 }
51 
52 problib::PDF PDFtoMsg(const PDF& pdf) {
53  problib::PDF msg;
54  PDFtoMsg(pdf, msg);
55  return msg;
56 }
57 
58 PDF* msgToPDF(const problib::PDF& msg) {
59  int i_data = 1;
60  return deserialize(msg, msg.type, i_data);
61 }
62 
63 Gaussian* msgToGaussian(const problib::PDF& msg) {
64  int i_data = 1;
65  if (msg.type == problib::PDF::GAUSSIAN) {
66  return deserialize_gaussian(msg, i_data);
67  }
68  return 0;
69 }
70 
71 Mixture* msgToMixture(const problib::PDF& msg) {
72  int i_data = 1;
73  if (msg.type == problib::PDF::MIXTURE) {
74  return deserialize_mixture(msg, i_data);
75  }
76  return 0;
77 }
78 
79 PMF* msgToPMF(const problib::PDF& msg) {
80  if (msg.type == problib::PDF::DISCRETE) {
81  return deserialize_discrete(msg);
82  }
83  return 0;
84 }
85 
86 const Mixture* PDFtoMixture(const PDF& pdf) {
87  if (pdf.type() != PDF::MIXTURE) {
88  return 0;
89  }
90  return static_cast<const Mixture*>(&pdf);
91 }
92 
93 const Gaussian* PDFtoGaussian(const PDF& pdf) {
94  if (pdf.type() != PDF::GAUSSIAN) {
95  return 0;
96  }
97  const Gaussian* G = static_cast<const Gaussian*>(&pdf);
98  return G;
99 }
100 
101 const Uniform* PDFtoUniform(const PDF& pdf) {
102  if (pdf.type() != PDF::UNIFORM) {
103  return 0;
104  }
105  const Uniform* U = static_cast<const Uniform*>(&pdf);
106  return U;
107 }
108 
109 const PMF* PDFtoPMF(const PDF& pdf) {
110  if (pdf.type() != PDF::DISCRETE) {
111  return 0;
112  }
113  return static_cast<const PMF*>(&pdf);
114 }
115 
116 const Hybrid* PDFtoHybrid(const PDF& pdf) {
117  if (pdf.type() != PDF::HYBRID) {
118  return 0;
119  }
120  return static_cast<const Hybrid*>(&pdf);
121 }
122 
123 std::string typeToName(PDF::PDFType type) {
124  if (type == PDF::GAUSSIAN) {
125  return "gaussian";
126  } else if (type == PDF::MIXTURE) {
127  return "mixture";
128  } else if (type == PDF::UNIFORM) {
129  return "uniform";
130  } else if (type == PDF::DISCRETE) {
131  return "discrete";
132  } else if (type == PDF::HYBRID) {
133  return "hybrid";
134  }
135  return "unknown";
136 }
137 
138 /* * * * * * * SERIALIZATION AND DESERIALIZATION * * * * * * */
139 
140 void serialize(const PDF& pdf, problib::PDF& msg) {
141  if (pdf.type() == PDF::GAUSSIAN) {
142  const Gaussian* gauss = static_cast<const Gaussian*>(&pdf);
143  serialize_gaussian(*gauss, msg);
144  } else if (pdf.type() == PDF::MIXTURE) {
145  const Mixture* mix = static_cast<const Mixture*>(&pdf);
146  serialize_mixture(*mix, msg);
147  } else if (pdf.type() == PDF::UNIFORM) {
148  const Uniform* uniform = static_cast<const Uniform*>(&pdf);
149  serialize_uniform(*uniform, msg);
150  } else if (pdf.type() == PDF::DISCRETE) {
151  const PMF* pmf = static_cast<const PMF*>(&pdf);
152  serialize_discrete(*pmf, msg);
153  } else if (pdf.type() == PDF::HYBRID) {
154  const Hybrid* hybrid = static_cast<const Hybrid*>(&pdf);
155  serialize_hybrid(*hybrid, msg);
156  }
157 }
158 
159 PDF* deserialize(const problib::PDF& msg, int type, int& i_data) {
160  if (type == problib::PDF::MIXTURE) {
161  return deserialize_mixture(msg, i_data);
162  } else if (type == problib::PDF::GAUSSIAN) {
163  return deserialize_gaussian(msg, i_data);
164  } else if (type == problib::PDF::UNIFORM) {
165  return deserialize_uniform(msg, i_data);
166  } else if (type == problib::PDF::DISCRETE) {
167  return deserialize_discrete(msg);
168  } else if (type == problib::PDF::EXACT) {
169  return deserialize_exact(msg);
170  } else if (type == problib::PDF::HYBRID) {
171  return deserialize_hybrid(msg, i_data);
172  }
173  return 0;
174 }
175 
176 void serialize_gaussian(const Gaussian& gauss, problib::PDF& msg) {
177  int dimensions = gauss.dimensions();
178  int new_data_size = dimensions + ((dimensions + 1) * dimensions / 2) + 1;
179 
180  msg.data.reserve(msg.data.size() + new_data_size);
181 
182  msg.type = problib::PDF::GAUSSIAN;
183  msg.data.push_back(msg.type);
184 
185  const arma::vec& mu = gauss.getMean();
186  for(int i = 0; i < dimensions; ++i) {
187  msg.data.push_back(mu(i));
188  }
189 
190  const arma::mat& cov = gauss.getCovariance();
191  for(int i = 0; i < dimensions; ++i) {
192  for(int j = i; j < dimensions; ++j) {
193  msg.data.push_back(cov(i, j));
194  }
195  }
196 }
197 
198 Gaussian* deserialize_gaussian(const problib::PDF& msg, int& i_data) {
199  arma::vec mu(msg.dimensions);
200  for(unsigned int i = 0; i < msg.dimensions; ++i) {
201  mu(i) = msg.data[i_data++];
202  }
203 
204  arma::mat cov(msg.dimensions, msg.dimensions);
205  for(unsigned int i = 0; i < msg.dimensions; ++i) {
206  for(unsigned int j = i; j < msg.dimensions; ++j) {
207  cov(i, j) = msg.data[i_data];
208  cov(j, i) = msg.data[i_data];
209  ++i_data;
210  }
211  }
212 
213  return new Gaussian(mu, cov);
214 }
215 
216 void serialize_mixture(const Mixture& mix, problib::PDF& msg) {
217  // add type of pdf (mixture)
218  msg.data.push_back(problib::PDF::MIXTURE);
219 
220  // add number of mixture components
221  msg.data.push_back(mix.components());
222 
223  // add weights and components themselves
224  for(int i = 0; i < mix.components(); ++i) {
225  msg.data.push_back(mix.getWeight(i));
226  const PDF& pdf = mix.getComponent(i);
227  serialize(pdf, msg);
228  }
229 }
230 
231 Mixture* deserialize_mixture(const problib::PDF& msg, int& i_data) {
232  Mixture* mix = new Mixture();
233 
234  int num_components = (int)msg.data[i_data++];
235 
236  for(int c = 0; c < num_components; ++c) {
237  double w = msg.data[i_data++];
238  int type = (int)msg.data[i_data++];
239 
240  PDF* component = deserialize(msg, type, i_data);
241  mix->addComponent(*component, w);
242  delete component;
243  }
244 
245  mix->normalizeWeights();
246 
247  return mix;
248 }
249 
250 void serialize_uniform(const Uniform& uniform, problib::PDF& msg) {
251  msg.data.push_back(problib::PDF::UNIFORM);
252  msg.data.push_back(uniform.getMaxDensity());
253 }
254 
255 Uniform* deserialize_uniform(const problib::PDF& msg, int& i_data) {
256  Uniform* uniform = new Uniform(msg.dimensions);
257  uniform->setDensity(msg.data[i_data++]);
258  return uniform;
259 }
260 
261 void serialize_discrete(const PMF& pmf, problib::PDF& msg) {
262  pmf.getValues(msg.values);
263  pmf.getProbabilities(msg.probabilities);
264  msg.domain_size = pmf.getDomainSize();
265 }
266 
267 PMF* deserialize_discrete(const problib::PDF& msg) {
268  PMF* pmf = new PMF(msg.domain_size);
269  std::vector<double>::const_iterator it_p = msg.probabilities.begin();
270  for(std::vector<std::string>::const_iterator it_v = msg.values.begin(); it_v != msg.values.end(); ++it_v) {
271  pmf->setProbability(*it_v, *it_p);
272  ++it_p;
273  }
274  pmf->setDomainSize(msg.domain_size);
275  return pmf;
276 }
277 
278 void serialize_hybrid(const Hybrid& hybrid, problib::PDF& msg) {
279  // add type of pdf (hybrid)
280  msg.data.push_back(problib::PDF::HYBRID);
281 
282  // add number of hybrid components
283  msg.data.push_back(hybrid.getPDFS().size());
284 
285  // add components themselves
286  const std::vector<PDF*> pdfs = hybrid.getPDFS();
287  for(std::vector<PDF*>::const_iterator it = pdfs.begin(); it != pdfs.end(); ++it) {
288  const PDF& pdf = **it;
289 
290  if (pdf.type() == PDF::DISCRETE) {
291  bool already_contains_pmf = msg.domain_size != 0 || !msg.values.empty();
292  assert_msg(!already_contains_pmf, "Can currently only decode at most one discrete pdf in hybrid pdf message.");
293  msg.data.push_back(problib::PDF::DISCRETE);
294  }
295 
296  serialize(pdf, msg);
297  }
298 }
299 
300 Hybrid* deserialize_hybrid(const problib::PDF& msg, int& i_data) {
301  Hybrid* hybrid = new Hybrid();
302 
303  int num_components = (int)msg.data[i_data++];
304 
305  for(int c = 0; c < num_components; ++c) {
306  int type = (int)msg.data[i_data++];
307 
308  PDF* pdf = deserialize(msg, type, i_data);
309  hybrid->addPDF(*pdf, -1);
310  delete pdf;
311  }
312 
313  return hybrid;
314 }
315 
316 PDF* deserialize_exact(const problib::PDF& msg) {
317  if (!msg.exact_value_vec.empty()) {
318  // vector value, so we ASSUME continuous
319  unsigned int dim = msg.exact_value_vec.size();
320  arma::vec mu(dim);
321  for(unsigned int i = 0; i < dim; ++i) {
322  mu(i) = msg.exact_value_vec[i];
323  }
324  arma::mat cov = arma::zeros(dim, dim);
325  return new Gaussian(mu, cov);
326  } else if (msg.exact_value_str != "") {
327  // string value, so discrete
328  PMF* pmf = new PMF();
329  pmf->setProbability(msg.exact_value_str, 1.0);
330  return pmf;
331  }
332  // no exact value found
333  return 0;
334 }
335 
336 }
PDF * msgToPDF(const problib::PDF &msg)
Converts a PDF ROS message to a PDF object.
Definition: conversions.cpp:58
int dimensions() const
Definition: PDF.cpp:52
Gaussian * msgToGaussian(const problib::PDF &msg)
Converts a PDF ROS message to a Gaussian object if the message represents a Gaussian.
Definition: conversions.cpp:63
This class represents the weighted sum of a finite set of probability density functions.
Definition: Mixture.h:54
PDFType type() const
Definition: PDF.cpp:56
void serialize_hybrid(const Hybrid &hybrid, problib::PDF &msg)
arma_hot const Col< eT > & zeros()
#define assert_msg(_Expression, _Msg)
Definition: globals.h:53
Gaussian * deserialize_gaussian(const problib::PDF &msg, int &i_data)
void normalizeWeights()
Normalizes the weights of all components.
Definition: Mixture.cpp:149
int components() const
Returns the number of components.
Definition: Mixture.cpp:116
This class represents a multi-variate Gaussian (Normal) distribution.
Definition: Gaussian.h:51
void addPDF(const PDF &pdf, double priority)
Definition: Hybrid.cpp:106
const PMF * PDFtoPMF(const PDF &pdf)
Casts a PDF object to a PMF if the PDF represents a PMF.
double getMaxDensity() const
Returns the maximum density of this distribution, which always equals 1 / volume. ...
Definition: Uniform.cpp:132
std::string typeToName(PDF::PDFType type)
const Uniform * PDFtoUniform(const PDF &pdf)
Casts a PDF object to a Uniform distribution if the PDF represents a Uniform distribution.
Mat< double > mat
void addComponent(const PDF &pdf, double w)
Adds a component pdf with given weight.
Definition: Mixture.cpp:120
const arma::mat & getCovariance() const
Returns the covariance matrix of the Gaussian.
Definition: Gaussian.cpp:186
PMF * deserialize_discrete(const problib::PDF &msg)
void serialize_mixture(const Mixture &mix, problib::PDF &msg)
void setDomainSize(int domain_size)
Sets the domain size of this discrete distribution.
Definition: PMF.cpp:247
void serialize(const PDF &gauss, problib::PDF &msg)
void setDensity(const double &density)
Sets the density of the uniform distribution.
Definition: Uniform.cpp:123
const PDF & getComponent(int i) const
Returns a reference to the i&#39;th component.
Definition: Mixture.cpp:139
void serialize_discrete(const PMF &pmf, problib::PDF &msg)
const_iterator(const field< oT > &in_M, const bool at_end=false)
void getValues(std::vector< std::string > &values) const
Returns a vector of values for which a probability is specified.
Definition: PMF.cpp:124
void serialize_uniform(const Uniform &uniform, problib::PDF &msg)
const arma::vec & getMean() const
Returns the mean of the Gaussian.
Definition: Gaussian.cpp:181
Hybrid * deserialize_hybrid(const problib::PDF &msg, int &i_data)
void serialize_gaussian(const Gaussian &gauss, problib::PDF &msg)
const std::vector< PDF * > & getPDFS() const
Definition: Hybrid.cpp:122
const Op< T1, op_cov > cov(const Base< typename T1::elem_type, T1 > &X, const uword norm_type=0)
int getDomainSize() const
Returns the domain size of this distribution.
Definition: PMF.cpp:252
void getProbabilities(std::vector< double > &probabilities) const
Returns all probabilities of the known values.
Definition: PMF.cpp:130
This class represents a hyper-cube shaped uniform distribution.
Definition: Uniform.h:51
Definition: PDF.h:47
PMF * msgToPMF(const problib::PDF &msg)
Converts a PDF ROS message to a PMF object if the message represents a PMF.
Definition: conversions.cpp:79
Uniform * deserialize_uniform(const problib::PDF &msg, int &i_data)
double getWeight(int i) const
Returns the weight of the i&#39;th component.
Definition: Mixture.cpp:144
PDF * deserialize_exact(const problib::PDF &msg)
Mixture * msgToMixture(const problib::PDF &msg)
Converts a PDF ROS message to a Mixture object if the message represents a Mixture.
Definition: conversions.cpp:71
const Mixture * PDFtoMixture(const PDF &pdf)
Casts a PDF object to a Mixture if the PDF represents a Mixture.
Definition: conversions.cpp:86
Mixture * deserialize_mixture(const problib::PDF &msg, int &i_data)
void setProbability(const std::string &value, double p)
Set the probability of a given value.
Definition: PMF.cpp:100
PDF * deserialize(const problib::PDF &msg, int type, int &i_data)
Col< double > vec
This class represents a discrete probability distribution (or probability mass function). Currently, this PMF can only take strings as values.
Definition: PMF.h:52
PDFType
Definition: PDF.h:51
const Gaussian * PDFtoGaussian(const PDF &pdf)
Casts a PDF object to a Gaussian if the PDF represents a Gaussian.
Definition: conversions.cpp:93
void PDFtoMsg(const PDF &pdf, problib::PDF &msg)
Converts a PDF object to a ROS message.
Definition: conversions.cpp:41
const Hybrid * PDFtoHybrid(const PDF &pdf)


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