UnscentedKalmanFilter.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * ArmarX is free software; you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License version 2 as
6  * published by the Free Software Foundation.
7  *
8  * ArmarX is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  * GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * @package ROBDEKON
17  * @author Christoph Pohl ( christoph dot pohl at kit dot edu )
18  * @date 16.03.21
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  *
22  * Code adapted to C++ from: https://github.com/CAOR-MINES-ParisTech/ukfm
23  * See also:
24  * - https://arxiv.org/pdf/2002.00878.pdf
25  * - https://ieeexplore.ieee.org/document/8206066/
26  */
27 
28 #include "UnscentedKalmanFilter.h"
29 
30 #include <complex>
31 #include <utility>
32 
34 
35 template <typename SystemModelT>
37  ObsCovT R,
38  const AlphaT& alpha,
39  StateT state0,
40  StateCovT P0) :
41  Q_(Q),
42  chol_Q_(Q.llt().matrixL().transpose()),
43  R_(std::move(R)),
44  alpha_(alpha),
45  state_(std::move(state0)),
46  P_(std::move(P0)),
47  weights_(alpha)
48 {
49 }
50 
51 template <typename SystemModelT>
52 void
54 {
55  StateCovT P = P_ + eps * StateCovT::Identity();
56  ARMARX_CHECK(P.allFinite());
57  ControlNoiseT w = ControlNoiseT::Zero();
58  // update mean
59  StateT state_after = SystemModelT::propagationFunction(state_, omega, w, dt);
60 
61  // set sigma points (Xi in paper when on Manifold, sigma in Tangent Space)
62  Eigen::LLT<StateCovT> llt = P.llt();
63  if (llt.info() != Eigen::ComputationInfo::Success)
64  {
65  P = calculateClosestPosSemidefMatrix(P);
66  P += eps * StateCovT::Identity();
67  llt = P.llt();
68  ARMARX_CHECK(llt.info() == Eigen::ComputationInfo::Success);
69  }
70  StateCovT xi_j_before =
71  weights_.state.sqrt_d_lambda * llt.matrixL().transpose().toDenseMatrix();
74 
75  auto propagate_and_retract = [&omega, &dt, &state_after](long row,
76  long offset,
77  const StateT& state,
78  const ControlNoiseT& noise,
79  auto& xi_j) -> void
80  {
81  const StateT sig_j_after = SystemModelT::propagationFunction(state, omega, noise, dt);
82  xi_j.row(offset + row) = SystemModelT::inverseRetraction(state_after, sig_j_after);
83  };
84 
85  auto calculate_covariance = [](FloatT wj, FloatT w0, auto& xi_j) -> StateCovT
86  {
87  SigmaPointsT xi_0 = wj * xi_j.colwise().sum();
88  xi_j.rowwise() -= xi_0.transpose();
89  StateCovT cov_after = wj * xi_j.transpose() * xi_j + w0 * xi_0 * xi_0.transpose();
90  return cov_after;
91  };
92 
93  for (long j = 0; j < dim::state; j++)
94  {
95  const SigmaPointsT sigma = xi_j_before.row(j);
96  const StateT sig_j_plus = SystemModelT::retraction(state_, sigma);
97  const StateT sig_j_minus = SystemModelT::retraction(state_, -sigma);
98  propagate_and_retract(j, 0, sig_j_plus, w, xi_j_after);
99  propagate_and_retract(j, dim::state, sig_j_minus, w, xi_j_after);
100  }
101 
102  StateCovT P_after = calculate_covariance(weights_.state.wj, weights_.state.w0, xi_j_after);
103  ARMARX_CHECK(P_after.allFinite());
104  for (long j = 0; j < dim::control; j++)
105  {
106  const ControlNoiseT w_plus = weights_.control.sqrt_d_lambda * chol_Q_.row(j);
107  const ControlNoiseT w_minus = -weights_.control.sqrt_d_lambda * chol_Q_.row(j);
108  propagate_and_retract(j, 0, state_, w_plus, w_j_after);
109  propagate_and_retract(j, dim::control, state_, w_minus, w_j_after);
110  }
111 
112  StateCovT Q = calculate_covariance(weights_.control.wj, weights_.control.w0, w_j_after);
113  ARMARX_CHECK(Q.allFinite());
114  StateCovT new_P = P_after + Q;
115  P_ = std::move((new_P + new_P.transpose()) / 2.0f);
116  state_ = std::move(state_after);
117 }
118 
119 template <typename SystemModelT>
120 void
122 {
123  StateCovT P = P_ + eps * StateCovT::Identity();
124  ARMARX_CHECK(P.allFinite());
125  StateCovT xi_j = weights_.state.sqrt_d_lambda * P.llt().matrixL().transpose().toDenseMatrix();
126  ARMARX_CHECK(P.llt().info() == Eigen::ComputationInfo::Success);
127  ARMARX_CHECK(xi_j.allFinite());
130  ObsT y_hat = SystemModelT::observationFunction(state_);
131 
132  for (long j = 0; j < dim::state; j++)
133  {
134  const SigmaPointsT sigma = xi_j.row(j);
135  const StateT sig_j_plus = SystemModelT::retraction(state_, sigma);
136  const StateT sig_j_minus = SystemModelT::retraction(state_, -sigma);
137  y_j.row(j) = SystemModelT::observationFunction(sig_j_plus);
138  y_j.row(j + dim::state) = SystemModelT::observationFunction(sig_j_minus);
139  }
140  ARMARX_CHECK(y_j.allFinite());
141  const ObsT y_mean =
142  weights_.update.wm * y_hat + weights_.update.wj * y_j.colwise().sum().transpose();
143  y_j.rowwise() -= y_mean.transpose();
144  y_hat -= y_mean;
145 
146  const ObsCovT P_yy = weights_.update.w0 * y_hat * y_hat.transpose() +
147  weights_.update.wj * y_j.transpose() * y_j + R_;
148  ARMARX_CHECK(P_yy.allFinite());
150  weights_.update.wj *
151  (Eigen::Matrix<FloatT, dim::state, 2 * dim::state>() << xi_j, -xi_j).finished() *
152  y_j /* + weights_.update.w0 * xi_0 * y_hat.transpose()*/;
153  ARMARX_CHECK(P_xiy.allFinite());
155  P_yy.colPivHouseholderQr().solve(P_xiy.transpose()).transpose();
156  FloatT relative_error = (P_yy * K.transpose() - P_xiy.transpose()).norm() / P_xiy.norm();
157  ARMARX_CHECK(relative_error < 1e-4);
158  ARMARX_CHECK(K.allFinite());
159  SigmaPointsT xi_plus = K * (y - y_mean);
160  ARMARX_CHECK(xi_plus.allFinite());
161  state_ = SystemModelT::retraction(state_, xi_plus);
162  StateCovT new_P = P - K * (P_yy)*K.transpose();
163 
164  // make result symmetric
165  P_ = calculateClosestPosSemidefMatrix(new_P);
166 }
167 
168 template <typename SystemModelT>
171 {
172  return state_;
173 }
174 
175 template <typename SystemModelT>
178 {
179  return P_;
180 }
181 
182 template <typename SystemModelT>
186 {
187  const StateCovT new_P = ((cov + cov.transpose()) / 2.0f);
188  Eigen::EigenSolver<StateCovT> solver(new_P);
189  Eigen::Matrix<FloatT, dim::state, dim::state> D = solver.eigenvalues().real().asDiagonal();
190  const Eigen::Matrix<FloatT, dim::state, dim::state> V = solver.eigenvectors().real();
191  D = D.cwiseMax(0);
192 
193  return (V * D * V.inverse());
194 }
195 
196 template <typename SystemModelT>
198  state(dim::state, alpha(0)), control(dim::control, alpha(1)), update(dim::state, alpha(2))
199 {
200 }
201 
202 template <typename SystemModelT>
204 {
205  ARMARX_CHECK_GREATER(alpha, 0);
206  FloatT m = (alpha * alpha - 1) * l;
207  sqrt_d_lambda = std::sqrt(l + m);
208  wj = 1 / (2 * (l + m));
209  wm = m / (m + l);
210  w0 = m / (m + l) + 3 - alpha * alpha;
211 }
212 
214 
216 
218 
220 
221 
222 ///////////////////
223 
224 
225 
226 template <typename SystemModelT>
228  ObsCovT R,
229  const AlphaT& alpha,
230  StateT state0,
231  StateCovT P0) :
232  R_(std::move(R)),
233  alpha_(alpha),
234  state_(std::move(state0)),
235  P_(std::move(P0)),
236  weights_(alpha)
237 {
238 }
239 
240 template <typename SystemModelT>
241 void
243 {
244  StateCovT P = P_ + eps * StateCovT::Identity();
245  ARMARX_CHECK(P.allFinite());
246  // ControlNoiseT w = ControlNoiseT::Zero();
247  // update mean
248  StateT state_after = SystemModelT::propagationFunction(state_, dt);
249 
250  // set sigma points (Xi in paper when on Manifold, sigma in Tangent Space)
251  Eigen::LLT<StateCovT> llt = P.llt();
252  if (llt.info() != Eigen::ComputationInfo::Success)
253  {
254  P = calculateClosestPosSemidefMatrix(P);
255  P += eps * StateCovT::Identity();
256  llt = P.llt();
257  ARMARX_CHECK(llt.info() == Eigen::ComputationInfo::Success);
258  }
259  StateCovT xi_j_before =
260  weights_.state.sqrt_d_lambda * llt.matrixL().transpose().toDenseMatrix();
263 
264  auto propagate_and_retract = [&dt, &state_after](long row,
265  long offset,
266  const StateT& state,
267  auto& xi_j) -> void
268  {
269  const StateT sig_j_after = SystemModelT::propagationFunction(state, dt);
270  xi_j.row(offset + row) = SystemModelT::inverseRetraction(state_after, sig_j_after);
271  };
272 
273  auto calculate_covariance = [](FloatT wj, FloatT w0, auto& xi_j) -> StateCovT
274  {
275  SigmaPointsT xi_0 = wj * xi_j.colwise().sum();
276  xi_j.rowwise() -= xi_0.transpose();
277  StateCovT cov_after = wj * xi_j.transpose() * xi_j + w0 * xi_0 * xi_0.transpose();
278  return cov_after;
279  };
280 
281  for (long j = 0; j < dim::state; j++)
282  {
283  const SigmaPointsT sigma = xi_j_before.row(j);
284  const StateT sig_j_plus = SystemModelT::retraction(state_, sigma);
285  const StateT sig_j_minus = SystemModelT::retraction(state_, -sigma);
286  propagate_and_retract(j, 0, sig_j_plus, xi_j_after);
287  propagate_and_retract(j, dim::state, sig_j_minus, xi_j_after);
288  }
289 
290  StateCovT P_after = calculate_covariance(weights_.state.wj, weights_.state.w0, xi_j_after);
291  ARMARX_CHECK(P_after.allFinite());
292  // for (long j = 0; j < dim::control; j++)
293  // {
294  // const ControlNoiseT w_plus = weights_.control.sqrt_d_lambda * chol_Q_.row(j);
295  // const ControlNoiseT w_minus = -weights_.control.sqrt_d_lambda * chol_Q_.row(j);
296  // propagate_and_retract(j, 0, state_, w_plus, w_j_after);
297  // propagate_and_retract(j, dim::control, state_, w_minus, w_j_after);
298  // }
299 
300  // StateCovT Q = calculate_covariance(weights_.control.wj, weights_.control.w0, w_j_after);
301  // ARMARX_CHECK(Q.allFinite());
302  StateCovT new_P = P_after; // + Q;
303  P_ = std::move((new_P + new_P.transpose()) / 2.0f);
304  // P_ = new_P;
305  state_ = std::move(state_after);
306 }
307 
308 template <typename SystemModelT>
309 void
311 {
312  StateCovT P = P_ + eps * StateCovT::Identity();
313  ARMARX_CHECK(P.allFinite());
314  StateCovT xi_j = weights_.state.sqrt_d_lambda * P.llt().matrixL().transpose().toDenseMatrix();
315  ARMARX_CHECK(P.llt().info() == Eigen::ComputationInfo::Success);
316  ARMARX_CHECK(xi_j.allFinite());
319  ObsT y_hat = SystemModelT::observationFunction(state_);
320 
321  for (long j = 0; j < dim::state; j++)
322  {
323  const SigmaPointsT sigma = xi_j.row(j);
324  const StateT sig_j_plus = SystemModelT::retraction(state_, sigma);
325  const StateT sig_j_minus = SystemModelT::retraction(state_, -sigma);
326  y_j.row(j) = SystemModelT::observationFunction(sig_j_plus);
327  y_j.row(j + dim::state) = SystemModelT::observationFunction(sig_j_minus);
328  }
329  ARMARX_CHECK(y_j.allFinite());
330  const ObsT y_mean =
331  weights_.update.wm * y_hat + weights_.update.wj * y_j.colwise().sum().transpose();
332  y_j.rowwise() -= y_mean.transpose();
333  y_hat -= y_mean;
334 
335  const ObsCovT P_yy = weights_.update.w0 * y_hat * y_hat.transpose() +
336  weights_.update.wj * y_j.transpose() * y_j + R_;
337  ARMARX_CHECK(P_yy.allFinite());
339  weights_.update.wj *
340  (Eigen::Matrix<FloatT, dim::state, 2 * dim::state>() << xi_j, -xi_j).finished() *
341  y_j /* + weights_.update.w0 * xi_0 * y_hat.transpose()*/;
342  ARMARX_CHECK(P_xiy.allFinite());
344  P_yy.colPivHouseholderQr().solve(P_xiy.transpose()).transpose();
345  FloatT relative_error = (P_yy * K.transpose() - P_xiy.transpose()).norm() / P_xiy.norm();
346  ARMARX_CHECK(relative_error < 1e-4);
347  ARMARX_CHECK(K.allFinite());
348 
349  const auto residual = y - y_mean;
350 
351  SigmaPointsT xi_plus = K * residual;
352  ARMARX_CHECK(xi_plus.allFinite());
353  state_ = SystemModelT::retraction(state_, xi_plus);
354  StateCovT new_P = P - K * (P_yy)*K.transpose();
355 
356  // make result symmetric
357  P_ = calculateClosestPosSemidefMatrix(new_P);
358 }
359 
360 template <typename SystemModelT>
363 {
364  return state_;
365 }
366 
367 template <typename SystemModelT>
370 {
371  return P_;
372 }
373 
374 template <typename SystemModelT>
378 {
379  const StateCovT new_P = ((cov + cov.transpose()) / 2.0f);
380  Eigen::EigenSolver<StateCovT> solver(new_P);
381  Eigen::Matrix<FloatT, dim::state, dim::state> D = solver.eigenvalues().real().asDiagonal();
382  const Eigen::Matrix<FloatT, dim::state, dim::state> V = solver.eigenvectors().real();
383  D = D.cwiseMax(0);
384 
385  return (V * D * V.inverse());
386 }
387 
388 template <typename SystemModelT>
390  state(dim::state, alpha(0)), update(dim::state, alpha(2))
391 {
392 }
393 
394 template <typename SystemModelT>
396 {
397  ARMARX_CHECK_GREATER(alpha, 0);
398  FloatT m = (alpha * alpha - 1) * l;
399  sqrt_d_lambda = std::sqrt(l + m);
400  wj = 1 / (2 * (l + m));
401  wm = m / (m + l);
402  w0 = m / (m + l) + 3 - alpha * alpha;
403 }
GfxTL::sqrt
VectorXD< D, T > sqrt(const VectorXD< D, T > &a)
Definition: VectorXD.h:662
UnscentedKalmanFilter
Definition: UnscentedKalmanFilter.h:37
UnscentedKalmanFilter::UnscentedKalmanFilter
UnscentedKalmanFilter()=delete
UnscentedKalmanFilterWithoutControl::Weights::W::sqrt_d_lambda
float sqrt_d_lambda
Definition: UnscentedKalmanFilter.h:136
UnscentedKalmanFilterWithoutControl::getCurrentStateCovariance
const StateCovT & getCurrentStateCovariance() const
Definition: UnscentedKalmanFilter.cpp:369
UnscentedKalmanFilter::FloatT
typename SystemModelT::FloatT FloatT
Definition: UnscentedKalmanFilter.h:40
UnscentedKalmanFilterWithoutControl::propagation
void propagation(FloatT dt)
Definition: UnscentedKalmanFilter.cpp:242
UnscentedKalmanFilter::Weights::W::sqrt_d_lambda
float sqrt_d_lambda
Definition: UnscentedKalmanFilter.h:77
ARMARX_CHECK_GREATER
#define ARMARX_CHECK_GREATER(lhs, rhs)
This macro evaluates whether lhs is greater (>) than rhs and if it turns out to be false it will thro...
Definition: ExpressionException.h:116
UnscentedKalmanFilter::propagation
void propagation(const ControlT &omega, FloatT dt)
Definition: UnscentedKalmanFilter.cpp:53
UnscentedKalmanFilter::StateT
typename SystemModelT::StateT StateT
Definition: UnscentedKalmanFilter.h:44
ARMARX_CHECK
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
Definition: ExpressionException.h:82
UnscentedKalmanFilter::Weights::W::wm
float wm
Definition: UnscentedKalmanFilter.h:77
UnscentedKalmanFilter::Weights::W::wj
float wj
Definition: UnscentedKalmanFilter.h:77
UnscentedKalmanFilterWithoutControl::FloatT
typename SystemModelT::FloatT FloatT
Definition: UnscentedKalmanFilter.h:105
SystemModelSE3::retraction
static StateT retraction(const StateT &state, const SigmaPointsT &sigmaPoints)
Definition: SystemModel.cpp:62
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:523
SystemModelSE3::inverseRetraction
static SigmaPointsT inverseRetraction(const StateT &state1, const StateT &state2)
Definition: SystemModel.cpp:52
UnscentedKalmanFilter::ControlNoiseT
typename SystemModelT::ControlNoiseT ControlNoiseT
Definition: UnscentedKalmanFilter.h:47
SystemModelSE3::observationFunction
static ObsT observationFunction(const StateT &state)
Definition: SystemModel.cpp:33
UnscentedKalmanFilterWithoutControl::getCurrentState
const StateT & getCurrentState() const
Definition: UnscentedKalmanFilter.cpp:362
UnscentedKalmanFilter::update
void update(const ObsT &y)
Definition: UnscentedKalmanFilter.cpp:121
SystemModelSE3::propagationFunction
static StateT propagationFunction(const StateT &state, const ControlT &control, const ControlNoiseT &noise, FloatT dt)
Definition: SystemModel.cpp:41
armarx::armem::server::ltm::util::mongodb::detail::update
bool update(mongocxx::collection &coll, const nlohmann::json &query, const nlohmann::json &update)
Definition: mongodb.cpp:67
UnscentedKalmanFilterWithoutControl::StateT
typename SystemModelT::StateT StateT
Definition: UnscentedKalmanFilter.h:109
UnscentedKalmanFilterWithoutControl::SigmaPointsT
typename SystemModelT::SigmaPointsT SigmaPointsT
Definition: UnscentedKalmanFilter.h:110
ExpressionException.h
UnscentedKalmanFilterWithoutControl::Weights::W::W
W(size_t l, FloatT alpha)
Definition: UnscentedKalmanFilter.cpp:395
UnscentedKalmanFilter::getCurrentState
const StateT & getCurrentState() const
Definition: UnscentedKalmanFilter.cpp:170
UnscentedKalmanFilterWithoutControl
Definition: UnscentedKalmanFilter.h:102
std
Definition: Application.h:66
UnscentedKalmanFilterWithoutControl::UnscentedKalmanFilterWithoutControl
UnscentedKalmanFilterWithoutControl()=delete
UnscentedKalmanFilter::getCurrentStateCovariance
const StateCovT & getCurrentStateCovariance() const
Definition: UnscentedKalmanFilter.cpp:177
UnscentedKalmanFilterWithoutControl::Weights::W::wm
float wm
Definition: UnscentedKalmanFilter.h:136
UnscentedKalmanFilterWithoutControl::Weights::W::wj
float wj
Definition: UnscentedKalmanFilter.h:136
Eigen::Matrix< FloatT, dim::control, dim::control >
UnscentedKalmanFilter::Weights::W::w0
float w0
Definition: UnscentedKalmanFilter.h:77
UnscentedKalmanFilter.h
UnscentedKalmanFilter::SigmaPointsT
typename SystemModelT::SigmaPointsT SigmaPointsT
Definition: UnscentedKalmanFilter.h:48
UnscentedKalmanFilterWithoutControl::update
void update(const ObsT &y)
Definition: UnscentedKalmanFilter.cpp:310
armarx::transpose
std::vector< std::vector< T > > transpose(const std::vector< std::vector< T >> &src, Thrower thrower)
Definition: SimoxCSpace.cpp:706
UnscentedKalmanFilter::Weights::W::W
W(size_t l, FloatT alpha)
Definition: UnscentedKalmanFilter.cpp:203
control
This file is part of ArmarX.
dt
constexpr T dt
Definition: UnscentedKalmanFilterTest.cpp:42
UnscentedKalmanFilter::ControlT
typename SystemModelT::ControlT ControlT
Definition: UnscentedKalmanFilter.h:45
UnscentedKalmanFilterWithoutControl::Weights::W::w0
float w0
Definition: UnscentedKalmanFilter.h:136
norm
double norm(const Point &a)
Definition: point.hpp:94