Class AngleStatistics

java.lang.Object
edu.wpi.first.math.estimator.AngleStatistics

public final class AngleStatistics
extends Object
  • Method Details

    • angleResidual

      public static <S extends Num> Matrix<S,​N1> angleResidual​(Matrix<S,​N1> a, Matrix<S,​N1> b, int angleStateIdx)
      Subtracts a and b while normalizing the resulting value in the selected row as if it were an angle.
      Type Parameters:
      S - Number of rows in vector.
      Parameters:
      a - A vector to subtract from.
      b - A vector to subtract with.
      angleStateIdx - The row containing angles to be normalized.
      Returns:
      Difference of two vectors with angle at the given index normalized.
    • angleResidual

      public static <S extends Num> BiFunction<Matrix<S,​N1>,​Matrix<S,​N1>,​Matrix<S,​N1>> angleResidual​(int angleStateIdx)
      Returns a function that subtracts two vectors while normalizing the resulting value in the selected row as if it were an angle.
      Type Parameters:
      S - Number of rows in vector.
      Parameters:
      angleStateIdx - The row containing angles to be normalized.
      Returns:
      Function returning difference of two vectors with angle at the given index normalized.
    • angleAdd

      public static <S extends Num> Matrix<S,​N1> angleAdd​(Matrix<S,​N1> a, Matrix<S,​N1> b, int angleStateIdx)
      Adds a and b while normalizing the resulting value in the selected row as an angle.
      Type Parameters:
      S - Number of rows in vector.
      Parameters:
      a - A vector to add with.
      b - A vector to add with.
      angleStateIdx - The row containing angles to be normalized.
      Returns:
      Sum of two vectors with angle at the given index normalized.
    • angleAdd

      public static <S extends Num> BiFunction<Matrix<S,​N1>,​Matrix<S,​N1>,​Matrix<S,​N1>> angleAdd​(int angleStateIdx)
      Returns a function that adds two vectors while normalizing the resulting value in the selected row as an angle.
      Type Parameters:
      S - Number of rows in vector.
      Parameters:
      angleStateIdx - The row containing angles to be normalized.
      Returns:
      Function returning of two vectors with angle at the given index normalized.
    • angleMean

      public static <S extends Num> Matrix<S,​N1> angleMean​(Matrix<S,​?> sigmas, Matrix<?,​N1> Wm, int angleStateIdx)
      Computes the mean of sigmas with the weights Wm while computing a special angle mean for a select row.
      Type Parameters:
      S - Number of rows in sigma point matrix.
      Parameters:
      sigmas - Sigma points.
      Wm - Weights for the mean.
      angleStateIdx - The row containing the angles.
      Returns:
      Mean of sigma points.
    • angleMean

      public static <S extends Num> BiFunction<Matrix<S,​?>,​Matrix<?,​N1>,​Matrix<S,​N1>> angleMean​(int angleStateIdx)
      Returns a function that computes the mean of sigmas with the weights Wm while computing a special angle mean for a select row.
      Type Parameters:
      S - Number of rows in sigma point matrix.
      Parameters:
      angleStateIdx - The row containing the angles.
      Returns:
      Function returning mean of sigma points.