WPILibC++ 2024.3.2
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
8
9#include "frc/EigenCore.h"
10#include "units/time.h"
11
12namespace frc {
13
14/**
15 * Discretizes the given continuous A matrix.
16 *
17 * @tparam States Number of states.
18 * @param contA Continuous system matrix.
19 * @param dt Discretization timestep.
20 * @param discA Storage for discrete system matrix.
21 */
22template <int States>
23void DiscretizeA(const Matrixd<States, States>& contA, units::second_t dt,
25 // A_d = eᴬᵀ
26 *discA = (contA * dt.value()).exp();
27}
28
29/**
30 * Discretizes the given continuous A and B matrices.
31 *
32 * @tparam States Number of states.
33 * @tparam Inputs Number of inputs.
34 * @param contA Continuous system matrix.
35 * @param contB Continuous input matrix.
36 * @param dt Discretization timestep.
37 * @param discA Storage for discrete system matrix.
38 * @param discB Storage for discrete input matrix.
39 */
40template <int States, int Inputs>
42 const Matrixd<States, Inputs>& contB, units::second_t dt,
45 // M = [A B]
46 // [0 0]
48 M.template block<States, States>(0, 0) = contA;
49 M.template block<States, Inputs>(0, States) = contB;
50 M.template block<Inputs, States + Inputs>(States, 0).setZero();
51
52 // ϕ = eᴹᵀ = [A_d B_d]
53 // [ 0 I ]
54 Matrixd<States + Inputs, States + Inputs> phi = (M * dt.value()).exp();
55
56 *discA = phi.template block<States, States>(0, 0);
57 *discB = phi.template block<States, Inputs>(0, States);
58}
59
60/**
61 * Discretizes the given continuous A and Q matrices.
62 *
63 * @tparam States Number of states.
64 * @param contA Continuous system matrix.
65 * @param contQ Continuous process noise covariance matrix.
66 * @param dt Discretization timestep.
67 * @param discA Storage for discrete system matrix.
68 * @param discQ Storage for discrete process noise covariance matrix.
69 */
70template <int States>
72 const Matrixd<States, States>& contQ, units::second_t dt,
75 // Make continuous Q symmetric if it isn't already
76 Matrixd<States, States> Q = (contQ + contQ.transpose()) / 2.0;
77
78 // M = [−A Q ]
79 // [ 0 Aᵀ]
81 M.template block<States, States>(0, 0) = -contA;
82 M.template block<States, States>(0, States) = Q;
83 M.template block<States, States>(States, 0).setZero();
84 M.template block<States, States>(States, States) = contA.transpose();
85
86 // ϕ = eᴹᵀ = [−A_d A_d⁻¹Q_d]
87 // [ 0 A_dᵀ ]
88 Matrixd<2 * States, 2 * States> phi = (M * dt.value()).exp();
89
90 // ϕ₁₂ = A_d⁻¹Q_d
91 Matrixd<States, States> phi12 = phi.block(0, States, States, States);
92
93 // ϕ₂₂ = A_dᵀ
94 Matrixd<States, States> phi22 = phi.block(States, States, States, States);
95
96 *discA = phi22.transpose();
97
98 Q = *discA * phi12;
99
100 // Make discrete Q symmetric if it isn't already
101 *discQ = (Q + Q.transpose()) / 2.0;
102}
103
104/**
105 * Returns a discretized version of the provided continuous measurement noise
106 * covariance matrix.
107 *
108 * @tparam Outputs Number of outputs.
109 * @param R Continuous measurement noise covariance matrix.
110 * @param dt Discretization timestep.
111 */
112template <int Outputs>
114 units::second_t dt) {
115 // R_d = 1/T R
116 return R / dt.value();
117}
118
119} // namespace frc
Definition: AprilTagPoseEstimator.h:15
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition: EigenCore.h:21
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:71
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:41
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:113
void DiscretizeA(const Matrixd< States, States > &contA, units::second_t dt, Matrixd< States, States > *discA)
Discretizes the given continuous A matrix.
Definition: Discretization.h:23
static constexpr const unit_t< compound_unit< energy::joules, inverse< temperature::kelvin >, inverse< substance::moles > > > R(8.3144598)
Gas constant.