A class that describes the Wiener process noise.
More...
#include <wiener_noise.hpp>
|
| | WienerNoise (const std::array< typename State::Scalar, State::size()> &acceleration_variances) |
| | Constructor from acceleration variances. More...
|
| |
| auto | covariance (const std::chrono::nanoseconds &dt) const |
| | Get a covariance matrix for this noise model. More...
|
| |
template<typename StateT>
class autoware::prediction::WienerNoise< StateT >
A class that describes the Wiener process noise.
For more details see notebook here: https://nbviewer.jupyter.org/github/rlabbe/Kalman-and-Bayesian-Filters-in-Python/ blob/master/07-Kalman-Filter-Math.ipynb%23Piecewise-White-Noise-Model (combine into one line)
- Template Parameters
-
| StateT | A given state type. |
◆ State
template<typename StateT >
◆ WienerNoise()
template<typename StateT >
Constructor from acceleration variances.
- Parameters
-
| [in] | acceleration_variances | The acceleration variances, note that these are sigmas, not sigmas squared. |
◆ crtp_covariance() [1/5]
◆ crtp_covariance() [2/5]
◆ crtp_covariance() [3/5]
template<typename StateT >
A CRTP-called covariance getter.
- Returns
- A covariance of the noise process over given time.
◆ crtp_covariance() [4/5]
A specialization of covariance matrix computation for ConstAccelerationXY state.
- Parameters
-
- Returns
- Covariance matrix.
◆ crtp_covariance() [5/5]
A specialization of covariance matrix computation for ConstAccelerationXYYaw state.
- Parameters
-
- Returns
- Covariance matrix.
◆ NoiseInterface< WienerNoise< StateT > >
template<typename StateT >
The documentation for this class was generated from the following file: