easykf-2.04
 All Classes Namespaces Files Functions Variables Enumerations Enumerator Macros Pages
List of all members | Public Attributes
ukf::srstate::ukf_param Struct Reference

Structure holding the parameters of the statistical linearization. More...

#include <ukf_types.h>

Public Attributes

double kpa
 $\kappa \geq 0$, $\kappa = 0$ is a good choice. According to van der Merwe, its value is not critical More...
 
double alpha
 $0 \leq \alpha \leq 1$ : "Size" of sigma-point distribution. Should be small if the function is strongly non-linear More...
 
double beta
 Non negative weights used to introduce knowledge about the higher order moments of the distribution. For gaussian distributions, $\beta = 2$ is a good choice. More...
 
double lambda
 $\lambda = \alpha^2 (n + \kappa) - n$ More...
 
double lambda_aug
 
double gamma
 $\gamma = \sqrt{\lambda + n}$ More...
 
double gamma_aug
 
int n
 Size of the state vector. More...
 
int nbSamples
 $nbSamples = (2 n + 1)$ Number of sigma-points More...
 
int nbSamplesMeasure
 $nbSamplesMeasure = (4 n + 1)$ Number of sigma-points More...
 
int no
 Dimension of the output : the measurements. More...
 
double prior_x
 Prior estimate of the covariance matrix of the state. More...
 
ProcessNoise process_noise_type
 Type of process noise. More...
 
double process_noise
 Parameter used for the evolution noise. More...
 
double measurement_noise
 Covariance of the observation noise. More...
 

Detailed Description

Structure holding the parameters of the statistical linearization.

Member Data Documentation

double ukf::srstate::ukf_param::alpha

$0 \leq \alpha \leq 1$ : "Size" of sigma-point distribution. Should be small if the function is strongly non-linear

double ukf::srstate::ukf_param::beta

Non negative weights used to introduce knowledge about the higher order moments of the distribution. For gaussian distributions, $\beta = 2$ is a good choice.

double ukf::srstate::ukf_param::gamma

$\gamma = \sqrt{\lambda + n}$

double ukf::srstate::ukf_param::gamma_aug
double ukf::srstate::ukf_param::kpa

$\kappa \geq 0$, $\kappa = 0$ is a good choice. According to van der Merwe, its value is not critical

double ukf::srstate::ukf_param::lambda

$\lambda = \alpha^2 (n + \kappa) - n$

double ukf::srstate::ukf_param::lambda_aug
double ukf::srstate::ukf_param::measurement_noise

Covariance of the observation noise.

int ukf::srstate::ukf_param::n

Size of the state vector.

int ukf::srstate::ukf_param::nbSamples

$nbSamples = (2 n + 1)$ Number of sigma-points

int ukf::srstate::ukf_param::nbSamplesMeasure

$nbSamplesMeasure = (4 n + 1)$ Number of sigma-points

int ukf::srstate::ukf_param::no

Dimension of the output : the measurements.

double ukf::srstate::ukf_param::prior_x

Prior estimate of the covariance matrix of the state.

double ukf::srstate::ukf_param::process_noise

Parameter used for the evolution noise.

ProcessNoise ukf::srstate::ukf_param::process_noise_type

Type of process noise.


The documentation for this struct was generated from the following file: