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 };
84 
85 template <typename T, typename FLT_TYPE = float>
86 class Particle
87 {
88 public:
90  {
91  probability_ = 0.0;
92  probability_bias_ = 0.0;
93  }
94  explicit Particle(FLT_TYPE prob)
95  {
96  accum_probability_ = prob;
97  }
98  T state_;
99  FLT_TYPE probability_;
102  bool operator<(const Particle& p2) const
103  {
104  return this->accum_probability_ < p2.accum_probability_;
105  }
106 };
107 
108 template <typename T, typename FLT_TYPE = float>
110 {
111 protected:
112  T e_;
113  FLT_TYPE p_sum_;
114 
115 public:
117  : e_()
118  , p_sum_(0.0)
119  {
120  }
121 
122  void add(const T& s, const FLT_TYPE& prob)
123  {
124  p_sum_ += prob;
125 
126  T e1 = s;
127  for (size_t i = 0; i < e1.size(); i++)
128  {
129  e1[i] = e1[i] * prob;
130  }
131  e_ = e1 + e_;
132  }
133 
135  {
136  assert(p_sum_ > 0.0);
137 
138  T s = e_;
139 
140  for (size_t i = 0; i < s.size(); i++)
141  {
142  s[i] = s[i] / p_sum_;
143  }
144 
145  return s;
146  }
147 
149  {
150  return p_sum_;
151  }
152 };
153 
154 template <typename T, typename FLT_TYPE = float, typename MEAN = ParticleWeightedMean<T, FLT_TYPE>,
155  typename RANDOM_ENGINE = std::default_random_engine>
157 {
158 public:
159  // random_seed is used to generate same results in tests.
160  explicit ParticleFilter(const int num_particles, const unsigned int random_seed = std::random_device()())
161  : engine_(random_seed)
162  {
163  particles_.resize(num_particles);
164  }
165  void init(T mean, T sigma)
166  {
167  return initUsingNoiseGenerator(DiagonalNoiseGenerator<FLT_TYPE>(mean, sigma));
168  }
169  template <typename GEN>
170  void initUsingNoiseGenerator(const GEN& generator)
171  {
172  for (auto& p : particles_)
173  {
174  p.state_ = T::template generateNoise<T>(engine_, generator);
175  p.probability_ = 1.0 / particles_.size();
176  }
177  }
178  void resample(T sigma)
179  {
180  resampleUsingNoiseGenerator(DiagonalNoiseGenerator<FLT_TYPE>(T(), sigma));
181  }
182  template <typename GEN>
183  void resampleUsingNoiseGenerator(const GEN& generator)
184  {
185  FLT_TYPE accum = 0;
186  for (auto& p : particles_)
187  {
188  accum += p.probability_;
189  p.accum_probability_ = accum;
190  }
191 
192  particles_dup_ = particles_;
193  std::sort(particles_dup_.begin(), particles_dup_.end());
194  const FLT_TYPE pstep = accum / particles_.size();
195  const FLT_TYPE initial_p = std::uniform_real_distribution<FLT_TYPE>(0.0, pstep)(engine_);
196  auto it = particles_dup_.begin();
197  auto it_prev = particles_dup_.begin();
198  const FLT_TYPE prob = 1.0 / particles_.size();
199  for (size_t i = 0; i < particles_.size(); ++i)
200  {
201  auto& p = particles_[i];
202  const FLT_TYPE pscan = pstep * i + initial_p;
203  it = std::lower_bound(it, particles_dup_.end(), Particle<T, FLT_TYPE>(pscan));
204  p.probability_ = prob;
205  if (it == particles_dup_.end())
206  {
207  p.state_ = it_prev->state_;
208  continue;
209  }
210  else if (it == it_prev)
211  {
212  p.state_ = it->state_ + T::template generateNoise<T>(engine_, generator);
213  p.state_.normalize();
214  }
215  else
216  {
217  p.state_ = it->state_;
218  }
219  it_prev = it;
220  }
221  }
222  void noise(T sigma)
223  {
224  addNoiseUsingNoiseGenerator(DiagonalNoiseGenerator<FLT_TYPE>(T(), sigma));
225  }
226  template <typename GEN>
227  void addNoiseUsingNoiseGenerator(const GEN& generator)
228  {
229  for (auto& p : particles_)
230  {
231  p.state_ = p.state_ + T::template generateNoise<T>(engine_, generator);
232  }
233  }
234  void predict(std::function<void(T&)> model)
235  {
236  for (auto& p : particles_)
237  {
238  model(p.state_);
239  }
240  }
241  void bias(std::function<void(const T&, float& p_bias)> prob)
242  {
243  for (auto& p : particles_)
244  {
245  prob(p.state_, p.probability_bias_);
246  }
247  }
248  void measure(std::function<FLT_TYPE(const T&)> likelihood)
249  {
250  auto particles_prev = particles_; // backup old
251  FLT_TYPE sum = 0;
252  for (auto& p : particles_)
253  {
254  p.probability_ *= likelihood(p.state_);
255  sum += p.probability_;
256  }
257  if (sum > 0.0)
258  {
259  for (auto& p : particles_)
260  {
261  p.probability_ /= sum;
262  }
263  }
264  else
265  {
266  particles_ = particles_prev;
267  // std::cerr << "No Particle alive, restoring." << std::endl;
268  }
269  }
270  T expectation(const FLT_TYPE pass_ratio = 1.0)
271  {
272  MEAN mean;
273 
274  if (pass_ratio < 1.0)
275  std::sort(particles_.rbegin(), particles_.rend());
276  for (auto& p : particles_)
277  {
278  mean.add(p.state_, p.probability_);
279  if (mean.getTotalProbability() > pass_ratio)
280  break;
281  }
282  return mean.getMean();
283  }
285  {
286  MEAN mean;
287 
288  for (auto& p : particles_)
289  {
290  mean.add(p.state_, p.probability_ * p.probability_bias_);
291  }
292  return mean.getMean();
293  }
294  std::vector<T> covariance(
295  const FLT_TYPE pass_ratio = 1.0,
296  const FLT_TYPE random_sample_ratio = 1.0)
297  {
298  T e = expectation(pass_ratio);
299  FLT_TYPE p_sum = 0;
300  std::vector<T> cov;
301  cov.resize(e.size());
302 
303  size_t p_num = 0;
304  for (auto& p : particles_)
305  {
306  p_num++;
307  p_sum += p.probability_;
308  if (p_sum > pass_ratio)
309  break;
310  }
311 
312  std::vector<size_t> indices(p_num);
313  std::iota(indices.begin(), indices.end(), 0);
314  if (random_sample_ratio < 1.0)
315  {
316  std::shuffle(indices.begin(), indices.end(), engine_);
317 
318  const size_t sample_num =
319  std::min(
320  p_num,
321  std::max(
322  size_t(0),
323  static_cast<size_t>(p_num * random_sample_ratio)));
324  indices.resize(sample_num);
325  }
326 
327  p_sum = 0.0;
328  for (size_t i : indices)
329  {
330  auto& p = particles_[i];
331  p_sum += p.probability_;
332  for (size_t j = 0; j < ie_.size(); j++)
333  {
334  for (size_t k = j; k < ie_.size(); k++)
335  {
336  cov[k][j] = cov[j][k] += p.state_.covElement(e, j, k) * p.probability_;
337  }
338  }
339  }
340  for (size_t j = 0; j < ie_.size(); j++)
341  {
342  for (size_t k = 0; k < ie_.size(); k++)
343  {
344  cov[k][j] /= p_sum;
345  }
346  }
347 
348  return cov;
349  }
350  T max()
351  {
352  T* m = &particles_[0].state_;
353  FLT_TYPE max_probability = particles_[0].probability_;
354  for (auto& p : particles_)
355  {
356  if (max_probability < p.probability_)
357  {
358  max_probability = p.probability_;
359  m = &p.state_;
360  }
361  }
362  return *m;
363  }
365  {
366  T* m = &particles_[0].state_;
367  FLT_TYPE max_probability =
368  particles_[0].probability_ * particles_[0].probability_bias_;
369  for (auto& p : particles_)
370  {
371  const FLT_TYPE prob = p.probability_ * p.probability_bias_;
372  if (max_probability < prob)
373  {
374  max_probability = prob;
375  m = &p.state_;
376  }
377  }
378  return *m;
379  }
380  T getParticle(const size_t i) const
381  {
382  return particles_[i].state_;
383  }
384  size_t getParticleSize() const
385  {
386  return particles_.size();
387  }
388  void resizeParticle(const size_t num)
389  {
390  FLT_TYPE accum = 0;
391  for (auto& p : particles_)
392  {
393  accum += p.probability_;
394  p.accum_probability_ = accum;
395  }
396 
397  particles_dup_ = particles_;
398  std::sort(particles_dup_.begin(), particles_dup_.end());
399 
400  FLT_TYPE pstep = accum / num;
401  FLT_TYPE pscan = 0;
402  auto it = particles_dup_.begin();
403  auto it_prev = particles_dup_.begin();
404 
405  particles_.resize(num);
406 
407  FLT_TYPE prob = 1.0 / num;
408  for (auto& p : particles_)
409  {
410  pscan += pstep;
411  it = std::lower_bound(it, particles_dup_.end(),
412  Particle<T, FLT_TYPE>(pscan));
413  p.probability_ = prob;
414  if (it == particles_dup_.end())
415  {
416  p.state_ = it_prev->state_;
417  continue;
418  }
419  else
420  {
421  p.state_ = it->state_;
422  }
423  it_prev = it;
424  }
425  }
426  typename std::vector<Particle<T, FLT_TYPE>>::iterator appendParticle(const size_t num)
427  {
428  const size_t size_orig = particles_.size();
429  particles_.resize(size_orig + num);
430  return begin() + size_orig;
431  }
432  typename std::vector<Particle<T, FLT_TYPE>>::iterator begin()
433  {
434  return particles_.begin();
435  }
436  typename std::vector<Particle<T, FLT_TYPE>>::iterator end()
437  {
438  return particles_.end();
439  }
440 
441 protected:
442  std::vector<Particle<T, FLT_TYPE>> particles_;
443  std::vector<Particle<T, FLT_TYPE>> particles_dup_;
444  RANDOM_ENGINE engine_;
445  T ie_;
446 };
447 
448 } // namespace pf
449 } // namespace mcl_3dl
450 
451 #endif // MCL_3DL_PF_H
virtual FLT_TYPE & operator[](const size_t i)=0
T getParticle(const size_t i) const
Definition: pf.h:380
size_t getParticleSize() const
Definition: pf.h:384
void resample(T sigma)
Definition: pf.h:178
T expectation(const FLT_TYPE pass_ratio=1.0)
Definition: pf.h:270
XmlRpcServer s
void resizeParticle(const size_t num)
Definition: pf.h:388
void init(T mean, T sigma)
Definition: pf.h:165
static T generateNoise(RANDOM_ENGINE &engine, const NOISE_GEN &gen)
Definition: pf.h:73
std::vector< T > covariance(const FLT_TYPE pass_ratio=1.0, const FLT_TYPE random_sample_ratio=1.0)
Definition: pf.h:294
FLT_TYPE covElement(const T &e, const size_t &j, const size_t &k)
Definition: pf.h:65
void initUsingNoiseGenerator(const GEN &generator)
Definition: pf.h:170
T operator+(const T &a)
Definition: pf.h:54
void noise(T sigma)
Definition: pf.h:222
FLT_TYPE probability_bias_
Definition: pf.h:100
std::vector< Particle< T, FLT_TYPE > > particles_dup_
Definition: pf.h:443
std::vector< Particle< T, FLT_TYPE > >::iterator appendParticle(const size_t num)
Definition: pf.h:426
void add(const T &s, const FLT_TYPE &prob)
Definition: pf.h:122
std::vector< Particle< T, FLT_TYPE > >::iterator begin()
Definition: pf.h:432
RANDOM_ENGINE engine_
Definition: pf.h:444
std::vector< Particle< T, FLT_TYPE > > particles_
Definition: pf.h:442
bool operator<(const Particle &p2) const
Definition: pf.h:102
void resampleUsingNoiseGenerator(const GEN &generator)
Definition: pf.h:183
INLINE Rall1d< T, V, S > exp(const Rall1d< T, V, S > &arg)
std::vector< Particle< T, FLT_TYPE > >::iterator end()
Definition: pf.h:436
virtual size_t size() const =0
virtual void normalize()=0
FLT_TYPE getTotalProbability()
Definition: pf.h:148
ParticleFilter(const int num_particles, const unsigned int random_seed=std::random_device()())
Definition: pf.h:160
FLT_TYPE probability_
Definition: pf.h:99
void addNoiseUsingNoiseGenerator(const GEN &generator)
Definition: pf.h:227
FLT_TYPE accum_probability_
Definition: pf.h:101
Particle(FLT_TYPE prob)
Definition: pf.h:94
void measure(std::function< FLT_TYPE(const T &)> likelihood)
Definition: pf.h:248
void predict(std::function< void(T &)> model)
Definition: pf.h:234
void bias(std::function< void(const T &, float &p_bias)> prob)
Definition: pf.h:241


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:16:29