- 3.0.2 optimal control module.
|
Settings for setting up an ExtendedKF. More...
#include <ExtendedKalmanFilter.h>
Public Member Functions | |
ExtendedKalmanFilterSettings () | |
default constructor More... | |
void | print () const |
print the current settings More... | |
void | load (const std::string &filename, bool verbose, const std::string &ns) |
load settings from file More... | |
Public Attributes | |
ct::core::StateVector< STATE_DIM > | x0 |
ct::core::StateMatrix< STATE_DIM, SCALAR > | P0 |
Settings for setting up an ExtendedKF.
The ExtendedKF settings are designed to make the initialization smoother and possible through a file configuration.
|
inline |
default constructor
|
inline |
print the current settings
|
inline |
load settings from file
References ct::core::loadMatrix(), and ct::optcon::StateObserverSettings< OUTPUT_DIM, STATE_DIM, SCALAR >::print().
ct::core::StateVector<STATE_DIM> ct::optcon::ExtendedKalmanFilterSettings< STATE_DIM, SCALAR >::x0 |
Initial state estimate.
ct::core::StateMatrix<STATE_DIM, SCALAR> ct::optcon::ExtendedKalmanFilterSettings< STATE_DIM, SCALAR >::P0 |
Initial covariance matrix.