pf.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2016-2017, the mcl_3dl authors
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 are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef MCL_3DL_PF_H
31 #define MCL_3DL_PF_H
32 
33 #include <algorithm>
34 #include <cassert>
35 #include <cmath>
36 #include <functional>
37 #include <random>
38 #include <vector>
39 
41 
42 namespace mcl_3dl
43 {
44 namespace pf
45 {
46 template <typename FLT_TYPE = float>
48 {
49 public:
50  virtual FLT_TYPE& operator[](const size_t i) = 0;
51  virtual size_t size() const = 0;
52  virtual void normalize() = 0;
53  template <typename T>
54  T operator+(const T& a)
55  {
56  T in = a;
57  T ret;
58  for (size_t i = 0; i < size(); i++)
59  {
60  ret[i] = (*this)[i] + in[i];
61  }
62  return ret;
63  }
64  template <typename T>
65  FLT_TYPE covElement(
66  const T& e, const size_t& j, const size_t& k)
67  {
68  T exp = e;
69  return ((*this)[k] - exp[k]) * ((*this)[j] - exp[j]);
70  }
71 
72  template <typename T, typename RANDOM_ENGINE, typename NOISE_GEN>
73  static T generateNoise(RANDOM_ENGINE& engine, const NOISE_GEN& gen)
74  {
75  const auto org_noise = gen(engine);
76  T noise;
77  for (size_t i = 0; i < noise.size(); i++)
78  {
79  noise[i] = org_noise[i];
80  }
81  return noise;
82  }
83  virtual size_t covDimension() const
84  {
85  return size();
86  }
87 };
88 
89 template <typename T, typename FLT_TYPE = float>
90 class Particle
91 {
92 public:
94  {
95  probability_ = 0.0;
96  probability_bias_ = 0.0;
97  }
98  explicit Particle(FLT_TYPE prob)
99  {
100  accum_probability_ = prob;
101  }
103  FLT_TYPE probability_;
106  bool operator<(const Particle& p2) const
107  {
108  return this->accum_probability_ < p2.accum_probability_;
109  }
110 };
111 
112 template <typename T, typename FLT_TYPE = float>
114 {
115 protected:
116  T e_;
117  FLT_TYPE p_sum_;
118 
119 public:
121  : e_()
122  , p_sum_(0.0)
123  {
124  }
125 
126  void add(const T& s, const FLT_TYPE& prob)
127  {
128  p_sum_ += prob;
129 
130  T e1 = s;
131  for (size_t i = 0; i < e1.size(); i++)
132  {
133  e1[i] = e1[i] * prob;
134  }
135  e_ = e1 + e_;
136  }
137 
139  {
140  assert(p_sum_ > 0.0);
141 
142  T s = e_;
143 
144  for (size_t i = 0; i < s.size(); i++)
145  {
146  s[i] = s[i] / p_sum_;
147  }
148 
149  return s;
150  }
151 
153  {
154  return p_sum_;
155  }
156 };
157 
158 template <typename T, typename FLT_TYPE = float, typename MEAN = ParticleWeightedMean<T, FLT_TYPE>,
159  typename RANDOM_ENGINE = std::default_random_engine>
161 {
162 public:
163  // random_seed is used to generate same results in tests.
164  explicit ParticleFilter(const int num_particles, const unsigned int random_seed = std::random_device()())
165  : engine_(random_seed)
166  {
167  particles_.resize(num_particles);
168  }
169  void init(T mean, T sigma)
170  {
172  }
173  template <typename GEN>
174  void initUsingNoiseGenerator(const GEN& generator)
175  {
176  for (auto& p : particles_)
177  {
178  p.state_ = T::template generateNoise<T>(engine_, generator);
179  p.probability_ = 1.0 / particles_.size();
180  }
181  }
182  void resample(T sigma)
183  {
185  }
186  template <typename GEN>
187  void resampleUsingNoiseGenerator(const GEN& generator)
188  {
189  FLT_TYPE accum = 0;
190  for (auto& p : particles_)
191  {
192  accum += p.probability_;
193  p.accum_probability_ = accum;
194  }
195 
197  std::sort(particles_dup_.begin(), particles_dup_.end());
198  const FLT_TYPE pstep = accum / particles_.size();
199  const FLT_TYPE initial_p = std::uniform_real_distribution<FLT_TYPE>(0.0, pstep)(engine_);
200  auto it = particles_dup_.begin();
201  auto it_prev = particles_dup_.begin();
202  const FLT_TYPE prob = 1.0 / particles_.size();
203  for (size_t i = 0; i < particles_.size(); ++i)
204  {
205  auto& p = particles_[i];
206  const FLT_TYPE pscan = pstep * i + initial_p;
207  it = std::lower_bound(it, particles_dup_.end(), Particle<T, FLT_TYPE>(pscan));
208  p.probability_ = prob;
209  if (it == particles_dup_.end())
210  {
211  p.state_ = it_prev->state_;
212  continue;
213  }
214  else if (it == it_prev)
215  {
216  p.state_ = it->state_ + T::template generateNoise<T>(engine_, generator);
217  p.state_.normalize();
218  }
219  else
220  {
221  p.state_ = it->state_;
222  }
223  it_prev = it;
224  }
225  }
226  void noise(T sigma)
227  {
229  }
230  template <typename GEN>
231  void addNoiseUsingNoiseGenerator(const GEN& generator)
232  {
233  for (auto& p : particles_)
234  {
235  p.state_ = p.state_ + T::template generateNoise<T>(engine_, generator);
236  }
237  }
238  void predict(std::function<void(T&)> model)
239  {
240  for (auto& p : particles_)
241  {
242  model(p.state_);
243  }
244  }
245  void bias(std::function<void(const T&, float& p_bias)> prob)
246  {
247  for (auto& p : particles_)
248  {
249  prob(p.state_, p.probability_bias_);
250  }
251  }
252  void measure(std::function<FLT_TYPE(const T&)> likelihood)
253  {
254  auto particles_prev = particles_; // backup old
255  FLT_TYPE sum = 0;
256  for (auto& p : particles_)
257  {
258  p.probability_ *= likelihood(p.state_);
259  sum += p.probability_;
260  }
261  if (sum > 0.0)
262  {
263  entropy_ = 0;
264  for (auto& p : particles_)
265  {
266  p.probability_ /= sum;
267  if (p.probability_ > 0)
268  {
269  entropy_ += p.probability_ * std::log(p.probability_);
270  }
271  }
272  entropy_ *= -1;
273  }
274  else
275  {
276  particles_ = particles_prev;
277  // std::cerr << "No Particle alive, restoring." << std::endl;
278  }
279  }
280  T expectation(const FLT_TYPE pass_ratio = 1.0)
281  {
282  MEAN mean;
283 
284  if (pass_ratio < 1.0)
285  std::sort(particles_.rbegin(), particles_.rend());
286  for (auto& p : particles_)
287  {
288  mean.add(p.state_, p.probability_);
289  if (mean.getTotalProbability() > pass_ratio)
290  break;
291  }
292  return mean.getMean();
293  }
295  {
296  MEAN mean;
297 
298  for (auto& p : particles_)
299  {
300  mean.add(p.state_, p.probability_ * p.probability_bias_);
301  }
302  return mean.getMean();
303  }
304  std::vector<T> covariance(
305  const FLT_TYPE pass_ratio = 1.0,
306  const FLT_TYPE random_sample_ratio = 1.0)
307  {
308  T e = expectation(pass_ratio);
309  FLT_TYPE p_sum = 0;
310 
311  size_t p_num = 0;
312  for (auto& p : particles_)
313  {
314  p_num++;
315  p_sum += p.probability_;
316  if (p_sum > pass_ratio)
317  break;
318  }
319 
320  std::vector<size_t> indices(p_num);
321  std::iota(indices.begin(), indices.end(), 0);
322  if (random_sample_ratio < 1.0)
323  {
324  std::shuffle(indices.begin(), indices.end(), engine_);
325 
326  const size_t sample_num =
327  std::min(
328  p_num,
329  std::max(
330  size_t(0),
331  static_cast<size_t>(p_num * random_sample_ratio)));
332  indices.resize(sample_num);
333  }
334 
335  std::vector<T> cov;
336  cov.resize(ie_.covDimension());
337 
338  p_sum = 0.0;
339  for (size_t i : indices)
340  {
341  auto& p = particles_[i];
342  p_sum += p.probability_;
343  for (size_t j = 0; j < ie_.covDimension(); j++)
344  {
345  for (size_t k = j; k < ie_.covDimension(); k++)
346  {
347  cov[k][j] = cov[j][k] += p.state_.covElement(e, j, k) * p.probability_;
348  }
349  }
350  }
351  for (size_t j = 0; j < ie_.covDimension(); j++)
352  {
353  for (size_t k = 0; k < ie_.covDimension(); k++)
354  {
355  cov[k][j] /= p_sum;
356  }
357  }
358 
359  return cov;
360  }
361  T max()
362  {
363  T* m = &particles_[0].state_;
364  FLT_TYPE max_probability = particles_[0].probability_;
365  for (auto& p : particles_)
366  {
367  if (max_probability < p.probability_)
368  {
369  max_probability = p.probability_;
370  m = &p.state_;
371  }
372  }
373  return *m;
374  }
376  {
377  T* m = &particles_[0].state_;
378  FLT_TYPE max_probability =
379  particles_[0].probability_ * particles_[0].probability_bias_;
380  for (auto& p : particles_)
381  {
382  const FLT_TYPE prob = p.probability_ * p.probability_bias_;
383  if (max_probability < prob)
384  {
385  max_probability = prob;
386  m = &p.state_;
387  }
388  }
389  return *m;
390  }
391  T getParticle(const size_t i) const
392  {
393  return particles_[i].state_;
394  }
395  size_t getParticleSize() const
396  {
397  return particles_.size();
398  }
399  void resizeParticle(const size_t num)
400  {
401  FLT_TYPE accum = 0;
402  for (auto& p : particles_)
403  {
404  accum += p.probability_;
405  p.accum_probability_ = accum;
406  }
407 
409  std::sort(particles_dup_.begin(), particles_dup_.end());
410 
411  FLT_TYPE pstep = accum / num;
412  FLT_TYPE pscan = 0;
413  auto it = particles_dup_.begin();
414  auto it_prev = particles_dup_.begin();
415 
416  particles_.resize(num);
417 
418  FLT_TYPE prob = 1.0 / num;
419  for (auto& p : particles_)
420  {
421  pscan += pstep;
422  it = std::lower_bound(it, particles_dup_.end(),
423  Particle<T, FLT_TYPE>(pscan));
424  p.probability_ = prob;
425  if (it == particles_dup_.end())
426  {
427  p.state_ = it_prev->state_;
428  continue;
429  }
430  else
431  {
432  p.state_ = it->state_;
433  }
434  it_prev = it;
435  }
436  }
437  typename std::vector<Particle<T, FLT_TYPE>>::iterator appendParticle(const size_t num)
438  {
439  const size_t size_orig = particles_.size();
440  particles_.resize(size_orig + num);
441  return begin() + size_orig;
442  }
443  typename std::vector<Particle<T, FLT_TYPE>>::iterator begin()
444  {
445  return particles_.begin();
446  }
447  typename std::vector<Particle<T, FLT_TYPE>>::iterator end()
448  {
449  return particles_.end();
450  }
451  FLT_TYPE getEntropy() const
452  {
453  return entropy_;
454  }
455 
456 protected:
457  std::vector<Particle<T, FLT_TYPE>> particles_;
458  std::vector<Particle<T, FLT_TYPE>> particles_dup_;
459  RANDOM_ENGINE engine_;
460  T ie_;
461  FLT_TYPE entropy_;
462 };
463 
464 } // namespace pf
465 } // namespace mcl_3dl
466 
467 #endif // MCL_3DL_PF_H
mcl_3dl::pf::ParticleBase::size
virtual size_t size() const =0
mcl_3dl::pf::ParticleWeightedMean::getMean
T getMean()
Definition: pf.h:138
mcl_3dl::pf::ParticleWeightedMean::e_
T e_
Definition: pf.h:116
mcl_3dl::pf::ParticleFilter::getParticle
T getParticle(const size_t i) const
Definition: pf.h:391
mcl_3dl::pf::ParticleBase::covDimension
virtual size_t covDimension() const
Definition: pf.h:83
mcl_3dl::pf::ParticleFilter::getParticleSize
size_t getParticleSize() const
Definition: pf.h:395
mcl_3dl::pf::ParticleFilter::init
void init(T mean, T sigma)
Definition: pf.h:169
s
XmlRpcServer s
mcl_3dl::pf::ParticleWeightedMean::p_sum_
FLT_TYPE p_sum_
Definition: pf.h:117
mcl_3dl::pf::ParticleBase::operator[]
virtual FLT_TYPE & operator[](const size_t i)=0
mcl_3dl::pf::ParticleFilter
Definition: pf.h:160
mcl_3dl::pf::ParticleFilter::particles_
std::vector< Particle< T, FLT_TYPE > > particles_
Definition: pf.h:457
mcl_3dl::pf::ParticleFilter::resizeParticle
void resizeParticle(const size_t num)
Definition: pf.h:399
mcl_3dl::pf::Particle::probability_
FLT_TYPE probability_
Definition: pf.h:103
mcl_3dl::pf::ParticleFilter::ParticleFilter
ParticleFilter(const int num_particles, const unsigned int random_seed=std::random_device()())
Definition: pf.h:164
mcl_3dl::pf::ParticleFilter::predict
void predict(std::function< void(T &)> model)
Definition: pf.h:238
mcl_3dl::pf::Particle::probability_bias_
FLT_TYPE probability_bias_
Definition: pf.h:104
mcl_3dl::pf::ParticleWeightedMean::ParticleWeightedMean
ParticleWeightedMean()
Definition: pf.h:120
mcl_3dl::pf::ParticleFilter::appendParticle
std::vector< Particle< T, FLT_TYPE > >::iterator appendParticle(const size_t num)
Definition: pf.h:437
mcl_3dl::pf::ParticleFilter::resampleUsingNoiseGenerator
void resampleUsingNoiseGenerator(const GEN &generator)
Definition: pf.h:187
mcl_3dl::pf::ParticleBase::generateNoise
static T generateNoise(RANDOM_ENGINE &engine, const NOISE_GEN &gen)
Definition: pf.h:73
mcl_3dl::pf::ParticleFilter::addNoiseUsingNoiseGenerator
void addNoiseUsingNoiseGenerator(const GEN &generator)
Definition: pf.h:231
diagonal_noise_generator.h
mcl_3dl::pf::Particle::accum_probability_
FLT_TYPE accum_probability_
Definition: pf.h:105
mcl_3dl::pf::ParticleBase::operator+
T operator+(const T &a)
Definition: pf.h:54
mcl_3dl::pf::ParticleFilter::begin
std::vector< Particle< T, FLT_TYPE > >::iterator begin()
Definition: pf.h:443
mcl_3dl::pf::ParticleWeightedMean::add
void add(const T &s, const FLT_TYPE &prob)
Definition: pf.h:126
mcl_3dl::pf::ParticleFilter::resample
void resample(T sigma)
Definition: pf.h:182
mcl_3dl::pf::ParticleFilter::ie_
T ie_
Definition: pf.h:460
mcl_3dl::pf::Particle::operator<
bool operator<(const Particle &p2) const
Definition: pf.h:106
mcl_3dl::pf::ParticleFilter::measure
void measure(std::function< FLT_TYPE(const T &)> likelihood)
Definition: pf.h:252
mcl_3dl::pf::ParticleWeightedMean
Definition: pf.h:113
mcl_3dl::pf::ParticleFilter::initUsingNoiseGenerator
void initUsingNoiseGenerator(const GEN &generator)
Definition: pf.h:174
mcl_3dl::pf::ParticleFilter::maxBiased
T maxBiased()
Definition: pf.h:375
mcl_3dl
Definition: chunked_kdtree.h:43
mcl_3dl::pf::ParticleFilter::particles_dup_
std::vector< Particle< T, FLT_TYPE > > particles_dup_
Definition: pf.h:458
mcl_3dl::pf::ParticleFilter::max
T max()
Definition: pf.h:361
mcl_3dl::pf::ParticleFilter::end
std::vector< Particle< T, FLT_TYPE > >::iterator end()
Definition: pf.h:447
mcl_3dl::pf::ParticleBase
Definition: pf.h:47
mcl_3dl::pf::ParticleFilter::bias
void bias(std::function< void(const T &, float &p_bias)> prob)
Definition: pf.h:245
mcl_3dl::pf::ParticleBase::normalize
virtual void normalize()=0
mcl_3dl::pf::Particle::Particle
Particle(FLT_TYPE prob)
Definition: pf.h:98
mcl_3dl::pf::Particle
Definition: pf.h:90
mcl_3dl::DiagonalNoiseGenerator
Definition: diagonal_noise_generator.h:41
mcl_3dl::pf::ParticleFilter::engine_
RANDOM_ENGINE engine_
Definition: pf.h:459
mcl_3dl::pf::ParticleBase::covElement
FLT_TYPE covElement(const T &e, const size_t &j, const size_t &k)
Definition: pf.h:65
mcl_3dl::pf::ParticleFilter::expectationBiased
T expectationBiased()
Definition: pf.h:294
mcl_3dl::pf::ParticleWeightedMean::getTotalProbability
FLT_TYPE getTotalProbability()
Definition: pf.h:152
mcl_3dl::pf::Particle::state_
T state_
Definition: pf.h:102
mcl_3dl::pf::ParticleFilter::expectation
T expectation(const FLT_TYPE pass_ratio=1.0)
Definition: pf.h:280
mcl_3dl::pf::ParticleFilter::getEntropy
FLT_TYPE getEntropy() const
Definition: pf.h:451
mcl_3dl::pf::ParticleFilter::entropy_
FLT_TYPE entropy_
Definition: pf.h:461
mcl_3dl::pf::Particle::Particle
Particle()
Definition: pf.h:93
mcl_3dl::pf::ParticleFilter::noise
void noise(T sigma)
Definition: pf.h:226
mcl_3dl::pf::ParticleFilter::covariance
std::vector< T > covariance(const FLT_TYPE pass_ratio=1.0, const FLT_TYPE random_sample_ratio=1.0)
Definition: pf.h:304


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Oct 17 2024 02:18:04