Fang-Robotics-MCB
Fang Robotics Team Codebase
Loading...
Searching...
No Matches
tap::algorithms::ExtendedKalman Class Reference

#include <extended_kalman.hpp>

Public Member Functions

 ExtendedKalman (float tQ, float tR)
 
float filterData (float dat)
 
float getLastFiltered () const
 
void reset ()
 

Detailed Description

The kalman filter can be used by instantiating an ExtendedKalman object and calling filterData.

Example source:

float sensorData;
float filtered;
ExtendedKalman kalman(1.0f, 0.0f);
while(1)
{
filtered = kalman.filterData(sensorData);
}
Definition extended_kalman.hpp:53

Constructor & Destructor Documentation

◆ ExtendedKalman()

tap::algorithms::ExtendedKalman::ExtendedKalman ( float  tQ,
float  tR 
)

Initializes a kalman filter with the given covariances.

Note
tR can be fixed at 1 and then tQ can be modified (since the magnitude of tQ and tR are relative to each other). Larger tQ means more trust in the data we are measuring. Conversely, a smaller tQ means more trust in the model's prediction (rather than the measured) value.
Parameters
[in]tQthe system noise covariance.
[in]tRthe measurement noise covariance.

Member Function Documentation

◆ filterData()

float tap::algorithms::ExtendedKalman::filterData ( float  dat)

Runs the kalman filter, returning the current prediction.

Note
description of data:
$x(k | k)$ is the current prediction (filtered output)
(and then $k - 1$ would be the previous output)
Corresponding formula:

\begin{eqnarray*}
x(k | k-1) & = & A \cdot X(k-1 | k-1) + B \cdot U(k) + W(K)\\
p(k | k-1) & = & A \cdot p(k-1 | k-1) \cdot A^\prime + Q\\
kg(k) & = & p(k | k-1) \cdot \frac{H^\prime}{H \cdot p(k | k-1) \cdot H^\prime + R}\\
x(k | k) & = & X(k | k - 1) + kg(k) \cdot (Z(k) - H \cdot X(k | k-1))\\
p(k | k) & = & (I - kg(k) \cdot H) \cdot P(k | k-1)
\end{eqnarray*}

Parameters
[in]datthe value to be filtered.
Returns
The current prediction of what the data should be.

◆ getLastFiltered()

float tap::algorithms::ExtendedKalman::getLastFiltered ( ) const

Returns the last filtered data point.

◆ reset()

void tap::algorithms::ExtendedKalman::reset ( )

Resets the covariances and predictions.


The documentation for this class was generated from the following files: