Skip to content

Commit 331cd7f

Browse files
Merge pull request #60 from xEnVrE/impl/gaussian_pdf
Implement utility for evaluating multivariate Gaussian density.
2 parents 9b623d0 + 3db7065 commit 331cd7f

File tree

9 files changed

+115
-32
lines changed

9 files changed

+115
-32
lines changed

CHANGELOG.md

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,8 @@
1212
- Implemented method GaussianMixture::resize().
1313
- Implemented method Gaussian::resize().
1414
- Implemented method ParticleSet::resize().
15+
- Implemented evaluation of a multivariate Gaussian probability density function in method utils::multivariate_gaussian_density.
16+
- Implemented evaluation of the logarithm of a multivariate Gaussian probability density function in method utils::multivariate_gaussian_log_density.
1517
- Methods EstimatesExtraction::extract() return a std::pair containing a boolean indicating if the estimate is valid and the estracted estimate.
1618
- Methods EstimatesExtraction::extract() assume that particle weights are in the log space.
1719
- Constructor HistoryBuffer::HistoryBuffer() takes the state size.
@@ -23,9 +25,14 @@
2325
##### `Filtering functions`
2426
- Added pure public virtual method GaussianPrediction::getStateModel() (required to properly implement GPFPrediction::getStateModel()).
2527
- Implemented method KFPrediction::getStateModel().
28+
- Implemented method KFCorrection::getLikelihood().
2629
- Implemented method UKFPrediction::getStateModel().
30+
- Implemented method UKFCorrection::getLikelihood().
31+
- Changed implementation of GaussianLikelihood::likelihood().
2732
- Changed implementation of GPFPrediction::getStateModel().
2833
- Changed implementation of GPFCorrection::getLikelihood().
34+
- Changed implementation of GPFCorrection::evaluateProposal().
35+
- Changed implementation of WhiteNoiseAcceleration::getTransitionProbability().
2936
- Fixed missing const(s) keywords in signature of method StateModel::getTransitionProbability().
3037
- Fixed missing const(s) keywords in signature of method WhiteNoiseAcceleration::getTransitionProbability().
3138
- SUKFCorrection::getNoiseCovarianceMatrix() is now virtual.

src/BayesFilters/include/BayesFilters/KFCorrection.h

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,11 +30,16 @@ class bfl::KFCorrection : public GaussianCorrection
3030

3131
MeasurementModel& getMeasurementModel() override;
3232

33+
std::pair<bool, Eigen::VectorXd> getLikelihood() override;
34+
3335
protected:
3436
void correctStep(const GaussianMixture& pred_state, GaussianMixture& corr_state) override;
3537

36-
private:
3738
std::unique_ptr<LinearMeasurementModel> measurement_model_;
39+
40+
Eigen::MatrixXd innovations_;
41+
42+
GaussianMixture meas_covariances_;
3843
};
3944

4045
#endif /* KFCORRECTION_H */

src/BayesFilters/include/BayesFilters/UKFCorrection.h

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,8 @@ class bfl::UKFCorrection : public GaussianCorrection
3434

3535
MeasurementModel& getMeasurementModel() override;
3636

37+
std::pair<bool, Eigen::VectorXd> getLikelihood() override;
38+
3739
protected:
3840
void correctStep(const GaussianMixture& pred_state, GaussianMixture& corr_state) override;
3941

@@ -53,6 +55,10 @@ class bfl::UKFCorrection : public GaussianCorrection
5355
* Unscented transform weight.
5456
*/
5557
sigma_point::UTWeight ut_weight_;
58+
59+
Eigen::MatrixXd innovations_;
60+
61+
GaussianMixture predicted_meas_;
5662
};
5763

5864
#endif /* UKFCORRECTION_H */

src/BayesFilters/include/BayesFilters/utils.h

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -61,6 +61,44 @@ std::unique_ptr<T> make_unique(Args&& ...args)
6161
double log_sum_exp(const Eigen::Ref<const Eigen::VectorXd>& arguments);
6262

6363

64+
/**
65+
* Evaluate the logarithm of a multivariate Gaussian probability density function.
66+
*
67+
* @param input Input representing the argument of the function as a vector or matrix.
68+
* @param mean The mean of the associated Gaussian distribution as a vector.
69+
* @param covariance The covariance matrix of the associated Gaussian distribution as a matrix.
70+
*
71+
* @return The value of the logarithm of the density function evaluated on the input data as a vector.
72+
*/
73+
template<typename Derived>
74+
Eigen::VectorXd multivariate_gaussian_log_density(const Eigen::MatrixBase<Derived>& input, const Eigen::Ref<const Eigen::VectorXd>& mean, const Eigen::Ref<const Eigen::MatrixXd>& covariance)
75+
{
76+
const auto diff = input.colwise() - mean;
77+
78+
Eigen::VectorXd values(diff.cols());
79+
for (std::size_t i = 0; i < diff.cols(); i++)
80+
values(i) = - 0.5 * (static_cast<double>(diff.rows()) * std::log(2.0 * M_PI) + std::log(covariance.determinant()) + (diff.col(i).transpose() * covariance.inverse() * diff.col(i)));
81+
82+
return values;
83+
}
84+
85+
86+
/**
87+
* Evaluate a multivariate Gaussian probability density function.
88+
*
89+
* @param input Input representing the argument of the function as a vector or matrix.
90+
* @param mean The mean of the associated Gaussian distribution as a vector.
91+
* @param covariance The covariance matrix of the associated Gaussian distribution as a matrix.
92+
*
93+
* @return The value of the density function evaluated on the input data as a vector.
94+
*/
95+
template<typename Derived>
96+
Eigen::VectorXd multivariate_gaussian_density(const Eigen::MatrixBase<Derived>& input, const Eigen::Ref<const Eigen::VectorXd>& mean, const Eigen::Ref<const Eigen::MatrixXd>& covariance)
97+
{
98+
return multivariate_gaussian_log_density(input, mean, covariance).array().exp();
99+
}
100+
101+
64102
/**
65103
* This template class provides methods to keep track of time. The default time unit is milliseconds,
66104
* but can be changed during object creation using a different std::chrono::duration type.

src/BayesFilters/src/GPFCorrection.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
*/
77

88
#include <BayesFilters/GPFCorrection.h>
9+
#include <BayesFilters/utils.h>
910

1011
#include <Eigen/Cholesky>
1112

@@ -144,7 +145,5 @@ double GPFCorrection::evaluateProposal
144145
{
145146
/* Evaluate the proposal distribution, a Gaussian centered in 'mean' and having
146147
covariance 'covariance', in the state 'state'. */
147-
VectorXd difference = state - mean;
148-
149-
return (-0.5 * static_cast<double>(difference.size()) * log(2.0 * M_PI) -0.5 * log(covariance.determinant()) -0.5 * (difference.transpose() * covariance.inverse() * difference).array()).exp().coeff(0);
148+
return utils::multivariate_gaussian_density(state, mean, covariance).coeff(0);
150149
}

src/BayesFilters/src/GaussianLikelihood.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
*/
77

88
#include <BayesFilters/GaussianLikelihood.h>
9+
#include <BayesFilters/utils.h>
910

1011
using namespace bfl;
1112
using namespace Eigen;
@@ -68,9 +69,7 @@ std::pair<bool, VectorXd> GaussianLikelihood::likelihood
6869
if (!valid_covariance_matrix)
6970
return std::make_pair(false, VectorXd::Zero(1));
7071

71-
72-
for (unsigned int i = 0; i < innovations.cols(); ++i)
73-
likelihood(i) = scale_factor_ * (-0.5 * static_cast<double>(innovations.rows()) * log(2.0*M_PI) - 0.5 * log(covariance_matrix.determinant()) - 0.5 * (innovations.col(i).transpose() * covariance_matrix.inverse() * innovations.col(i)).array()).exp().coeff(0);
72+
likelihood = scale_factor_ * utils::multivariate_gaussian_density(innovations, VectorXd::Zero(innovations.rows()), covariance_matrix);
7473

7574
return std::make_pair(true, likelihood);
7675
}

src/BayesFilters/src/KFCorrection.cpp

Lines changed: 26 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
*/
77

88
#include <BayesFilters/KFCorrection.h>
9+
#include <BayesFilters/utils.h>
910

1011
using namespace bfl;
1112
using namespace Eigen;
@@ -31,6 +32,21 @@ MeasurementModel& KFCorrection::getMeasurementModel()
3132
}
3233

3334

35+
std::pair<bool, VectorXd> KFCorrection::getLikelihood()
36+
{
37+
if ((innovations_.rows() == 0) || (innovations_.cols() == 0))
38+
return std::make_pair(false, VectorXd());
39+
40+
VectorXd likelihood(innovations_.cols());
41+
for (std::size_t i = 0; i < likelihood.size(); i++)
42+
{
43+
likelihood(i) = utils::multivariate_gaussian_density(innovations_.col(i), VectorXd::Zero(innovations_.rows()), meas_covariances_.covariance(i)).coeff(0);
44+
}
45+
46+
return std::make_pair(true, likelihood);
47+
}
48+
49+
3450
void KFCorrection::correctStep(const GaussianMixture& pred_state, GaussianMixture& corr_state)
3551
{
3652
/* Get the current measurement if available. */
@@ -79,25 +95,29 @@ void KFCorrection::correctStep(const GaussianMixture& pred_state, GaussianMixtur
7995
MatrixXd H = measurement_model_->getMeasurementMatrix();
8096

8197
/* Cast innovations once for all. */
82-
MatrixXd innovations = any::any_cast<MatrixXd&&>(std::move(innovation));
98+
innovations_ = any::any_cast<MatrixXd&&>(std::move(innovation));
99+
100+
/* Initialize measurement covariances.
101+
GaussianMixture will effectively resize only if it needs to. */
102+
meas_covariances_.resize(pred_state.components, H.rows());
83103

84104
/* Process all the components in the mixture. */
85-
for (size_t i=0; i < pred_state.components; i++)
105+
for (size_t i = 0; i < pred_state.components; i++)
86106
{
87107
/* Evaluate the measurement covariance matrix
88108
Py = H * Px * H' + R */
89-
MatrixXd Py = H * pred_state.covariance(i) * H.transpose() + R;
109+
meas_covariances_.covariance(i) = H * pred_state.covariance(i) * H.transpose() + R;
90110

91111
/* Evaluate the Kalman Gain
92112
K = Px * H' * (Py)^{-1} */
93-
MatrixXd K = pred_state.covariance(i) * H.transpose() * Py.inverse();
113+
MatrixXd K = pred_state.covariance(i) * H.transpose() * meas_covariances_.covariance(i).inverse();
94114

95115
/* Evaluate the filtered mean
96116
x_{k}+ = x{k}- + K * (y - y_predicted) */
97-
corr_state.mean(i) = pred_state.mean(i) + K * innovations.col(i);
117+
corr_state.mean(i) = pred_state.mean(i) + K * innovations_.col(i);
98118

99119
/* Evaluate the filtered covariance
100120
P_{k}+ = P_{k}- - K * Py * K' */
101-
corr_state.covariance(i).noalias() = pred_state.covariance(i) - K * Py * K.transpose();
121+
corr_state.covariance(i).noalias() = pred_state.covariance(i) - K * meas_covariances_.covariance(i) * K.transpose();
102122
}
103123
}

src/BayesFilters/src/UKFCorrection.cpp

Lines changed: 26 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
*/
77

88
#include <BayesFilters/UKFCorrection.h>
9+
#include <BayesFilters/utils.h>
910

1011
using namespace bfl;
1112
using namespace bfl::sigma_point;
@@ -61,6 +62,21 @@ MeasurementModel& UKFCorrection::getMeasurementModel()
6162
}
6263

6364

65+
std::pair<bool, VectorXd> UKFCorrection::getLikelihood()
66+
{
67+
if ((innovations_.rows() == 0) || (innovations_.cols() == 0))
68+
return std::make_pair(false, VectorXd());
69+
70+
VectorXd likelihood(innovations_.cols());
71+
for (std::size_t i = 0; i < innovations_.cols(); i++)
72+
{
73+
likelihood(i) = utils::multivariate_gaussian_density(innovations_.col(i), VectorXd::Zero(innovations_.rows()), predicted_meas_.covariance(i)).coeff(0);
74+
}
75+
76+
return std::make_pair(true, likelihood);
77+
}
78+
79+
6480
void UKFCorrection::correctStep(const GaussianMixture& pred_state, GaussianMixture& corr_state)
6581
{
6682
/* Pick the correct measurement model. */
@@ -80,7 +96,8 @@ void UKFCorrection::correctStep(const GaussianMixture& pred_state, GaussianMixtu
8096
/* Initialize predicted measurement GaussianMixture. */
8197
std::pair<std::size_t, std::size_t> meas_sizes = model.getOutputSize();
8298
std::size_t meas_size = meas_sizes.first + meas_sizes.second;
83-
GaussianMixture pred_meas(pred_state.components, meas_size);
99+
/* GaussianMixture will effectively resize only if it needs to. */
100+
predicted_meas_.resize(pred_state.components, meas_size);
84101

85102
/* Evaluate the joint state-measurement statistics, if possible. */
86103
bool valid = false;
@@ -94,11 +111,11 @@ void UKFCorrection::correctStep(const GaussianMixture& pred_state, GaussianMixtu
94111
std::tie(std::ignore, noise_covariance_matrix) = model.getNoiseCovarianceMatrix();
95112
pred_state_augmented.augmentWithNoise(noise_covariance_matrix);
96113

97-
std::tie(valid, pred_meas, Pxy) = sigma_point::unscented_transform(pred_state_augmented, ut_weight_, *measurement_model_);
114+
std::tie(valid, predicted_meas_, Pxy) = sigma_point::unscented_transform(pred_state_augmented, ut_weight_, *measurement_model_);
98115
}
99116
else if (type_ == UKFCorrectionType::Additive)
100117
{
101-
std::tie(valid, pred_meas, Pxy) = sigma_point::unscented_transform(pred_state, ut_weight_, *additive_measurement_model_);
118+
std::tie(valid, predicted_meas_, Pxy) = sigma_point::unscented_transform(pred_state, ut_weight_, *additive_measurement_model_);
102119
}
103120

104121
if (!valid)
@@ -113,8 +130,8 @@ void UKFCorrection::correctStep(const GaussianMixture& pred_state, GaussianMixtu
113130
/* This temporary is required since some MeasurementModel::innovation methods may try to cast from
114131
const Ref<const MatrixXd> to MatrixXd resulting in a bfl::any::bad_any_cast.
115132
116-
Hopefully, using std::move, it is possible to steal the memory from pred_meas.mean(). */
117-
MatrixXd y_p = std::move(pred_meas.mean());
133+
Hopefully, using std::move, it is possible to steal the memory from predicted_meas_.mean(). */
134+
MatrixXd y_p = std::move(predicted_meas_.mean());
118135
std::tie(valid_innovation, innovation) = model.innovation(y_p, measurement);
119136

120137
if (!valid_innovation)
@@ -124,21 +141,21 @@ void UKFCorrection::correctStep(const GaussianMixture& pred_state, GaussianMixtu
124141
}
125142

126143
/* Cast innovations once for all. */
127-
MatrixXd innovations = any::any_cast<MatrixXd&&>(std::move(innovation));
144+
innovations_ = any::any_cast<MatrixXd&&>(std::move(innovation));
128145

129146
/* Process all the components in the mixture. */
130147
for (size_t i=0; i < pred_state.components; i++)
131148
{
132149
/* Evaluate the Kalman Gain
133150
K = Pxy * (Py)^{-1} */
134-
MatrixXd K = Pxy.middleCols(meas_size * i, meas_size) * pred_meas.covariance(i).inverse();
151+
MatrixXd K = Pxy.middleCols(meas_size * i, meas_size) * predicted_meas_.covariance(i).inverse();
135152

136153
/* Evaluate the filtered mean.
137154
x_{k}+ = x{k}- + K * innovation */
138-
corr_state.mean(i) = pred_state.mean(i) + K * innovations.col(i);
155+
corr_state.mean(i) = pred_state.mean(i) + K * innovations_.col(i);
139156

140157
/* Evaluate the filtered covariance
141158
P_{k}+ = P_{k}- - K * Py * K' */
142-
corr_state.covariance(i) = pred_state.covariance(i) - K * pred_meas.covariance(i) * K.transpose();
159+
corr_state.covariance(i) = pred_state.covariance(i) - K * predicted_meas_.covariance(i) * K.transpose();
143160
}
144161
}

src/BayesFilters/src/WhiteNoiseAcceleration.cpp

Lines changed: 2 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
*/
77

88
#include <BayesFilters/WhiteNoiseAcceleration.h>
9+
#include <BayesFilters/utils.h>
910

1011
#include <cmath>
1112
#include <utility>
@@ -139,16 +140,7 @@ MatrixXd WhiteNoiseAcceleration::getStateTransitionMatrix()
139140

140141
VectorXd WhiteNoiseAcceleration::getTransitionProbability(const Ref<const MatrixXd>& prev_states, const Ref<const MatrixXd>& cur_states)
141142
{
142-
VectorXd probabilities(prev_states.cols());
143-
MatrixXd differences = cur_states - prev_states;
144-
145-
std::size_t size = differences.rows();
146-
for (std::size_t i = 0; i < prev_states.cols(); i++)
147-
{
148-
probabilities(i) = (-0.5 * static_cast<double>(size) * log(2.0 * M_PI) + -0.5 * log(Q_.determinant()) -0.5 * (differences.col(i).transpose() * Q_.inverse() * differences.col(i)).array()).exp().coeff(0);
149-
}
150-
151-
return probabilities;
143+
return utils::multivariate_gaussian_density(prev_states, prev_states.col(0), Q_);
152144
}
153145

154146

0 commit comments

Comments
 (0)