|
| template<int N> |
| Eigen::Matrix< double, N, 2 *N+1 > | vulcan::estimation::sigma_points (const Eigen::Matrix< double, N, 1 > &x, const Eigen::Matrix< double, N, N > &P, const UKFParams ¶ms) |
| | Generate sigma points for UKF.
|
| template<int N, int U, typename DynamicsFunc> |
| FilterState< double, N > | vulcan::estimation::ukf_predict (const FilterState< double, N > &state, const Eigen::Matrix< double, U, 1 > &u, DynamicsFunc f, const ProcessNoise< N > &noise, const UKFParams ¶ms={}) |
| | Unscented Kalman filter predict step.
|
| template<int N, typename DynamicsFunc> |
| FilterState< double, N > | vulcan::estimation::ukf_predict (const FilterState< double, N > &state, DynamicsFunc f, const ProcessNoise< N > &noise, const UKFParams ¶ms={}) |
| | UKF predict (no control input).
|
| template<int N, int M, typename MeasurementFunc> |
| FilterState< double, N > | vulcan::estimation::ukf_update (const FilterState< double, N > &state, const Eigen::Matrix< double, M, 1 > &z, MeasurementFunc h, const MeasurementNoise< M > &noise, const UKFParams ¶ms={}) |
| | Unscented Kalman filter update step.
|
| template<int N, int U, int M, typename DynamicsFunc, typename MeasurementFunc> |
| FilterState< double, N > | vulcan::estimation::ukf_step (const FilterState< double, N > &state, const Eigen::Matrix< double, U, 1 > &u, const Eigen::Matrix< double, M, 1 > &z, DynamicsFunc f, MeasurementFunc h, const ProcessNoise< N > &Q, const MeasurementNoise< M > &R, const UKFParams ¶ms={}) |
| | Combined UKF step (predict + update).
|