mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
dkf.h
1 // clang: MatousFormat
7 #ifndef DKF_H
8 #define DKF_H
9 
10 #include <mrs_lib/lkf.h>
11 #include <mrs_lib/geometry/misc.h>
12 #include <iostream>
13 
14 namespace mrs_lib
15 {
16 
17  /* class DKF //{ */
26  template <int n_states, int n_inputs>
27  class DKF : public LKF<n_states, n_inputs, -1>
28  {
29  public:
30  /* DKF definitions (typedefs, constants etc) //{ */
31  using Base_class = LKF<n_states, n_inputs, -1>;
33  static constexpr int n = Base_class::n;
34  static constexpr int m = Base_class::m;
35  static constexpr int p = Base_class::p;
37  using x_t = typename Base_class::x_t;
38  using u_t = typename Base_class::u_t;
39  using z_t = typename Base_class::z_t;
40  using P_t = typename Base_class::P_t;
41  using R_t = typename Base_class::R_t;
42  using Q_t = typename Base_class::Q_t;
45  typedef Eigen::Matrix<double, n, n> A_t;
46  typedef Eigen::Matrix<double, n, m> B_t;
47  typedef Eigen::Matrix<double, p, n> H_t;
48  typedef Eigen::Matrix<double, n, p> K_t;
50  using mat2_t = Eigen::Matrix<double, 2, 2>;
51  using mat3_t = Eigen::Matrix<double, 3, 3>;
52  using pt3_t = mrs_lib::geometry::vec3_t;
53  using pt2_t = mrs_lib::geometry::vec2_t;
54  using vec3_t = mrs_lib::geometry::vec3_t;
55  //}
56 
57  public:
64  DKF(){};
65 
73  DKF(const A_t& A, const B_t& B) : Base_class(A, B, {}) {};
74 
75  /* correctLine() method //{ */
89  virtual std::enable_if_t<(n > 3), statecov_t> correctLine(const statecov_t& sc, const pt3_t& line_origin, const vec3_t& line_direction, const double line_variance) const
90  {
91  assert(line_direction.norm() > 0.0);
92 
93  using M_t = Eigen::Matrix<double, 3, n>;
94  using W_t = Eigen::Matrix<double, 3, 1>;
95  using N_t = Eigen::Matrix<double, 3, 2>;
96  using o_t = Eigen::Matrix<double, 3, 1>;
97  using R_t = Eigen::Matrix<double, 2, 2>;
98 
99  const M_t M = M_t::Identity();
100  const W_t W = line_direction;
101  const o_t o = line_origin;
102 
103  // doesn't work - the kernel is always zero for some reason
104  /* const Eigen::FullPivLU<W_t> lu(W); */
105  /* const N_t N = lu.kernel(); */
106  // works for a line measurement
107  const mat3_t rot = mrs_lib::geometry::rotationBetween(W_t::UnitX(), W);
108  // the first column should have the same direction as W - we don't care about it,
109  // take the second and third column vectors, those are the null space of W
110  const N_t N = rot.block<3, 2>(0, 1);
111  const z_t z = N.transpose() * o;
112  const H_t H = N.transpose() * M;
113  const R_t R = line_variance * N.transpose() * N;
114 
115  return this->correction_impl(sc, z, R, H);
116  };
117  //}
118 
119  /* correctPlane() method //{ */
133  virtual std::enable_if_t<(n > 3), statecov_t> correctPlane(const statecov_t& sc, const pt3_t& plane_origin, const vec3_t& plane_normal, const double plane_variance) const
134  {
135  assert(plane_normal.norm() > 0.0);
136 
137  // we don't need W, since the plane is minimally defined by its origin and normal, where the normal is a basis for its null space
138  using M_t = Eigen::Matrix<double, 3, n>;
139  using N_t = Eigen::Matrix<double, 3, 1>;
140  using o_t = Eigen::Matrix<double, 3, 1>;
141  using R_t = Eigen::Matrix<double, 1, 1>;
142 
143  const M_t M = M_t::Identity();
144  const o_t o = plane_origin;
145 
146  const N_t N = plane_normal.normalized(); //works for plane
147  const z_t z = N.transpose() * o;
148  const H_t H = N.transpose() * M;
149  const R_t R = (R_t() << plane_variance).finished(); //R is a scalar here
150 
151  return this->correction_impl(sc, z, R, H);
152  };
153  //}
154  };
155  //}
156 
157 } // namespace mrs_lib
158 
159 #endif // DKF_H
mrs_lib::LKF< n_states, n_inputs, -1 >::Q_t
typename Base_class::Q_t Q_t
Process noise covariance matrix type .
Definition: lkf.h:52
mrs_lib::LKF< n_states, n_inputs, -1 >::p
static constexpr int p
Length of the measurement vector of the system.
Definition: lkf.h:44
mrs_lib::DKF::m
static constexpr int m
Length of the input vector of the system.
Definition: dkf.h:34
mrs_lib::LKF< n_states, n_inputs, -1 >::P_t
typename Base_class::P_t P_t
State uncertainty covariance matrix type .
Definition: lkf.h:50
mrs_lib::DKF::H_t
Eigen::Matrix< double, p, n > H_t
State to measurement mapping matrix type .
Definition: dkf.h:47
mrs_lib::DKF::correctPlane
virtual std::enable_if_t<(n > 3), statecov_t > correctPlane(const statecov_t &sc, const pt3_t &plane_origin, const vec3_t &plane_normal, const double plane_variance) const
Applies the correction (update, measurement, data) step of the Kalman filter.
Definition: dkf.h:133
mrs_lib::DKF::x_t
typename Base_class::x_t x_t
State vector type .
Definition: dkf.h:37
mrs_lib::LKF< n_states, n_inputs, -1 >::H
H_t H
The state to measurement mapping matrix .
Definition: lkf.h:150
mrs_lib::DKF::statecov_t
typename Base_class::statecov_t statecov_t
Helper struct for passing around the state and its covariance in one variable.
Definition: dkf.h:43
mrs_lib::LKF< n_states, n_inputs, -1 >::statecov_t
typename Base_class::statecov_t statecov_t
Helper struct for passing around the state and its covariance in one variable.
Definition: lkf.h:53
mrs_lib::LKF< n_states, n_inputs, -1 >::R_t
typename Base_class::R_t R_t
Measurement noise covariance matrix type .
Definition: lkf.h:51
mrs_lib::DKF::p
static constexpr int p
Length of the measurement vector of the system.
Definition: dkf.h:35
mrs_lib::DKF::P_t
typename Base_class::P_t P_t
State uncertainty covariance matrix type .
Definition: dkf.h:40
mrs_lib::DKF::K_t
Eigen::Matrix< double, n, p > K_t
Kalman gain matrix type .
Definition: dkf.h:48
mrs_lib::DKF::n
static constexpr int n
Length of the state vector of the system.
Definition: dkf.h:33
mrs_lib::DKF::z_t
typename Base_class::z_t z_t
Measurement vector type .
Definition: dkf.h:39
mrs_lib::DKF::R_t
typename Base_class::R_t R_t
Measurement noise covariance matrix type .
Definition: dkf.h:41
misc.h
Defines useful geometry utilities and functions.
mrs_lib::LKF< n_states, n_inputs, -1 >::x_t
typename Base_class::x_t x_t
State vector type .
Definition: lkf.h:47
mrs_lib
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition: attitude_converter.h:29
mrs_lib::DKF::u_t
typename Base_class::u_t u_t
Input vector type .
Definition: dkf.h:38
mrs_lib::LKF< n_states, n_inputs, -1 >::n
static constexpr int n
Length of the state vector of the system.
Definition: lkf.h:42
mrs_lib::LKF< n_states, n_inputs, -1 >::B
B_t B
The input to state mapping matrix .
Definition: lkf.h:149
mrs_lib::DKF::DKF
DKF(const A_t &A, const B_t &B)
The main constructor.
Definition: dkf.h:73
mrs_lib::DKF::Q_t
typename Base_class::Q_t Q_t
Process noise covariance matrix type .
Definition: dkf.h:42
mrs_lib::LKF
Implementation of the Linear Kalman filter .
Definition: lkf.h:38
mrs_lib::DKF::B_t
Eigen::Matrix< double, n, m > B_t
Input to state mapping matrix type .
Definition: dkf.h:46
mrs_lib::LKF< n_states, n_inputs, -1 >::z_t
typename Base_class::z_t z_t
Measurement vector type .
Definition: lkf.h:49
mrs_lib::LKF< n_states, n_inputs, -1 >::m
static constexpr int m
Length of the input vector of the system.
Definition: lkf.h:43
mrs_lib::DKF::correctLine
virtual std::enable_if_t<(n > 3), statecov_t > correctLine(const statecov_t &sc, const pt3_t &line_origin, const vec3_t &line_direction, const double line_variance) const
Applies the correction (update, measurement, data) step of the Kalman filter.
Definition: dkf.h:89
mrs_lib::DKF::DKF
DKF()
Convenience default constructor.
Definition: dkf.h:64
mrs_lib::LKF< n_states, n_inputs, -1 >::A
A_t A
The system transition matrix .
Definition: lkf.h:144
mrs_lib::LKF< n_states, n_inputs, -1 >::u_t
typename Base_class::u_t u_t
Input vector type .
Definition: lkf.h:48
mrs_lib::DKF::A_t
Eigen::Matrix< double, n, n > A_t
System transition matrix type .
Definition: dkf.h:45
mrs_lib::DKF
Implementation of the Degenerate measurement Linear Kalman filter.
Definition: dkf.h:27