Public Member Functions | Protected Attributes
RobotLocalization::Ukf Class Reference

Unscented Kalman filter class. More...

#include <ukf.h>

Inheritance diagram for RobotLocalization::Ukf:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void correct (const Measurement &measurement)
 Carries out the correct step in the predict/update cycle.
void predict (const double referenceTime, const double delta)
 Carries out the predict step in the predict/update cycle.
 Ukf (std::vector< double > args)
 Constructor for the Ukf class.
 ~Ukf ()
 Destructor for the Ukf class.

Protected Attributes

std::vector< double > covarWeights_
 The weights associated with each sigma point when calculating a predicted estimateErrorCovariance_.
double lambda_
 Used in weight generation for the sigma points.
std::vector< Eigen::VectorXd > sigmaPoints_
 The UKF sigma points.
std::vector< double > stateWeights_
 The weights associated with each sigma point when generating a new state.
bool uncorrected_
 Used to determine if we need to re-compute the sigma points when carrying out multiple corrections.
Eigen::MatrixXd weightedCovarSqrt_
 This matrix is used to generate the sigmaPoints_.

Detailed Description

Unscented Kalman filter class.

Implementation of an unscenter Kalman filter (UKF). This class derives from FilterBase and overrides the predict() and correct() methods in keeping with the discrete time UKF algorithm. The algorithm was derived from the UKF Wikipedia article at (http://en.wikipedia.org/wiki/Kalman_filter#Unscented_Kalman_filter) ...and this paper: J. J. LaViola, Jr., “A comparison of unscented and extended Kalman filtering for estimating quaternion motion,” in Proc. American Control Conf., Denver, CO, June 4–6, 2003, pp. 2435–2440 Obtained here: http://www.cs.ucf.edu/~jjl/pubs/laviola_acc2003.pdf

Definition at line 60 of file ukf.h.


Constructor & Destructor Documentation

RobotLocalization::Ukf::Ukf ( std::vector< double >  args) [explicit]

Constructor for the Ukf class.

Parameters:
[in]args- Generic argument container. It is assumed that args[0] constains the alpha parameter, args[1] contains the kappa parameter, and args[2] contains the beta parameter.

Definition at line 51 of file ukf.cpp.

Destructor for the Ukf class.

Definition at line 81 of file ukf.cpp.


Member Function Documentation

void RobotLocalization::Ukf::correct ( const Measurement measurement) [virtual]

Carries out the correct step in the predict/update cycle.

Parameters:
[in]measurement- The measurement to fuse with our estimate

Implements RobotLocalization::FilterBase.

Definition at line 85 of file ukf.cpp.

void RobotLocalization::Ukf::predict ( const double  referenceTime,
const double  delta 
) [virtual]

Carries out the predict step in the predict/update cycle.

Projects the state and error matrices forward using a model of the vehicle's motion.

Parameters:
[in]referenceTime- The time at which the prediction is being made
[in]delta- The time step over which to predict.

Implements RobotLocalization::FilterBase.

Definition at line 285 of file ukf.cpp.


Member Data Documentation

std::vector<double> RobotLocalization::Ukf::covarWeights_ [protected]

The weights associated with each sigma point when calculating a predicted estimateErrorCovariance_.

Definition at line 110 of file ukf.h.

double RobotLocalization::Ukf::lambda_ [protected]

Used in weight generation for the sigma points.

Definition at line 114 of file ukf.h.

std::vector<Eigen::VectorXd> RobotLocalization::Ukf::sigmaPoints_ [protected]

The UKF sigma points.

Used to sample possible next states during prediction.

Definition at line 96 of file ukf.h.

std::vector<double> RobotLocalization::Ukf::stateWeights_ [protected]

The weights associated with each sigma point when generating a new state.

Definition at line 105 of file ukf.h.

Used to determine if we need to re-compute the sigma points when carrying out multiple corrections.

Definition at line 119 of file ukf.h.

Eigen::MatrixXd RobotLocalization::Ukf::weightedCovarSqrt_ [protected]

This matrix is used to generate the sigmaPoints_.

Definition at line 100 of file ukf.h.


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


robot_localization
Author(s): Tom Moore
autogenerated on Sun Apr 2 2017 03:39:46