#include <filter_base.h>
Public Member Functions | |
virtual void | correct (const Measurement &measurement)=0 |
Carries out the correct step in the predict/update cycle. This method must be implemented by subclasses. | |
FilterBase () | |
Constructor for the FilterBase class. | |
bool | getDebug () |
Gets the value of the debug_ variable. | |
const Eigen::MatrixXd & | getEstimateErrorCovariance () |
Gets the estimate error covariance. | |
bool | getInitializedStatus () |
Gets the filter's initialized status. | |
double | getLastMeasurementTime () |
Gets the most recent measurement time. | |
double | getLastUpdateTime () |
Gets the filter's last update time. | |
const Eigen::VectorXd & | getPredictedState () |
Gets the filter's predicted state, i.e., the state estimate before correct() is called. | |
const Eigen::MatrixXd & | getProcessNoiseCovariance () |
Gets the filter's process noise covariance. | |
double | getSensorTimeout () |
Gets the sensor timeout value (in seconds) | |
const Eigen::VectorXd & | getState () |
Gets the filter state. | |
virtual void | predict (const double delta)=0 |
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. This method must be implemented by subclasses. | |
virtual void | processMeasurement (const Measurement &measurement) |
Does some final preprocessing, carries out the predict/update cycle. | |
void | setDebug (const bool debug, std::ostream *outStream=NULL) |
Sets the filter into debug mode. | |
void | setEstimateErrorCovariance (const Eigen::MatrixXd &estimateErrorCovariance) |
Manually sets the filter's estimate error covariance. | |
void | setLastMeasurementTime (const double lastMeasurementTime) |
Sets the filter's last measurement time. | |
void | setLastUpdateTime (const double lastUpdateTime) |
Sets the filter's last update time. | |
void | setProcessNoiseCovariance (const Eigen::MatrixXd &processNoiseCovariance) |
Sets the process noise covariance for the filter. | |
void | setSensorTimeout (const double sensorTimeout) |
Sets the sensor timeout. | |
void | setState (const Eigen::VectorXd &state) |
Manually sets the filter's state. | |
void | validateDelta (double &delta) |
Ensures a given time delta is valid (helps with bag file playback issues) | |
virtual | ~FilterBase () |
Destructor for the FilterBase class. | |
Protected Member Functions | |
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. | |
virtual void | wrapStateAngles () |
Keeps the state Euler angles in the range [-pi, pi]. | |
Protected Attributes | |
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. | |
std::ostream * | debugStream_ |
Used for outputting debug messages. | |
Eigen::MatrixXd | estimateErrorCovariance_ |
This matrix stores the total error in our position estimate (the state_ variable). | |
Eigen::MatrixXd | identity_ |
We need the identity for a few operations. Better to store it. | |
bool | initialized_ |
Whether or not we've received any measurements. | |
double | lastMeasurementTime_ |
Tracks the time the filter was last updated using a measurement. | |
double | lastUpdateTime_ |
Used for tracking the latest update time as determined by this class. | |
Eigen::VectorXd | predictedState_ |
Holds the last predicted state of the filter. | |
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. | |
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. | |
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. | |
Eigen::MatrixXd | transferFunction_ |
The Kalman filter transfer function. | |
Eigen::MatrixXd | transferFunctionJacobian_ |
The Kalman filter transfer function Jacobian. | |
Private Attributes | |
bool | debug_ |
Whether or not the filter is in debug mode. |
Definition at line 93 of file filter_base.h.
Constructor for the FilterBase class.
Definition at line 43 of file filter_base.cpp.
RobotLocalization::FilterBase::~FilterBase | ( | ) | [virtual] |
Destructor for the FilterBase class.
Definition at line 109 of file filter_base.cpp.
bool RobotLocalization::FilterBase::checkMahalanobisThreshold | ( | const Eigen::VectorXd & | innovation, |
const Eigen::MatrixXd & | invCovariance, | ||
const double | nsigmas | ||
) | [protected, virtual] |
Tests if innovation is within N-sigmas of covariance. Returns true if passed the test.
Definition at line 298 of file filter_base.cpp.
virtual void RobotLocalization::FilterBase::correct | ( | const Measurement & | measurement | ) | [pure virtual] |
Carries out the correct step in the predict/update cycle. This method must be implemented by subclasses.
[in] | measurement | - The measurement to fuse with the state estimate |
Implemented in RobotLocalization::Ukf, RobotLocalization::Ekf, RobotLocalization::FilterDerived2, and RobotLocalization::FilterDerived.
Gets the value of the debug_ variable.
Definition at line 113 of file filter_base.cpp.
const Eigen::MatrixXd & RobotLocalization::FilterBase::getEstimateErrorCovariance | ( | ) |
Gets the estimate error covariance.
Definition at line 118 of file filter_base.cpp.
Gets the filter's initialized status.
Definition at line 123 of file filter_base.cpp.
Gets the most recent measurement time.
Definition at line 128 of file filter_base.cpp.
Gets the filter's last update time.
Definition at line 133 of file filter_base.cpp.
const Eigen::VectorXd & RobotLocalization::FilterBase::getPredictedState | ( | ) |
Gets the filter's predicted state, i.e., the state estimate before correct() is called.
Definition at line 138 of file filter_base.cpp.
const Eigen::MatrixXd & RobotLocalization::FilterBase::getProcessNoiseCovariance | ( | ) |
Gets the filter's process noise covariance.
Definition at line 143 of file filter_base.cpp.
Gets the sensor timeout value (in seconds)
Definition at line 148 of file filter_base.cpp.
const Eigen::VectorXd & RobotLocalization::FilterBase::getState | ( | ) |
Gets the filter state.
Definition at line 153 of file filter_base.cpp.
virtual void RobotLocalization::FilterBase::predict | ( | const double | delta | ) | [pure 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. This method must be implemented by subclasses.
[in] | delta | - The time step over which to predict. |
Implemented in RobotLocalization::Ukf, RobotLocalization::Ekf, RobotLocalization::FilterDerived2, and RobotLocalization::FilterDerived.
void RobotLocalization::FilterBase::processMeasurement | ( | const Measurement & | measurement | ) | [virtual] |
Does some final preprocessing, carries out the predict/update cycle.
[in] | measurement | - The measurement object to fuse into the filter |
Reimplemented in RobotLocalization::FilterDerived2.
Definition at line 158 of file filter_base.cpp.
void RobotLocalization::FilterBase::setDebug | ( | const bool | debug, |
std::ostream * | outStream = NULL |
||
) |
Sets the filter into debug mode.
NOTE: this will generates a lot of debug output to the provided stream. The value must be a pointer to a valid ostream object.
[in] | debug | - Whether or not to place the filter in debug mode |
[in] | outStream | - If debug is true, then this must have a valid pointer. If the pointer is invalid, the filter will not enter debug mode. If debug is false, outStream is ignored. |
Definition at line 230 of file filter_base.cpp.
void RobotLocalization::FilterBase::setEstimateErrorCovariance | ( | const Eigen::MatrixXd & | estimateErrorCovariance | ) |
Manually sets the filter's estimate error covariance.
[in] | estimateErrorCovariance | - The state to set as the filter's current state |
Definition at line 250 of file filter_base.cpp.
void RobotLocalization::FilterBase::setLastMeasurementTime | ( | const double | lastMeasurementTime | ) |
Sets the filter's last measurement time.
[in] | lastMeasurementTime | - The last measurement time of the filter |
Definition at line 255 of file filter_base.cpp.
void RobotLocalization::FilterBase::setLastUpdateTime | ( | const double | lastUpdateTime | ) |
Sets the filter's last update time.
This is used mostly for initialization purposes, as the integrateMeasurements() function will update the filter's last update time as well.
[in] | lastUpdateTime | - The last update time of the filter |
Definition at line 260 of file filter_base.cpp.
void RobotLocalization::FilterBase::setProcessNoiseCovariance | ( | const Eigen::MatrixXd & | processNoiseCovariance | ) |
Sets the process noise covariance for the filter.
This enables external initialization, which is important, as this matrix can be difficult to tune for a given implementation.
[in] | processNoiseCovariance | - The STATE_SIZExSTATE_SIZE process noise covariance matrix to use for the filter |
Definition at line 265 of file filter_base.cpp.
void RobotLocalization::FilterBase::setSensorTimeout | ( | const double | sensorTimeout | ) |
Sets the sensor timeout.
[in] | sensorTimeout | - The time, in seconds, for a sensor to be considered having timed out |
Definition at line 270 of file filter_base.cpp.
void RobotLocalization::FilterBase::setState | ( | const Eigen::VectorXd & | state | ) |
Manually sets the filter's state.
[in] | state | - The state to set as the filter's current state |
Definition at line 275 of file filter_base.cpp.
void RobotLocalization::FilterBase::validateDelta | ( | double & | delta | ) |
Ensures a given time delta is valid (helps with bag file playback issues)
[in] | delta | - The time delta, in seconds, to validate |
Definition at line 280 of file filter_base.cpp.
void RobotLocalization::FilterBase::wrapStateAngles | ( | ) | [protected, virtual] |
Keeps the state Euler angles in the range [-pi, pi].
Definition at line 291 of file filter_base.cpp.
Eigen::MatrixXd RobotLocalization::FilterBase::covarianceEpsilon_ [protected] |
Covariance matrices can be incredibly unstable. We can add a small value to it at each iteration to help maintain its positive-definite property.
Definition at line 259 of file filter_base.h.
bool RobotLocalization::FilterBase::debug_ [private] |
Whether or not the filter is in debug mode.
Definition at line 353 of file filter_base.h.
std::ostream* RobotLocalization::FilterBase::debugStream_ [protected] |
Used for outputting debug messages.
Definition at line 263 of file filter_base.h.
Eigen::MatrixXd RobotLocalization::FilterBase::estimateErrorCovariance_ [protected] |
This matrix stores the total error in our position estimate (the state_ variable).
Definition at line 268 of file filter_base.h.
Eigen::MatrixXd RobotLocalization::FilterBase::identity_ [protected] |
We need the identity for a few operations. Better to store it.
Definition at line 272 of file filter_base.h.
bool RobotLocalization::FilterBase::initialized_ [protected] |
Whether or not we've received any measurements.
Definition at line 276 of file filter_base.h.
double RobotLocalization::FilterBase::lastMeasurementTime_ [protected] |
Tracks the time the filter was last updated using a measurement.
This value is used to monitor sensor readings with respect to the sensorTimeout_. We also use it to compute the time delta values for our prediction step.
Definition at line 283 of file filter_base.h.
double RobotLocalization::FilterBase::lastUpdateTime_ [protected] |
Used for tracking the latest update time as determined by this class.
We assume that this class may receive measurements that occurred in the past, as may happen with sensors distributed on different machines on a network. This variable tracks when the filter was updated with respect to the executable in which this class was instantiated. We use this to determine if we have experienced a sensor timeout, i.e., if we haven't received any sensor data in a long time.
Definition at line 294 of file filter_base.h.
Eigen::VectorXd RobotLocalization::FilterBase::predictedState_ [protected] |
Holds the last predicted state of the filter.
Definition at line 298 of file filter_base.h.
Eigen::MatrixXd RobotLocalization::FilterBase::processNoiseCovariance_ [protected] |
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.
Definition at line 310 of file filter_base.h.
double RobotLocalization::FilterBase::sensorTimeout_ [protected] |
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.
Definition at line 317 of file filter_base.h.
Eigen::VectorXd RobotLocalization::FilterBase::state_ [protected] |
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.
Definition at line 322 of file filter_base.h.
Eigen::MatrixXd RobotLocalization::FilterBase::transferFunction_ [protected] |
The Kalman filter transfer function.
Kalman filters and extended Kalman filters project the current state forward in time. This is the "predict" part of the predict/correct cycle. A Kalman filter has a (typically constant) matrix A that defines how to turn the current state, x, into the predicted next state. For an EKF, this matrix becomes a function f(x). However, this function can still be expressed as a matrix to make the math a little cleaner, which is what we do here. Technically, each row in the matrix is actually a function. Some rows will contain many trigonometric functions, which are of course non-linear. In any case, you can think of this as the 'A' matrix in the Kalman filter formulation.
Definition at line 337 of file filter_base.h.
Eigen::MatrixXd RobotLocalization::FilterBase::transferFunctionJacobian_ [protected] |
The Kalman filter transfer function Jacobian.
The transfer function is allowed to be non-linear in an EKF, but for propagating (predicting) the covariance matrix, we need to linearize it about the current mean (i.e., state). This is done via a Jacobian, which calculates partial derivatives of each row of the transfer function matrix with respect to each state variable.
Definition at line 347 of file filter_base.h.