|
Autoware.Auto
|
|
A class that describes the Wiener process noise. More...
#include <wiener_noise.hpp>


Public Types | |
| using | State = StateT |
Public Member Functions | |
| WienerNoise (const std::array< typename State::Scalar, State::size()> &acceleration_variances) | |
| Constructor from acceleration variances. More... | |
Public Member Functions inherited from autoware::prediction::NoiseInterface< WienerNoise< StateT > > | |
| auto | covariance (const std::chrono::nanoseconds &dt) const |
| Get a covariance matrix for this noise model. More... | |
Protected Member Functions | |
| State::Matrix | crtp_covariance (const std::chrono::nanoseconds &) const |
| A CRTP-called covariance getter. More... | |
| KALMAN_FILTER_PUBLIC state::ConstAccelerationXY::Matrix | crtp_covariance (const std::chrono::nanoseconds &dt) const |
| A specialization of covariance matrix computation for ConstAccelerationXY state. More... | |
| KALMAN_FILTER_PUBLIC state::ConstAccelerationXYYaw::Matrix | crtp_covariance (const std::chrono::nanoseconds &dt) const |
| A specialization of covariance matrix computation for ConstAccelerationXYYaw state. More... | |
| state::ConstAccelerationXYYaw::Matrix | crtp_covariance (const std::chrono::nanoseconds &dt) const |
| state::ConstAccelerationXY::Matrix | crtp_covariance (const std::chrono::nanoseconds &dt) const |
Protected Attributes | |
| friend | NoiseInterface< 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#Piecewise-White-Noise-Model (combine into
one line)
| StateT | A given state type. |
| using autoware::prediction::WienerNoise< StateT >::State = StateT |
|
inlineexplicit |
Constructor from acceleration variances.
| [in] | acceleration_variances | The acceleration variances, note that these are sigmas, not sigmas squared. |
|
inlineprotected |
A CRTP-called covariance getter.
|
protected |
|
protected |
|
protected |
A specialization of covariance matrix computation for ConstAccelerationXY state.
| [in] | dt | Time step. |
|
protected |
A specialization of covariance matrix computation for ConstAccelerationXYYaw state.
| [in] | dt | Time step. |
|
protected |