WPILibC++ 2023.4.3
Discretization.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include "frc/EigenCore.h"
8#include "units/time.h"
10
11namespace frc {
12
13/**
14 * Discretizes the given continuous A matrix.
15 *
16 * @tparam States Number of states.
17 * @param contA Continuous system matrix.
18 * @param dt Discretization timestep.
19 * @param discA Storage for discrete system matrix.
20 */
21template <int States>
22void DiscretizeA(const Matrixd<States, States>& contA, units::second_t dt,
24 // A_d = eᴬᵀ
25 *discA = (contA * dt.value()).exp();
26}
27
28/**
29 * Discretizes the given continuous A and B matrices.
30 *
31 * @tparam States Number of states.
32 * @tparam Inputs Number of inputs.
33 * @param contA Continuous system matrix.
34 * @param contB Continuous input matrix.
35 * @param dt Discretization timestep.
36 * @param discA Storage for discrete system matrix.
37 * @param discB Storage for discrete input matrix.
38 */
39template <int States, int Inputs>
41 const Matrixd<States, Inputs>& contB, units::second_t dt,
44 // M = [A B]
45 // [0 0]
47 M.template block<States, States>(0, 0) = contA;
48 M.template block<States, Inputs>(0, States) = contB;
49 M.template block<Inputs, States + Inputs>(States, 0).setZero();
50
51 // ϕ = eᴹᵀ = [A_d B_d]
52 // [ 0 I ]
53 Matrixd<States + Inputs, States + Inputs> phi = (M * dt.value()).exp();
54
55 *discA = phi.template block<States, States>(0, 0);
56 *discB = phi.template block<States, Inputs>(0, States);
57}
58
59/**
60 * Discretizes the given continuous A and Q matrices.
61 *
62 * @tparam States Number of states.
63 * @param contA Continuous system matrix.
64 * @param contQ Continuous process noise covariance matrix.
65 * @param dt Discretization timestep.
66 * @param discA Storage for discrete system matrix.
67 * @param discQ Storage for discrete process noise covariance matrix.
68 */
69template <int States>
71 const Matrixd<States, States>& contQ, units::second_t dt,
74 // Make continuous Q symmetric if it isn't already
75 Matrixd<States, States> Q = (contQ + contQ.transpose()) / 2.0;
76
77 // M = [−A Q ]
78 // [ 0 Aᵀ]
80 M.template block<States, States>(0, 0) = -contA;
81 M.template block<States, States>(0, States) = Q;
82 M.template block<States, States>(States, 0).setZero();
83 M.template block<States, States>(States, States) = contA.transpose();
84
85 // ϕ = eᴹᵀ = [−A_d A_d⁻¹Q_d]
86 // [ 0 A_dᵀ ]
87 Matrixd<2 * States, 2 * States> phi = (M * dt.value()).exp();
88
89 // ϕ₁₂ = A_d⁻¹Q_d
90 Matrixd<States, States> phi12 = phi.block(0, States, States, States);
91
92 // ϕ₂₂ = A_dᵀ
93 Matrixd<States, States> phi22 = phi.block(States, States, States, States);
94
95 *discA = phi22.transpose();
96
97 Q = *discA * phi12;
98
99 // Make discrete Q symmetric if it isn't already
100 *discQ = (Q + Q.transpose()) / 2.0;
101}
102
103/**
104 * Discretizes the given continuous A and Q matrices.
105 *
106 * Rather than solving a 2N x 2N matrix exponential like in DiscretizeAQ()
107 * (which is expensive), we take advantage of the structure of the block matrix
108 * of A and Q.
109 *
110 * <ul>
111 * <li>eᴬᵀ, which is only N x N, is relatively cheap.
112 * <li>The upper-right quarter of the 2N x 2N matrix, which we can approximate
113 * using a taylor series to several terms and still be substantially
114 * cheaper than taking the big exponential.
115 * </ul>
116 *
117 * @tparam States Number of states.
118 * @param contA Continuous system matrix.
119 * @param contQ Continuous process noise covariance matrix.
120 * @param dt Discretization timestep.
121 * @param discA Storage for discrete system matrix.
122 * @param discQ Storage for discrete process noise covariance matrix.
123 */
124template <int States>
126 const Matrixd<States, States>& contQ,
127 units::second_t dt, Matrixd<States, States>* discA,
129 // T
130 // Q_d = ∫ e^(Aτ) Q e^(Aᵀτ) dτ
131 // 0
132 //
133 // M = [−A Q ]
134 // [ 0 Aᵀ]
135 // ϕ = eᴹᵀ
136 // ϕ₁₂ = A_d⁻¹Q_d
137 //
138 // Taylor series of ϕ:
139 //
140 // ϕ = eᴹᵀ = I + MT + 1/2 M²T² + 1/6 M³T³ + …
141 // ϕ = eᴹᵀ = I + MT + 1/2 T²M² + 1/6 T³M³ + …
142 //
143 // Taylor series of ϕ expanded for ϕ₁₂:
144 //
145 // ϕ₁₂ = 0 + QT + 1/2 T² (−AQ + QAᵀ) + 1/6 T³ (−A lastTerm + Q Aᵀ²) + …
146 //
147 // ```
148 // lastTerm = Q
149 // lastCoeff = T
150 // ATn = Aᵀ
151 // ϕ₁₂ = lastTerm lastCoeff = QT
152 //
153 // for i in range(2, 6):
154 // // i = 2
155 // lastTerm = −A lastTerm + Q ATn = −AQ + QAᵀ
156 // lastCoeff *= T/i → lastCoeff *= T/2 = 1/2 T²
157 // ATn *= Aᵀ = Aᵀ²
158 //
159 // // i = 3
160 // lastTerm = −A lastTerm + Q ATn = −A (−AQ + QAᵀ) + QAᵀ² = …
161 // …
162 // ```
163
164 // Make continuous Q symmetric if it isn't already
165 Matrixd<States, States> Q = (contQ + contQ.transpose()) / 2.0;
166
167 Matrixd<States, States> lastTerm = Q;
168 double lastCoeff = dt.value();
169
170 // Aᵀⁿ
171 Matrixd<States, States> ATn = contA.transpose();
172
173 Matrixd<States, States> phi12 = lastTerm * lastCoeff;
174
175 // i = 6 i.e. 5th order should be enough precision
176 for (int i = 2; i < 6; ++i) {
177 lastTerm = -contA * lastTerm + Q * ATn;
178 lastCoeff *= dt.value() / static_cast<double>(i);
179
180 phi12 += lastTerm * lastCoeff;
181
182 ATn *= contA.transpose();
183 }
184
185 DiscretizeA<States>(contA, dt, discA);
186 Q = *discA * phi12;
187
188 // Make discrete Q symmetric if it isn't already
189 *discQ = (Q + Q.transpose()) / 2.0;
190}
191
192/**
193 * Returns a discretized version of the provided continuous measurement noise
194 * covariance matrix.
195 *
196 * @tparam Outputs Number of outputs.
197 * @param R Continuous measurement noise covariance matrix.
198 * @param dt Discretization timestep.
199 */
200template <int Outputs>
202 units::second_t dt) {
203 // R_d = 1/T R
204 return R / dt.value();
205}
206
207} // namespace frc
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:180
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
Resizes to the given size, and sets all coefficients in this expression to zero.
Definition: CwiseNullaryOp.h:562
Definition: AprilTagFieldLayout.h:22
void DiscretizeAQTaylor(const Matrixd< States, States > &contA, const Matrixd< States, States > &contQ, units::second_t dt, Matrixd< States, States > *discA, Matrixd< States, States > *discQ)
Discretizes the given continuous A and Q matrices.
Definition: Discretization.h:125
void DiscretizeAQ(const Matrixd< States, States > &contA, const Matrixd< States, States > &contQ, units::second_t dt, Matrixd< States, States > *discA, Matrixd< States, States > *discQ)
Discretizes the given continuous A and Q matrices.
Definition: Discretization.h:70
void DiscretizeAB(const Matrixd< States, States > &contA, const Matrixd< States, Inputs > &contB, units::second_t dt, Matrixd< States, States > *discA, Matrixd< States, Inputs > *discB)
Discretizes the given continuous A and B matrices.
Definition: Discretization.h:40
Matrixd< Outputs, Outputs > DiscretizeR(const Matrixd< Outputs, Outputs > &R, units::second_t dt)
Returns a discretized version of the provided continuous measurement noise covariance matrix.
Definition: Discretization.h:201
void DiscretizeA(const Matrixd< States, States > &contA, units::second_t dt, Matrixd< States, States > *discA)
Discretizes the given continuous A matrix.
Definition: Discretization.h:22
static constexpr const unit_t< compound_unit< energy::joules, inverse< temperature::kelvin >, inverse< substance::moles > > > R(8.3144598)
Gas constant.