-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
kalman_filter.h
96 lines (88 loc) · 3.81 KB
/
kalman_filter.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
#pragma once
#include <memory>
#include <Eigen/Dense>
#include "drake/systems/estimators/luenberger_observer.h"
#include "drake/systems/primitives/linear_system.h"
namespace drake {
namespace systems {
namespace estimators {
/// Computes the optimal observer gain, L, for the linear system defined by
/// @f[ \dot{x} = Ax + Bu + w, @f]
/// @f[ y = Cx + Du + v. @f]
/// The resulting observer is of the form
/// @f[ \dot{\hat{x}} = A\hat{x} + Bu + L(y - C\hat{x} - Du). @f]
/// The process noise, w, and the measurement noise, v, are assumed to be iid
/// mean-zero Gaussian.
///
/// This is a simplified form of the full Kalman filter obtained by assuming
/// that the state-covariance matrix has already converged to its steady-state
/// solution.
///
/// @param A The state-space dynamics matrix of size num_states x num_states.
/// @param C The state-space output matrix of size num_outputs x num_states.
/// @param W The process noise covariance matrix, E[ww'], of size num_states x
/// num_states.
/// @param V The measurement noise covariance matrix, E[vv'], of size num_.
/// @returns The steady-state observer gain matrix of size num_states x
/// num_outputs.
///
/// @throws std::exception if V is not positive definite.
/// @ingroup estimator_systems
///
Eigen::MatrixXd SteadyStateKalmanFilter(
const Eigen::Ref<const Eigen::MatrixXd>& A,
const Eigen::Ref<const Eigen::MatrixXd>& C,
const Eigen::Ref<const Eigen::MatrixXd>& W,
const Eigen::Ref<const Eigen::MatrixXd>& V);
/// Creates a Luenberger observer system using the optimal steady-state Kalman
/// filter gain matrix, L, as described above.
///
/// @param system A unique_ptr to a LinearSystem describing the system to be
/// observed. The new observer will take and maintain ownership of this
/// pointer.
/// @param W The process noise covariance matrix, E[ww'], of size num_states x
/// num_states.
/// @param V The measurement noise covariance matrix, E[vv'], of size num_.
/// @returns A unique_ptr to the constructed observer system.
///
/// @throws std::exception if V is not positive definite.
/// @ingroup estimator_systems
std::unique_ptr<LuenbergerObserver<double>> SteadyStateKalmanFilter(
std::unique_ptr<LinearSystem<double>> system,
const Eigen::Ref<const Eigen::MatrixXd>& W,
const Eigen::Ref<const Eigen::MatrixXd>& V);
/// Creates a Luenberger observer system using the steady-state Kalman filter
/// observer gain.
///
/// Assuming @p system has the (continuous-time) dynamics:
/// dx/dt = f(x,u),
/// and the output:
/// y = g(x,u),
/// then the resulting observer will have the form
/// dx̂/dt = f(x̂,u) + L(y - g(x̂,u)),
/// where x̂ is the estimated state and the gain matrix, L, is designed
/// as a steady-state Kalman filter using a linearization of f(x,u) at @p
/// context as described above.
///
/// @param system A unique_ptr to a System describing the system to be
/// observed. The new observer will take and maintain ownership of this
/// pointer.
/// @param context A unique_ptr to the context describing a fixed-point of the
/// system (plus any additional parameters). The new observer will take and
/// maintain ownership of this pointer for use in its internal forward
/// simulation.
/// @param W The process noise covariance matrix, E[ww'], of size num_states x
/// num_states.
/// @param V The measurement noise covariance matrix, E[vv'], of size num_.
/// @returns A unique_ptr to the constructed observer system.
///
/// @throws std::exception if V is not positive definite.
/// @ingroup estimator_systems
std::unique_ptr<LuenbergerObserver<double>> SteadyStateKalmanFilter(
std::unique_ptr<System<double>> system,
std::unique_ptr<Context<double>> context,
const Eigen::Ref<const Eigen::MatrixXd>& W,
const Eigen::Ref<const Eigen::MatrixXd>& V);
} // namespace estimators
} // namespace systems
} // namespace drake