Class Drake

java.lang.Object
edu.wpi.first.math.Drake

public final class Drake
extends Object
  • Method Details

    • discreteAlgebraicRiccatiEquation

      public static org.ejml.simple.SimpleMatrix discreteAlgebraicRiccatiEquation​(org.ejml.simple.SimpleMatrix A, org.ejml.simple.SimpleMatrix B, org.ejml.simple.SimpleMatrix Q, org.ejml.simple.SimpleMatrix R)
      Solves the discrete alegebraic Riccati equation.
      Parameters:
      A - System matrix.
      B - Input matrix.
      Q - State cost matrix.
      R - Input cost matrix.
      Returns:
      Solution of DARE.
    • discreteAlgebraicRiccatiEquation

      public static <States extends Num,​ Inputs extends Num> Matrix<States,​States> discreteAlgebraicRiccatiEquation​(Matrix<States,​States> A, Matrix<States,​Inputs> B, Matrix<States,​States> Q, Matrix<Inputs,​Inputs> R)
      Solves the discrete alegebraic Riccati equation.
      Type Parameters:
      States - Number of states.
      Inputs - Number of inputs.
      Parameters:
      A - System matrix.
      B - Input matrix.
      Q - State cost matrix.
      R - Input cost matrix.
      Returns:
      Solution of DARE.
    • discreteAlgebraicRiccatiEquation

      public static org.ejml.simple.SimpleMatrix discreteAlgebraicRiccatiEquation​(org.ejml.simple.SimpleMatrix A, org.ejml.simple.SimpleMatrix B, org.ejml.simple.SimpleMatrix Q, org.ejml.simple.SimpleMatrix R, org.ejml.simple.SimpleMatrix N)
      Solves the discrete alegebraic Riccati equation.
      Parameters:
      A - System matrix.
      B - Input matrix.
      Q - State cost matrix.
      R - Input cost matrix.
      N - State-input cross-term cost matrix.
      Returns:
      Solution of DARE.
    • discreteAlgebraicRiccatiEquation

      public static <States extends Num,​ Inputs extends Num> Matrix<States,​States> discreteAlgebraicRiccatiEquation​(Matrix<States,​States> A, Matrix<States,​Inputs> B, Matrix<States,​States> Q, Matrix<Inputs,​Inputs> R, Matrix<States,​Inputs> N)
      Solves the discrete alegebraic Riccati equation.
      Type Parameters:
      States - Number of states.
      Inputs - Number of inputs.
      Parameters:
      A - System matrix.
      B - Input matrix.
      Q - State cost matrix.
      R - Input cost matrix.
      N - State-input cross-term cost matrix.
      Returns:
      Solution of DARE.