Public Member Functions | Protected Attributes | List of all members
RobotLocalization::Ukf Class Reference

Unscented Kalman filter class. More...

#include <ukf.h>

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

Public Member Functions

void correct (const Measurement &measurement)
 Carries out the correct step in the predict/update cycle. More...
 
void predict (const double referenceTime, const double delta)
 Carries out the predict step in the predict/update cycle. More...
 
 Ukf (std::vector< double > args)
 Constructor for the Ukf class. More...
 
 ~Ukf ()
 Destructor for the Ukf class. More...
 
- Public Member Functions inherited from RobotLocalization::FilterBase
void computeDynamicProcessNoiseCovariance (const Eigen::VectorXd &state, const double delta)
 Computes a dynamic process noise covariance matrix using the parameterized state. More...
 
 FilterBase ()
 Constructor for the FilterBase class. More...
 
const Eigen::VectorXd & getControl ()
 Returns the control vector currently being used. More...
 
double getControlTime ()
 Returns the time at which the control term was issued. More...
 
bool getDebug ()
 Gets the value of the debug_ variable. More...
 
const Eigen::MatrixXd & getEstimateErrorCovariance ()
 Gets the estimate error covariance. More...
 
bool getInitializedStatus ()
 Gets the filter's initialized status. More...
 
double getLastMeasurementTime ()
 Gets the most recent measurement time. More...
 
const Eigen::VectorXd & getPredictedState ()
 Gets the filter's predicted state, i.e., the state estimate before correct() is called. More...
 
const Eigen::MatrixXd & getProcessNoiseCovariance ()
 Gets the filter's process noise covariance. More...
 
double getSensorTimeout ()
 Gets the sensor timeout value (in seconds) More...
 
const Eigen::VectorXd & getState ()
 Gets the filter state. More...
 
virtual void processMeasurement (const Measurement &measurement)
 Does some final preprocessing, carries out the predict/update cycle. More...
 
void reset ()
 Resets filter to its unintialized state. More...
 
void setControl (const Eigen::VectorXd &control, const double controlTime)
 Sets the most recent control term. More...
 
void setControlParams (const std::vector< int > &updateVector, const double controlTimeout, const std::vector< double > &accelerationLimits, const std::vector< double > &accelerationGains, const std::vector< double > &decelerationLimits, const std::vector< double > &decelerationGains)
 Sets the control update vector and acceleration limits. More...
 
void setDebug (const bool debug, std::ostream *outStream=NULL)
 Sets the filter into debug mode. More...
 
void setEstimateErrorCovariance (const Eigen::MatrixXd &estimateErrorCovariance)
 Manually sets the filter's estimate error covariance. More...
 
void setLastMeasurementTime (const double lastMeasurementTime)
 Sets the filter's last measurement time. More...
 
void setProcessNoiseCovariance (const Eigen::MatrixXd &processNoiseCovariance)
 Sets the process noise covariance for the filter. More...
 
void setSensorTimeout (const double sensorTimeout)
 Sets the sensor timeout. More...
 
void setState (const Eigen::VectorXd &state)
 Manually sets the filter's state. More...
 
void setUseDynamicProcessNoiseCovariance (const bool dynamicProcessNoiseCovariance)
 Enables dynamic process noise covariance calculation. More...
 
void validateDelta (double &delta)
 Ensures a given time delta is valid (helps with bag file playback issues) More...
 
virtual ~FilterBase ()
 Destructor for the FilterBase class. More...
 

Protected Attributes

std::vector< double > covarWeights_
 The weights associated with each sigma point when calculating a predicted estimateErrorCovariance_. More...
 
double lambda_
 Used in weight generation for the sigma points. More...
 
std::vector< Eigen::VectorXd > sigmaPoints_
 The UKF sigma points. More...
 
std::vector< double > stateWeights_
 The weights associated with each sigma point when generating a new state. More...
 
bool uncorrected_
 Used to determine if we need to re-compute the sigma points when carrying out multiple corrections. More...
 
Eigen::MatrixXd weightedCovarSqrt_
 This matrix is used to generate the sigmaPoints_. More...
 
- Protected Attributes inherited from RobotLocalization::FilterBase
std::vector< double > accelerationGains_
 Gains applied to acceleration derived from control term. More...
 
std::vector< double > accelerationLimits_
 Caps the acceleration we apply from control input. More...
 
Eigen::VectorXd controlAcceleration_
 Variable that gets updated every time we process a measurement and we have a valid control. More...
 
double controlTimeout_
 Timeout value, in seconds, after which a control is considered stale. More...
 
std::vector< int > controlUpdateVector_
 Which control variables are being used (e.g., not every vehicle is controllable in Y or Z) More...
 
Eigen::MatrixXd covarianceEpsilon_
 Covariance matrices can be incredibly unstable. We can add a small value to it at each iteration to help maintain its positive-definite property. More...
 
std::ostream * debugStream_
 Used for outputting debug messages. More...
 
std::vector< double > decelerationGains_
 Gains applied to deceleration derived from control term. More...
 
std::vector< double > decelerationLimits_
 Caps the deceleration we apply from control input. More...
 
Eigen::MatrixXd dynamicProcessNoiseCovariance_
 Gets updated when useDynamicProcessNoise_ is true. More...
 
Eigen::MatrixXd estimateErrorCovariance_
 This matrix stores the total error in our position estimate (the state_ variable). More...
 
Eigen::MatrixXd identity_
 We need the identity for a few operations. Better to store it. More...
 
bool initialized_
 Whether or not we've received any measurements. More...
 
double lastMeasurementTime_
 Tracks the time the filter was last updated using a measurement. More...
 
Eigen::VectorXd latestControl_
 Latest control term. More...
 
double latestControlTime_
 The time of reception of the most recent control term. More...
 
Eigen::VectorXd predictedState_
 Holds the last predicted state of the filter. More...
 
Eigen::MatrixXd processNoiseCovariance_
 As we move through the world, we follow a predict/update cycle. If one were to imagine a scenario where all we did was make predictions without correcting, the error in our position estimate would grow without bound. This error is stored in the stateEstimateCovariance_ matrix. However, this matrix doesn't answer the question of how much our error should grow for each time step. That's where the processNoiseCovariance matrix comes in. When we make a prediction using the transfer function, we add this matrix (times deltaT) to the state estimate covariance matrix. More...
 
double sensorTimeout_
 The updates to the filter - both predict and correct - are driven by measurements. If we get a gap in measurements for some reason, we want the filter to continue estimating. When this gap occurs, as specified by this timeout, we will continue to call predict() at the filter's frequency. More...
 
Eigen::VectorXd state_
 This is the robot's state vector, which is what we are trying to filter. The values in this vector are what get reported by the node. More...
 
Eigen::MatrixXd transferFunction_
 The Kalman filter transfer function. More...
 
Eigen::MatrixXd transferFunctionJacobian_
 The Kalman filter transfer function Jacobian. More...
 
bool useControl_
 Whether or not we apply the control term. More...
 
bool useDynamicProcessNoiseCovariance_
 If true, uses the robot's vehicle state and the static process noise covariance matrix to generate a dynamic process noise covariance matrix. More...
 

Additional Inherited Members

- Protected Member Functions inherited from RobotLocalization::FilterBase
virtual bool checkMahalanobisThreshold (const Eigen::VectorXd &innovation, const Eigen::MatrixXd &invCovariance, const double nsigmas)
 Tests if innovation is within N-sigmas of covariance. Returns true if passed the test. More...
 
double computeControlAcceleration (const double state, const double control, const double accelerationLimit, const double accelerationGain, const double decelerationLimit, const double decelerationGain)
 Method for settings bounds on acceleration values derived from controls. More...
 
void prepareControl (const double referenceTime, const double predictionDelta)
 Converts the control term to an acceleration to be applied in the prediction step. More...
 
virtual void wrapStateAngles ()
 Keeps the state Euler angles in the range [-pi, pi]. More...
 

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.

RobotLocalization::Ukf::~Ukf ( )

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 284 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.

bool RobotLocalization::Ukf::uncorrected_
protected

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 Wed Feb 3 2021 03:34:02