|
mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
10 #include <mrs_lib/lkf.h>
26 template <
int n_states,
int n_inputs>
27 class DKF :
public LKF<n_states, n_inputs, -1>
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;
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
91 assert(line_direction.norm() > 0.0);
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>;
99 const M_t M = M_t::Identity();
100 const W_t W = line_direction;
101 const o_t o = line_origin;
107 const mat3_t rot = mrs_lib::geometry::rotationBetween(W_t::UnitX(), 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;
115 return this->correction_impl(sc, z, R,
H);
135 assert(plane_normal.norm() > 0.0);
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>;
143 const M_t M = M_t::Identity();
144 const o_t o = plane_origin;
146 const N_t N = plane_normal.normalized();
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();
151 return this->correction_impl(sc, z, R,
H);
typename Base_class::Q_t Q_t
Process noise covariance matrix type .
Definition: lkf.h:52
static constexpr int p
Length of the measurement vector of the system.
Definition: lkf.h:44
static constexpr int m
Length of the input vector of the system.
Definition: dkf.h:34
typename Base_class::P_t P_t
State uncertainty covariance matrix type .
Definition: lkf.h:50
Eigen::Matrix< double, p, n > H_t
State to measurement mapping matrix type .
Definition: dkf.h:47
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
typename Base_class::x_t x_t
State vector type .
Definition: dkf.h:37
H_t H
The state to measurement mapping matrix .
Definition: lkf.h:150
typename Base_class::statecov_t statecov_t
Helper struct for passing around the state and its covariance in one variable.
Definition: dkf.h:43
typename Base_class::statecov_t statecov_t
Helper struct for passing around the state and its covariance in one variable.
Definition: lkf.h:53
typename Base_class::R_t R_t
Measurement noise covariance matrix type .
Definition: lkf.h:51
static constexpr int p
Length of the measurement vector of the system.
Definition: dkf.h:35
typename Base_class::P_t P_t
State uncertainty covariance matrix type .
Definition: dkf.h:40
Eigen::Matrix< double, n, p > K_t
Kalman gain matrix type .
Definition: dkf.h:48
static constexpr int n
Length of the state vector of the system.
Definition: dkf.h:33
typename Base_class::z_t z_t
Measurement vector type .
Definition: dkf.h:39
typename Base_class::R_t R_t
Measurement noise covariance matrix type .
Definition: dkf.h:41
Defines useful geometry utilities and functions.
typename Base_class::x_t x_t
State vector type .
Definition: lkf.h:47
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition: attitude_converter.h:29
typename Base_class::u_t u_t
Input vector type .
Definition: dkf.h:38
static constexpr int n
Length of the state vector of the system.
Definition: lkf.h:42
B_t B
The input to state mapping matrix .
Definition: lkf.h:149
DKF(const A_t &A, const B_t &B)
The main constructor.
Definition: dkf.h:73
typename Base_class::Q_t Q_t
Process noise covariance matrix type .
Definition: dkf.h:42
Implementation of the Linear Kalman filter .
Definition: lkf.h:38
Eigen::Matrix< double, n, m > B_t
Input to state mapping matrix type .
Definition: dkf.h:46
typename Base_class::z_t z_t
Measurement vector type .
Definition: lkf.h:49
static constexpr int m
Length of the input vector of the system.
Definition: lkf.h:43
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
DKF()
Convenience default constructor.
Definition: dkf.h:64
A_t A
The system transition matrix .
Definition: lkf.h:144
typename Base_class::u_t u_t
Input vector type .
Definition: lkf.h:48
Eigen::Matrix< double, n, n > A_t
System transition matrix type .
Definition: dkf.h:45
Implementation of the Degenerate measurement Linear Kalman filter.
Definition: dkf.h:27