Skip to content

Commit 4360735

Browse files
committed
Fix for UnscentedKalmannFilter
1 parent e7a29a6 commit 4360735

File tree

3 files changed

+8
-5
lines changed

3 files changed

+8
-5
lines changed

ct_optcon/examples/KalmanFiltering.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -105,7 +105,7 @@ int main(int argc, char** argv)
105105
new ct::optcon::CTSystemModel<state_dim, control_dim>(oscillator_observer_model, sensApprox, dFdv));
106106

107107
// set up the measurement model
108-
ct::core::OutputStateMatrix<output_dim, state_dim> dHdw;
108+
ct::core::OutputMatrix<output_dim> dHdw;
109109
dHdw.setIdentity();
110110
std::shared_ptr<ct::optcon::LinearMeasurementModel<output_dim, state_dim>> measModel(
111111
new ct::optcon::LTIMeasurementModel<output_dim, state_dim>(C, dHdw));

ct_optcon/include/ct/optcon/filter/UnscentedKalmanFilter-impl.h

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -62,6 +62,7 @@ UnscentedKalmanFilter<STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR>::UnscentedKalm
6262
const ct::core::StateMatrix<STATE_DIM, SCALAR>& P0)
6363
: Base(f, h, x0), alpha_(alpha), beta_(beta), kappa_(kappa), P_(P0)
6464
{
65+
computeWeights();
6566
}
6667

6768
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
7576
kappa_(ukf_settings.kappa),
7677
P_(ukf_settings.P0)
7778
{
79+
computeWeights();
7880
}
7981

8082
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
263265

264266
template <size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR>
265267
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)
268271
{
269272
// Use efficient matrix x vector computation
270273
return sigmaPoints * sigmaWeights_m_;

ct_optcon/include/ct/optcon/filter/UnscentedKalmanFilter.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -147,9 +147,9 @@ class UnscentedKalmanFilter final : public EstimatorBase<STATE_DIM, CONTROL_DIM,
147147
//! Predict measurements of sigma points.
148148
void computeSigmaPointMeasurements(SigmaPoints<OUTPUT_DIM>& sigmaMeasurementPoints, const ct::core::Time& t = 0);
149149

150-
//! Make a prediction based on sigma points.
150+
//! Make a prediction based on sigma points. Used for both state and output prediction.
151151
template <size_t DIM>
152-
state_vector_t computePredictionFromSigmaPoints(const SigmaPoints<DIM>& sigmaPoints);
152+
Eigen::Matrix<SCALAR, DIM, 1> computePredictionFromSigmaPoints(const SigmaPoints<DIM>& sigmaPoints);
153153

154154
private:
155155
state_matrix_t P_; //! Covariance matrix.

0 commit comments

Comments
 (0)