26 *discA = (contA * dt.value()).exp();
40template <
int States,
int Inputs>
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();
56 *discA = phi.template block<States, States>(0, 0);
57 *discB = phi.template block<States, Inputs>(0, States);
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();
96 *discA = phi22.transpose();
101 *discQ = (Q + Q.transpose()) / 2.0;
112template <
int Outputs>
114 units::second_t dt) {
116 return R / dt.value();
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.