KalmanFilter.h
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 #ifndef SE_KALMANFILTER_H_
38 #define SE_KALMANFILTER_H_
39 
40 #include "problib/pdfs/Gaussian.h"
41 
46 class KalmanFilter {
47 public:
48 
53  KalmanFilter(int dim);
54 
58  KalmanFilter(const KalmanFilter& orig);
59 
63  virtual KalmanFilter* clone() const;
64 
68  virtual ~KalmanFilter();
69 
76  virtual void init(const pbl::Gaussian& G);
77 
82  void update(const pbl::Gaussian& z);
83 
89  virtual void propagate(const double& dt);
90 
97  double getLikelihood(const pbl::Gaussian& z) const;
98 
103  const pbl::Gaussian& getGaussian() const;
104 
109  const pbl::Vector& getState() const;
110 
115  const pbl::Matrix& getStateCovariance() const;
116 
124  void setMaxAcceleration(double a_max);
125 
126 protected:
127 
130 
133 
136 
139 
142 
144  double a_max_;
145 };
146 
147 #endif /* KALMANTRACKER_H_ */
const pbl::Matrix & getStateCovariance() const
Returns the covariance of the Kalman state.
double getLikelihood(const pbl::Gaussian &z) const
Calculates the likelihood that the given measurement originates from the estimated Kalman state...
void setMaxAcceleration(double a_max)
Set the maximum expected acceleration. This parameter is used to determine the system noise in the pr...
KalmanFilter(int dim)
Constructs a Kalman filter with specified state dimensionality.
const pbl::Vector & getState() const
Returns the Kalman state (mean of the estimated Gaussian)
arma::vec Vector
Kalman filter with constant-velocity system model. The system noise is automatically calculated from ...
Definition: KalmanFilter.h:46
virtual void init(const pbl::Gaussian &G)
Initializes the Kalman filter according to the given Gaussian, i.e., the initial state and state cova...
virtual ~KalmanFilter()
Destructor.
pbl::Matrix H_
Definition: KalmanFilter.h:141
pbl::Gaussian G_
Definition: KalmanFilter.h:135
TFSIMD_FORCE_INLINE const tfScalar & z() const
virtual void propagate(const double &dt)
Propagates the state of the Kalman filter according to the (constant- velocity) system model...
const pbl::Gaussian & getGaussian() const
Returns the Kalman state and covariance as Gaussian.
void update(const pbl::Gaussian &z)
Updates the Kalman filter with the given (Gaussian) measurement.
arma::mat Matrix
virtual KalmanFilter * clone() const
Clone operator.
pbl::Gaussian G_small_
Definition: KalmanFilter.h:138


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