Extended Kalman filter class. More...
#include <ekf.h>
Public Member Functions | |
void | correct (const Measurement &measurement) |
Carries out the correct step in the predict/update cycle. | |
Ekf (std::vector< double > args=std::vector< double >()) | |
Constructor for the Ekf class. | |
void | predict (const double delta) |
Carries out the predict step in the predict/update cycle. | |
~Ekf () | |
Destructor for the Ekf class. |
Extended Kalman filter class.
Implementation of an extended Kalman filter (EKF). This class derives from FilterBase and overrides the predict() and correct() methods in keeping with the discrete time EKF algorithm.
RobotLocalization::Ekf::Ekf | ( | std::vector< double > | args = std::vector<double>() | ) |
void RobotLocalization::Ekf::correct | ( | const Measurement & | measurement | ) | [virtual] |
Carries out the correct step in the predict/update cycle.
[in] | measurement | - The measurement to fuse with our estimate |
Implements RobotLocalization::FilterBase.
void RobotLocalization::Ekf::predict | ( | 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.
[in] | delta | - The time step over which to predict. |
Implements RobotLocalization::FilterBase.