Package edu.wpi.first.math.system
Class Discretization
java.lang.Object
edu.wpi.first.math.system.Discretization
Discretization helper functions.
-
Method Summary
Modifier and TypeMethodDescriptiondiscretizeA(Matrix<States, States> contA, double dtSeconds) Discretizes the given continuous A matrix.discretizeAB(Matrix<States, States> contA, Matrix<States, Inputs> contB, double dtSeconds) Discretizes the given continuous A and B matrices.discretizeAQ(Matrix<States, States> contA, Matrix<States, States> contQ, double dtSeconds) Discretizes the given continuous A and Q matrices.discretizeR(Matrix<O, O> contR, double dtSeconds) Returns a discretized version of the provided continuous measurement noise covariance matrix.
-
Method Details
-
discretizeA
public static <States extends Num> Matrix<States,States> discretizeA(Matrix<States, States> contA, double dtSeconds) Discretizes the given continuous A matrix.- Type Parameters:
States- Num representing the number of states.- Parameters:
contA- Continuous system matrix.dtSeconds- Discretization timestep.- Returns:
- the discrete matrix system.
-
discretizeAB
public static <States extends Num,Inputs extends Num> Pair<Matrix<States,States>, discretizeABMatrix<States, Inputs>> (Matrix<States, States> contA, Matrix<States, Inputs> contB, double dtSeconds) Discretizes the given continuous A and B matrices.- Type Parameters:
States- Nat representing the states of the system.Inputs- Nat representing the inputs to the system.- Parameters:
contA- Continuous system matrix.contB- Continuous input matrix.dtSeconds- Discretization timestep.- Returns:
- a Pair representing discA and diskB.
-
discretizeAQ
public static <States extends Num> Pair<Matrix<States,States>, discretizeAQMatrix<States, States>> (Matrix<States, States> contA, Matrix<States, States> contQ, double dtSeconds) Discretizes the given continuous A and Q matrices.- Type Parameters:
States- Nat representing the number of states.- Parameters:
contA- Continuous system matrix.contQ- Continuous process noise covariance matrix.dtSeconds- Discretization timestep.- Returns:
- a pair representing the discrete system matrix and process noise covariance matrix.
-
discretizeR
Returns a discretized version of the provided continuous measurement noise covariance matrix. Note that dt=0.0 divides R by zero.- Type Parameters:
O- Nat representing the number of outputs.- Parameters:
contR- Continuous measurement noise covariance matrix.dtSeconds- Discretization timestep.- Returns:
- Discretized version of the provided continuous measurement noise covariance matrix.
-