|
|
using | StateTransitionModel = _StateTransitionModel |
| |
|
using | MeasurementModel = _MeasurementModel |
| |
|
using | State = typename StateTransitionModel::Input_t |
| |
|
using | Measurement = typename MeasurementModel::Output_t |
| |
|
|
| ParticleFilter (const StateTransitionModel &state_transition_model, const MeasurementModel &measurement_model) |
| |
|
template<typename _Distribution > |
| _Distribution & | predict (_Distribution &x) const |
| |
|
template<typename _Distribution , typename _Noise > |
| _Distribution & | predict (_Distribution &x, const _Noise &process_noise) const |
| |
| template<typename ... Args> |
| auto | update (const typename measurement_transform_t::Input_variable_t &x, const measurement_t &z, const Args &... args) const |
| | Update the state, using prior state possibly augmented with measurement noise, propagating variable as Gaussian. More...
|
| |
| auto | update (typename measurement_transform_t::Input_variable_t::unaugmented_t &x, const measurement_t &z, const typename measurement_transform_t::Input_variable_t::augmentation_t &aug) const |
| | Update the state, using prior state possibly augmented with measurement noise, propagating variable as Gaussian. More...
|
| |
|
|
const StateTransitionModel & | state_transition_model |
| |
|
const MeasurementModel & | measurement_model |
| |
◆ update() [1/2]
template<typename _StateTransitionModel , typename _MeasurementModel >
template<typename ... Args>
| auto OpenKalman::ParticleFilter< _StateTransitionModel, _MeasurementModel >::update |
( |
const typename measurement_transform_t::Input_variable_t & |
x, |
|
|
const measurement_t & |
z, |
|
|
const Args &... |
args |
|
) |
| const |
|
inline |
Update the state, using prior state possibly augmented with measurement noise, propagating variable as Gaussian.
- Template Parameters
-
| Args | type of measurement noise (Gaussian or square root form, same dimensions as measurement variable) |
- Parameters
-
| x | the current state variable (Gaussian), possibly augmented with measurement noise |
| z | The measurement vector |
| args | the optional additive process noise |
- Returns
- updated state variable
◆ update() [2/2]
template<typename _StateTransitionModel , typename _MeasurementModel >
| auto OpenKalman::ParticleFilter< _StateTransitionModel, _MeasurementModel >::update |
( |
typename measurement_transform_t::Input_variable_t::unaugmented_t & |
x, |
|
|
const measurement_t & |
z, |
|
|
const typename measurement_transform_t::Input_variable_t::augmentation_t & |
aug |
|
) |
| const |
|
inline |
Update the state, using prior state possibly augmented with measurement noise, propagating variable as Gaussian.
- Parameters
-
| x | the current state variable (Gaussian), possibly augmented with measurement noise |
| z | The measurement vector |
| aug | the measurement noise for augmentation |
- Returns
- updated state variable
The documentation for this struct was generated from the following file: