@@ -62,6 +62,7 @@ UnscentedKalmanFilter<STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR>::UnscentedKalm
62
62
const ct::core::StateMatrix<STATE_DIM, SCALAR>& P0)
63
63
: Base(f, h, x0), alpha_(alpha), beta_(beta), kappa_(kappa), P_(P0)
64
64
{
65
+ computeWeights ();
65
66
}
66
67
67
68
template <size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR>
@@ -75,6 +76,7 @@ UnscentedKalmanFilter<STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR>::UnscentedKalm
75
76
kappa_(ukf_settings.kappa),
76
77
P_(ukf_settings.P0)
77
78
{
79
+ computeWeights ();
78
80
}
79
81
80
82
template <size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR>
@@ -263,8 +265,9 @@ void UnscentedKalmanFilter<STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR>::computeS
263
265
264
266
template <size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR>
265
267
template <size_t DIM>
266
- auto UnscentedKalmanFilter<STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR>::computePredictionFromSigmaPoints(
267
- const SigmaPoints<DIM>& sigmaPoints) -> state_vector_t
268
+ Eigen::Matrix<SCALAR, DIM, 1 >
269
+ UnscentedKalmanFilter<STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR>::computePredictionFromSigmaPoints(
270
+ const SigmaPoints<DIM>& sigmaPoints)
268
271
{
269
272
// Use efficient matrix x vector computation
270
273
return sigmaPoints * sigmaWeights_m_;
0 commit comments