gaussian_vector.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * 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 provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Wim Meeussen */
36 
38 #include <bfl/wrappers/rng/rng.h>
39 #include <cmath>
40 #include <cassert>
41 #include <vector>
42 
43 namespace BFL
44 {
46  : Pdf<tf::Vector3> (1),
47  mu_(mu),
48  sigma_(sigma),
49  sigma_changed_(true)
50 {
51  for (unsigned int i = 0; i < 3; i++)
52  assert(sigma[i] > 0);
53 }
54 
56 
57 std::ostream& operator<< (std::ostream& os, const GaussianVector& g)
58 {
59  os << "Mu :\n" << g.ExpectedValueGet() << std::endl
60  << "Sigma:\n" << g.CovarianceGet() << std::endl;
61  return os;
62 }
63 
65 {
66  sigma_ = sigma;
67  sigma_changed_ = true;
68 }
69 
71 {
72  if (sigma_changed_)
73  {
74  sigma_changed_ = false;
75  // 2 * sigma^2
76  for (unsigned int i = 0; i < 3; i++)
77  sigma_sq_[i] = 2 * sigma_[i] * sigma_[i];
78  // sqrt
79  sqrt_ = 1 / sqrt(M_PI * M_PI * M_PI * sigma_sq_[0] * sigma_sq_[1] * sigma_sq_[2]);
80  }
81 
82  tf::Vector3 diff = input - mu_;
83  return sqrt_ * exp(- (diff[0] * diff[0] / sigma_sq_[0])
84  - (diff[1] * diff[1] / sigma_sq_[1])
85  - (diff[2] * diff[2] / sigma_sq_[2]));
86 }
87 
88 bool
89 GaussianVector::SampleFrom(std::vector<Sample<tf::Vector3> >& list_samples, const int num_samples, int method,
90  void * args) const
91 {
92  list_samples.resize(num_samples);
93  std::vector<Sample<tf::Vector3> >::iterator sample_it = list_samples.begin();
94  for (sample_it = list_samples.begin(); sample_it != list_samples.end(); sample_it++)
95  SampleFrom(*sample_it, method, args);
96 
97  return true;
98 }
99 
100 bool
101 GaussianVector::SampleFrom(Sample<tf::Vector3>& one_sample, int method, void * args) const
102 {
103  one_sample.ValueSet(tf::Vector3(rnorm(mu_[0], sigma_[0]),
104  rnorm(mu_[1], sigma_[1]),
105  rnorm(mu_[2], sigma_[2])));
106  return true;
107 }
108 
111 {
112  return mu_;
113 }
114 
115 SymmetricMatrix
117 {
118  SymmetricMatrix sigma(3);
119  sigma = 0;
120  for (unsigned int i = 0; i < 3; i++)
121  sigma(i + 1, i + 1) = pow(sigma_[i], 2);
122  return sigma;
123 }
124 
127 {
128  return new GaussianVector(mu_, sigma_);
129 }
130 } // End namespace BFL
bool SampleFrom(vector< Sample< tf::Vector3 > > &list_samples, const int num_samples, int method=DEFAULT, void *args=NULL) const
void sigmaSet(const tf::Vector3 &sigma)
double rnorm(const double &mu, const double &sigma)
virtual Probability ProbabilityGet(const tf::Vector3 &input) const
void ValueSet(const T &value)
virtual ~GaussianVector()
Destructor.
Class representing gaussian vector.
virtual GaussianVector * Clone() const
GaussianVector(const tf::Vector3 &mu, const tf::Vector3 &sigma)
Constructor.
TFSIMD_FORCE_INLINE Vector3()
#define M_PI
virtual MatrixWrapper::SymmetricMatrix CovarianceGet() const
virtual tf::Vector3 ExpectedValueGet() const
friend std::ostream & operator<<(std::ostream &os, const GaussianVector &g)
output stream for GaussianVector


people_tracking_filter
Author(s): Caroline Pantofaru
autogenerated on Sun Feb 21 2021 03:56:47