25 *discA = (contA * dt.value()).exp();
39template <
int States,
int Inputs>
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();
55 *discA = phi.template block<States, States>(0, 0);
56 *discB = phi.template block<States, Inputs>(0, States);
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();
95 *discA = phi22.transpose();
100 *discQ = (Q + Q.transpose()) / 2.0;
168 double lastCoeff = dt.value();
176 for (
int i = 2; i < 6; ++i) {
177 lastTerm = -contA * lastTerm + Q * ATn;
178 lastCoeff *= dt.value() /
static_cast<double>(i);
180 phi12 += lastTerm * lastCoeff;
182 ATn *= contA.transpose();
185 DiscretizeA<States>(contA, dt, discA);
189 *discQ = (Q + Q.transpose()) / 2.0;
200template <
int Outputs>
202 units::second_t dt) {
204 return R / dt.value();
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.