dynamicModels#
Executive Summary#
This class provides an container for all the dynamics models and components to a kalman filter. This class is a necessary component to any Kalman Filter implementation
Virtual and Private method descriptors#
The following table lists all the class methods and their function
Method Name |
Method Function |
Protected or Private |
Virtual or not |
|---|---|---|---|
rk4 |
RK4 integrator |
private |
non-virtual |
propagate |
integrate the equations of motion provided in setter |
public |
non-virtual |
computeDynamicsMatrix |
compute the dynamics matrix given the partials provided in setter |
public |
non-virtual |
Module assumptions and limitations#
Only an RK4 is provided currently as an integrator
User Guide#
This section lists all the setters and getters that are defined by the interface
Method Name |
Method Function |
Necessity |
|---|---|---|
setDynamics |
set the equations of motion function |
necessary |
setDynamicsMatrix |
set the dynamics matrix given a state |
necessary for extended kalman filters |
-
class DynamicsModel#
Measurement models used to map a state vector to a measurement.
Public Functions
-
FilterStateVector propagate(std::array<double, 2>, const FilterStateVector &state, double dt) const#
Call the propagation function for the dynamics
- Parameters:
std::array<double, 2> – interval : time interval
FilterStateVector – state : initial state
double – dt: time step
- Returns:
FilterStateVector propagatedState
-
void setDynamics(const std::function<const FilterStateVector(const double, const FilterStateVector&)> &dynamicsPropagator)#
Set the propagation function for the dynamics
- Parameters:
std::function<const – FilterStateVector(const FilterStateVector&)>& dynamicsPropagator
-
Eigen::MatrixXd computeDynamicsMatrix(double time, const FilterStateVector &state) const#
Call the dynamics matrix containing the partials of the dynamics with respect to the state
- Parameters:
std::function<const – Eigen::MatrixXd(const FilterStateVector&)>& dynamicsMatrixCalculator
-
void setDynamicsMatrix(const std::function<const Eigen::MatrixXd(const double, const FilterStateVector&)> &dynamicsMatrixCalculator)#
Set the dynamics matrix containing the partials of the dynamics with respect to the state
- Parameters:
std::function<const – Eigen::MatrixXd(const FilterStateVector&)>& dynamicsMatrixCalculator
-
FilterStateVector propagate(std::array<double, 2>, const FilterStateVector &state, double dt) const#