Package edu.wpi.first.math.estimator
Interface SigmaPoints<States extends Num>
- Type Parameters:
States
- The dimensionality of the state.
- All Known Implementing Classes:
MerweScaledSigmaPoints
,S3SigmaPoints
public interface SigmaPoints<States extends Num>
A sigma points generator for the UnscentedKalmanFilter class.
-
Method Summary
Modifier and TypeMethodDescriptionint
Returns number of sigma points for each variable in the state x.getWc()
Returns the weight for each sigma point for the covariance.double
getWc
(int element) Returns an element of the weight for each sigma point for the covariance.getWm()
Returns the weight for each sigma point for the mean.double
getWm
(int element) Returns an element of the weight for each sigma point for the mean.Computes the sigma points for an unscented Kalman filter given the mean (x) and square-root covariance (s) of the filter.
-
Method Details
-
getNumSigmas
int getNumSigmas()Returns number of sigma points for each variable in the state x.- Returns:
- The number of sigma points for each variable in the state x.
-
squareRootSigmaPoints
Computes the sigma points for an unscented Kalman filter given the mean (x) and square-root covariance (s) of the filter.- Parameters:
x
- An array of the means.s
- Square-root covariance of the filter.- Returns:
- Two-dimensional array of sigma points. Each column contains all the sigmas for one dimension in the problem space. Ordered by Xi_0, Xi_{1..n}, Xi_{n+1..2n}.
-
getWm
Returns the weight for each sigma point for the mean.- Returns:
- the weight for each sigma point for the mean.
-
getWm
Returns an element of the weight for each sigma point for the mean.- Parameters:
element
- Element of vector to return.- Returns:
- the element i's weight for the mean.
-
getWc
Returns the weight for each sigma point for the covariance.- Returns:
- the weight for each sigma point for the covariance.
-
getWc
Returns an element of the weight for each sigma point for the covariance.- Parameters:
element
- Element of vector to return.- Returns:
- The element I's weight for the covariance.
-